|
From: <stu...@us...> - 2009-08-07 20:52:54
|
Revision: 21045
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=21045&view=rev
Author: stuglaser
Date: 2009-08-07 20:52:44 +0000 (Fri, 07 Aug 2009)
Log Message:
-----------
Find/replace for robot_msgs/Polygon3D -> geometry_msgs/Polygon
Modified Paths:
--------------
pkg/trunk/demos/tabletop_manipulation/tabletop_msgs/msg/Table.msg
pkg/trunk/mapping/annotated_map_msgs/msg/TaggedPolygon3D.msg
pkg/trunk/mapping/annotated_planar_patch_map/include/annotated_planar_patch_map/annotated_map_lib.h
pkg/trunk/mapping/annotated_planar_patch_map/include/annotated_planar_patch_map/projection.h
pkg/trunk/mapping/annotated_planar_patch_map/src/annotated_map_lib.cpp
pkg/trunk/mapping/annotated_planar_patch_map/src/annotated_planar_patch_map_builder.cpp
pkg/trunk/mapping/annotated_planar_patch_map/src/annotation2d_lifter_to_planar_patch_map.cpp
pkg/trunk/mapping/annotated_planar_patch_map/src/annotation2d_lifter_to_tagged_patch_map.cpp
pkg/trunk/mapping/annotated_planar_patch_map/src/annotation2d_lifter_to_tagged_patch_map_via_service.cpp
pkg/trunk/mapping/annotated_planar_patch_map/src/projection.cpp
pkg/trunk/mapping/annotated_planar_patch_map/test/projection_test.cpp
pkg/trunk/mapping/door_stereo_detector/src/door_stereo_detector.cpp
pkg/trunk/mapping/door_tracker/src/door_tracker.cpp
pkg/trunk/mapping/hallway_tracker/src/hallway_tracker.cpp
pkg/trunk/mapping/planar_patch_map/src/planar_patch_map.cpp
pkg/trunk/mapping/planar_patch_map/src/planar_patch_map_omp.cpp
pkg/trunk/mapping/stereo_convex_patch_histogram/src/convex_patch_histogram.cpp
pkg/trunk/mapping/table_object_detector/src/table_object_detector.cpp
pkg/trunk/nav/people_aware_nav/include/people_aware_nav/move_base_constrained.h
pkg/trunk/nav/people_aware_nav/include/people_aware_nav/navfn_constrained.h
pkg/trunk/nav/people_aware_nav/msg/ConstrainedGoal.msg
pkg/trunk/nav/people_aware_nav/src/move_base_constrained.cpp
pkg/trunk/nav/people_aware_nav/srv/SetNavConstraint.srv
pkg/trunk/sandbox/planar_objects/src/find_planes.h
pkg/trunk/sandbox/planar_objects/src/rectangular_fit.h
pkg/trunk/sandbox/planar_objects/src/vis_utils.cpp
pkg/trunk/sandbox/planar_objects/src/vis_utils.h
pkg/trunk/stacks/common_msgs/mapping_msgs/msg/PolygonalMap.msg
pkg/trunk/stacks/semantic_mapping/door_handle_detector/include/door_handle_detector/geometric_helper.h
pkg/trunk/stacks/semantic_mapping/door_handle_detector/include/door_handle_detector/handle_detector.h
pkg/trunk/stacks/semantic_mapping/door_handle_detector/src/geometric_helper.cpp
pkg/trunk/stacks/semantic_mapping/door_handle_detector/src/handle_detector.cpp
pkg/trunk/stacks/semantic_mapping/plug_onbase_detector/include/plug_onbase_detector/plug_onbase_detector.h
pkg/trunk/stacks/semantic_mapping/point_cloud_mapping/include/point_cloud_mapping/geometry/angles.h
pkg/trunk/stacks/semantic_mapping/point_cloud_mapping/include/point_cloud_mapping/geometry/areas.h
pkg/trunk/stacks/semantic_mapping/point_cloud_mapping/include/point_cloud_mapping/geometry/distances.h
pkg/trunk/stacks/semantic_mapping/point_cloud_mapping/include/point_cloud_mapping/geometry/intersections.h
pkg/trunk/stacks/semantic_mapping/point_cloud_mapping/include/point_cloud_mapping/geometry/nearest.h
pkg/trunk/stacks/semantic_mapping/point_cloud_mapping/include/point_cloud_mapping/geometry/point.h
pkg/trunk/stacks/semantic_mapping/point_cloud_mapping/include/point_cloud_mapping/geometry/projections.h
pkg/trunk/stacks/semantic_mapping/point_cloud_mapping/include/point_cloud_mapping/geometry/statistics.h
pkg/trunk/stacks/semantic_mapping/point_cloud_mapping/src/cloud_geometry/areas.cpp
pkg/trunk/stacks/semantic_mapping/point_cloud_mapping/src/cloud_geometry/intersections.cpp
pkg/trunk/stacks/semantic_mapping/point_cloud_mapping/test/cloud_geometry/test_geometry_areas.cpp
pkg/trunk/stacks/semantic_mapping/semantic_point_annotator/src/sac_ground_removal.cpp
pkg/trunk/stacks/semantic_mapping/semantic_point_annotator/src/sac_inc_ground_removal.cpp
pkg/trunk/stacks/semantic_mapping/semantic_point_annotator/src/semantic_point_annotator.cpp
pkg/trunk/stacks/semantic_mapping/semantic_point_annotator/src/semantic_point_annotator_omp.cpp
pkg/trunk/stacks/visualization/rviz/src/rviz/displays/polygonal_map_display.h
pkg/trunk/vision/recognition_lambertian/src/plane_fit.cpp
pkg/trunk/vision/recognition_lambertian/src/rec_lam_normal_features.cpp
Modified: pkg/trunk/demos/tabletop_manipulation/tabletop_msgs/msg/Table.msg
===================================================================
--- pkg/trunk/demos/tabletop_manipulation/tabletop_msgs/msg/Table.msg 2009-08-07 20:49:05 UTC (rev 21044)
+++ pkg/trunk/demos/tabletop_manipulation/tabletop_msgs/msg/Table.msg 2009-08-07 20:52:44 UTC (rev 21045)
@@ -1,5 +1,5 @@
Header header
-robot_msgs/Polygon3D table
+geometry_msgs/Polygon table
geometry_msgs/Point table_min
geometry_msgs/Point table_max
ObjectOnTable[] objects
Modified: pkg/trunk/mapping/annotated_map_msgs/msg/TaggedPolygon3D.msg
===================================================================
--- pkg/trunk/mapping/annotated_map_msgs/msg/TaggedPolygon3D.msg 2009-08-07 20:49:05 UTC (rev 21044)
+++ pkg/trunk/mapping/annotated_map_msgs/msg/TaggedPolygon3D.msg 2009-08-07 20:52:44 UTC (rev 21045)
@@ -1,4 +1,4 @@
string name
string[] tags
sensor_msgs/ChannelFloat32[] tags_chan
-robot_msgs/Polygon3D polygon
+geometry_msgs/Polygon polygon
Modified: pkg/trunk/mapping/annotated_planar_patch_map/include/annotated_planar_patch_map/annotated_map_lib.h
===================================================================
--- pkg/trunk/mapping/annotated_planar_patch_map/include/annotated_planar_patch_map/annotated_map_lib.h 2009-08-07 20:49:05 UTC (rev 21044)
+++ pkg/trunk/mapping/annotated_planar_patch_map/include/annotated_planar_patch_map/annotated_map_lib.h 2009-08-07 20:52:44 UTC (rev 21045)
@@ -189,7 +189,7 @@
-geometry_msgs::Point32 computeMean(const robot_msgs::Polygon3D& poly);
+geometry_msgs::Point32 computeMean(const geometry_msgs::Polygon& poly);
} //end namespace
Modified: pkg/trunk/mapping/annotated_planar_patch_map/include/annotated_planar_patch_map/projection.h
===================================================================
--- pkg/trunk/mapping/annotated_planar_patch_map/include/annotated_planar_patch_map/projection.h 2009-08-07 20:49:05 UTC (rev 21044)
+++ pkg/trunk/mapping/annotated_planar_patch_map/include/annotated_planar_patch_map/projection.h 2009-08-07 20:52:44 UTC (rev 21045)
@@ -62,7 +62,7 @@
namespace projection
{
-void projectAnyObject(const sensor_msgs::CameraInfo& cam_info,robot_msgs::Polygon3D polyIn,robot_msgs::Polygon3D& polyOut);
+void projectAnyObject(const sensor_msgs::CameraInfo& cam_info,geometry_msgs::Polygon polyIn,geometry_msgs::Polygon& polyOut);
void projectAnyObject(const sensor_msgs::StereoInfo& stereo_info_, const annotated_map_msgs::TaggedPolygonalMap& transformed_map_3D, annotated_map_msgs::TaggedPolygonalMap &transformed_map_2D);
@@ -76,8 +76,8 @@
void projectPolygonalMap(const sensor_msgs::StereoInfo& stereo_info_, const mapping_msgs::PolygonalMap& transformed_map_3D, mapping_msgs::PolygonalMap &transformed_map_2D);
-void projectPolygonPoints(double* projection,double img_w, double img_h, robot_msgs::Polygon3D polyIn,robot_msgs::Polygon3D& polyOut);
-void projectPolygonPointsNOP(double* projection,double img_w, double img_h, robot_msgs::Polygon3D polyIn,robot_msgs::Polygon3D& polyOut);
+void projectPolygonPoints(double* projection,double img_w, double img_h, geometry_msgs::Polygon polyIn,geometry_msgs::Polygon& polyOut);
+void projectPolygonPointsNOP(double* projection,double img_w, double img_h, geometry_msgs::Polygon polyIn,geometry_msgs::Polygon& polyOut);
@@ -95,7 +95,7 @@
const std::vector<double>& viewport);
-bool checkPolyInside(const robot_msgs::Polygon3D& poly,const std::vector<double>& viewport);
+bool checkPolyInside(const geometry_msgs::Polygon& poly,const std::vector<double>& viewport);
}
} //end namespace
Modified: pkg/trunk/mapping/annotated_planar_patch_map/src/annotated_map_lib.cpp
===================================================================
--- pkg/trunk/mapping/annotated_planar_patch_map/src/annotated_map_lib.cpp 2009-08-07 20:49:05 UTC (rev 21044)
+++ pkg/trunk/mapping/annotated_planar_patch_map/src/annotated_map_lib.cpp 2009-08-07 20:52:44 UTC (rev 21045)
@@ -59,7 +59,7 @@
for(unsigned int iPoly=0;iPoly<num_polygons;iPoly++)
{
- const robot_msgs::Polygon3D* p=&polymapIn.polygons[iPoly];
+ const geometry_msgs::Polygon* p=&polymapIn.polygons[iPoly];
unsigned int length = p->get_points_size();
@@ -77,7 +77,7 @@
boost::numeric::ublas::matrix<double> matOut = prod(transform, matIn);
- robot_msgs::Polygon3D *polyOut;
+ geometry_msgs::Polygon *polyOut;
if (!bSame)
{
polyOut = &(polymapOut.polygons[iPoly]);
@@ -304,7 +304,7 @@
-geometry_msgs::Point32 annotated_map_lib::computeMean (const robot_msgs::Polygon3D& poly)
+geometry_msgs::Point32 annotated_map_lib::computeMean (const geometry_msgs::Polygon& poly)
{
geometry_msgs::Point32 mean;
mean.x=0;mean.y=0;mean.z=0;
Modified: pkg/trunk/mapping/annotated_planar_patch_map/src/annotated_planar_patch_map_builder.cpp
===================================================================
--- pkg/trunk/mapping/annotated_planar_patch_map/src/annotated_planar_patch_map_builder.cpp 2009-08-07 20:49:05 UTC (rev 21044)
+++ pkg/trunk/mapping/annotated_planar_patch_map/src/annotated_planar_patch_map_builder.cpp 2009-08-07 20:52:44 UTC (rev 21045)
@@ -106,7 +106,7 @@
boost::numeric::ublas::matrix<double> transform = transformAsMatrix(net_transform);
- typedef std::vector<robot_msgs::Polygon3D> poly_vec;
+ typedef std::vector<geometry_msgs::Polygon> poly_vec;
bool bSame = (&polymapIn == &polymapOut);
unsigned int num_polygons = polymapIn.get_polygons_size();
@@ -117,7 +117,7 @@
for(unsigned int iPoly=0;iPoly<num_polygons;iPoly++)
{
- const robot_msgs::Polygon3D* p=&polymapIn.polygons[iPoly];
+ const geometry_msgs::Polygon* p=&polymapIn.polygons[iPoly];
unsigned int length = p->get_points_size();
@@ -135,7 +135,7 @@
boost::numeric::ublas::matrix<double> matOut = prod(transform, matIn);
- robot_msgs::Polygon3D *polyOut;
+ geometry_msgs::Polygon *polyOut;
if (!bSame)
{
polyOut = &(polymapOut.polygons[iPoly]);
Modified: pkg/trunk/mapping/annotated_planar_patch_map/src/annotation2d_lifter_to_planar_patch_map.cpp
===================================================================
--- pkg/trunk/mapping/annotated_planar_patch_map/src/annotation2d_lifter_to_planar_patch_map.cpp 2009-08-07 20:49:05 UTC (rev 21044)
+++ pkg/trunk/mapping/annotated_planar_patch_map/src/annotation2d_lifter_to_planar_patch_map.cpp 2009-08-07 20:52:44 UTC (rev 21045)
@@ -216,7 +216,7 @@
for(unsigned int iPoly = 0; iPoly<num_3D_poly; iPoly++)
{
//we're checking this one
- robot_msgs::Polygon3D &map_poly=transformed_map_2D.polygons[iPoly];
+ geometry_msgs::Polygon &map_poly=transformed_map_2D.polygons[iPoly];
int num_in=0,num_out=0;
for(unsigned int iPt=0;iPt<map_poly.get_points_size();iPt++)
{
@@ -339,7 +339,7 @@
for(unsigned int iPoly = 0; iPoly<num_3D_poly; iPoly++)
{
//we're checking this one
- robot_msgs::Polygon3D &map_poly=transformed_map.polygons[iPoly];
+ geometry_msgs::Polygon &map_poly=transformed_map.polygons[iPoly];
for(unsigned int iPt=0;iPt<map_poly.get_points_size();iPt++){
fprintf(fOut,"%f %f %f\n",map_poly.points[iPt].x,
map_poly.points[iPt].y,
Modified: pkg/trunk/mapping/annotated_planar_patch_map/src/annotation2d_lifter_to_tagged_patch_map.cpp
===================================================================
--- pkg/trunk/mapping/annotated_planar_patch_map/src/annotation2d_lifter_to_tagged_patch_map.cpp 2009-08-07 20:49:05 UTC (rev 21044)
+++ pkg/trunk/mapping/annotated_planar_patch_map/src/annotation2d_lifter_to_tagged_patch_map.cpp 2009-08-07 20:52:44 UTC (rev 21045)
@@ -237,7 +237,7 @@
for(unsigned int iPoly = 0; iPoly<num_3D_poly; iPoly++)
{
//we're checking this one
- const robot_msgs::Polygon3D &map_poly=transformed_map_2D.polygons[iPoly].polygon;
+ const geometry_msgs::Polygon &map_poly=transformed_map_2D.polygons[iPoly].polygon;
int num_in=0,num_out=0;
for(unsigned int iPt=0;iPt<map_poly.get_points_size();iPt++)
{
@@ -366,7 +366,7 @@
for(unsigned int iPoly = 0; iPoly<num_3D_poly; iPoly++)
{
//we're checking this one
- robot_msgs::Polygon3D &map_poly=transformed_map.polygons[iPoly];
+ geometry_msgs::Polygon &map_poly=transformed_map.polygons[iPoly];
for(unsigned int iPt=0;iPt<map_poly.get_points_size();iPt++){
fprintf(fOut,"%f %f %f\n",map_poly.points[iPt].x,
map_poly.points[iPt].y,
Modified: pkg/trunk/mapping/annotated_planar_patch_map/src/annotation2d_lifter_to_tagged_patch_map_via_service.cpp
===================================================================
--- pkg/trunk/mapping/annotated_planar_patch_map/src/annotation2d_lifter_to_tagged_patch_map_via_service.cpp 2009-08-07 20:49:05 UTC (rev 21044)
+++ pkg/trunk/mapping/annotated_planar_patch_map/src/annotation2d_lifter_to_tagged_patch_map_via_service.cpp 2009-08-07 20:52:44 UTC (rev 21045)
@@ -277,7 +277,7 @@
for(unsigned int iPoly = 0; iPoly<num_3D_poly; iPoly++)
{
//we're checking this one
- robot_msgs::Polygon3D &map_poly=transformed_map_2D.polygons[iPoly].polygon;
+ geometry_msgs::Polygon &map_poly=transformed_map_2D.polygons[iPoly].polygon;
int num_in=0,num_out=0;
for(unsigned int iPt=0;iPt<map_poly.get_points_size();iPt++)
{
@@ -401,7 +401,7 @@
for(unsigned int iPoly = 0; iPoly<num_3D_poly; iPoly++)
{
//we're checking this one
- robot_msgs::Polygon3D &map_poly=transformed_map.polygons[iPoly].polygon;
+ geometry_msgs::Polygon &map_poly=transformed_map.polygons[iPoly].polygon;
for(unsigned int iPt=0;iPt<map_poly.get_points_size();iPt++){
fprintf(fOut,"%f %f %f\n",map_poly.points[iPt].x,
map_poly.points[iPt].y,
Modified: pkg/trunk/mapping/annotated_planar_patch_map/src/projection.cpp
===================================================================
--- pkg/trunk/mapping/annotated_planar_patch_map/src/projection.cpp 2009-08-07 20:49:05 UTC (rev 21044)
+++ pkg/trunk/mapping/annotated_planar_patch_map/src/projection.cpp 2009-08-07 20:52:44 UTC (rev 21045)
@@ -71,7 +71,7 @@
for(unsigned int iPoly = 0; iPoly<num_polygons; iPoly++)
{
//create new polygon 2D (z=1)
- robot_msgs::Polygon3D newPoly;
+ geometry_msgs::Polygon newPoly;
projectPolygonPoints(projection,double(stereo_info.width),double(stereo_info.height),transformed_map_3D.polygons[iPoly],newPoly);
//put the polygon into 2D map
@@ -79,7 +79,7 @@
}
}
-void annotated_planar_patch_map::projection::projectAnyObject(const sensor_msgs::CameraInfo& cam_info,robot_msgs::Polygon3D polyIn,robot_msgs::Polygon3D& polyOut)
+void annotated_planar_patch_map::projection::projectAnyObject(const sensor_msgs::CameraInfo& cam_info,geometry_msgs::Polygon polyIn,geometry_msgs::Polygon& polyOut)
{
//Projection setup
CvMat *K_ = cvCreateMat(3, 3, CV_64FC1);
@@ -194,7 +194,7 @@
-void annotated_planar_patch_map::projection::projectPolygonPoints(double* projection,double img_w,double img_h,robot_msgs::Polygon3D polyIn,robot_msgs::Polygon3D& polyOut)
+void annotated_planar_patch_map::projection::projectPolygonPoints(double* projection,double img_w,double img_h,geometry_msgs::Polygon polyIn,geometry_msgs::Polygon& polyOut)
{
//Project all points of all polygons
unsigned int num_pts = polyIn.get_points_size();
@@ -240,7 +240,7 @@
}
}
-void annotated_planar_patch_map::projection::projectPolygonPointsNOP(double* projection,double img_w,double img_h,robot_msgs::Polygon3D polyIn,robot_msgs::Polygon3D& polyOut)
+void annotated_planar_patch_map::projection::projectPolygonPointsNOP(double* projection,double img_w,double img_h,geometry_msgs::Polygon polyIn,geometry_msgs::Polygon& polyOut)
{
//Project all points of all polygons
unsigned int num_pts = polyIn.get_points_size();
@@ -309,7 +309,7 @@
for(unsigned int iPoly = 0; iPoly<num_polygons; iPoly++)
{
//create new polygon 2D (z=1)
- robot_msgs::Polygon3D newPoly;
+ geometry_msgs::Polygon newPoly;
projectPolygonPoints(projection,double(stereo_info.width),double(stereo_info.height),transformed_map_3D.polygons[iPoly].polygon,newPoly);
//put the polygon into 2D map
@@ -357,7 +357,7 @@
for(unsigned int iPoly = 0; iPoly<num_polygons; iPoly++)
{
//create new polygon 2D (z=1)
- robot_msgs::Polygon3D newPoly;
+ geometry_msgs::Polygon newPoly;
projectPolygonPointsNOP(projection,double(stereo_info.width),double(stereo_info.height),transformed_map_3D.polygons[iPoly].polygon,newPoly);
//put the polygon into 2D map
@@ -386,7 +386,7 @@
for(unsigned int iPoly = 0; iPoly<num_polygons; iPoly++)
{
//create new polygon 2D (z=1)
- robot_msgs::Polygon3D newPoly;
+ geometry_msgs::Polygon newPoly;
projectAnyObject(cam_info,transformed_map_3D.polygons[iPoly].polygon,newPoly);
@@ -410,7 +410,7 @@
-bool annotated_planar_patch_map::projection::checkPolyInside(const robot_msgs::Polygon3D& poly,const std::vector<double>& viewport)
+bool annotated_planar_patch_map::projection::checkPolyInside(const geometry_msgs::Polygon& poly,const std::vector<double>& viewport)
{
unsigned int num_pts = poly.get_points_size();
for(unsigned int iPt = 0; iPt<num_pts; iPt++)
Modified: pkg/trunk/mapping/annotated_planar_patch_map/test/projection_test.cpp
===================================================================
--- pkg/trunk/mapping/annotated_planar_patch_map/test/projection_test.cpp 2009-08-07 20:49:05 UTC (rev 21044)
+++ pkg/trunk/mapping/annotated_planar_patch_map/test/projection_test.cpp 2009-08-07 20:52:44 UTC (rev 21045)
@@ -30,7 +30,7 @@
#include <gtest/gtest.h>
#include <sys/time.h>
-#include "robot_msgs/Polygon3D.h"
+#include "geometry_msgs/Polygon.h"
#include "geometry_msgs/Point32.h"
#include <math.h>
@@ -42,8 +42,8 @@
TEST(annotated_map, projectPolygon)
{
- robot_msgs::Polygon3D input_polygon;
- robot_msgs::Polygon3D projected_polygon;
+ geometry_msgs::Polygon input_polygon;
+ geometry_msgs::Polygon projected_polygon;
sensor_msgs::CameraInfo cam_info;
Modified: pkg/trunk/mapping/door_stereo_detector/src/door_stereo_detector.cpp
===================================================================
--- pkg/trunk/mapping/door_stereo_detector/src/door_stereo_detector.cpp 2009-08-07 20:49:05 UTC (rev 21044)
+++ pkg/trunk/mapping/door_stereo_detector/src/door_stereo_detector.cpp 2009-08-07 20:52:44 UTC (rev 21045)
@@ -45,7 +45,7 @@
#include <ros/node.h>
// ROS messages
#include <sensor_msgs/PointCloud.h>
-#include <robot_msgs/Polygon3D.h>
+#include <geometry_msgs/Polygon.h>
#include <mapping_msgs/PolygonalMap.h>
#include <geometry_msgs/Point32.h>
Modified: pkg/trunk/mapping/door_tracker/src/door_tracker.cpp
===================================================================
--- pkg/trunk/mapping/door_tracker/src/door_tracker.cpp 2009-08-07 20:49:05 UTC (rev 21044)
+++ pkg/trunk/mapping/door_tracker/src/door_tracker.cpp 2009-08-07 20:52:44 UTC (rev 21045)
@@ -47,7 +47,7 @@
#include <door_handle_detector/DoorsDetector.h>
#include <sensor_msgs/PointCloud.h>
-#include <robot_msgs/Polygon3D.h>
+#include <geometry_msgs/Polygon.h>
#include <mapping_msgs/PolygonalMap.h>
#include <geometry_msgs/Point32.h>
Modified: pkg/trunk/mapping/hallway_tracker/src/hallway_tracker.cpp
===================================================================
--- pkg/trunk/mapping/hallway_tracker/src/hallway_tracker.cpp 2009-08-07 20:49:05 UTC (rev 21044)
+++ pkg/trunk/mapping/hallway_tracker/src/hallway_tracker.cpp 2009-08-07 20:52:44 UTC (rev 21045)
@@ -48,7 +48,7 @@
#include <ros/node.h>
// ROS messages
#include <sensor_msgs/PointCloud.h>
-#include <robot_msgs/Polygon3D.h>
+#include <geometry_msgs/Polygon.h>
#include <mapping_msgs/PolygonalMap.h>
#include <geometry_msgs/Point32.h>
Modified: pkg/trunk/mapping/planar_patch_map/src/planar_patch_map.cpp
===================================================================
--- pkg/trunk/mapping/planar_patch_map/src/planar_patch_map.cpp 2009-08-07 20:49:05 UTC (rev 21044)
+++ pkg/trunk/mapping/planar_patch_map/src/planar_patch_map.cpp 2009-08-07 20:52:44 UTC (rev 21045)
@@ -43,7 +43,7 @@
#include <ros/node.h>
// ROS messages
#include <sensor_msgs/PointCloud.h>
-#include <robot_msgs/Polygon3D.h>
+#include <geometry_msgs/Polygon.h>
#include <mapping_msgs/PolygonalMap.h>
// Sample Consensus
Modified: pkg/trunk/mapping/planar_patch_map/src/planar_patch_map_omp.cpp
===================================================================
--- pkg/trunk/mapping/planar_patch_map/src/planar_patch_map_omp.cpp 2009-08-07 20:49:05 UTC (rev 21044)
+++ pkg/trunk/mapping/planar_patch_map/src/planar_patch_map_omp.cpp 2009-08-07 20:52:44 UTC (rev 21045)
@@ -43,7 +43,7 @@
#include <ros/node.h>
// ROS messages
#include <sensor_msgs/PointCloud.h>
-#include <robot_msgs/Polygon3D.h>
+#include <geometry_msgs/Polygon.h>
#include <mapping_msgs/PolygonalMap.h>
// Sample Consensus
Modified: pkg/trunk/mapping/stereo_convex_patch_histogram/src/convex_patch_histogram.cpp
===================================================================
--- pkg/trunk/mapping/stereo_convex_patch_histogram/src/convex_patch_histogram.cpp 2009-08-07 20:49:05 UTC (rev 21044)
+++ pkg/trunk/mapping/stereo_convex_patch_histogram/src/convex_patch_histogram.cpp 2009-08-07 20:52:44 UTC (rev 21045)
@@ -45,7 +45,7 @@
#include <ros/node.h>
// ROS messages
#include <sensor_msgs/PointCloud.h>
-#include <robot_msgs/Polygon3D.h>
+#include <geometry_msgs/Polygon.h>
#include <mapping_msgs/PolygonalMap.h>
// Sample Consensus
Modified: pkg/trunk/mapping/table_object_detector/src/table_object_detector.cpp
===================================================================
--- pkg/trunk/mapping/table_object_detector/src/table_object_detector.cpp 2009-08-07 20:49:05 UTC (rev 21044)
+++ pkg/trunk/mapping/table_object_detector/src/table_object_detector.cpp 2009-08-07 20:52:44 UTC (rev 21045)
@@ -43,7 +43,7 @@
#include <ros/node.h>
// ROS messages
#include <sensor_msgs/PointCloud.h>
-#include <robot_msgs/Polygon3D.h>
+#include <geometry_msgs/Polygon.h>
#include <mapping_msgs/PolygonalMap.h>
// Sample Consensus
Modified: pkg/trunk/nav/people_aware_nav/include/people_aware_nav/move_base_constrained.h
===================================================================
--- pkg/trunk/nav/people_aware_nav/include/people_aware_nav/move_base_constrained.h 2009-08-07 20:49:05 UTC (rev 21044)
+++ pkg/trunk/nav/people_aware_nav/include/people_aware_nav/move_base_constrained.h 2009-08-07 20:52:44 UTC (rev 21045)
@@ -91,7 +91,7 @@
* @brief Make a new global plan
* @param goal The goal to plan to
*/
- void makePlan(const geometry_msgs::PoseStamped& goal, const robot_msgs::Polygon3D& forbidden);
+ void makePlan(const geometry_msgs::PoseStamped& goal, const geometry_msgs::Polygon& forbidden);
/**
* @brief Get the current pose of the robot in the specified frame
@@ -107,7 +107,7 @@
void resetState();
- bool tryPlan(geometry_msgs::PoseStamped goal, const robot_msgs::Polygon3D& forbidden);
+ bool tryPlan(geometry_msgs::PoseStamped goal, const geometry_msgs::Polygon& forbidden);
ros::Node& ros_node_;
tf::TransformListener& tf_;
Modified: pkg/trunk/nav/people_aware_nav/include/people_aware_nav/navfn_constrained.h
===================================================================
--- pkg/trunk/nav/people_aware_nav/include/people_aware_nav/navfn_constrained.h 2009-08-07 20:49:05 UTC (rev 21044)
+++ pkg/trunk/nav/people_aware_nav/include/people_aware_nav/navfn_constrained.h 2009-08-07 20:52:44 UTC (rev 21045)
@@ -55,7 +55,7 @@
virtual void getCostmap (costmap_2d::Costmap2D& cmap);
private:
- robot_msgs::Polygon3D forbidden_;
+ geometry_msgs::Polygon forbidden_;
ros::NodeHandle node_;
ros::ServiceServer service_;
ros::Publisher vis_pub_add_;
Modified: pkg/trunk/nav/people_aware_nav/msg/ConstrainedGoal.msg
===================================================================
--- pkg/trunk/nav/people_aware_nav/msg/ConstrainedGoal.msg 2009-08-07 20:49:05 UTC (rev 21044)
+++ pkg/trunk/nav/people_aware_nav/msg/ConstrainedGoal.msg 2009-08-07 20:52:44 UTC (rev 21045)
@@ -8,4 +8,4 @@
float32 th
# Region where robot can't go
-robot_msgs/Polygon3D forbidden
\ No newline at end of file
+geometry_msgs/Polygon forbidden
\ No newline at end of file
Modified: pkg/trunk/nav/people_aware_nav/src/move_base_constrained.cpp
===================================================================
--- pkg/trunk/nav/people_aware_nav/src/move_base_constrained.cpp 2009-08-07 20:49:05 UTC (rev 21044)
+++ pkg/trunk/nav/people_aware_nav/src/move_base_constrained.cpp 2009-08-07 20:52:44 UTC (rev 21045)
@@ -45,7 +45,7 @@
using geometry_msgs::Point;
using geometry_msgs::Point32;
using geometry_msgs::PoseStamped;
-using robot_msgs::Polygon3D;
+using geometry_msgs::Polygon;
namespace people_aware_nav {
MoveBaseConstrained::MoveBaseConstrained(ros::Node& ros_node, tf::TransformListener& tf) :
Modified: pkg/trunk/nav/people_aware_nav/srv/SetNavConstraint.srv
===================================================================
--- pkg/trunk/nav/people_aware_nav/srv/SetNavConstraint.srv 2009-08-07 20:49:05 UTC (rev 21044)
+++ pkg/trunk/nav/people_aware_nav/srv/SetNavConstraint.srv 2009-08-07 20:52:44 UTC (rev 21045)
@@ -1,2 +1,2 @@
-robot_msgs/Polygon3D forbidden
+geometry_msgs/Polygon forbidden
---
Modified: pkg/trunk/sandbox/planar_objects/src/find_planes.h
===================================================================
--- pkg/trunk/sandbox/planar_objects/src/find_planes.h 2009-08-07 20:49:05 UTC (rev 21044)
+++ pkg/trunk/sandbox/planar_objects/src/find_planes.h 2009-08-07 20:52:44 UTC (rev 21045)
@@ -11,7 +11,7 @@
#include "ros/ros.h"
#include "sensor_msgs/PointCloud.h"
-#include <robot_msgs/Polygon3D.h>
+#include <geometry_msgs/Polygon.h>
#include <visualization_msgs/Marker.h>
#include "opencv/cxcore.h"
Modified: pkg/trunk/sandbox/planar_objects/src/rectangular_fit.h
===================================================================
--- pkg/trunk/sandbox/planar_objects/src/rectangular_fit.h 2009-08-07 20:49:05 UTC (rev 21044)
+++ pkg/trunk/sandbox/planar_objects/src/rectangular_fit.h 2009-08-07 20:52:44 UTC (rev 21045)
@@ -5,7 +5,7 @@
#include <ros/node.h>
// ROS messages
#include <sensor_msgs/PointCloud.h>
-#include <robot_msgs/Polygon3D.h>
+#include <geometry_msgs/Polygon.h>
// Cloud geometry
#include <point_cloud_mapping/geometry/angles.h>
@@ -47,7 +47,7 @@
std::vector<std::vector<int> > &indices, std::vector<std::vector<
double> > &models,int number);
void publishNormals(sensor_msgs::PointCloud points, std::vector<geometry_msgs::Vector3> coeff, float length=0.1);
- void publishPolygon(sensor_msgs::PointCloud pointcloud,robot_msgs::Polygon3D points,int number);
+ void publishPolygon(sensor_msgs::PointCloud pointcloud,geometry_msgs::Polygon points,int number);
protected:
ros::Node& node_;
Modified: pkg/trunk/sandbox/planar_objects/src/vis_utils.cpp
===================================================================
--- pkg/trunk/sandbox/planar_objects/src/vis_utils.cpp 2009-08-07 20:49:05 UTC (rev 21044)
+++ pkg/trunk/sandbox/planar_objects/src/vis_utils.cpp 2009-08-07 20:52:44 UTC (rev 21045)
@@ -121,7 +121,7 @@
}
-void visualizePolygon(const sensor_msgs::PointCloud& cloud,robot_msgs::Polygon3D &polygon, int rgb, int id, ros::Publisher& visualization_pub ) {
+void visualizePolygon(const sensor_msgs::PointCloud& cloud,geometry_msgs::Polygon &polygon, int rgb, int id, ros::Publisher& visualization_pub ) {
visualization_msgs::Marker marker;
marker.header.frame_id = cloud.header.frame_id;
marker.header.stamp = ros::Time((uint64_t)0ULL);
Modified: pkg/trunk/sandbox/planar_objects/src/vis_utils.h
===================================================================
--- pkg/trunk/sandbox/planar_objects/src/vis_utils.h 2009-08-07 20:49:05 UTC (rev 21044)
+++ pkg/trunk/sandbox/planar_objects/src/vis_utils.h 2009-08-07 20:52:44 UTC (rev 21045)
@@ -11,7 +11,7 @@
#include "ros/ros.h"
#include "sensor_msgs/PointCloud.h"
-#include <robot_msgs/Polygon3D.h>
+#include <geometry_msgs/Polygon.h>
#include <visualization_msgs/Marker.h>
// transform library
#include <tf/transform_listener.h>
@@ -36,7 +36,7 @@
sensor_msgs::PointCloud& outside,
ros::Publisher& cloud_planes_pub,ros::Publisher& visualization_pub_,bool convexHull=false);
-void visualizePolygon(const sensor_msgs::PointCloud& cloud, robot_msgs::Polygon3D &polygon, int rgb, int id,
+void visualizePolygon(const sensor_msgs::PointCloud& cloud, geometry_msgs::Polygon &polygon, int rgb, int id,
ros::Publisher& visualization_pub);
void visualizeLines(ros::Publisher& visualization_pub_, std::string frame_id, std::vector<std::pair<btVector3,
Modified: pkg/trunk/stacks/common_msgs/mapping_msgs/msg/PolygonalMap.msg
===================================================================
--- pkg/trunk/stacks/common_msgs/mapping_msgs/msg/PolygonalMap.msg 2009-08-07 20:49:05 UTC (rev 21044)
+++ pkg/trunk/stacks/common_msgs/mapping_msgs/msg/PolygonalMap.msg 2009-08-07 20:52:44 UTC (rev 21045)
@@ -1,3 +1,3 @@
Header header
-robot_msgs/Polygon3D[] polygons
+geometry_msgs/Polygon[] polygons
sensor_msgs/ChannelFloat32[] chan
Modified: pkg/trunk/stacks/semantic_mapping/door_handle_detector/include/door_handle_detector/geometric_helper.h
===================================================================
--- pkg/trunk/stacks/semantic_mapping/door_handle_detector/include/door_handle_detector/geometric_helper.h 2009-08-07 20:49:05 UTC (rev 21044)
+++ pkg/trunk/stacks/semantic_mapping/door_handle_detector/include/door_handle_detector/geometric_helper.h 2009-08-07 20:52:44 UTC (rev 21045)
@@ -40,7 +40,7 @@
#include "ros/node.h" //\todo Switch to node handle API
#include <sensor_msgs/PointCloud.h>
-#include <robot_msgs/Polygon3D.h>
+#include <geometry_msgs/Polygon.h>
#include <geometry_msgs/Point32.h>
#include <geometry_msgs/PointStamped.h>
#include <visualization_msgs/Marker.h>
@@ -191,7 +191,7 @@
void getCloudViewPoint (const std::string cloud_frame, geometry_msgs::PointStamped &viewpoint_cloud, const tf::TransformListener *tf);
-bool checkDoorEdges (const robot_msgs::Polygon3D &poly, const geometry_msgs::Point32 &z_axis, double min_height, double eps_angle,
+bool checkDoorEdges (const geometry_msgs::Polygon &poly, const geometry_msgs::Point32 &z_axis, double min_height, double eps_angle,
double &door_frame1, double &door_frame2);
void selectBestDistributionStatistics (const sensor_msgs::PointCloud &points, const std::vector<int> &indices, int d_idx, std::vector<int> &inliers);
Modified: pkg/trunk/stacks/semantic_mapping/door_handle_detector/include/door_handle_detector/handle_detector.h
===================================================================
--- pkg/trunk/stacks/semantic_mapping/door_handle_detector/include/door_handle_detector/handle_detector.h 2009-08-07 20:49:05 UTC (rev 21044)
+++ pkg/trunk/stacks/semantic_mapping/door_handle_detector/include/door_handle_detector/handle_detector.h 2009-08-07 20:52:44 UTC (rev 21045)
@@ -85,7 +85,7 @@
* distance_from_door_margin_, euclidean_cluster_distance_tolerance_, euclidean_cluster_min_pts_
*/
void refineHandleCandidatesWithDoorOutliers (std::vector<int> &handle_indices, std::vector<int> &outliers,
- const robot_msgs::Polygon3D &polygon,
+ const geometry_msgs::Polygon &polygon,
const std::vector<double> &coeff, const geometry_msgs::Point32 &door_axis,
const door_msgs::Door& door_prior,
sensor_msgs::PointCloud& pointcloud) const;
@@ -106,7 +106,7 @@
* cloud_tr_, viewpoint_cloud_
*/
void getHandleCandidates (const std::vector<int> &indices, const std::vector<double> &coeff,
- const robot_msgs::Polygon3D &polygon, const robot_msgs::Polygon3D &polygon_tr,
+ const geometry_msgs::Polygon &polygon, const geometry_msgs::Polygon &polygon_tr,
Eigen::Matrix4d transformation, std::vector<int> &handle_indices,
sensor_msgs::PointCloud& pointcloud, geometry_msgs::PointStamped& viewpoint_cloud) const;
@@ -126,8 +126,8 @@
* distance_from_door_margin_, euclidean_cluster_distance_tolerance_, euclidean_cluster_min_pts_
*/
void getDoorOutliers (const std::vector<int> &indices, const std::vector<int> &inliers,
- const std::vector<double> &coeff, const robot_msgs::Polygon3D &polygon,
- const robot_msgs::Polygon3D &polygon_tr, Eigen::Matrix4d transformation,
+ const std::vector<double> &coeff, const geometry_msgs::Polygon &polygon,
+ const geometry_msgs::Polygon &polygon_tr, Eigen::Matrix4d transformation,
std::vector<int> &outliers, sensor_msgs::PointCloud& pointcloud) const;
/** \brief Main point cloud callback. */
Modified: pkg/trunk/stacks/semantic_mapping/door_handle_detector/src/geometric_helper.cpp
===================================================================
--- pkg/trunk/stacks/semantic_mapping/door_handle_detector/src/geometric_helper.cpp 2009-08-07 20:49:05 UTC (rev 21044)
+++ pkg/trunk/stacks/semantic_mapping/door_handle_detector/src/geometric_helper.cpp 2009-08-07 20:52:44 UTC (rev 21045)
@@ -110,7 +110,7 @@
//////////////////////////////////////////////////////////////////////////////////////////////////////////////////
bool
- checkDoorEdges (const robot_msgs::Polygon3D &poly, const geometry_msgs::Point32 &z_axis, double min_height, double eps_angle,
+ checkDoorEdges (const geometry_msgs::Polygon &poly, const geometry_msgs::Point32 &z_axis, double min_height, double eps_angle,
double &door_frame1, double &door_frame2)
{
// Compute the centroid of the polygon
Modified: pkg/trunk/stacks/semantic_mapping/door_handle_detector/src/handle_detector.cpp
===================================================================
--- pkg/trunk/stacks/semantic_mapping/door_handle_detector/src/handle_detector.cpp 2009-08-07 20:49:05 UTC (rev 21044)
+++ pkg/trunk/stacks/semantic_mapping/door_handle_detector/src/handle_detector.cpp 2009-08-07 20:52:44 UTC (rev 21045)
@@ -166,7 +166,7 @@
return (false);
}
// Compute the convex hull of the door
- robot_msgs::Polygon3D polygon, polygon_tr;
+ geometry_msgs::Polygon polygon, polygon_tr;
cloud_geometry::areas::convexHull2D (pointcloud, inliers, coeff, polygon);
// Create a polygonal representation on the X-Y plane (makes all isPointIn2DPolygon computations easier)
Modified: pkg/trunk/stacks/semantic_mapping/plug_onbase_detector/include/plug_onbase_detector/plug_onbase_detector.h
===================================================================
--- pkg/trunk/stacks/semantic_mapping/plug_onbase_detector/include/plug_onbase_detector/plug_onbase_detector.h 2009-08-07 20:49:05 UTC (rev 21044)
+++ pkg/trunk/stacks/semantic_mapping/plug_onbase_detector/include/plug_onbase_detector/plug_onbase_detector.h 2009-08-07 20:52:44 UTC (rev 21045)
@@ -45,7 +45,7 @@
#include <ros/node.h>
// ROS messages
#include <sensor_msgs/PointCloud.h>
-#include <robot_msgs/Polygon3D.h>
+#include <geometry_msgs/Polygon.h>
#include <mapping_msgs/PolygonalMap.h>
#include <plugs_msgs/PlugStow.h>
Modified: pkg/trunk/stacks/semantic_mapping/point_cloud_mapping/include/point_cloud_mapping/geometry/angles.h
===================================================================
--- pkg/trunk/stacks/semantic_mapping/point_cloud_mapping/include/point_cloud_mapping/geometry/angles.h 2009-08-07 20:49:05 UTC (rev 21044)
+++ pkg/trunk/stacks/semantic_mapping/point_cloud_mapping/include/point_cloud_mapping/geometry/angles.h 2009-08-07 20:52:44 UTC (rev 21045)
@@ -38,7 +38,7 @@
#include <geometry_msgs/Point32.h>
#include <geometry_msgs/PointStamped.h>
#include <sensor_msgs/PointCloud.h>
-#include <robot_msgs/Polygon3D.h>
+#include <geometry_msgs/Polygon.h>
#include <visualization_msgs/Polyline.h>
#include <point_cloud_mapping/geometry/point.h>
Modified: pkg/trunk/stacks/semantic_mapping/point_cloud_mapping/include/point_cloud_mapping/geometry/areas.h
===================================================================
--- pkg/trunk/stacks/semantic_mapping/point_cloud_mapping/include/point_cloud_mapping/geometry/areas.h 2009-08-07 20:49:05 UTC (rev 21044)
+++ pkg/trunk/stacks/semantic_mapping/point_cloud_mapping/include/point_cloud_mapping/geometry/areas.h 2009-08-07 20:52:44 UTC (rev 21045)
@@ -36,7 +36,7 @@
// ROS includes
#include <geometry_msgs/Point32.h>
#include <sensor_msgs/PointCloud.h>
-#include <robot_msgs/Polygon3D.h>
+#include <geometry_msgs/Polygon.h>
#include <visualization_msgs/Polyline.h>
#include <point_cloud_mapping/geometry/nearest.h>
@@ -77,14 +77,14 @@
else return (false);
}
- bool compute2DPolygonNormal(const robot_msgs::Polygon3D &poly, std::vector<double> &normal);
+ bool compute2DPolygonNormal(const geometry_msgs::Polygon &poly, std::vector<double> &normal);
double compute2DPolygonalArea (const sensor_msgs::PointCloud &points, const std::vector<double> &normal);
- double compute2DPolygonalArea (const robot_msgs::Polygon3D &polygon, const std::vector<double> &normal);
- double compute2DPolygonalArea (const robot_msgs::Polygon3D &polygon);
- void convexHull2D (const sensor_msgs::PointCloud &points, const std::vector<int> &indices, const std::vector<double> &coeff, robot_msgs::Polygon3D &hull);
+ double compute2DPolygonalArea (const geometry_msgs::Polygon &polygon, const std::vector<double> &normal);
+ double compute2DPolygonalArea (const geometry_msgs::Polygon &polygon);
+ void convexHull2D (const sensor_msgs::PointCloud &points, const std::vector<int> &indices, const std::vector<double> &coeff, geometry_msgs::Polygon &hull);
void convexHull2D (const std::vector<geometry_msgs::Point32> &points, visualization_msgs::Polyline &hull);
- bool isPointIn2DPolygon (const geometry_msgs::Point32 &point, const robot_msgs::Polygon3D &polygon);
+ bool isPointIn2DPolygon (const geometry_msgs::Point32 &point, const geometry_msgs::Polygon &polygon);
}
}
Modified: pkg/trunk/stacks/semantic_mapping/point_cloud_mapping/include/point_cloud_mapping/geometry/distances.h
===================================================================
--- pkg/trunk/stacks/semantic_mapping/point_cloud_mapping/include/point_cloud_mapping/geometry/distances.h 2009-08-07 20:49:05 UTC (rev 21044)
+++ pkg/trunk/stacks/semantic_mapping/point_cloud_mapping/include/point_cloud_mapping/geometry/distances.h 2009-08-07 20:52:44 UTC (rev 21045)
@@ -332,7 +332,7 @@
* \param poly the polygon
*/
inline double
- pointToPolygonDistanceSqr (const geometry_msgs::Point32 &p, const robot_msgs::Polygon3D &poly)
+ pointToPolygonDistanceSqr (const geometry_msgs::Point32 &p, const geometry_msgs::Polygon &poly)
{
double min_distance = FLT_MAX;
geometry_msgs::Point32 dir, p_t;
@@ -383,7 +383,7 @@
* \param poly the polygon
*/
inline double
- pointToPolygonDistance (const geometry_msgs::Point32 &p, const robot_msgs::Polygon3D &poly)
+ pointToPolygonDistance (const geometry_msgs::Point32 &p, const geometry_msgs::Polygon &poly)
{
return (sqrt (pointToPolygonDistanceSqr (p, poly)));
}
Modified: pkg/trunk/stacks/semantic_mapping/point_cloud_mapping/include/point_cloud_mapping/geometry/intersections.h
===================================================================
--- pkg/trunk/stacks/semantic_mapping/point_cloud_mapping/include/point_cloud_mapping/geometry/intersections.h 2009-08-07 20:49:05 UTC (rev 21044)
+++ pkg/trunk/stacks/semantic_mapping/point_cloud_mapping/include/point_cloud_mapping/geometry/intersections.h 2009-08-07 20:52:44 UTC (rev 21045)
@@ -35,7 +35,7 @@
// ROS includes
#include <geometry_msgs/Point32.h>
-#include <robot_msgs/Polygon3D.h>
+#include <geometry_msgs/Polygon.h>
namespace cloud_geometry
{
@@ -46,7 +46,7 @@
bool planeWithPlaneIntersection (const std::vector<double> &plane_a, const std::vector<double> &plane_b, std::vector<double> &line);
bool lineWithPlaneIntersection (const std::vector<double> &plane, const std::vector<double> &line, geometry_msgs::Point32 &point);
bool lineWithLineIntersection (const std::vector<double> &line_a, const std::vector<double> &line_b, geometry_msgs::Point32 &point, double sqr_eps);
- bool planeWithCubeIntersection (const std::vector<double> &plane, const std::vector<double> &cube, robot_msgs::Polygon3D &polygon);
+ bool planeWithCubeIntersection (const std::vector<double> &plane, const std::vector<double> &cube, geometry_msgs::Polygon &polygon);
bool lineToBoxIntersection (const std::vector<double> &line, const std::vector<double> &cube);
}
}
Modified: pkg/trunk/stacks/semantic_mapping/point_cloud_mapping/include/point_cloud_mapping/geometry/nearest.h
===================================================================
--- pkg/trunk/stacks/semantic_mapping/point_cloud_mapping/include/point_cloud_mapping/geometry/nearest.h 2009-08-07 20:49:05 UTC (rev 21044)
+++ pkg/trunk/stacks/semantic_mapping/point_cloud_mapping/include/point_cloud_mapping/geometry/nearest.h 2009-08-07 20:52:44 UTC (rev 21045)
@@ -37,7 +37,7 @@
#include <sensor_msgs/PointCloud.h>
#include <geometry_msgs/PointStamped.h>
#include <geometry_msgs/Point32.h>
-#include <robot_msgs/Polygon3D.h>
+#include <geometry_msgs/Polygon.h>
#include <Eigen/Core>
#include <Eigen/QR>
@@ -77,7 +77,7 @@
* \param centroid the output centroid
*/
inline void
- computeCentroid (const robot_msgs::Polygon3D &poly, geometry_msgs::Point32 ¢roid)
+ computeCentroid (const geometry_msgs::Polygon &poly, geometry_msgs::Point32 ¢roid)
{
centroid.x = centroid.y = centroid.z = 0;
// For each point in the cloud
Modified: pkg/trunk/stacks/semantic_mapping/point_cloud_mapping/include/point_cloud_mapping/geometry/point.h
===================================================================
--- pkg/trunk/stacks/semantic_mapping/point_cloud_mapping/include/point_cloud_mapping/geometry/point.h 2009-08-07 20:49:05 UTC (rev 21044)
+++ pkg/trunk/stacks/semantic_mapping/point_cloud_mapping/include/point_cloud_mapping/geometry/point.h 2009-08-07 20:52:44 UTC (rev 21045)
@@ -35,7 +35,7 @@
// ROS includes
#include <sensor_msgs/PointCloud.h>
-#include <robot_msgs/Polygon3D.h>
+#include <geometry_msgs/Polygon.h>
#include <geometry_msgs/Point32.h>
#include <geometry_msgs/Point.h>
#include <geometry_msgs/Vector3.h>
@@ -420,7 +420,7 @@
* \param poly the polygon
*/
inline void
- cerr_poly (const robot_msgs::Polygon3D &poly)
+ cerr_poly (const geometry_msgs::Polygon &poly)
{
for (unsigned int i = 0; i < poly.points.size (); i++)
{
Modified: pkg/trunk/stacks/semantic_mapping/point_cloud_mapping/include/point_cloud_mapping/geometry/projections.h
===================================================================
--- pkg/trunk/stacks/semantic_mapping/point_cloud_mapping/include/point_cloud_mapping/geometry/projections.h 2009-08-07 20:49:05 UTC (rev 21044)
+++ pkg/trunk/stacks/semantic_mapping/point_cloud_mapping/include/point_cloud_mapping/geometry/projections.h 2009-08-07 20:52:44 UTC (rev 21045)
@@ -35,7 +35,7 @@
// ROS includes
#include <geometry_msgs/Point32.h>
-#include <robot_msgs/Polygon3D.h>
+#include <geometry_msgs/Polygon.h>
namespace cloud_geometry
{
@@ -69,7 +69,7 @@
* \param plane_coefficients the normalized coefficients (a, b, c, d) of a plane
*/
inline void
- pointsToPlane (const robot_msgs::Polygon3D &p, robot_msgs::Polygon3D &q, const std::vector<double> &plane_coefficients)
+ pointsToPlane (const geometry_msgs::Polygon &p, geometry_msgs::Polygon &q, const std::vector<double> &plane_coefficients)
{
q.points.resize (p.points.size ());
for (unsigned int i = 0; i < p.points.size (); i++)
Modified: pkg/trunk/stacks/semantic_mapping/point_cloud_mapping/include/point_cloud_mapping/geometry/statistics.h
===================================================================
--- pkg/trunk/stacks/semantic_mapping/point_cloud_mapping/include/point_cloud_mapping/geometry/statistics.h 2009-08-07 20:49:05 UTC (rev 21044)
+++ pkg/trunk/stacks/semantic_mapping/point_cloud_mapping/include/point_cloud_mapping/geometry/statistics.h 2009-08-07 20:52:44 UTC (rev 21045)
@@ -36,7 +36,7 @@
// ROS includes
#include <sensor_msgs/PointCloud.h>
#include <geometry_msgs/Point32.h>
-#include <robot_msgs/Polygon3D.h>
+#include <geometry_msgs/Polygon.h>
#include <cfloat>
namespace cloud_geometry
@@ -52,7 +52,7 @@
* \param max_idx the resultant index of the 'maximum' point
*/
inline void
- getLargestDiagonalIndices (const robot_msgs::Polygon3D &poly, int &min_idx, int &max_idx)
+ getLargestDiagonalIndices (const geometry_msgs::Polygon &poly, int &min_idx, int &max_idx)
{
double largest_diagonal = -FLT_MAX;
for (unsigned int i = 0; i < poly.points.size (); i++)
@@ -137,7 +137,7 @@
* \param maxP the resultant maximum point in the set
*/
inline void
- getLargestDiagonalPoints (const robot_msgs::Polygon3D &poly, geometry_msgs::Point32 &min_p, geometry_msgs::Point32 &max_p)
+ getLargestDiagonalPoints (const geometry_msgs::Polygon &poly, geometry_msgs::Point32 &min_p, geometry_msgs::Point32 &max_p)
{
double largest_diagonal = -FLT_MAX;
for (unsigned int i = 0; i < poly.points.size (); i++)
@@ -230,7 +230,7 @@
* \param maxP the resultant maximum point in the set
*/
inline void
- getLargestXYPoints (const robot_msgs::Polygon3D &poly, geometry_msgs::Point32 &min_p, geometry_msgs::Point32 &max_p)
+ getLargestXYPoints (const geometry_msgs::Polygon &poly, geometry_msgs::Point32 &min_p, geometry_msgs::Point32 &max_p)
{
double largest_xy = -FLT_MAX;
for (unsigned int i = 0; i < poly.points.size (); i++)
@@ -353,7 +353,7 @@
* \param max_p the resultant maximum bounding box coordinates
*/
inline void
- getMinMax (const robot_msgs::Polygon3D &poly, geometry_msgs::Point32 &min_p, geometry_msgs::Point32 &max_p)
+ getMinMax (const geometry_msgs::Polygon &poly, geometry_msgs::Point32 &min_p, geometry_msgs::Point32 &max_p)
{
min_p.x = min_p.y = min_p.z = FLT_MAX;
max_p.x = max_p.y = max_p.z = -FLT_MAX;
Modified: pkg/trunk/stacks/semantic_mapping/point_cloud_mapping/src/cloud_geometry/areas.cpp
===================================================================
--- pkg/trunk/stacks/semantic_mapping/point_cloud_mapping/src/cloud_geometry/areas.cpp 2009-08-07 20:49:05 UTC (rev 21044)
+++ pkg/trunk/stacks/semantic_mapping/point_cloud_mapping/src/cloud_geometry/areas.cpp 2009-08-07 20:52:44 UTC (rev 21045)
@@ -88,7 +88,7 @@
* \param normal the plane normal
*/
double
- compute2DPolygonalArea (const robot_msgs::Polygon3D &polygon, const std::vector<double> &normal)
+ compute2DPolygonalArea (const geometry_msgs::Polygon &polygon, const std::vector<double> &normal)
{
int k0, k1, k2;
@@ -118,7 +118,7 @@
}
- bool compute2DPolygonNormal(const robot_msgs::Polygon3D &poly, std::vector<double> &normal)
+ bool compute2DPolygonNormal(const geometry_msgs::Polygon &poly, std::vector<double> &normal)
{
int k0,k1,k2;
int sz=poly.points.size();
@@ -159,7 +159,7 @@
* \param normal the plane normal
*/
double
- compute2DPolygonalArea (const robot_msgs::Polygon3D &polygon)
+ compute2DPolygonalArea (const geometry_msgs::Polygon &polygon)
{
std::vector<double> normal;
if(!compute2DPolygonNormal(polygon,normal))
@@ -178,7 +178,7 @@
*/
void
convexHull2D (const sensor_msgs::PointCloud &points, const std::vector<int> &indices, const std::vector<double> &coeff,
- robot_msgs::Polygon3D &hull)
+ geometry_msgs::Polygon &hull)
{
// Copy the point data to a local Eigen::Matrix. This is slow and should be replaced by extending geometry_msgs::Point32
// to allow []/() accessors.
@@ -403,7 +403,7 @@
* \param polygon a polygon
*/
bool
- isPointIn2DPolygon (const geometry_msgs::Point32 &point, const robot_msgs::Polygon3D &polygon)
+ isPointIn2DPolygon (const geometry_msgs::Point32 &point, const geometry_msgs::Polygon &polygon)
{
bool in_poly = false;
double x1, x2, y1, y2;
Modified: pkg/trunk/stacks/semantic_mapping/point_cloud_mapping/src/cloud_geometry/intersections.cpp
===================================================================
--- pkg/trunk/stacks/semantic_mapping/point_cloud_mapping/src/cloud_geometry/intersections.cpp 2009-08-07 20:49:05 UTC (rev 21044)
+++ pkg/trunk/stacks/semantic_mapping/point_cloud_mapping/src/cloud_geometry/intersections.cpp 2009-08-07 20:52:44 UTC (rev 21045)
@@ -151,7 +151,7 @@
* \param polygon the resulting polygon
*/
bool
- planeWithCubeIntersection (const std::vector<double> &plane, const std::vector<double> &cube, robot_msgs::Polygon3D &polygon)
+ planeWithCubeIntersection (const std::vector<double> &plane, const std::vector<double> &cube, geometry_msgs::Polygon &polygon)
{
double width[3];
for (int d = 0; d < 3; d++)
Modified: pkg/trunk/stacks/semantic_mapping/point_cloud_mapping/test/cloud_geometry/test_geometry_areas.cpp
===================================================================
--- pkg/trunk/stacks/semantic_mapping/point_cloud_mapping/test/cloud_geometry/test_geometry_areas.cpp 2009-08-07 20:49:05 UTC (rev 21044)
+++ pkg/trunk/stacks/semantic_mapping/point_cloud_mapping/test/cloud_geometry/test_geometry_areas.cpp 2009-08-07 20:52:44 UTC (rev 21045)
@@ -32,7 +32,7 @@
#include <gtest/gtest.h>
#include <geometry_msgs/Point32.h>
-#include <robot_msgs/Polygon3D.h>
+#include <geometry_msgs/Polygon.h>
#include <point_cloud_mapping/geometry/areas.h>
@@ -41,7 +41,7 @@
TEST (Geometry, PolygonAreas)
{
geometry_msgs::Point32 p1, p2, p3, p4;
- robot_msgs::Polygon3D poly;
+ geometry_msgs::Polygon poly;
std::vector<double> normal;
double area;
Modified: pkg/trunk/stacks/semantic_mapping/semantic_point_annotator/src/sac_ground_removal.cpp
===================================================================
--- pkg/trunk/stacks/semantic_mapping/semantic_point_annotator/src/sac_ground_removal.cpp 2009-08-07 20:49:05 UTC (rev 21044)
+++ pkg/trunk/stacks/semantic_mapping/semantic_point_annotator/src/sac_ground_removal.cpp 2009-08-07 20:52:44 UTC (rev 21045)
@@ -43,7 +43,7 @@
#include <ros/node.h>
// ROS messages
#include <sensor_msgs/PointCloud.h>
-#include <robot_msgs/Polygon3D.h>
+#include <geometry_msgs/Polygon.h>
#include <mapping_msgs/PolygonalMap.h>
// Sample Consensus
Modified: pkg/trunk/stacks/semantic_mapping/semantic_point_annotator/src/sac_inc_ground_removal.cpp
===================================================================
--- pkg/trunk/stacks/semantic_mapping/semantic_point_annotator/src/sac_inc_ground_removal.cpp 2009-08-07 20:49:05 UTC (rev 21044)
+++ pkg/trunk/stacks/semantic_mapping/semantic_point_annotator/src/sac_inc_ground_removal.cpp 2009-08-07 20:52:44 UTC (rev 21045)
@@ -43,7 +43,7 @@
#include <ros/node.h>
// ROS messages
#include <sensor_msgs/PointCloud.h>
-#include <robot_msgs/Polygon3D.h>
+#include <geometry_msgs/Polygon.h>
#include <mapping_msgs/PolygonalMap.h>
// Sample Consensus
Modified: pkg/trunk/stacks/semantic_mapping/semantic_point_annotator/src/semantic_point_annotator.cpp
===================================================================
--- pkg/trunk/stacks/semantic_mapping/semantic_point_annotator/src/semantic_point_annotator.cpp 2009-08-07 20:49:05 UTC (rev 21044)
+++ pkg/trunk/stacks/semantic_mapping/semantic_point_annotator/src/semantic_point_annotator.cpp 2009-08-07 20:52:44 UTC (rev 21045)
@@ -44,7 +44,7 @@
#include <ros/node.h>
// ROS messages
#include <sensor_msgs/PointCloud.h>
-#include <robot_msgs/Polygon3D.h>
+#include <geometry_msgs/Polygon.h>
#include <mapping_msgs/PolygonalMap.h>
// Sample Consensus
Modified: pkg/trunk/stacks/semantic_mapping/semantic_point_annotator/src/semantic_point_annotator_omp.cpp
===================================================================
--- pkg/trunk/stacks/semantic_mapping/semantic_point_annotator/src/semantic_point_annotator_omp.cpp 2009-08-07 20:49:05 UTC (rev 21044)
+++ pkg/trunk/stacks/semantic_mapping/semantic_point_annotator/src/semantic_point_annotator_omp.cpp 2009-08-07 20:52:44 UTC (rev 21045)
@@ -43,7 +43,7 @@
#include <ros/node.h>
// ROS messages
#include <sensor_msgs/PointCloud.h>
-#include <robot_msgs/Polygon3D.h>
+#include <geometry_msgs/Polygon.h>
#include <mapping_msgs/PolygonalMap.h>
// Sample Consensus
@@ -250,7 +250,7 @@
//////////////////////////////////////////////////////////////////////////////////////////////////////////////////
void
- sortConcaveHull2D (const sensor_msgs::PointCloud &points, const vector<int> &indices, robot_msgs::Polygon3D &poly)
+ sortConcaveHull2D (const sensor_msgs::PointCloud &points, const vector<int> &indices, geometry_msgs::Polygon &poly)
{
// Create a tree for these points
cloud_kdtree::KdTree* tree = new cloud_kdtree::KdTreeANN (points, indices);
@@ -425,7 +425,7 @@
//////////////////////////////////////////////////////////////////////////////////////////////////////////////////
void
computeConcaveHull (const sensor_msgs::PointCloud &points, const vector<int> &indices, const vector<double> &coeff,
- const vector<vector<int> > &neighbors, robot_msgs::Polygon3D &poly)
+ const vector<vector<int> > &neighbors, geometry_msgs::Polygon &poly)
{
Eigen::Vector3d u, v;
cloud_geometry::getCoordinateSystemOnPlane (coeff, u, v);
Modified: pkg/trunk/stacks/visualization/rviz/src/rviz/displays/polygonal_map_display.h
===================================================================
--- pkg/trunk/stacks/visualization/rviz/src/rviz/displays/polygonal_map_display.h 2009-08-07 20:49:05 UTC (rev 21044)
+++ pkg/trunk/stacks/visualization/rviz/src/rviz/displays/polygonal_map_display.h 2009-08-07 20:52:44 UTC (rev 21045)
@@ -42,7 +42,7 @@
#include <boost/shared_ptr.hpp>
-#include <robot_msgs/Polygon3D.h>
+#include <geometry_msgs/Polygon.h>
#include <mapping_msgs/PolygonalMap.h>
#include <message_filters/subscriber.h>
Modified: pkg/trunk/vision/recognition_lambertian/src/plane_fit.cpp
===================================================================
--- pkg/trunk/vision/recognition_lambertian/src/plane_fit.cpp 2009-08-07 20:49:05 UTC (rev 21044)
+++ pkg/trunk/vision/recognition_lambertian/src/plane_fit.cpp 2009-08-07 20:52:44 UTC (rev 21045)
@@ -30,7 +30,7 @@
#include <ros/node.h>
// ROS messages
#include <sensor_msgs/PointCloud.h>
-#include <robot_msgs/Polygon3D.h>
+#include <geometry_msgs/Polygon.h>
// Cloud kd-tree
#include <point_cloud_mapping/kdtree/kdtree_ann.h>
Modified: pkg/trunk/vision/recognition_lambertian/src/rec_lam_normal_features.cpp
===================================================================
--- pkg/trunk/vision/recognition_lambertian/src/rec_lam_normal_features.cpp 2009-08-07 20:49:05 UTC (rev 21044)
+++ pkg/trunk/vision/recognition_lambertian/src/rec_lam_normal_features.cpp 2009-08-07 20:52:44 UTC (rev 21045)
@@ -60,7 +60,7 @@
#include "geometry_msgs/Point32.h"
#include "geometry_msgs/Vector3.h"
#include "geometry_msgs/PointStamped.h"
-#include <robot_msgs/Polygon3D.h>
+#include <geometry_msgs/Polygon.h>
#include "door_msgs/Door.h"
//#include "robot_msgs/VisualizationMarker.h"
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|