|
From: <is...@us...> - 2009-06-30 22:47:24
|
Revision: 18021
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=18021&view=rev
Author: isucan
Date: 2009-06-30 22:47:21 +0000 (Tue, 30 Jun 2009)
Log Message:
-----------
moving mapping messages
Modified Paths:
--------------
pkg/trunk/mapping/collision_map/manifest.xml
pkg/trunk/mapping/collision_map/src/collision_map.cpp
pkg/trunk/mapping/collision_map/src/collision_map_buffer.cpp
pkg/trunk/mapping/collision_map/src/collision_map_occ.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/motion_planning/planning_environment/include/planning_environment/collision_space_monitor.h
pkg/trunk/motion_planning/planning_environment/manifest.xml
pkg/trunk/motion_planning/planning_environment/src/collision_space_monitor.cpp
pkg/trunk/motion_planning/planning_research/sbpl_arm_planner_node/include/sbpl_arm_planner_node/sbpl_arm_check_path.h
pkg/trunk/motion_planning/planning_research/sbpl_arm_planner_node/include/sbpl_arm_planner_node/sbpl_arm_planner_node.h
pkg/trunk/motion_planning/planning_research/sbpl_arm_planner_node/manifest.xml
pkg/trunk/motion_planning/planning_research/sbpl_arm_planner_node/src/sbpl_arm_planner_node.cpp
pkg/trunk/motion_planning/planning_research/sbpl_door_planner_action/include/sbpl_door_planner_action/sbpl_door_planner_action.h
pkg/trunk/motion_planning/planning_research/sbpl_door_planner_action/manifest.xml
pkg/trunk/motion_planning/planning_research/sbpl_planner_node/include/sbpl_planner_node/sbpl_planner_node.h
pkg/trunk/motion_planning/planning_research/sbpl_planner_node/manifest.xml
pkg/trunk/openrave_planning/orrosplanning/manifest.xml
pkg/trunk/openrave_planning/orrosplanning/src/collisionmapsystem.h
pkg/trunk/stacks/semantic_mapping/door_handle_detector/include/door_handle_detector/doors_detector.h
pkg/trunk/stacks/semantic_mapping/door_handle_detector/include/door_handle_detector/handle_detector.h
pkg/trunk/stacks/semantic_mapping/door_handle_detector/manifest.xml
pkg/trunk/stacks/semantic_mapping/door_handle_detector/src/doors_detector.cpp
pkg/trunk/stacks/semantic_mapping/door_handle_detector/src/handle_detector.cpp
pkg/trunk/stacks/visualization/rviz/manifest.xml
pkg/trunk/stacks/visualization/rviz/src/rviz/displays/collision_map_display.cpp
pkg/trunk/stacks/visualization/rviz/src/rviz/displays/collision_map_display.h
pkg/trunk/stacks/visualization/rviz/src/rviz/displays/polygonal_map_display.cpp
pkg/trunk/stacks/visualization/rviz/src/rviz/displays/polygonal_map_display.h
Added Paths:
-----------
pkg/trunk/stacks/common_msgs/mapping_msgs/
pkg/trunk/stacks/common_msgs/mapping_msgs/CMakeLists.txt
pkg/trunk/stacks/common_msgs/mapping_msgs/Makefile
pkg/trunk/stacks/common_msgs/mapping_msgs/mainpage.dox
pkg/trunk/stacks/common_msgs/mapping_msgs/manifest.xml
pkg/trunk/stacks/common_msgs/mapping_msgs/msg/
pkg/trunk/stacks/common_msgs/mapping_msgs/msg/CollisionMap.msg
pkg/trunk/stacks/common_msgs/mapping_msgs/msg/OrientedBoundingBox.msg
pkg/trunk/stacks/common_msgs/mapping_msgs/msg/PolygonalMap.msg
Removed Paths:
-------------
pkg/trunk/stacks/common_msgs/robot_msgs/msg/CollisionMap.msg
pkg/trunk/stacks/common_msgs/robot_msgs/msg/OrientedBoundingBox.msg
pkg/trunk/stacks/common_msgs/robot_msgs/msg/PolygonalMap.msg
Modified: pkg/trunk/mapping/collision_map/manifest.xml
===================================================================
--- pkg/trunk/mapping/collision_map/manifest.xml 2009-06-30 22:47:15 UTC (rev 18020)
+++ pkg/trunk/mapping/collision_map/manifest.xml 2009-06-30 22:47:21 UTC (rev 18021)
@@ -16,6 +16,7 @@
<depend package="visualization_msgs" />
<depend package="tabletop_msgs" />
<depend package="tabletop_srvs" />
+ <depend package="mapping_msgs" />
<depend package="point_cloud_mapping" />
<depend package="robot_self_filter" />
</package>
Modified: pkg/trunk/mapping/collision_map/src/collision_map.cpp
===================================================================
--- pkg/trunk/mapping/collision_map/src/collision_map.cpp 2009-06-30 22:47:15 UTC (rev 18020)
+++ pkg/trunk/mapping/collision_map/src/collision_map.cpp 2009-06-30 22:47:21 UTC (rev 18021)
@@ -58,8 +58,8 @@
#include <boost/thread/mutex.hpp>
-#include <robot_msgs/OrientedBoundingBox.h>
-#include <robot_msgs/CollisionMap.h>
+#include <mapping_msgs/OrientedBoundingBox.h>
+#include <mapping_msgs/CollisionMap.h>
#include <tf/transform_listener.h>
#include <sys/time.h>
@@ -67,6 +67,7 @@
using namespace std;
using namespace std_msgs;
using namespace robot_msgs;
+using namespace mapping_msgs;
struct Leaf
{
Modified: pkg/trunk/mapping/collision_map/src/collision_map_buffer.cpp
===================================================================
--- pkg/trunk/mapping/collision_map/src/collision_map_buffer.cpp 2009-06-30 22:47:15 UTC (rev 18020)
+++ pkg/trunk/mapping/collision_map/src/collision_map_buffer.cpp 2009-06-30 22:47:21 UTC (rev 18021)
@@ -54,8 +54,8 @@
#include <boost/thread/mutex.hpp>
-#include <robot_msgs/OrientedBoundingBox.h>
-#include <robot_msgs/CollisionMap.h>
+#include <mapping_msgs/OrientedBoundingBox.h>
+#include <mapping_msgs/CollisionMap.h>
#include <tabletop_srvs/RecordStaticMapTrigger.h>
#include <tabletop_srvs/SubtractObjectFromCollisionMap.h>
@@ -64,7 +64,7 @@
using namespace std;
using namespace robot_msgs;
-using namespace robot_msgs;
+using namespace mapping_msgs;
using namespace tabletop_srvs;
using namespace visualization_msgs;
Modified: pkg/trunk/mapping/collision_map/src/collision_map_occ.cpp
===================================================================
--- pkg/trunk/mapping/collision_map/src/collision_map_occ.cpp 2009-06-30 22:47:15 UTC (rev 18020)
+++ pkg/trunk/mapping/collision_map/src/collision_map_occ.cpp 2009-06-30 22:47:21 UTC (rev 18021)
@@ -36,7 +36,7 @@
#include <ros/ros.h>
#include <robot_msgs/PointCloud.h>
-#include <robot_msgs/CollisionMap.h>
+#include <mapping_msgs/CollisionMap.h>
#include <tf/transform_listener.h>
#include <tf/message_notifier.h>
#include <robot_self_filter/self_mask.h>
@@ -57,10 +57,10 @@
loadParams();
// advertise our topics: full map and updates
- cmapPublisher_ = nh_.advertise<robot_msgs::CollisionMap>("collision_map_occ", 1);
- cmapUpdPublisher_ = nh_.advertise<robot_msgs::CollisionMap>("collision_map_occ_update", 1);
+ cmapPublisher_ = nh_.advertise<mapping_msgs::CollisionMap>("collision_map_occ", 1);
+ cmapUpdPublisher_ = nh_.advertise<mapping_msgs::CollisionMap>("collision_map_occ_update", 1);
if (publishOcclusion_)
- occPublisher_ = nh_.advertise<robot_msgs::CollisionMap>("collision_map_occ_occlusion", 1);
+ occPublisher_ = nh_.advertise<mapping_msgs::CollisionMap>("collision_map_occ_occlusion", 1);
// create a message notifier (and enable subscription) for both the full map and for the updates
mnCloud_ = new tf::MessageNotifier<robot_msgs::PointCloud>(tf_, boost::bind(&CollisionMapperOcc::cloudCallback, this, _1), "cloud_in", "", 1);
@@ -719,14 +719,14 @@
void publishCollisionMap(const CMap &map, ros::Publisher &pub) const
{
- robot_msgs::CollisionMap cmap;
+ mapping_msgs::CollisionMap cmap;
cmap.header = header_;
const unsigned int ms = map.size();
for (CMap::const_iterator it = map.begin() ; it != map.end() ; ++it)
{
const CollisionPoint &cp = *it;
- robot_msgs::OrientedBoundingBox box;
+ mapping_msgs::OrientedBoundingBox box;
box.extents.x = box.extents.y = box.extents.z = bi_.resolution;
box.axis.x = box.axis.y = 0.0; box.axis.z = 1.0;
box.angle = 0.0;
Modified: pkg/trunk/motion_planning/ompl_planning/manifest.xml
===================================================================
--- pkg/trunk/motion_planning/ompl_planning/manifest.xml 2009-06-30 22:47:15 UTC (rev 18020)
+++ pkg/trunk/motion_planning/ompl_planning/manifest.xml 2009-06-30 22:47:21 UTC (rev 18021)
@@ -16,6 +16,8 @@
<depend package="visualization_msgs" />
<depend package="motion_planning_msgs" />
<depend package="motion_planning_srvs" />
+ <depend package="mapping_msgs" />
+ <depend package="tabletop_msgs" />
<depend package="planning_environment"/>
<depend package="ompl" />
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-06-30 22:47:15 UTC (rev 18020)
+++ pkg/trunk/motion_planning/ompl_planning/src/display_planner_collision_model.cpp 2009-06-30 22:47:21 UTC (rev 18021)
@@ -75,7 +75,7 @@
protected:
- void afterWorldUpdate(const robot_msgs::CollisionMapConstPtr &collisionMap)
+ void afterWorldUpdate(const mapping_msgs::CollisionMapConstPtr &collisionMap)
{
unsigned int n = collisionMap->get_boxes_size();
for (unsigned int i = 0 ; i < n ; ++i)
Modified: pkg/trunk/motion_planning/ompl_planning/src/state_validity_monitor.cpp
===================================================================
--- pkg/trunk/motion_planning/ompl_planning/src/state_validity_monitor.cpp 2009-06-30 22:47:15 UTC (rev 18020)
+++ pkg/trunk/motion_planning/ompl_planning/src/state_validity_monitor.cpp 2009-06-30 22:47:21 UTC (rev 18021)
@@ -73,7 +73,7 @@
protected:
- void afterWorldUpdate(const robot_msgs::CollisionMapConstPtr &collisionMap)
+ void afterWorldUpdate(const mapping_msgs::CollisionMapConstPtr &collisionMap)
{
last_ = -1;
}
Modified: pkg/trunk/motion_planning/planning_environment/include/planning_environment/collision_space_monitor.h
===================================================================
--- pkg/trunk/motion_planning/planning_environment/include/planning_environment/collision_space_monitor.h 2009-06-30 22:47:15 UTC (rev 18020)
+++ pkg/trunk/motion_planning/planning_environment/include/planning_environment/collision_space_monitor.h 2009-06-30 22:47:21 UTC (rev 18021)
@@ -41,7 +41,7 @@
#include "planning_environment/kinematic_model_state_monitor.h"
#include <tf/message_notifier.h>
-#include <robot_msgs/CollisionMap.h>
+#include <mapping_msgs/CollisionMap.h>
#include <tabletop_msgs/AttachedObject.h>
#include <boost/thread/mutex.hpp>
@@ -105,13 +105,13 @@
}
/** \brief Define a callback for before updating a map */
- void setOnBeforeMapUpdateCallback(const boost::function<void(const robot_msgs::CollisionMapConstPtr)> &callback)
+ void setOnBeforeMapUpdateCallback(const boost::function<void(const mapping_msgs::CollisionMapConstPtr)> &callback)
{
onBeforeMapUpdate_ = callback;
}
/** \brief Define a callback for after updating a map */
- void setOnAfterMapUpdateCallback(const boost::function<void(const robot_msgs::CollisionMapConstPtr)> &callback)
+ void setOnAfterMapUpdateCallback(const boost::function<void(const mapping_msgs::CollisionMapConstPtr)> &callback)
{
onAfterMapUpdate_ = callback;
}
@@ -144,25 +144,25 @@
protected:
void setupCSM(void);
- void updateCollisionSpace(const robot_msgs::CollisionMapConstPtr &collisionMap, bool clear);
- void collisionMapCallback(const robot_msgs::CollisionMapConstPtr &collisionMap);
- void collisionMapUpdateCallback(const robot_msgs::CollisionMapConstPtr &collisionMap);
+ void updateCollisionSpace(const mapping_msgs::CollisionMapConstPtr &collisionMap, bool clear);
+ void collisionMapCallback(const mapping_msgs::CollisionMapConstPtr &collisionMap);
+ void collisionMapUpdateCallback(const mapping_msgs::CollisionMapConstPtr &collisionMap);
void attachObjectCallback(const tabletop_msgs::AttachedObjectConstPtr &attachedObject);
- CollisionModels *cm_;
- collision_space::EnvironmentModel *collisionSpace_;
- double boxScale_;
- boost::mutex mapUpdateLock_;
+ CollisionModels *cm_;
+ collision_space::EnvironmentModel *collisionSpace_;
+ double boxScale_;
+ boost::mutex mapUpdateLock_;
- bool haveMap_;
- ros::Time lastMapUpdate_;
- tf::MessageNotifier<robot_msgs::CollisionMap> *collisionMapNotifier_;
- tf::MessageNotifier<robot_msgs::CollisionMap> *collisionMapUpdateNotifier_;
- tf::MessageNotifier<tabletop_msgs::AttachedObject> *attachedBodyNotifier_;
+ bool haveMap_;
+ ros::Time lastMapUpdate_;
+ tf::MessageNotifier<mapping_msgs::CollisionMap> *collisionMapNotifier_;
+ tf::MessageNotifier<mapping_msgs::CollisionMap> *collisionMapUpdateNotifier_;
+ tf::MessageNotifier<tabletop_msgs::AttachedObject> *attachedBodyNotifier_;
- boost::function<void(const robot_msgs::CollisionMapConstPtr)> onBeforeMapUpdate_;
- boost::function<void(const robot_msgs::CollisionMapConstPtr)> onAfterMapUpdate_;
- boost::function<void(planning_models::KinematicModel::Link*)> onAfterAttachBody_;
+ boost::function<void(const mapping_msgs::CollisionMapConstPtr)> onBeforeMapUpdate_;
+ boost::function<void(const mapping_msgs::CollisionMapConstPtr)> onAfterMapUpdate_;
+ boost::function<void(planning_models::KinematicModel::Link*)> onAfterAttachBody_;
};
Modified: pkg/trunk/motion_planning/planning_environment/manifest.xml
===================================================================
--- pkg/trunk/motion_planning/planning_environment/manifest.xml 2009-06-30 22:47:15 UTC (rev 18020)
+++ pkg/trunk/motion_planning/planning_environment/manifest.xml 2009-06-30 22:47:21 UTC (rev 18021)
@@ -18,6 +18,7 @@
<depend package="tabletop_msgs" />
<depend package="mechanism_msgs" />
<depend package="motion_planning_msgs" />
+ <depend package="mapping_msgs" />
<depend package="geometric_shapes" />
<depend package="planning_models" />
<depend package="collision_space" />
Modified: pkg/trunk/motion_planning/planning_environment/src/collision_space_monitor.cpp
===================================================================
--- pkg/trunk/motion_planning/planning_environment/src/collision_space_monitor.cpp 2009-06-30 22:47:15 UTC (rev 18020)
+++ pkg/trunk/motion_planning/planning_environment/src/collision_space_monitor.cpp 2009-06-30 22:47:21 UTC (rev 18021)
@@ -89,10 +89,10 @@
ROS_INFO("Added static plane %fx + %fy + %fz + %f = 0", planeValues[i * 4], planeValues[i * 4 + 1], planeValues[i * 4 + 2], planeValues[i * 4 + 3]);
}
- collisionMapNotifier_ = new tf::MessageNotifier<robot_msgs::CollisionMap>(*tf_, boost::bind(&CollisionSpaceMonitor::collisionMapCallback, this, _1), "collision_map", getFrameId(), 1);
+ collisionMapNotifier_ = new tf::MessageNotifier<mapping_msgs::CollisionMap>(*tf_, boost::bind(&CollisionSpaceMonitor::collisionMapCallback, this, _1), "collision_map", getFrameId(), 1);
ROS_DEBUG("Listening to collision_map using message notifier with target frame %s", collisionMapNotifier_->getTargetFramesString().c_str());
- collisionMapUpdateNotifier_ = new tf::MessageNotifier<robot_msgs::CollisionMap>(*tf_, boost::bind(&CollisionSpaceMonitor::collisionMapUpdateCallback, this, _1), "collision_map_update", getFrameId(), 1);
+ collisionMapUpdateNotifier_ = new tf::MessageNotifier<mapping_msgs::CollisionMap>(*tf_, boost::bind(&CollisionSpaceMonitor::collisionMapUpdateCallback, this, _1), "collision_map_update", getFrameId(), 1);
ROS_DEBUG("Listening to collision_map_update using message notifier with target frame %s", collisionMapUpdateNotifier_->getTargetFramesString().c_str());
if (cm_->loadedModels())
@@ -127,18 +127,18 @@
ROS_INFO("Map received!");
}
-void planning_environment::CollisionSpaceMonitor::collisionMapUpdateCallback(const robot_msgs::CollisionMapConstPtr &collisionMap)
+void planning_environment::CollisionSpaceMonitor::collisionMapUpdateCallback(const mapping_msgs::CollisionMapConstPtr &collisionMap)
{
if (collisionMap->boxes.size() > 0)
updateCollisionSpace(collisionMap, false);
}
-void planning_environment::CollisionSpaceMonitor::collisionMapCallback(const robot_msgs::CollisionMapConstPtr &collisionMap)
+void planning_environment::CollisionSpaceMonitor::collisionMapCallback(const mapping_msgs::CollisionMapConstPtr &collisionMap)
{
updateCollisionSpace(collisionMap, true);
}
-void planning_environment::CollisionSpaceMonitor::updateCollisionSpace(const robot_msgs::CollisionMapConstPtr &collisionMap, bool clear)
+void planning_environment::CollisionSpaceMonitor::updateCollisionSpace(const mapping_msgs::CollisionMapConstPtr &collisionMap, bool clear)
{
boost::mutex::scoped_lock lock(mapUpdateLock_);
Modified: pkg/trunk/motion_planning/planning_research/sbpl_arm_planner_node/include/sbpl_arm_planner_node/sbpl_arm_check_path.h
===================================================================
--- pkg/trunk/motion_planning/planning_research/sbpl_arm_planner_node/include/sbpl_arm_planner_node/sbpl_arm_check_path.h 2009-06-30 22:47:15 UTC (rev 18020)
+++ pkg/trunk/motion_planning/planning_research/sbpl_arm_planner_node/include/sbpl_arm_planner_node/sbpl_arm_check_path.h 2009-06-30 22:47:21 UTC (rev 18021)
@@ -40,7 +40,7 @@
/** Messages needed for trajectory control and collision map**/
#include <robot_msgs/Pose.h>
#include <manipulation_msgs/JointTraj.h>
-#include <robot_msgs/CollisionMap.h>
+#include <mapping_msgs/CollisionMap.h>
#include <manipulation_msgs/JointTrajPoint.h>
/** sbpl planner include files **/
@@ -78,7 +78,7 @@
std::string node_name_;
- robot_msgs::CollisionMap collision_map_;
+ mapping_msgs::CollisionMap collision_map_;
MDPConfig mdp_cfg_;
Modified: pkg/trunk/motion_planning/planning_research/sbpl_arm_planner_node/include/sbpl_arm_planner_node/sbpl_arm_planner_node.h
===================================================================
--- pkg/trunk/motion_planning/planning_research/sbpl_arm_planner_node/include/sbpl_arm_planner_node/sbpl_arm_planner_node.h 2009-06-30 22:47:15 UTC (rev 18020)
+++ pkg/trunk/motion_planning/planning_research/sbpl_arm_planner_node/include/sbpl_arm_planner_node/sbpl_arm_planner_node.h 2009-06-30 22:47:21 UTC (rev 18021)
@@ -44,7 +44,7 @@
/** Messages needed for trajectory control and collision map**/
#include <robot_msgs/Pose.h>
#include <manipulation_msgs/JointTraj.h>
-#include <robot_msgs/CollisionMap.h>
+#include <mapping_msgs/CollisionMap.h>
#include <manipulation_msgs/JointTrajPoint.h>
#include <motion_planning_msgs/KinematicPath.h>
#include <motion_planning_msgs/KinematicState.h>
@@ -103,9 +103,9 @@
std::vector<std::string> joint_names_;
- robot_msgs::CollisionMap collision_map_;
+ mapping_msgs::CollisionMap collision_map_;
- robot_msgs::CollisionMap sbpl_collision_map_;
+ mapping_msgs::CollisionMap sbpl_collision_map_;
MDPConfig mdp_cfg_;
Modified: pkg/trunk/motion_planning/planning_research/sbpl_arm_planner_node/manifest.xml
===================================================================
--- pkg/trunk/motion_planning/planning_research/sbpl_arm_planner_node/manifest.xml 2009-06-30 22:47:15 UTC (rev 18020)
+++ pkg/trunk/motion_planning/planning_research/sbpl_arm_planner_node/manifest.xml 2009-06-30 22:47:21 UTC (rev 18021)
@@ -8,6 +8,7 @@
<depend package="sbpl_arm_planner" />
<depend package="std_msgs"/>
<depend package="robot_msgs" />
+ <depend package="mapping_msgs" />
<depend package="manipulation_msgs" />
<depend package="motion_planning_msgs" />
<depend package="motion_planning_srvs" />
Modified: pkg/trunk/motion_planning/planning_research/sbpl_arm_planner_node/src/sbpl_arm_planner_node.cpp
===================================================================
--- pkg/trunk/motion_planning/planning_research/sbpl_arm_planner_node/src/sbpl_arm_planner_node.cpp 2009-06-30 22:47:15 UTC (rev 18020)
+++ pkg/trunk/motion_planning/planning_research/sbpl_arm_planner_node/src/sbpl_arm_planner_node.cpp 2009-06-30 22:47:21 UTC (rev 18021)
@@ -65,7 +65,7 @@
// collision map
subscribe(collision_map_topic_, collision_map_, &SBPLArmPlannerNode::collisionMapCallback,1);
- advertise<robot_msgs::CollisionMap> ("sbpl_collision_map", 1);
+ advertise<mapping_msgs::CollisionMap> ("sbpl_collision_map", 1);
//initialize planner
planner_ = new ARAPlanner(&pr2_arm_env_, forward_search_);
Modified: pkg/trunk/motion_planning/planning_research/sbpl_door_planner_action/include/sbpl_door_planner_action/sbpl_door_planner_action.h
===================================================================
--- pkg/trunk/motion_planning/planning_research/sbpl_door_planner_action/include/sbpl_door_planner_action/sbpl_door_planner_action.h 2009-06-30 22:47:15 UTC (rev 18020)
+++ pkg/trunk/motion_planning/planning_research/sbpl_door_planner_action/include/sbpl_door_planner_action/sbpl_door_planner_action.h 2009-06-30 22:47:21 UTC (rev 18021)
@@ -46,7 +46,7 @@
#include <robot_msgs/Pose.h>
#include <manipulation_msgs/JointTraj.h>
#include <manipulation_msgs/JointTrajPoint.h>
-#include <robot_msgs/CollisionMap.h>
+#include <mapping_msgs/CollisionMap.h>
// Costmap used for the map representation
#include <costmap_2d/costmap_2d_ros.h>
Modified: pkg/trunk/motion_planning/planning_research/sbpl_door_planner_action/manifest.xml
===================================================================
--- pkg/trunk/motion_planning/planning_research/sbpl_door_planner_action/manifest.xml 2009-06-30 22:47:15 UTC (rev 18020)
+++ pkg/trunk/motion_planning/planning_research/sbpl_door_planner_action/manifest.xml 2009-06-30 22:47:21 UTC (rev 18021)
@@ -19,6 +19,7 @@
<depend package="door_handle_detector"/>
<depend package="door_functions"/>
<depend package="door_msgs"/>
+ <depend package="mapping_msgs"/>
<depend package="pr2_ik"/>
<url></url>
Modified: pkg/trunk/motion_planning/planning_research/sbpl_planner_node/include/sbpl_planner_node/sbpl_planner_node.h
===================================================================
--- pkg/trunk/motion_planning/planning_research/sbpl_planner_node/include/sbpl_planner_node/sbpl_planner_node.h 2009-06-30 22:47:15 UTC (rev 18020)
+++ pkg/trunk/motion_planning/planning_research/sbpl_planner_node/include/sbpl_planner_node/sbpl_planner_node.h 2009-06-30 22:47:21 UTC (rev 18021)
@@ -45,7 +45,7 @@
#include <robot_msgs/Pose.h>
#include <manipulation_msgs/JointTraj.h>
#include <manipulation_msgs/JointTrajPoint.h>
-#include <robot_msgs/CollisionMap.h>
+#include <mapping_msgs/CollisionMap.h>
// Costmap used for the map representation
#include <costmap_2d/costmap_2d_ros.h>
Modified: pkg/trunk/motion_planning/planning_research/sbpl_planner_node/manifest.xml
===================================================================
--- pkg/trunk/motion_planning/planning_research/sbpl_planner_node/manifest.xml 2009-06-30 22:47:15 UTC (rev 18020)
+++ pkg/trunk/motion_planning/planning_research/sbpl_planner_node/manifest.xml 2009-06-30 22:47:21 UTC (rev 18021)
@@ -9,6 +9,7 @@
<depend package="rosconsole"/>
<depend package="std_msgs"/>
<depend package="robot_msgs"/>
+ <depend package="mapping_msgs"/>
<depend package="costmap_2d"/>
<depend package="tf"/>
<depend package="mpglue"/>
Modified: pkg/trunk/openrave_planning/orrosplanning/manifest.xml
===================================================================
--- pkg/trunk/openrave_planning/orrosplanning/manifest.xml 2009-06-30 22:47:15 UTC (rev 18020)
+++ pkg/trunk/openrave_planning/orrosplanning/manifest.xml 2009-06-30 22:47:21 UTC (rev 18021)
@@ -11,6 +11,7 @@
<depend package="pr2_mechanism_controllers"/>
<depend package="tf"/>
<depend package="robot_msgs"/>
+ <depend package="mapping_msgs"/>
<depend package="mechanism_msgs" />
<depend package="manipulation_msgs" />
<depend package="mocap_msgs"/>
Modified: pkg/trunk/openrave_planning/orrosplanning/src/collisionmapsystem.h
===================================================================
--- pkg/trunk/openrave_planning/orrosplanning/src/collisionmapsystem.h 2009-06-30 22:47:15 UTC (rev 18020)
+++ pkg/trunk/openrave_planning/orrosplanning/src/collisionmapsystem.h 2009-06-30 22:47:21 UTC (rev 18021)
@@ -27,7 +27,7 @@
#define COLLISIONMAP_MOCAP_SYSTEM
#include "rossensorsystem.h"
-#include <robot_msgs/CollisionMap.h>
+#include <mapping_msgs/CollisionMap.h>
// used to update objects through a mocap system
class CollisionMapXMLID
@@ -36,16 +36,16 @@
static const char* GetXMLId() { return "collisionmap"; }
};
-class CollisionMapSystem : public ROSSensorSystem<robot_msgs::CollisionMap, CollisionMapXMLID>
+class CollisionMapSystem : public ROSSensorSystem<mapping_msgs::CollisionMap, CollisionMapXMLID>
{
public:
CollisionMapSystem(EnvironmentBase* penv)
- : ROSSensorSystem<robot_msgs::CollisionMap, CollisionMapXMLID>(penv), _robotid(0), _nNextId(1), _bEnableCollisions(true)
+ : ROSSensorSystem<mapping_msgs::CollisionMap, CollisionMapXMLID>(penv), _robotid(0), _nNextId(1), _bEnableCollisions(true)
{
}
virtual ~CollisionMapSystem() {
stopsubscriptions(); // need to stop the subscriptions because the virtual destructor will not call the overridden stopsubscriptions
- ROSSensorSystem<robot_msgs::CollisionMap, CollisionMapXMLID>::Destroy();
+ ROSSensorSystem<mapping_msgs::CollisionMap, CollisionMapXMLID>::Destroy();
}
virtual bool Init(istream& sinput)
@@ -88,7 +88,7 @@
private:
virtual void startsubscriptions()
{
- ROSSensorSystem<robot_msgs::CollisionMap, CollisionMapXMLID>::startsubscriptions();
+ ROSSensorSystem<mapping_msgs::CollisionMap, CollisionMapXMLID>::startsubscriptions();
if( _bSubscribed ) {
boost::mutex::scoped_lock lock(_mutex);
@@ -117,7 +117,7 @@
virtual void stopsubscriptions()
{
- ROSSensorSystem<robot_msgs::CollisionMap, CollisionMapXMLID>::stopsubscriptions();
+ ROSSensorSystem<mapping_msgs::CollisionMap, CollisionMapXMLID>::stopsubscriptions();
_tf.reset();
}
Added: pkg/trunk/stacks/common_msgs/mapping_msgs/CMakeLists.txt
===================================================================
--- pkg/trunk/stacks/common_msgs/mapping_msgs/CMakeLists.txt (rev 0)
+++ pkg/trunk/stacks/common_msgs/mapping_msgs/CMakeLists.txt 2009-06-30 22:47:21 UTC (rev 18021)
@@ -0,0 +1,7 @@
+cmake_minimum_required(VERSION 2.4.6)
+include($ENV{ROS_ROOT}/core/rosbuild/rosbuild.cmake)
+
+rospack(mapping_msgs)
+
+genmsg()
+gensrv()
Added: pkg/trunk/stacks/common_msgs/mapping_msgs/Makefile
===================================================================
--- pkg/trunk/stacks/common_msgs/mapping_msgs/Makefile (rev 0)
+++ pkg/trunk/stacks/common_msgs/mapping_msgs/Makefile 2009-06-30 22:47:21 UTC (rev 18021)
@@ -0,0 +1 @@
+include $(shell rospack find mk)/cmake.mk
\ No newline at end of file
Added: pkg/trunk/stacks/common_msgs/mapping_msgs/mainpage.dox
===================================================================
--- pkg/trunk/stacks/common_msgs/mapping_msgs/mainpage.dox (rev 0)
+++ pkg/trunk/stacks/common_msgs/mapping_msgs/mainpage.dox 2009-06-30 22:47:21 UTC (rev 18021)
@@ -0,0 +1,119 @@
+/**
+\mainpage
+\htmlinclude manifest.html
+
+\b mapping_msgs is ...
+
+<!--
+In addition to providing an overview of your package,
+this is the section where the specification and design/architecture
+should be detailed. While the original specification may be done on the
+wiki, it should be transferred here once your package starts to take shape.
+You can then link to this documentation page from the Wiki.
+-->
+
+
+\section codeapi Code API
+
+<!--
+Provide links to specific auto-generated API documentation within your
+package that is of particular interest to a reader. Doxygen will
+document pretty much every part of your code, so do your best here to
+point the reader to the actual API.
+
+If your codebase is fairly large or has different sets of APIs, you
+should use the doxygen 'group' tag to keep these APIs together. For
+example, the roscpp documentation has 'libros' group.
+-->
+
+\section rosapi ROS API
+
+<!--
+Names are very important in ROS because they can be remapped on the
+command-line, so it is VERY IMPORTANT THAT YOU LIST NAMES AS THEY
+APPEAR IN THE CODE. You should list names of every topic, service and
+parameter used in your code. There is a template below that you can
+use to document each node separately.
+
+List of nodes:
+- \b node_name1
+- \b node_name2
+-->
+
+<!-- START: copy from here to 'END' for each node
+
+<hr>
+
+\subsection node_name node_name
+
+node_name does (provide a basic description of your node)
+
+\subsubsection Usage
+\verbatim
+$ node_type1 [standard ROS args]
+\endverbatim
+
+\par Example
+
+\verbatim
+$ node_type1
+\endverbatim
+
+
+\subsubsection topics ROS topics
+
+Subscribes to:
+- \b "in": [std_msgs/FooType] description of in
+
+Publishes to:
+- \b "out": [std_msgs/FooType] description of out
+
+
+\subsubsection parameters ROS parameters
+
+Reads the following parameters from the parameter server
+
+- \b "~param_name" : \b [type] description of param_name
+- \b "~my_param" : \b [string] description of my_param
+
+Sets the following parameters on the parameter server
+
+- \b "~param_name" : \b [type] description of param_name
+
+
+\subsubsection services ROS services
+- \b "foo_service": [std_srvs/FooType] description of foo_service
+
+
+END: copy for each node -->
+
+
+<!-- START: Uncomment if you have any command-line tools
+
+\section commandline Command-line tools
+
+This section is a catch-all for any additional tools that your package
+provides or uses that may be of use to the reader. For example:
+
+- tools/scripts (e.g. rospack, roscd)
+- roslaunch .launch files
+- xmlparam files
+
+\subsection script_name script_name
+
+Description of what this script/file does.
+
+\subsubsection Usage
+\verbatim
+$ ./script_name [args]
+\endverbatim
+
+\par Example
+
+\verbatim
+$ ./script_name foo bar
+\endverbatim
+
+END: Command-Line Tools Section -->
+
+*/
\ No newline at end of file
Added: pkg/trunk/stacks/common_msgs/mapping_msgs/manifest.xml
===================================================================
--- pkg/trunk/stacks/common_msgs/mapping_msgs/manifest.xml (rev 0)
+++ pkg/trunk/stacks/common_msgs/mapping_msgs/manifest.xml 2009-06-30 22:47:21 UTC (rev 18021)
@@ -0,0 +1,21 @@
+<package>
+ <description brief="mapping_msgs">
+
+ mapping_msgs
+
+ </description>
+ <author>Ioan Sucan</author>
+ <license>BSD</license>
+ <review status="unreviewed" notes=""/>
+ <url>http://pr.willowgarage.com/wiki/mapping_msgs</url>
+
+ <depend package="std_msgs"/>
+ <depend package="robot_msgs"/>
+
+ <export>
+ <cpp cflags="-I${prefix}/msg/cpp"/>
+ </export>
+
+</package>
+
+
Copied: pkg/trunk/stacks/common_msgs/mapping_msgs/msg/CollisionMap.msg (from rev 18003, pkg/trunk/stacks/common_msgs/robot_msgs/msg/CollisionMap.msg)
===================================================================
--- pkg/trunk/stacks/common_msgs/mapping_msgs/msg/CollisionMap.msg (rev 0)
+++ pkg/trunk/stacks/common_msgs/mapping_msgs/msg/CollisionMap.msg 2009-06-30 22:47:21 UTC (rev 18021)
@@ -0,0 +1,2 @@
+Header header
+OrientedBoundingBox[] boxes
Property changes on: pkg/trunk/stacks/common_msgs/mapping_msgs/msg/CollisionMap.msg
___________________________________________________________________
Added: svn:mergeinfo
+ /pkg/branches/gazebo-branch-merge/common/robot_msgs/msg/CollisionMap.msg:15683-15684,15739-15794,15797-15820,15822-15839,15852-15870,15983-16008,16010-16016,16129-16141,16145-16169,16245-16262,16274-16334
Copied: pkg/trunk/stacks/common_msgs/mapping_msgs/msg/OrientedBoundingBox.msg (from rev 18003, pkg/trunk/stacks/common_msgs/robot_msgs/msg/OrientedBoundingBox.msg)
===================================================================
--- pkg/trunk/stacks/common_msgs/mapping_msgs/msg/OrientedBoundingBox.msg (rev 0)
+++ pkg/trunk/stacks/common_msgs/mapping_msgs/msg/OrientedBoundingBox.msg 2009-06-30 22:47:21 UTC (rev 18021)
@@ -0,0 +1,4 @@
+robot_msgs/Point32 center
+robot_msgs/Point32 extents
+robot_msgs/Point32 axis
+float32 angle
Property changes on: pkg/trunk/stacks/common_msgs/mapping_msgs/msg/OrientedBoundingBox.msg
___________________________________________________________________
Added: svn:mergeinfo
+ /pkg/branches/gazebo-branch-merge/common/robot_msgs/msg/OrientedBoundingBox.msg:15683-15684,15739-15794,15797-15820,15822-15839,15852-15870,15983-16008,16010-16016,16129-16141,16145-16169,16245-16262,16274-16334
Copied: pkg/trunk/stacks/common_msgs/mapping_msgs/msg/PolygonalMap.msg (from rev 18003, pkg/trunk/stacks/common_msgs/robot_msgs/msg/PolygonalMap.msg)
===================================================================
--- pkg/trunk/stacks/common_msgs/mapping_msgs/msg/PolygonalMap.msg (rev 0)
+++ pkg/trunk/stacks/common_msgs/mapping_msgs/msg/PolygonalMap.msg 2009-06-30 22:47:21 UTC (rev 18021)
@@ -0,0 +1,3 @@
+Header header
+robot_msgs/Polygon3D[] polygons
+robot_msgs/ChannelFloat32[] chan
Property changes on: pkg/trunk/stacks/common_msgs/mapping_msgs/msg/PolygonalMap.msg
___________________________________________________________________
Added: svn:mergeinfo
+ /pkg/branches/gazebo-branch-merge/common/robot_msgs/msg/PolygonalMap.msg:15683-15684,15739-15794,15797-15820,15822-15839,15852-15870,15983-16008,16010-16016,16129-16141,16145-16169,16245-16262,16274-16334
Deleted: pkg/trunk/stacks/common_msgs/robot_msgs/msg/CollisionMap.msg
===================================================================
--- pkg/trunk/stacks/common_msgs/robot_msgs/msg/CollisionMap.msg 2009-06-30 22:47:15 UTC (rev 18020)
+++ pkg/trunk/stacks/common_msgs/robot_msgs/msg/CollisionMap.msg 2009-06-30 22:47:21 UTC (rev 18021)
@@ -1,2 +0,0 @@
-Header header
-OrientedBoundingBox[] boxes
Deleted: pkg/trunk/stacks/common_msgs/robot_msgs/msg/OrientedBoundingBox.msg
===================================================================
--- pkg/trunk/stacks/common_msgs/robot_msgs/msg/OrientedBoundingBox.msg 2009-06-30 22:47:15 UTC (rev 18020)
+++ pkg/trunk/stacks/common_msgs/robot_msgs/msg/OrientedBoundingBox.msg 2009-06-30 22:47:21 UTC (rev 18021)
@@ -1,4 +0,0 @@
-robot_msgs/Point32 center
-robot_msgs/Point32 extents
-robot_msgs/Point32 axis
-float32 angle
Deleted: pkg/trunk/stacks/common_msgs/robot_msgs/msg/PolygonalMap.msg
===================================================================
--- pkg/trunk/stacks/common_msgs/robot_msgs/msg/PolygonalMap.msg 2009-06-30 22:47:15 UTC (rev 18020)
+++ pkg/trunk/stacks/common_msgs/robot_msgs/msg/PolygonalMap.msg 2009-06-30 22:47:21 UTC (rev 18021)
@@ -1,3 +0,0 @@
-Header header
-Polygon3D[] polygons
-ChannelFloat32[] chan
Modified: pkg/trunk/stacks/semantic_mapping/door_handle_detector/include/door_handle_detector/doors_detector.h
===================================================================
--- pkg/trunk/stacks/semantic_mapping/door_handle_detector/include/door_handle_detector/doors_detector.h 2009-06-30 22:47:15 UTC (rev 18020)
+++ pkg/trunk/stacks/semantic_mapping/door_handle_detector/include/door_handle_detector/doors_detector.h 2009-06-30 22:47:21 UTC (rev 18021)
@@ -49,7 +49,7 @@
// ROS core
#include <ros/node.h>
#include <roslib/Header.h>
-#include <robot_msgs/PolygonalMap.h>
+#include <mapping_msgs/PolygonalMap.h>
// Most of the geometric routines that contribute to the door finding job are located here
#include <door_handle_detector/geometric_helper.h>
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-06-30 22:47:15 UTC (rev 18020)
+++ pkg/trunk/stacks/semantic_mapping/door_handle_detector/include/door_handle_detector/handle_detector.h 2009-06-30 22:47:21 UTC (rev 18021)
@@ -44,7 +44,7 @@
// ROS core
#include <ros/node.h>
#include <roslib/Header.h>
-#include <robot_msgs/PolygonalMap.h>
+#include <mapping_msgs/PolygonalMap.h>
// Most of the geometric routines that contribute to the door finding job are located here
#include <door_handle_detector/geometric_helper.h>
Modified: pkg/trunk/stacks/semantic_mapping/door_handle_detector/manifest.xml
===================================================================
--- pkg/trunk/stacks/semantic_mapping/door_handle_detector/manifest.xml 2009-06-30 22:47:15 UTC (rev 18020)
+++ pkg/trunk/stacks/semantic_mapping/door_handle_detector/manifest.xml 2009-06-30 22:47:21 UTC (rev 18021)
@@ -17,6 +17,7 @@
<depend package="std_msgs" />
<depend package="robot_msgs" />
+ <depend package="mapping_msgs" />
<depend package="door_msgs" />
<depend package="sensor_msgs"/>
<depend package="visualization_msgs" />
Modified: pkg/trunk/stacks/semantic_mapping/door_handle_detector/src/doors_detector.cpp
===================================================================
--- pkg/trunk/stacks/semantic_mapping/door_handle_detector/src/doors_detector.cpp 2009-06-30 22:47:15 UTC (rev 18020)
+++ pkg/trunk/stacks/semantic_mapping/door_handle_detector/src/doors_detector.cpp 2009-06-30 22:47:21 UTC (rev 18021)
@@ -35,6 +35,7 @@
using namespace std;
using namespace robot_msgs;
using namespace door_msgs;
+using namespace mapping_msgs;
using namespace ros;
using namespace door_handle_detector;
using namespace door_functions;
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-06-30 22:47:15 UTC (rev 18020)
+++ pkg/trunk/stacks/semantic_mapping/door_handle_detector/src/handle_detector.cpp 2009-06-30 22:47:21 UTC (rev 18021)
@@ -35,6 +35,7 @@
using namespace std;
using namespace ros;
using namespace robot_msgs;
+using namespace mapping_msgs;
using namespace door_msgs;
using namespace door_handle_detector;
using namespace door_functions;
@@ -271,7 +272,7 @@
}
node_->publish ("~door_outliers", cloud_regions);
- robot_msgs::PolygonalMap pmap;
+ PolygonalMap pmap;
pmap.header = pointcloud.header;
pmap.polygons.resize (1); // Allocate space for the handle polygonal representation
pmap.polygons[0] = polygon;
Modified: pkg/trunk/stacks/visualization/rviz/manifest.xml
===================================================================
--- pkg/trunk/stacks/visualization/rviz/manifest.xml 2009-06-30 22:47:15 UTC (rev 18020)
+++ pkg/trunk/stacks/visualization/rviz/manifest.xml 2009-06-30 22:47:21 UTC (rev 18021)
@@ -26,13 +26,12 @@
<depend package="rxtools"/>
<depend package="mechanism_model" />
<depend package="planning_environment"/>
- <depend package="robot_msgs" />
<depend package="robot_srvs" />
<depend package="wxswig"/>
<depend package="wxPython_swig_interface"/>
- <depend package="sensor_msgs"/>
<depend package="visualization_msgs" />
<depend package="motion_planning_msgs"/>
+ <depend package="mapping_msgs"/>
<export>
<cpp cflags="-I${prefix}/src/" lflags="-Wl,-rpath,${prefix}/lib -L${prefix}/lib -lrviz.so"/>
Modified: pkg/trunk/stacks/visualization/rviz/src/rviz/displays/collision_map_display.cpp
===================================================================
--- pkg/trunk/stacks/visualization/rviz/src/rviz/displays/collision_map_display.cpp 2009-06-30 22:47:15 UTC (rev 18020)
+++ pkg/trunk/stacks/visualization/rviz/src/rviz/displays/collision_map_display.cpp 2009-06-30 22:47:21 UTC (rev 18021)
@@ -70,7 +70,7 @@
setZPosition(0.0f);
scene_node_->attachObject(cloud_);
- notifier_ = new tf::MessageNotifier<robot_msgs::CollisionMap>(tf_,
+ notifier_ = new tf::MessageNotifier<mapping_msgs::CollisionMap>(tf_,
ros_node_, boost::bind(&CollisionMapDisplay::incomingMessage, this, _1),
"", "", 1);
}
@@ -394,13 +394,13 @@
category_, this);
ROSTopicStringPropertyPtr topic_prop = topic_property_.lock();
topic_prop->setMessageType(
- robot_msgs::CollisionMap::__s_getDataType());
+ mapping_msgs::CollisionMap::__s_getDataType());
}
const char*
CollisionMapDisplay::getDescription()
{
- return ("Displays data from a robot_msgs::CollisionMap message as either points or lines.");
+ return ("Displays data from a mapping_msgs::CollisionMap message as either points or lines.");
}
} // namespace rviz
Modified: pkg/trunk/stacks/visualization/rviz/src/rviz/displays/collision_map_display.h
===================================================================
--- pkg/trunk/stacks/visualization/rviz/src/rviz/displays/collision_map_display.h 2009-06-30 22:47:15 UTC (rev 18020)
+++ pkg/trunk/stacks/visualization/rviz/src/rviz/displays/collision_map_display.h 2009-06-30 22:47:21 UTC (rev 18021)
@@ -41,8 +41,8 @@
#include <boost/shared_ptr.hpp>
-#include <robot_msgs/OrientedBoundingBox.h>
-#include <robot_msgs/CollisionMap.h>
+#include <mapping_msgs/OrientedBoundingBox.h>
+#include <mapping_msgs/CollisionMap.h>
namespace ogre_tools
{
@@ -146,7 +146,7 @@
void subscribe();
void unsubscribe();
void clear();
- typedef boost::shared_ptr<robot_msgs::CollisionMap> CollisionMapPtr;
+ typedef boost::shared_ptr<mapping_msgs::CollisionMap> CollisionMapPtr;
void incomingMessage(const CollisionMapPtr& message);
void processMessage();
@@ -169,7 +169,7 @@
boost::mutex message_mutex_;
CollisionMapPtr new_message_;
CollisionMapPtr current_message_;
- tf::MessageNotifier<robot_msgs::CollisionMap>* notifier_;
+ tf::MessageNotifier<mapping_msgs::CollisionMap>* notifier_;
ColorPropertyWPtr color_property_;
ROSTopicStringPropertyWPtr topic_property_;
Modified: pkg/trunk/stacks/visualization/rviz/src/rviz/displays/polygonal_map_display.cpp
===================================================================
--- pkg/trunk/stacks/visualization/rviz/src/rviz/displays/polygonal_map_display.cpp 2009-06-30 22:47:15 UTC (rev 18020)
+++ pkg/trunk/stacks/visualization/rviz/src/rviz/displays/polygonal_map_display.cpp 2009-06-30 22:47:21 UTC (rev 18021)
@@ -77,9 +77,9 @@
setLineWidth(0.02f);
setZPosition (0.0f);
- notifier_ = new tf::MessageNotifier<robot_msgs::PolygonalMap> (tf_, ros_node_,
- boost::bind(&PolygonalMapDisplay::incomingMessage, this, _1),
- "", "", 1);
+ notifier_ = new tf::MessageNotifier<mapping_msgs::PolygonalMap> (tf_, ros_node_,
+ boost::bind(&PolygonalMapDisplay::incomingMessage, this, _1),
+ "", "", 1);
}
PolygonalMapDisplay::~PolygonalMapDisplay()
@@ -426,7 +426,7 @@
topic_property_ = property_manager_->createProperty<ROSTopicStringProperty> ("Topic", property_prefix_, boost::bind(&PolygonalMapDisplay::getTopic, this),
boost::bind(&PolygonalMapDisplay::setTopic, this, _1), category_, this);
ROSTopicStringPropertyPtr topic_prop = topic_property_.lock();
- topic_prop->setMessageType(robot_msgs::PolygonalMap::__s_getDataType());
+ topic_prop->setMessageType(mapping_msgs::PolygonalMap::__s_getDataType());
}
@@ -434,7 +434,7 @@
const char*
PolygonalMapDisplay::getDescription()
{
- return ("Displays data from a robot_msgs::PolygonalMap message as either points, billboards, or lines.");
+ return ("Displays data from a mapping_msgs::PolygonalMap message as either points, billboards, or lines.");
}
} // namespace rviz
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-06-30 22:47:15 UTC (rev 18020)
+++ pkg/trunk/stacks/visualization/rviz/src/rviz/displays/polygonal_map_display.h 2009-06-30 22:47:21 UTC (rev 18021)
@@ -43,7 +43,7 @@
#include <boost/shared_ptr.hpp>
#include <robot_msgs/Polygon3D.h>
-#include <robot_msgs/PolygonalMap.h>
+#include <mapping_msgs/PolygonalMap.h>
namespace ogre_tools
{
@@ -153,7 +153,7 @@
void subscribe();
void unsubscribe();
void clear();
- typedef boost::shared_ptr<robot_msgs::PolygonalMap> PolygonalMapPtr;
+ typedef boost::shared_ptr<mapping_msgs::PolygonalMap> PolygonalMapPtr;
void incomingMessage(const PolygonalMapPtr& message);
void processMessage();
@@ -177,7 +177,7 @@
boost::mutex message_mutex_;
PolygonalMapPtr new_message_;
PolygonalMapPtr current_message_;
- tf::MessageNotifier<robot_msgs::PolygonalMap>* notifier_;
+ tf::MessageNotifier<mapping_msgs::PolygonalMap>* notifier_;
ogre_tools::BillboardLine* billboard_line_;
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|