|
From: <jfa...@us...> - 2009-04-30 20:46:19
|
Revision: 14682
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=14682&view=rev
Author: jfaustwg
Date: 2009-04-30 20:46:11 +0000 (Thu, 30 Apr 2009)
Log Message:
-----------
Move VisualizationMarker and Polyline to visualization_msgs
Modified Paths:
--------------
pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/head_pan_tilt_controller.h
pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/head_servoing_controller.h
pkg/trunk/controllers/pr2_mechanism_controllers/manifest.xml
pkg/trunk/controllers/pr2_mechanism_controllers/src/head_pan_tilt_controller.cpp
pkg/trunk/controllers/pr2_mechanism_controllers/src/head_servoing_controller.cpp
pkg/trunk/controllers/robot_mechanism_controllers/include/robot_mechanism_controllers/endeffector_constraint_controller.h
pkg/trunk/controllers/robot_mechanism_controllers/include/robot_mechanism_controllers/plug_controller.h
pkg/trunk/controllers/robot_mechanism_controllers/manifest.xml
pkg/trunk/controllers/robot_mechanism_controllers/src/cartesian_hybrid_controller.cpp
pkg/trunk/controllers/robot_mechanism_controllers/src/endeffector_constraint_controller.cpp
pkg/trunk/demos/plug_in/manifest.xml
pkg/trunk/demos/tabletop_manipulation/manifest.xml
pkg/trunk/demos/tabletop_manipulation/scripts/approachtable.py
pkg/trunk/demos/tabletop_manipulation/scripts/executive.py
pkg/trunk/deprecated/old_costmap_2d/manifest.xml
pkg/trunk/deprecated/old_costmap_2d/src/costmap_2d_ros.cpp
pkg/trunk/deprecated/old_costmap_2d/src/costmap_node.cpp
pkg/trunk/drivers/motor/ethercat_hardware/manifest.xml
pkg/trunk/drivers/motor/ethercat_hardware/src/pressure_node.py
pkg/trunk/drivers/robot/pr2/fingertip_pressure/manifest.xml
pkg/trunk/drivers/robot/pr2/fingertip_pressure/scripts/pressure_visualization_marker.py
pkg/trunk/highlevel/doors/doors_core/manifest.xml
pkg/trunk/highlevel/doors/doors_core/src/move_base_door_action.cpp
pkg/trunk/mapping/collision_map/manifest.xml
pkg/trunk/mapping/collision_map/src/collision_map_buffer.cpp
pkg/trunk/mapping/door_handle_detector/include/door_handle_detector/geometric_helper.h
pkg/trunk/mapping/door_handle_detector/manifest.xml
pkg/trunk/mapping/door_handle_detector/src/doors_detector.cpp
pkg/trunk/mapping/door_handle_detector/src/handle_detector.cpp
pkg/trunk/mapping/door_handle_detector/src/handle_detector_vision.cpp
pkg/trunk/mapping/door_stereo_detector/manifest.xml
pkg/trunk/mapping/door_stereo_detector/src/door_stereo_detector.cpp
pkg/trunk/mapping/door_tracker/manifest.xml
pkg/trunk/mapping/door_tracker/src/door_database.cpp
pkg/trunk/mapping/door_tracker/src/door_tracker.cpp
pkg/trunk/mapping/hallway_tracker/manifest.xml
pkg/trunk/mapping/hallway_tracker/src/hallway_tracker.cpp
pkg/trunk/mapping/point_cloud_mapping/include/point_cloud_mapping/geometry/angles.h
pkg/trunk/mapping/point_cloud_mapping/include/point_cloud_mapping/geometry/areas.h
pkg/trunk/mapping/point_cloud_mapping/manifest.xml
pkg/trunk/mapping/point_cloud_mapping/src/cloud_geometry/areas.cpp
pkg/trunk/motion_planning/navfn/include/navfn/navfn_ros.h
pkg/trunk/motion_planning/navfn/manifest.xml
pkg/trunk/motion_planning/navfn/src/navfn_ros.cpp
pkg/trunk/motion_planning/ompl_planning/manifest.xml
pkg/trunk/motion_planning/ompl_planning/src/display_planner_collision_model.cpp
pkg/trunk/motion_planning/ompl_planning/src/state_validity_monitor.cpp
pkg/trunk/nav/amcl/manifest.xml
pkg/trunk/nav/amcl/src/amcl_node.cpp
pkg/trunk/nav/base_local_planner/manifest.xml
pkg/trunk/nav/base_local_planner/src/trajectory_planner_ros.cpp
pkg/trunk/nav/nav_view/manifest.xml
pkg/trunk/nav/nav_view/src/nav_view/nav_view_panel.cpp
pkg/trunk/nav/nav_view/src/nav_view/nav_view_panel.h
pkg/trunk/nav/people_aware_nav/manifest.xml
pkg/trunk/nav/people_aware_nav/src/is_person_on_path.cpp
pkg/trunk/nav/visual_nav/manifest.xml
pkg/trunk/nav/visual_nav/src/ros_visual_nav.cpp
pkg/trunk/nav/wavefront/manifest.xml
pkg/trunk/nav/wavefront/src/wavefront_node.cpp
pkg/trunk/vision/outlet_detection/manifest.xml
pkg/trunk/vision/outlet_detection/src/outlet_spotting.cpp
pkg/trunk/vision/recognition_lambertian/manifest.xml
pkg/trunk/vision/recognition_lambertian/src/recognition_lambertian.cpp
pkg/trunk/vision/visual_odometry/manifest.xml
pkg/trunk/vision/visual_odometry/nodes/camview_py.py
pkg/trunk/vision/visual_odometry/nodes/corrector.py
pkg/trunk/vision/visual_odometry/nodes/lineperf.py
pkg/trunk/vision/visual_odometry/src/marker.py
pkg/trunk/visualization/rviz/manifest.xml
pkg/trunk/visualization/rviz/src/rviz/displays/marker_display.cpp
pkg/trunk/visualization/rviz/src/rviz/displays/marker_display.h
pkg/trunk/visualization/rviz/src/rviz/displays/poly_line_2d_display.cpp
pkg/trunk/visualization/rviz/src/rviz/displays/poly_line_2d_display.h
pkg/trunk/visualization/rviz/src/test/marker_test.cpp
pkg/trunk/world_models/costmap_2d/include/costmap_2d/costmap_2d_publisher.h
pkg/trunk/world_models/costmap_2d/include/costmap_2d/costmap_2d_ros.h
pkg/trunk/world_models/costmap_2d/manifest.xml
pkg/trunk/world_models/costmap_2d/src/costmap_2d_publisher.cpp
pkg/trunk/world_models/costmap_2d/src/costmap_test.cpp
pkg/trunk/world_models/test_collision_space/manifest.xml
pkg/trunk/world_models/test_collision_space/src/test_cs_point_inclusion.cpp
Added Paths:
-----------
pkg/trunk/visualization_core/visualization_msgs/
pkg/trunk/visualization_core/visualization_msgs/CMakeLists.txt
pkg/trunk/visualization_core/visualization_msgs/Makefile
pkg/trunk/visualization_core/visualization_msgs/mainpage.dox
pkg/trunk/visualization_core/visualization_msgs/manifest.xml
pkg/trunk/visualization_core/visualization_msgs/msg/
pkg/trunk/visualization_core/visualization_msgs/msg/Polyline.msg
pkg/trunk/visualization_core/visualization_msgs/msg/VisualizationMarker.msg
Removed Paths:
-------------
pkg/trunk/common/robot_msgs/msg/Polyline.msg
pkg/trunk/common/robot_msgs/msg/VisualizationMarker.msg
Property Changed:
----------------
pkg/trunk/visualization/
Deleted: pkg/trunk/common/robot_msgs/msg/Polyline.msg
===================================================================
--- pkg/trunk/common/robot_msgs/msg/Polyline.msg 2009-04-30 20:36:55 UTC (rev 14681)
+++ pkg/trunk/common/robot_msgs/msg/Polyline.msg 2009-04-30 20:46:11 UTC (rev 14682)
@@ -1,3 +0,0 @@
-Header header
-Point[] points
-std_msgs/ColorRGBA color
Deleted: pkg/trunk/common/robot_msgs/msg/VisualizationMarker.msg
===================================================================
--- pkg/trunk/common/robot_msgs/msg/VisualizationMarker.msg 2009-04-30 20:36:55 UTC (rev 14681)
+++ pkg/trunk/common/robot_msgs/msg/VisualizationMarker.msg 2009-04-30 20:46:11 UTC (rev 14682)
@@ -1,36 +0,0 @@
-#
-# Visualization Marker message
-# For inserting pre-made objects into the visualization
-#
-
-byte ARROW=0
-byte CUBE=1
-byte SPHERE=2
-byte ROBOT=3
-byte CYLINDER=4
-byte LINE_STRIP=5
-byte LINE_LIST=6
-
-byte ADD=0
-byte MODIFY=0
-byte DELETE=2
-
-Header header # header for time/frame information
-int32 id # object ID useful for manipulating and deleting the object later
-int32 type # Type of object
-int32 action # 0 add/modify an object, 1 (deprecated), 2 deletes an object
-float32 x # x location of the object
-float32 y # y location of the object
-float32 z # z location of the object
-float32 roll # roll of the object
-float32 pitch # pitch of the object
-float32 yaw # yaw of the object
-float32 xScale # scale of the object in the x direction (1 does not change size) (default sizes are usually 1 meter square)
-float32 yScale # scale in y direction
-float32 zScale # scale in z direction
-int32 alpha # alpha (0-255) (amount of transparency, 255 is opaque)
-int32 r # red color value (0-255) (if available)
-int32 g # green color value
-int32 b # blue color value
-#These are only used if the object type is LINE_STRIP or LINE_LIST
-Point[] points
Modified: pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/head_pan_tilt_controller.h
===================================================================
--- pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/head_pan_tilt_controller.h 2009-04-30 20:36:55 UTC (rev 14681)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/head_pan_tilt_controller.h 2009-04-30 20:46:11 UTC (rev 14682)
@@ -49,7 +49,7 @@
#include <robot_msgs/JointCmd.h>
#include <robot_srvs/GetJointCmd.h>
#include <robot_msgs/PointStamped.h>
-#include <robot_msgs/VisualizationMarker.h>
+#include <visualization_msgs/VisualizationMarker.h>
// Math utils
#include <math.h>
Modified: pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/head_servoing_controller.h
===================================================================
--- pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/head_servoing_controller.h 2009-04-30 20:36:55 UTC (rev 14681)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/head_servoing_controller.h 2009-04-30 20:46:11 UTC (rev 14682)
@@ -49,7 +49,7 @@
#include <robot_msgs/JointCmd.h>
#include <robot_srvs/GetJointCmd.h>
#include <robot_msgs/PointStamped.h>
-#include <robot_msgs/VisualizationMarker.h>
+#include <visualization_msgs/VisualizationMarker.h>
// Math utils
#include <math.h>
Modified: pkg/trunk/controllers/pr2_mechanism_controllers/manifest.xml
===================================================================
--- pkg/trunk/controllers/pr2_mechanism_controllers/manifest.xml 2009-04-30 20:36:55 UTC (rev 14681)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/manifest.xml 2009-04-30 20:46:11 UTC (rev 14682)
@@ -17,6 +17,7 @@
<depend package="deprecated_msgs" />
<depend package="pr2_msgs" />
<depend package="robot_msgs" />
+ <depend package="visualization_msgs" />
<depend package="robot_kinematics" />
<depend package="robot_actions" />
<depend package="rosconsole" />
Modified: pkg/trunk/controllers/pr2_mechanism_controllers/src/head_pan_tilt_controller.cpp
===================================================================
--- pkg/trunk/controllers/pr2_mechanism_controllers/src/head_pan_tilt_controller.cpp 2009-04-30 20:36:55 UTC (rev 14681)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/src/head_pan_tilt_controller.cpp 2009-04-30 20:46:11 UTC (rev 14682)
@@ -194,7 +194,7 @@
//services
node_->advertiseService(service_prefix_ + "/get_command_array", &HeadPanTiltControllerNode::getJointCmd, this);
guard_get_command_array_.set(service_prefix_ + "/get_command_array");
- node_->advertise<robot_msgs::VisualizationMarker>( "visualizationMarker", 0 );
+ node_->advertise<visualization_msgs::VisualizationMarker>( "visualizationMarker", 0 );
return true;
}
@@ -340,7 +340,7 @@
c_->setJointCmd(pos,names);
- robot_msgs::VisualizationMarker marker;
+ visualization_msgs::VisualizationMarker marker;
marker.header.frame_id = "stereo";
marker.id = 0;
marker.type = 0;
Modified: pkg/trunk/controllers/pr2_mechanism_controllers/src/head_servoing_controller.cpp
===================================================================
--- pkg/trunk/controllers/pr2_mechanism_controllers/src/head_servoing_controller.cpp 2009-04-30 20:36:55 UTC (rev 14681)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/src/head_servoing_controller.cpp 2009-04-30 20:46:11 UTC (rev 14682)
@@ -219,7 +219,7 @@
//services
node_->advertiseService(service_prefix_ + "/get_command_array", &HeadServoingControllerNode::getJointCmd, this);
guard_get_command_array_.set(service_prefix_ + "/get_command_array");
- node_->advertise<robot_msgs::VisualizationMarker>( "visualizationMarker", 0 );
+ node_->advertise<visualization_msgs::VisualizationMarker>( "visualizationMarker", 0 );
return true;
}
@@ -357,7 +357,7 @@
c_->setJointCmd(pos,names);
- robot_msgs::VisualizationMarker marker;
+ visualization_msgs::VisualizationMarker marker;
marker.header.frame_id = "stereo";
marker.id = 0;
marker.type = 0;
Modified: pkg/trunk/controllers/robot_mechanism_controllers/include/robot_mechanism_controllers/endeffector_constraint_controller.h
===================================================================
--- pkg/trunk/controllers/robot_mechanism_controllers/include/robot_mechanism_controllers/endeffector_constraint_controller.h 2009-04-30 20:36:55 UTC (rev 14681)
+++ pkg/trunk/controllers/robot_mechanism_controllers/include/robot_mechanism_controllers/endeffector_constraint_controller.h 2009-04-30 20:46:11 UTC (rev 14682)
@@ -49,7 +49,7 @@
#include "joy/Joy.h"
#include "Eigen/LU"
#include "Eigen/Core"
-#include <robot_msgs/VisualizationMarker.h>
+#include <visualization_msgs/VisualizationMarker.h>
namespace controller {
Modified: pkg/trunk/controllers/robot_mechanism_controllers/include/robot_mechanism_controllers/plug_controller.h
===================================================================
--- pkg/trunk/controllers/robot_mechanism_controllers/include/robot_mechanism_controllers/plug_controller.h 2009-04-30 20:36:55 UTC (rev 14681)
+++ pkg/trunk/controllers/robot_mechanism_controllers/include/robot_mechanism_controllers/plug_controller.h 2009-04-30 20:46:11 UTC (rev 14682)
@@ -58,7 +58,7 @@
#include "Eigen/LU"
#include "Eigen/Core"
-#include <robot_msgs/VisualizationMarker.h>
+#include <visualization_msgs/VisualizationMarker.h>
namespace controller {
Modified: pkg/trunk/controllers/robot_mechanism_controllers/manifest.xml
===================================================================
--- pkg/trunk/controllers/robot_mechanism_controllers/manifest.xml 2009-04-30 20:36:55 UTC (rev 14681)
+++ pkg/trunk/controllers/robot_mechanism_controllers/manifest.xml 2009-04-30 20:46:11 UTC (rev 14682)
@@ -15,6 +15,7 @@
<depend package="std_msgs" />
<depend package="robot_srvs" />
<depend package="robot_msgs" />
+ <depend package="visualization_msgs" />
<depend package="tf" />
<depend package="tf_conversions" />
<depend package="kdl" />
Modified: pkg/trunk/controllers/robot_mechanism_controllers/src/cartesian_hybrid_controller.cpp
===================================================================
--- pkg/trunk/controllers/robot_mechanism_controllers/src/cartesian_hybrid_controller.cpp 2009-04-30 20:36:55 UTC (rev 14681)
+++ pkg/trunk/controllers/robot_mechanism_controllers/src/cartesian_hybrid_controller.cpp 2009-04-30 20:46:11 UTC (rev 14682)
@@ -40,7 +40,7 @@
#include "tf_conversions/tf_kdl.h"
#include "realtime_tools/realtime_publisher.h"
#include "control_toolbox/pid.h"
-#include "robot_msgs/VisualizationMarker.h"
+#include "visualization_msgs/VisualizationMarker.h"
#include "angles/angles.h"
#include "std_msgs/Float64MultiArray.h"
Modified: pkg/trunk/controllers/robot_mechanism_controllers/src/endeffector_constraint_controller.cpp
===================================================================
--- pkg/trunk/controllers/robot_mechanism_controllers/src/endeffector_constraint_controller.cpp 2009-04-30 20:36:55 UTC (rev 14681)
+++ pkg/trunk/controllers/robot_mechanism_controllers/src/endeffector_constraint_controller.cpp 2009-04-30 20:46:11 UTC (rev 14682)
@@ -361,7 +361,7 @@
node_->subscribe(topic_ + "/command", wrench_msg_,
&EndeffectorConstraintControllerNode::command, this, 1);
guard_command_.set(topic_ + "/command");
- node_->advertise<robot_msgs::VisualizationMarker>( "visualizationMarker", 0 );
+ node_->advertise<visualization_msgs::VisualizationMarker>( "visualizationMarker", 0 );
return true;
@@ -379,10 +379,10 @@
// Debugging code. Not currently realtime safe
- robot_msgs::VisualizationMarker marker;
+ visualization_msgs::VisualizationMarker marker;
marker.header.frame_id = "torso_lift_link";
marker.id = 0;
- marker.type = robot_msgs::VisualizationMarker::CUBE;
+ marker.type = visualization_msgs::VisualizationMarker::CUBE;
marker.action = 0;
marker.x = 0.6;
marker.y = 0;
@@ -399,10 +399,10 @@
marker.b = 0;
node_->publish("visualizationMarker", marker );
- robot_msgs::VisualizationMarker marker;
+ visualization_msgs::VisualizationMarker marker;
marker.header.frame_id = "torso_lift_link";
marker.id = 1;
- marker.type = robot_msgs::VisualizationMarker::SPHERE;
+ marker.type = visualization_msgs::VisualizationMarker::SPHERE;
marker.action = 0;
marker.x = 0.6;
marker.y = 0;
Modified: pkg/trunk/demos/plug_in/manifest.xml
===================================================================
--- pkg/trunk/demos/plug_in/manifest.xml 2009-04-30 20:36:55 UTC (rev 14681)
+++ pkg/trunk/demos/plug_in/manifest.xml 2009-04-30 20:46:11 UTC (rev 14682)
@@ -21,4 +21,6 @@
<depend package="pytf" />
<depend package="tf" />
+
+ <depend package="visualization_msgs" />
</package>
Modified: pkg/trunk/demos/tabletop_manipulation/manifest.xml
===================================================================
--- pkg/trunk/demos/tabletop_manipulation/manifest.xml 2009-04-30 20:36:55 UTC (rev 14681)
+++ pkg/trunk/demos/tabletop_manipulation/manifest.xml 2009-04-30 20:46:11 UTC (rev 14682)
@@ -14,6 +14,7 @@
<depend package="executive_python"/>
<depend package="plan_ompl_path"/>
<depend package="pr2_msgs"/>
+ <depend package="visualization_msgs" />
<depend package="rosviz"/>
<depend package="robot_actions"/>
<depend package="tf"/>
Modified: pkg/trunk/demos/tabletop_manipulation/scripts/approachtable.py
===================================================================
--- pkg/trunk/demos/tabletop_manipulation/scripts/approachtable.py 2009-04-30 20:36:55 UTC (rev 14681)
+++ pkg/trunk/demos/tabletop_manipulation/scripts/approachtable.py 2009-04-30 20:46:11 UTC (rev 14682)
@@ -37,7 +37,8 @@
roslib.load_manifest('tabletop_manipulation')
import rospy
from robot_srvs.srv import FindTable, FindTableRequest
-from robot_msgs.msg import Polygon3D, Point, VisualizationMarker
+from robot_msgs.msg import Polygon3D, Point
+from visualization_msgs.msg import VisualizationMarker
from deprecated_msgs.msg import RobotBase2DOdom
from tf.msg import tfMessage
Modified: pkg/trunk/demos/tabletop_manipulation/scripts/executive.py
===================================================================
--- pkg/trunk/demos/tabletop_manipulation/scripts/executive.py 2009-04-30 20:36:55 UTC (rev 14681)
+++ pkg/trunk/demos/tabletop_manipulation/scripts/executive.py 2009-04-30 20:46:11 UTC (rev 14682)
@@ -125,7 +125,7 @@
import rospy
import random
import sys
-from robot_msgs.msg import VisualizationMarker
+from visualization_msgs.msg import VisualizationMarker
from robot_msgs.msg import AttachedObject, PoseConstraint
from robot_srvs.srv import FindTable, FindTableRequest, SubtractObjectFromCollisionMap, SubtractObjectFromCollisionMapRequest, RecordStaticMapTrigger, RecordStaticMapTriggerRequest
from pr2_mechanism_controllers.srv import SetProfile, SetProfileRequest
Modified: pkg/trunk/deprecated/old_costmap_2d/manifest.xml
===================================================================
--- pkg/trunk/deprecated/old_costmap_2d/manifest.xml 2009-04-30 20:36:55 UTC (rev 14681)
+++ pkg/trunk/deprecated/old_costmap_2d/manifest.xml 2009-04-30 20:46:11 UTC (rev 14682)
@@ -14,6 +14,7 @@
<depend package="robot_filter" />
<depend package="robot_srvs" />
<depend package="angles" />
+<depend package="visualization_msgs"/>
<export>
<cpp cflags="-I${prefix}/include -I${prefix}/msg/cpp `rosboost-cfg --cflags`" lflags="-Wl,-rpath,${prefix}/lib -L${prefix}/lib `rosboost-cfg --lflags thread` -lold_costmap_2d"/>
</export>
Modified: pkg/trunk/deprecated/old_costmap_2d/src/costmap_2d_ros.cpp
===================================================================
--- pkg/trunk/deprecated/old_costmap_2d/src/costmap_2d_ros.cpp 2009-04-30 20:36:55 UTC (rev 14681)
+++ pkg/trunk/deprecated/old_costmap_2d/src/costmap_2d_ros.cpp 2009-04-30 20:46:11 UTC (rev 14682)
@@ -53,7 +53,7 @@
#include <old_costmap_2d/costmap_2d.h>
// For GUI debug
-#include <robot_msgs/Polyline.h>
+#include <visualization_msgs/Polyline.h>
//window length for remembering laser data (seconds)
static const double WINDOW_LENGTH = 1.0;
@@ -90,7 +90,7 @@
//laser scan message
laser_scan::LaserScan laser_msg_;
- robot_msgs::Polyline pointcloud_msg_;
+ visualization_msgs::Polyline pointcloud_msg_;
//projector for the laser
laser_scan::LaserProjection projector_;
Modified: pkg/trunk/deprecated/old_costmap_2d/src/costmap_node.cpp
===================================================================
--- pkg/trunk/deprecated/old_costmap_2d/src/costmap_node.cpp 2009-04-30 20:36:55 UTC (rev 14681)
+++ pkg/trunk/deprecated/old_costmap_2d/src/costmap_node.cpp 2009-04-30 20:46:11 UTC (rev 14682)
@@ -63,8 +63,8 @@
* - @b "obstacle_cloud"/robot_msgs::PointCloud : low obstacles near the ground
* Publishes to (name / type):
- * - @b "raw_obstacles"robot_msgs::Polyline : contains all workspace obstacles in a window around the robot
- * - @b "inflated_obstacles"/robot_msgs::Polyline : contains c-space expansion, up to the inscribed radius of the robot
+ * - @b "raw_obstacles"visualization_msgs::Polyline : contains all workspace obstacles in a window around the robot
+ * - @b "inflated_obstacles"/visualization_msgs::Polyline : contains c-space expansion, up to the inscribed radius of the robot
* <hr>
*
* @section parameters ROS parameters (in addition to base class parameters):
@@ -104,7 +104,7 @@
#include <robot_msgs/PoseDot.h>
#include <robot_msgs/PointCloud.h>
#include <deprecated_msgs/Pose2DFloat32.h>
-#include <robot_msgs/Polyline.h>
+#include <visualization_msgs/Polyline.h>
#include <robot_srvs/StaticMap.h>
#include <robot_msgs/PointStamped.h>
#include <algorithm>
@@ -307,8 +307,8 @@
local_map_accessor_ = new CostMapAccessor(*costMap_, local_access_mapsize_, 0.0, 0.0);
// Advertize messages to publish cost map updates
- ros::Node::instance()->advertise<robot_msgs::Polyline>("raw_obstacles", 1);
- ros::Node::instance()->advertise<robot_msgs::Polyline>("inflated_obstacles", 1);
+ ros::Node::instance()->advertise<visualization_msgs::Polyline>("raw_obstacles", 1);
+ ros::Node::instance()->advertise<visualization_msgs::Polyline>("inflated_obstacles", 1);
// Advertise costmap service
// Might be worth eventually having a dedicated node provide this service and all
@@ -522,7 +522,7 @@
}
// First publish raw obstacles in red
- robot_msgs::Polyline pointCloudMsg;
+ visualization_msgs::Polyline pointCloudMsg;
pointCloudMsg.header.frame_id = global_frame_;
unsigned int pointCount = rawObstacles.size();
pointCloudMsg.set_points_size(pointCount);
@@ -590,7 +590,7 @@
}
// First publish raw obstacles in red
- robot_msgs::Polyline pointCloudMsg;
+ visualization_msgs::Polyline pointCloudMsg;
pointCloudMsg.header.frame_id = global_frame_;
unsigned int pointCount = rawObstacles.size();
pointCloudMsg.set_points_size(pointCount);
Modified: pkg/trunk/drivers/motor/ethercat_hardware/manifest.xml
===================================================================
--- pkg/trunk/drivers/motor/ethercat_hardware/manifest.xml 2009-04-30 20:36:55 UTC (rev 14681)
+++ pkg/trunk/drivers/motor/ethercat_hardware/manifest.xml 2009-04-30 20:46:11 UTC (rev 14682)
@@ -13,6 +13,7 @@
<depend package='roscpp' />
<depend package='realtime_tools' />
<depend package='robot_msgs' />
+<depend package="visualization_msgs" />
<depend package='rospy' />
<export>
<cpp cflags="-I${prefix}/include" lflags="-L${prefix}/lib -lethercat_hardware -Wl,-rpath,${prefix}/lib -lloki"/>
Modified: pkg/trunk/drivers/motor/ethercat_hardware/src/pressure_node.py
===================================================================
--- pkg/trunk/drivers/motor/ethercat_hardware/src/pressure_node.py 2009-04-30 20:36:55 UTC (rev 14681)
+++ pkg/trunk/drivers/motor/ethercat_hardware/src/pressure_node.py 2009-04-30 20:46:11 UTC (rev 14682)
@@ -44,7 +44,7 @@
import rospy
from ethercat_hardware.msg import PressureState
-from robot_msgs.msg import VisualizationMarker
+from visualization_msgs.msg import VisualizationMarker
positions = [ # x, y, z, xscale, yscale, zscale
( 0.026, 0.007, 0.000, 0.010, 0.010, 0.015),
Modified: pkg/trunk/drivers/robot/pr2/fingertip_pressure/manifest.xml
===================================================================
--- pkg/trunk/drivers/robot/pr2/fingertip_pressure/manifest.xml 2009-04-30 20:36:55 UTC (rev 14681)
+++ pkg/trunk/drivers/robot/pr2/fingertip_pressure/manifest.xml 2009-04-30 20:46:11 UTC (rev 14682)
@@ -10,5 +10,6 @@
<depend package='roscpp' />
<depend package='rospy' />
<depend package='robot_msgs' />
+<depend package="visualization_msgs" />
<repository>http://pr.willowgarage.com/repos</repository>
</package>
Modified: pkg/trunk/drivers/robot/pr2/fingertip_pressure/scripts/pressure_visualization_marker.py
===================================================================
--- pkg/trunk/drivers/robot/pr2/fingertip_pressure/scripts/pressure_visualization_marker.py 2009-04-30 20:36:55 UTC (rev 14681)
+++ pkg/trunk/drivers/robot/pr2/fingertip_pressure/scripts/pressure_visualization_marker.py 2009-04-30 20:46:11 UTC (rev 14682)
@@ -44,7 +44,7 @@
import rospy
from ethercat_hardware.msg import PressureState
-from robot_msgs.msg import VisualizationMarker
+from visualization_msgs.msg import VisualizationMarker
positions = [ # x, y, z, xscale, yscale, zscale
( 0.026, 0.007, 0.000, 0.010, 0.010, 0.015),
Modified: pkg/trunk/highlevel/doors/doors_core/manifest.xml
===================================================================
--- pkg/trunk/highlevel/doors/doors_core/manifest.xml 2009-04-30 20:36:55 UTC (rev 14681)
+++ pkg/trunk/highlevel/doors/doors_core/manifest.xml 2009-04-30 20:46:11 UTC (rev 14682)
@@ -21,6 +21,7 @@
<depend package="tf"/>
<depend package="costmap_2d"/>
<depend package="base_local_planner"/>
+ <depend package="visualization_msgs"/>
<export>
<cpp cflags="-I${prefix}/msg/cpp -I${prefix}/srv/cpp -I${prefix}/include" lflags="-Wl,-rpath,${prefix}/lib -L${prefix}/lib -lexecutive_functions"/>
Modified: pkg/trunk/highlevel/doors/doors_core/src/move_base_door_action.cpp
===================================================================
--- pkg/trunk/highlevel/doors/doors_core/src/move_base_door_action.cpp 2009-04-30 20:36:55 UTC (rev 14681)
+++ pkg/trunk/highlevel/doors/doors_core/src/move_base_door_action.cpp 2009-04-30 20:46:11 UTC (rev 14682)
@@ -59,9 +59,9 @@
ros_node_.param("diagnostics_expected_publish_time",diagnostics_expected_publish_time_,0.2);
ros_node_.param("~control_topic_name", control_topic_name_, std::string("/base/trajectory_controller/command"));
//for display purposes
- ros_node_.advertise<robot_msgs::Polyline>("~gui_path", 1);
- ros_node_.advertise<robot_msgs::Polyline>("~local_path", 1);
- ros_node_.advertise<robot_msgs::Polyline>("~robot_footprint", 1);
+ ros_node_.advertise<visualization_msgs::Polyline>("~gui_path", 1);
+ ros_node_.advertise<visualization_msgs::Polyline>("~local_path", 1);
+ ros_node_.advertise<visualization_msgs::Polyline>("~robot_footprint", 1);
ros_node_.advertise<robot_msgs::DiagnosticMessage> ("/diagnostics", 1) ;
//pass on some parameters to the components of the move base node if they are not explicitly overridden
@@ -361,7 +361,7 @@
std::vector<robot_msgs::Point> footprint;
planner_->computeOrientedFootprint(getPose2D(global_pose_), planner_->footprint_, footprint);
- robot_msgs::Polyline footprint_msg;
+ visualization_msgs::Polyline footprint_msg;
footprint_msg.header.frame_id = global_frame_;
footprint_msg.set_points_size(footprint.size());
footprint_msg.color.r = 1.0;
@@ -379,7 +379,7 @@
void MoveBaseDoorAction::publishPath(const std::vector<pr2_robot_actions::Pose2D>& path, std::string topic, double r, double g, double b, double a){
// Extract the plan in world co-ordinates
- robot_msgs::Polyline gui_path_msg;
+ visualization_msgs::Polyline gui_path_msg;
gui_path_msg.header.frame_id = global_frame_;
gui_path_msg.set_points_size(path.size());
for(unsigned int i=0; i < path.size(); i++){
Modified: pkg/trunk/mapping/collision_map/manifest.xml
===================================================================
--- pkg/trunk/mapping/collision_map/manifest.xml 2009-04-30 20:36:55 UTC (rev 14681)
+++ pkg/trunk/mapping/collision_map/manifest.xml 2009-04-30 20:46:11 UTC (rev 14682)
@@ -13,5 +13,6 @@
<depend package="tf" />
<depend package="robot_msgs" />
<depend package="robot_srvs" />
+ <depend package="visualization_msgs" />
<depend package="point_cloud_mapping" />
</package>
Modified: pkg/trunk/mapping/collision_map/src/collision_map_buffer.cpp
===================================================================
--- pkg/trunk/mapping/collision_map/src/collision_map_buffer.cpp 2009-04-30 20:36:55 UTC (rev 14681)
+++ pkg/trunk/mapping/collision_map/src/collision_map_buffer.cpp 2009-04-30 20:46:11 UTC (rev 14682)
@@ -46,7 +46,7 @@
#include <robot_msgs/Point.h>
#include <robot_msgs/PointCloud.h>
#include <robot_msgs/PoseStamped.h>
-#include <robot_msgs/VisualizationMarker.h>
+#include <visualization_msgs/VisualizationMarker.h>
#include <Eigen/Core>
#include <point_cloud_mapping/geometry/point.h>
@@ -66,6 +66,7 @@
using namespace robot_msgs;
using namespace robot_msgs;
using namespace robot_srvs;
+using namespace visualization_msgs;
struct Leaf
{
@@ -187,7 +188,7 @@
subtract_object_ = false;
m_id_ = 0;
- node_.advertise<robot_msgs::VisualizationMarker>("visualizationMarker", 100);
+ node_.advertise<visualization_msgs::VisualizationMarker>("visualizationMarker", 100);
}
//////////////////////////////////////////////////////////////////////////////////////////////////////////////////
Modified: pkg/trunk/mapping/door_handle_detector/include/door_handle_detector/geometric_helper.h
===================================================================
--- pkg/trunk/mapping/door_handle_detector/include/door_handle_detector/geometric_helper.h 2009-04-30 20:36:55 UTC (rev 14681)
+++ pkg/trunk/mapping/door_handle_detector/include/door_handle_detector/geometric_helper.h 2009-04-30 20:46:11 UTC (rev 14682)
@@ -41,7 +41,7 @@
#include <robot_msgs/Polygon3D.h>
#include <robot_msgs/Point32.h>
#include <robot_msgs/PointStamped.h>
-#include <robot_msgs/VisualizationMarker.h>
+#include <visualization_msgs/VisualizationMarker.h>
#include <robot_msgs/Door.h>
#include <tf/transform_listener.h>
@@ -155,14 +155,14 @@
sendMarker (float px, float py, float pz, std::string frame_id, ros::Node *anode, int &id,
int r, int g, int b, double radius = 0.03)
{
- robot_msgs::VisualizationMarker mk;
+ visualization_msgs::VisualizationMarker mk;
mk.header.stamp = ros::Time::now ();
mk.header.frame_id = frame_id;
mk.id = id++;
- mk.type = robot_msgs::VisualizationMarker::SPHERE;
- mk.action = robot_msgs::VisualizationMarker::ADD;
+ mk.type = visualization_msgs::VisualizationMarker::SPHERE;
+ mk.action = visualization_msgs::VisualizationMarker::ADD;
mk.x = px;
mk.y = py;
mk.z = pz;
Modified: pkg/trunk/mapping/door_handle_detector/manifest.xml
===================================================================
--- pkg/trunk/mapping/door_handle_detector/manifest.xml 2009-04-30 20:36:55 UTC (rev 14681)
+++ pkg/trunk/mapping/door_handle_detector/manifest.xml 2009-04-30 20:46:11 UTC (rev 14682)
@@ -24,6 +24,7 @@
<depend package="topic_synchronizer"/>
<depend package="stereo_utils"/>
<depend package="tf"/>
+ <depend package="visualization_msgs" />
<export>
<cpp cflags="-I${prefix}/msg/cpp -I${prefix}/srv/cpp -I${prefix}/include" lflags="-Wl,-rpath,${prefix}/lib -L${prefix}/lib -ldoor_functions"/>
Modified: pkg/trunk/mapping/door_handle_detector/src/doors_detector.cpp
===================================================================
--- pkg/trunk/mapping/door_handle_detector/src/doors_detector.cpp 2009-04-30 20:36:55 UTC (rev 14681)
+++ pkg/trunk/mapping/door_handle_detector/src/doors_detector.cpp 2009-04-30 20:46:11 UTC (rev 14682)
@@ -104,7 +104,7 @@
node_->param ("~input_cloud_topic", input_cloud_topic_, string ("/snapshot_cloud"));
node_->advertiseService ("doors_detector", &DoorDetector::detectDoorSrv, this);
node_->advertiseService ("doors_detector_cloud", &DoorDetector::detectDoorCloudSrv, this);
- node_->advertise<robot_msgs::VisualizationMarker> ("visualizationMarker", 100);
+ node_->advertise<visualization_msgs::VisualizationMarker> ("visualizationMarker", 100);
node_->advertise<PolygonalMap> ("~door_frames", 1);
node_->advertise<PointCloud> ("~door_regions", 1);
Modified: pkg/trunk/mapping/door_handle_detector/src/handle_detector.cpp
===================================================================
--- pkg/trunk/mapping/door_handle_detector/src/handle_detector.cpp 2009-04-30 20:36:55 UTC (rev 14681)
+++ pkg/trunk/mapping/door_handle_detector/src/handle_detector.cpp 2009-04-30 20:46:11 UTC (rev 14682)
@@ -67,7 +67,7 @@
node_->param ("~input_cloud_topic", input_cloud_topic_, string ("/snapshot_cloud"));
node_->advertiseService ("handle_detector", &HandleDetector::detectHandleSrv, this);
node_->advertiseService ("handle_detector_cloud", &HandleDetector::detectHandleCloudSrv, this);
- node_->advertise<robot_msgs::VisualizationMarker> ("visualizationMarker", 100);
+ node_->advertise<visualization_msgs::VisualizationMarker> ("visualizationMarker", 100);
node_->advertise<PolygonalMap> ("~handle_polygon", 1);
node_->advertise<PointCloud> ("~handle_regions", 1);
Modified: pkg/trunk/mapping/door_handle_detector/src/handle_detector_vision.cpp
===================================================================
--- pkg/trunk/mapping/door_handle_detector/src/handle_detector_vision.cpp 2009-04-30 20:36:55 UTC (rev 14681)
+++ pkg/trunk/mapping/door_handle_detector/src/handle_detector_vision.cpp 2009-04-30 20:46:11 UTC (rev 14682)
@@ -57,7 +57,7 @@
#include "robot_msgs/Point32.h"
#include "robot_msgs/PointStamped.h"
#include "robot_msgs/Door.h"
-#include "robot_msgs/VisualizationMarker.h"
+#include "visualization_msgs/VisualizationMarker.h"
#include "door_handle_detector/DoorsDetector.h"
#include "std_srvs/Empty.h"
@@ -189,7 +189,7 @@
// invalid location until we get a detection
// advertise<robot_msgs::PointStamped>("handle_detector/handle_location", 1);
- advertise<robot_msgs::VisualizationMarker>("visualizationMarker", 1);
+ advertise<visualization_msgs::VisualizationMarker>("visualizationMarker", 1);
advertiseService("door_handle_vision_detector", &HandleDetector::detectHandleSrv, this);
advertiseService("door_handle_vision_preempt", &HandleDetector::preempt, this);
}
@@ -384,12 +384,12 @@
*/
void showHandleMarker(robot_msgs::PointStamped p)
{
- robot_msgs::VisualizationMarker marker;
+ visualization_msgs::VisualizationMarker marker;
marker.header.frame_id = p.header.frame_id;
marker.header.stamp = ros::Time((uint64_t)(0ULL));
marker.id = 0;
- marker.type = robot_msgs::VisualizationMarker::SPHERE;
- marker.action = robot_msgs::VisualizationMarker::ADD;
+ marker.type = visualization_msgs::VisualizationMarker::SPHERE;
+ marker.action = visualization_msgs::VisualizationMarker::ADD;
marker.x = p.point.x;
marker.y = p.point.y;
marker.z = p.point.z;
@@ -422,12 +422,12 @@
// }
//
//
-// robot_msgs::VisualizationMarker marker;
+// visualization_msgs::VisualizationMarker marker;
// marker.header.frame_id = pc.header.frame_id;
// marker.header.stamp = pc.header.stamp;
// marker.id = 1211;
-// marker.type = robot_msgs::VisualizationMarker::SPHERE;
-// marker.action = robot_msgs::VisualizationMarker::ADD;
+// marker.type = visualization_msgs::VisualizationMarker::SPHERE;
+// marker.action = visualization_msgs::VisualizationMarker::ADD;
// marker.x = pc.pts[min_i].x;
// marker.y = pc.pts[min_i].y;
// marker.z = pc.pts[min_i].z;
Modified: pkg/trunk/mapping/door_stereo_detector/manifest.xml
===================================================================
--- pkg/trunk/mapping/door_stereo_detector/manifest.xml 2009-04-30 20:36:55 UTC (rev 14681)
+++ pkg/trunk/mapping/door_stereo_detector/manifest.xml 2009-04-30 20:46:11 UTC (rev 14682)
@@ -18,5 +18,6 @@
<depend package="opencv_latest" />
<depend package="image_msgs" />
<depend package="topic_synchronizer" />
+ <depend package="visualization_msgs" />
</package>
Modified: pkg/trunk/mapping/door_stereo_detector/src/door_stereo_detector.cpp
===================================================================
--- pkg/trunk/mapping/door_stereo_detector/src/door_stereo_detector.cpp 2009-04-30 20:36:55 UTC (rev 14681)
+++ pkg/trunk/mapping/door_stereo_detector/src/door_stereo_detector.cpp 2009-04-30 20:46:11 UTC (rev 14682)
@@ -50,7 +50,7 @@
#include <robot_msgs/Point32.h>
#include <robot_msgs/Door.h>
-#include <robot_msgs/VisualizationMarker.h>
+#include <visualization_msgs/VisualizationMarker.h>
#include "opencv_latest/CvBridge.h"
@@ -177,7 +177,7 @@
cvNamedWindow("disparity", CV_WINDOW_AUTOSIZE);
}
- advertise<robot_msgs::VisualizationMarker>( "visualizationMarker", 0 );
+ advertise<visualization_msgs::VisualizationMarker>( "visualizationMarker", 0 );
advertise<robot_msgs::PointCloud>( "filtered_cloud", 0 );
subscribeStereoData();
@@ -259,12 +259,12 @@
//Publish all the lines as visualization markers
for(unsigned int i=0; i < inliers.size(); i++)
{
- robot_msgs::VisualizationMarker marker;
+ visualization_msgs::VisualizationMarker marker;
marker.header.frame_id = cloud.header.frame_id;
marker.header.stamp = ros::Time((uint64_t)0ULL);
marker.id = i;
- marker.type = robot_msgs::VisualizationMarker::LINE_STRIP;
- marker.action = robot_msgs::VisualizationMarker::ADD;
+ marker.type = visualization_msgs::VisualizationMarker::LINE_STRIP;
+ marker.action = visualization_msgs::VisualizationMarker::ADD;
marker.x = 0.0;
marker.y = 0.0;
marker.z = 0.0;
Modified: pkg/trunk/mapping/door_tracker/manifest.xml
===================================================================
--- pkg/trunk/mapping/door_tracker/manifest.xml 2009-04-30 20:36:55 UTC (rev 14681)
+++ pkg/trunk/mapping/door_tracker/manifest.xml 2009-04-30 20:46:11 UTC (rev 14682)
@@ -17,5 +17,6 @@
<depend package="std_msgs" />
<depend package="door_handle_detector" />
<depend package="filters" />
+ <depend package="visualization_msgs" />
</package>
Modified: pkg/trunk/mapping/door_tracker/src/door_database.cpp
===================================================================
--- pkg/trunk/mapping/door_tracker/src/door_database.cpp 2009-04-30 20:36:55 UTC (rev 14681)
+++ pkg/trunk/mapping/door_tracker/src/door_database.cpp 2009-04-30 20:46:11 UTC (rev 14682)
@@ -47,7 +47,7 @@
#include <robot_msgs/Point32.h>
#include <robot_msgs/Door.h>
-#include <robot_msgs/VisualizationMarker.h>
+#include <visualization_msgs/VisualizationMarker.h>
#include <tf/transform_listener.h>
#include <tf/message_notifier.h>
@@ -105,7 +105,7 @@
node_->param<double>("~p_angle_difference_threshold",angle_difference_threshold_,M_PI/12.0);
node_->param<double>("~p_door_point_distance_threshold",door_point_distance_threshold_,0.25);
- node_->advertise<robot_msgs::VisualizationMarker>( "visualizationMarker", 0 );
+ node_->advertise<visualization_msgs::VisualizationMarker>( "visualizationMarker", 0 );
double tmp; int tmp2;
@@ -300,12 +300,12 @@
void publishPoint(const Point32 &point, const int &id, const std::string &frame_id)
{
- robot_msgs::VisualizationMarker marker;
+ visualization_msgs::VisualizationMarker marker;
marker.header.frame_id = frame_id;
marker.header.stamp = ros::Time();
marker.id = id;
- marker.type = robot_msgs::VisualizationMarker::SPHERE;
- marker.action = robot_msgs::VisualizationMarker::ADD;
+ marker.type = visualization_msgs::VisualizationMarker::SPHERE;
+ marker.action = visualization_msgs::VisualizationMarker::ADD;
marker.x = point.x;
marker.y = point.y;
marker.z = point.z;
Modified: pkg/trunk/mapping/door_tracker/src/door_tracker.cpp
===================================================================
--- pkg/trunk/mapping/door_tracker/src/door_tracker.cpp 2009-04-30 20:36:55 UTC (rev 14681)
+++ pkg/trunk/mapping/door_tracker/src/door_tracker.cpp 2009-04-30 20:46:11 UTC (rev 14682)
@@ -52,7 +52,7 @@
#include <robot_msgs/Point32.h>
#include <robot_msgs/Door.h>
-#include <robot_msgs/VisualizationMarker.h>
+#include <visualization_msgs/VisualizationMarker.h>
#include <std_msgs/String.h>
@@ -348,7 +348,7 @@
node_->param("~publish_all_candidates" , publish_all_candidates_, false);
// node_->subscribe(door_msg_topic_,door_msg_in_, &DoorTracker::doorMsgCallBack,this,1);
- node_->advertise<robot_msgs::VisualizationMarker>( "visualizationMarker", 0 );
+ node_->advertise<visualization_msgs::VisualizationMarker>( "visualizationMarker", 0 );
node_->advertise<robot_msgs::Door>( "~door_message", 0 );
node_->advertiseService ("~doors_detector", &DoorTracker::detectDoorService, this);
@@ -457,12 +457,12 @@
void publishLine(const Point32 &min_p, const Point32 &max_p, const int &id, const std::string &frame_id)
{
- robot_msgs::VisualizationMarker marker;
+ visualization_msgs::VisualizationMarker marker;
marker.header.frame_id = frame_id;
marker.header.stamp = ros::Time();
marker.id = id;
- marker.type = robot_msgs::VisualizationMarker::LINE_STRIP;
- marker.action = robot_msgs::VisualizationMarker::ADD;
+ marker.type = visualization_msgs::VisualizationMarker::LINE_STRIP;
+ marker.action = visualization_msgs::VisualizationMarker::ADD;
marker.x = 0.0;
marker.y = 0.0;
marker.z = 0.0;
Modified: pkg/trunk/mapping/hallway_tracker/manifest.xml
===================================================================
--- pkg/trunk/mapping/hallway_tracker/manifest.xml 2009-04-30 20:36:55 UTC (rev 14681)
+++ pkg/trunk/mapping/hallway_tracker/manifest.xml 2009-04-30 20:46:11 UTC (rev 14682)
@@ -16,4 +16,5 @@
<depend package="std_msgs" />
<depend package="laser_scan" />
<depend package="filters" />
+ <depend package="visualization_msgs" />
</package>
Modified: pkg/trunk/mapping/hallway_tracker/src/hallway_tracker.cpp
===================================================================
--- pkg/trunk/mapping/hallway_tracker/src/hallway_tracker.cpp 2009-04-30 20:36:55 UTC (rev 14681)
+++ pkg/trunk/mapping/hallway_tracker/src/hallway_tracker.cpp 2009-04-30 20:46:11 UTC (rev 14682)
@@ -53,7 +53,7 @@
#include <robot_msgs/Point32.h>
//#include <robot_msgs/Hallway.h>
-#include <robot_msgs/VisualizationMarker.h>
+#include <visualization_msgs/VisualizationMarker.h>
// Sample Consensus
#include <point_cloud_mapping/sample_consensus/sac.h>
@@ -147,7 +147,7 @@
// Visualization:
// The visualization markers are the two lines. The start/end points are arbitrary.
- node_->advertise<robot_msgs::VisualizationMarker>( "visualizationMarker", 0 );
+ node_->advertise<visualization_msgs::VisualizationMarker>( "visualizationMarker", 0 );
// A point cloud of model inliers.
node_->advertise<robot_msgs::PointCloud>("parallel_lines_inliers",10);
@@ -270,12 +270,12 @@
*/
void visualization(std::vector<double> coeffs, std::vector<int> inliers) {
// First line:
- robot_msgs::VisualizationMarker marker;
+ visualization_msgs::VisualizationMarker marker;
marker.header.frame_id = fixed_frame_;
marker.header.stamp = cloud_.header.stamp;
marker.id = 0;
- marker.type = robot_msgs::VisualizationMarker::LINE_STRIP;
- marker.action = robot_msgs::VisualizationMarker::ADD;
+ marker.type = visualization_msgs::VisualizationMarker::LINE_STRIP;
+ marker.action = visualization_msgs::VisualizationMarker::ADD;
marker.x = 0.0;
marker.y = 0.0;
marker.z = 0.0;
Modified: pkg/trunk/mapping/point_cloud_mapping/include/point_cloud_mapping/geometry/angles.h
===================================================================
--- pkg/trunk/mapping/point_cloud_mapping/include/point_cloud_mapping/geometry/angles.h 2009-04-30 20:36:55 UTC (rev 14681)
+++ pkg/trunk/mapping/point_cloud_mapping/include/point_cloud_mapping/geometry/angles.h 2009-04-30 20:46:11 UTC (rev 14682)
@@ -39,7 +39,7 @@
#include <robot_msgs/PointStamped.h>
#include <robot_msgs/PointCloud.h>
#include <robot_msgs/Polygon3D.h>
-#include <robot_msgs/Polyline.h>
+#include <visualization_msgs/Polyline.h>
#include <point_cloud_mapping/geometry/point.h>
#include <point_cloud_mapping/geometry/nearest.h>
Modified: pkg/trunk/mapping/point_cloud_mapping/include/point_cloud_mapping/geometry/areas.h
===================================================================
--- pkg/trunk/mapping/point_cloud_mapping/include/point_cloud_mapping/geometry/areas.h 2009-04-30 20:36:55 UTC (rev 14681)
+++ pkg/trunk/mapping/point_cloud_mapping/include/point_cloud_mapping/geometry/areas.h 2009-04-30 20:46:11 UTC (rev 14682)
@@ -37,7 +37,7 @@
#include <robot_msgs/Point32.h>
#include <robot_msgs/PointCloud.h>
#include <robot_msgs/Polygon3D.h>
-#include <robot_msgs/Polyline.h>
+#include <visualization_msgs/Polyline.h>
#include <point_cloud_mapping/geometry/nearest.h>
@@ -80,7 +80,7 @@
double compute2DPolygonalArea (const robot_msgs::PointCloud &points, const std::vector<double> &normal);
double compute2DPolygonalArea (const robot_msgs::Polygon3D &polygon, const std::vector<double> &normal);
void convexHull2D (const robot_msgs::PointCloud &points, const std::vector<int> &indices, const std::vector<double> &coeff, robot_msgs::Polygon3D &hull);
- void convexHull2D (const std::vector<robot_msgs::Point32> &points, robot_msgs::Polyline &hull);
+ void convexHull2D (const std::vector<robot_msgs::Point32> &points, visualization_msgs::Polyline &hull);
bool isPointIn2DPolygon (const robot_msgs::Point32 &point, const robot_msgs::Polygon3D &polygon);
}
Modified: pkg/trunk/mapping/point_cloud_mapping/manifest.xml
===================================================================
--- pkg/trunk/mapping/point_cloud_mapping/manifest.xml 2009-04-30 20:36:55 UTC (rev 14681)
+++ pkg/trunk/mapping/point_cloud_mapping/manifest.xml 2009-04-30 20:46:11 UTC (rev 14682)
@@ -36,6 +36,7 @@
<depend package="roscpp" />
<depend package="robot_msgs" />
+ <depend package="visualization_msgs" />
<depend package="angles" />
<depend package="eigen" />
<depend package="cminpack" />
Modified: pkg/trunk/mapping/point_cloud_mapping/src/cloud_geometry/areas.cpp
===================================================================
--- pkg/trunk/mapping/point_cloud_mapping/src/cloud_geometry/areas.cpp 2009-04-30 20:36:55 UTC (rev 14681)
+++ pkg/trunk/mapping/point_cloud_mapping/src/cloud_geometry/areas.cpp 2009-04-30 20:46:11 UTC (rev 14682)
@@ -165,7 +165,7 @@
std::sort (epoints_demean.begin (), epoints_demean.end (), comparePoint2D);
- robot_msgs::Polyline hull_2d;
+ visualization_msgs::Polyline hull_2d;
convexHull2D (epoints_demean, hull_2d);
int nr_points_hull = hull_2d.points.size ();
@@ -214,7 +214,7 @@
* \param hull the resultant 2D convex hull model as a \a Polyline
*/
void
- convexHull2D (const std::vector<robot_msgs::Point32> &points, robot_msgs::Polyline &hull)
+ convexHull2D (const std::vector<robot_msgs::Point32> &points, visualization_msgs::Polyline &hull)
{
int nr_points = points.size ();
hull.points.resize (nr_points + 1);
Modified: pkg/trunk/motion_planning/navfn/include/navfn/navfn_ros.h
===================================================================
--- pkg/trunk/motion_planning/navfn/include/navfn/navfn_ros.h 2009-04-30 20:36:55 UTC (rev 14681)
+++ pkg/trunk/motion_planning/navfn/include/navfn/navfn_ros.h 2009-04-30 20:46:11 UTC (rev 14682)
@@ -42,7 +42,7 @@
#include <costmap_2d/costmap_2d.h>
#include <robot_msgs/PoseStamped.h>
#include <robot_msgs/Point.h>
-#include <robot_msgs/Polyline.h>
+#include <visualization_msgs/Polyline.h>
#include <tf/transform_listener.h>
#include <vector>
#include <robot_msgs/Point.h>
Modified: pkg/trunk/motion_planning/navfn/manifest.xml
===================================================================
--- pkg/trunk/motion_planning/navfn/manifest.xml 2009-04-30 20:36:55 UTC (rev 14681)
+++ pkg/trunk/motion_planning/navfn/manifest.xml 2009-04-30 20:46:11 UTC (rev 14682)
@@ -10,6 +10,7 @@
<depend package="robot_msgs"/>
<depend package="costmap_2d"/>
<depend package="tf"/>
+ <depend package="visualization_msgs"/>
<sysdepend os="ubuntu" version="7.04-feisty" package="libfltk1.1-dev"/> <!-- actually optional -->
<sysdepend os="ubuntu" version="7.04-feisty" package="libnetpbm10-dev"/>
<sysdepend os="ubuntu" version="8.04-hardy" package="libfltk1.1-dev"/> <!-- actually optional -->
Modified: pkg/trunk/motion_planning/navfn/src/navfn_ros.cpp
===================================================================
--- pkg/trunk/motion_planning/navfn/src/navfn_ros.cpp 2009-04-30 20:36:55 UTC (rev 14681)
+++ pkg/trunk/motion_planning/navfn/src/navfn_ros.cpp 2009-04-30 20:46:11 UTC (rev 14682)
@@ -40,7 +40,7 @@
NavfnROS::NavfnROS(ros::Node& ros_node, tf::TransformListener& tf, costmap_2d::Costmap2D& costmap) : ros_node_(ros_node), tf_(tf),
costmap_(costmap), planner_(costmap.cellSizeX(), costmap.cellSizeY()) {
//advertise our plan visualization
- ros_node_.advertise<robot_msgs::Polyline>("~navfn/plan", 1);
+ ros_node_.advertise<visualization_msgs::Polyline>("~navfn/plan", 1);
//read parameters for the planner
ros_node_.param("~/navfn/costmap/global_frame", global_frame_, std::string("map"));
@@ -204,7 +204,7 @@
return;
// Extract the plan in world co-ordinates, we assume the path is all in the same frame
- robot_msgs::Polyline gui_path_msg;
+ visualization_msgs::Polyline gui_path_msg;
gui_path_msg.header.frame_id = path[0].header.frame_id;
gui_path_msg.header.stamp = path[0].header.stamp;
gui_path_msg.set_points_size(path.size());
Modified: pkg/trunk/motion_planning/ompl_planning/manifest.xml
===================================================================
--- pkg/trunk/motion_planning/ompl_planning/manifest.xml 2009-04-30 20:36:55 UTC (rev 14681)
+++ pkg/trunk/motion_planning/ompl_planning/manifest.xml 2009-04-30 20:46:11 UTC (rev 14682)
@@ -13,6 +13,7 @@
<depend package="std_srvs" />
<depend package="robot_msgs" />
<depend package="robot_srvs" />
+ <depend package="visualization_msgs" />
<depend package="wg_robot_description_parser"/>
<depend package="planning_models"/>
Modified: pkg/trunk/motion_planning/ompl_planning/src/display_planner_collision_model.cpp
===================================================================
--- pkg/trunk/motion_planning/ompl_planning/src/display_planner_collision_model.cpp 2009-04-30 20:36:55 UTC (rev 14681)
+++ pkg/trunk/motion_planning/ompl_planning/src/display_planner_collision_model.cpp 2009-04-30 20:46:11 UTC (rev 14682)
@@ -85,7 +85,7 @@
#include "kinematic_planning/CollisionSpaceMonitor.h"
#include <std_msgs/Byte.h>
-#include <robot_msgs/VisualizationMarker.h>
+#include <visualization_msgs/VisualizationMarker.h>
#include <iostream>
#include <sstream>
@@ -101,7 +101,7 @@
{
id_ = 0;
- m_node->advertise<robot_msgs::VisualizationMarker>("visualizationMarker", 10240);
+ m_node->advertise<visualization_msgs::VisualizationMarker>("visualizationMarker", 10240);
m_node->advertise<robot_msgs::AttachedObject>("attach_object", 1);
}
@@ -151,12 +151,12 @@
void sendPoint(double x, double y, double z, double radius, const roslib::Header &header, int color)
{
- robot_msgs::VisualizationMarker mk;
+ visualization_msgs::VisualizationMarker mk;
mk.header = header;
mk.id = id_++;
- mk.type = robot_msgs::VisualizationMarker::SPHERE;
- mk.action = robot_msgs::VisualizationMarker::ADD;
+ mk.type = visualization_msgs::VisualizationMarker::SPHERE;
+ mk.action = visualization_msgs::VisualizationMarker::ADD;
mk.x = x;
mk.y = y;
mk.z = z;
Modified: pkg/trunk/motion_planning/ompl_planning/src/state_validity_monitor.cpp
===================================================================
--- pkg/trunk/motion_planning/ompl_planning/src/state_validity_monitor.cpp 2009-04-30 20:36:55 UTC (rev 14681)
+++ pkg/trunk/motion_planning/ompl_planning/src/state_validity_monitor.cpp 2009-04-30 20:46:11 UTC (rev 14682)
@@ -86,7 +86,7 @@
#include "kinematic_planning/CollisionSpaceMonitor.h"
#include <std_msgs/Byte.h>
-#include <robot_msgs/VisualizationMarker.h>
+#include <visualization_msgs/VisualizationMarker.h>
#include <iostream>
#include <sstream>
Modified: pkg/trunk/nav/amcl/manifest.xml
===================================================================
--- pkg/trunk/nav/amcl/manifest.xml 2009-04-30 20:36:55 UTC (rev 14681)
+++ pkg/trunk/nav/amcl/manifest.xml 2009-04-30 20:46:11 UTC (rev 14682)
@@ -11,6 +11,7 @@
<depend package="robot_msgs" />
<depend package="std_srvs" />
<depend package="laser_scan" />
+ <depend package="visualization_msgs"/>
<!-- For tests -->
<depend package="map_server"/>
Modified: pkg/trunk/nav/amcl/src/amcl_node.cpp
===================================================================
--- pkg/trunk/nav/amcl/src/amcl_node.cpp 2009-04-30 20:36:55 UTC (rev 14681)
+++ pkg/trunk/nav/amcl/src/amcl_node.cpp 2009-04-30 20:46:11 UTC (rev 14682)
@@ -68,7 +68,7 @@
- @b "amcl_pose" robot_msgs/PoseWithCovariance : robot's estimated pose in the map, with covariance
- @b "particlecloud" robot_msgs/ParticleCloud : the set of pose estimates being maintained by the filter.
- @b "tf_message" tf/tfMessage : publishes the transform from "odom" (which can be remapped via the ~odom_frame_id parameter) to "map"
-- @b "gui_laser" robot_msgs/Polyline : re-projected laser scans (for visualization)
+- @b "gui_laser" visualization_msgs/Polyline : re-projected laser scans (for visualization)
Offers services (name type):
- @b "global_localization" std_srvs/Empty : Initiate global localization, wherein all particles are dispersed randomly through the free space in the map.
@@ -145,7 +145,7 @@
#include "robot_msgs/Pose.h"
#include "robot_srvs/StaticMap.h"
#include "std_srvs/Empty.h"
-#include "robot_msgs/Polyline.h"
+#include "visualization_msgs/Polyline.h"
// For transform support
#include "tf/transform_broadcaster.h"
@@ -189,7 +189,7 @@
// incoming messages
robot_msgs::PoseWithCovariance initial_pose_;
-
+
// Message callbacks
bool globalLocalizationCallback(std_srvs::Empty::Request& req,
std_srvs::Empty::Response& res);
@@ -235,10 +235,10 @@
map_t* requestMap();
// Helper to get odometric pose from transform system
- bool getOdomPose(double& x, double& y, double& yaw,
+ bool getOdomPose(double& x, double& y, double& yaw,
const ros::Time& t, const std::string& f);
- //time for tolerance on the published transform,
+ //time for tolerance on the published transform,
//basically defines how long a map->odom transform is good for
ros::Duration transform_tolerance_;
};
@@ -297,7 +297,7 @@
ros::Node::instance()->param("~laser_sigma_hit", sigma_hit, 0.2);
ros::Node::instance()->param("~laser_lambda_short", lambda_short, 0.1);
double laser_likelihood_max_dist;
- ros::Node::instance()->param("~laser_likelihood_max_dist",
+ ros::Node::instance()->param("~laser_likelihood_max_dist",
laser_likelihood_max_dist, 2.0);
std::string tmp_model_type;
laser_model_t laser_model_type;
@@ -336,11 +336,11 @@
tf_ = new tf::TransformListener(*ros::Node::instance());
map_ = requestMap();
-
+
// Create the particle filter
pf_ = pf_alloc(min_particles, max_particles,
alpha_slow, alpha_fast,
- (pf_init_model_fn_t)AmclNode::uniformPoseGenerator,
+ (pf_init_model_fn_t)AmclNode::uniformPoseGenerator,
(void *)map_);
pf_->pop_err = pf_err;
pf_->pop_z = pf_z;
@@ -365,23 +365,23 @@
laser_ = new AMCLLaser(max_beams, map_);
ROS_ASSERT(laser_);
if(laser_model_type == LASER_MODEL_BEAM)
- laser_->SetModelBeam(z_hit, z_short, z_max, z_rand,
+ laser_->SetModelBeam(z_hit, z_short, z_max, z_rand,
sigma_hit, lambda_short, 0.0);
else
- laser_->SetModelLikelihoodField(z_hit, z_rand, sigma_hit,
+ laser_->SetModelLikelihoodField(z_hit, z_rand, sigma_hit,
laser_likelihood_max_dist);
ros::Node::instance()->advertise<robot_msgs::PoseWithCovariance>("amcl_pose",2);
ros::Node::instance()->advertise<robot_msgs::ParticleCloud>("particlecloud",2);
- ros::Node::instance()->advertise<robot_msgs::Polyline>("gui_laser",2);
+ ros::Node::instance()->advertise<visualization_msgs::Polyline>("gui_laser",2);
ros::Node::instance()->advertiseService("global_localization",
&AmclNode::globalLocalizationCallback,
this);
- laser_scan_notifer =
+ laser_scan_notifer =
new tf::MessageNotifier<laser_scan::LaserScan>
- (tf_, ros::Node::instance(),
- boost::bind(&AmclNode::laserReceived,
- this, _1),
+ (tf_, ros::Node::instance(),
+ boost::bind(&AmclNode::laserReceived,
+ this, _1),
"scan", odom_frame_id_,
100);
ros::Node::instance()->subscribe("initialpose", initial_pose_, &AmclNode::initialPoseReceived,this,2);
@@ -441,11 +441,11 @@
}
bool
-AmclNode::getOdomPose(double& x, double& y, double& yaw,
+AmclNode::getOdomPose(double& x, double& y, double& yaw,
const ros::Time& t, const std::string& f)
{
- // Get the robot's pose
- tf::Stamped<tf::Pose> ident (btTransform(btQuaternion(0,0,0),
+ // Get the robot's pose
+ tf::Stamped<tf::Pose> ident (btTransform(btQuaternion(0,0,0),
btVector3(0,0,0)), t, f);
tf::Stamped<btTransform> odom_pose;
try
@@ -466,7 +466,7 @@
}
-pf_vector_t
+pf_vector_t
AmclNode::uniformPoseGenerator(void* arg)
{
map_t* map = (map_t*)arg;
@@ -502,7 +502,7 @@
{
pf_mutex_.lock();
ROS_INFO("Initializing with uniform distribution");
- pf_init_model(pf_, (pf_init_model_fn_t)AmclNode::uniformPoseGenerator,
+ pf_init_model(pf_, (pf_init_model_fn_t)AmclNode::uniformPoseGenerator,
(void *)map_);
pf_init_ = false;
pf_mutex_.unlock();
@@ -515,8 +515,8 @@
// Do we have the base->base_laser Tx yet?
if(!have_laser_pose)
{
- tf::Stamped<tf::Pose> ident (btTransform(btQuaternion(0,0,0),
- btVector3(0,0,0)),
+ tf::Stamped<tf::Pose> ident (btTransform(btQuaternion(0,0,0),
+ btVector3(0,0,0)),
ros::Time(), laser_scan->header.frame_id);
tf::Stamped<btTransform> laser_pose;
try
@@ -539,15 +539,15 @@
laser_pose.getBasis().getEulerZYX(laser_pose_v.v[2],p,r);
laser_->SetLaserPose(laser_pose_v);
ROS_DEBUG("Received laser's pose wrt robot: %.3f %.3f %.3f"...
[truncated message content] |