|
From: <is...@us...> - 2009-09-03 15:43:16
|
Revision: 23765
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=23765&view=rev
Author: isucan
Date: 2009-09-03 15:43:07 +0000 (Thu, 03 Sep 2009)
Log Message:
-----------
added map reset service
Modified Paths:
--------------
pkg/trunk/mapping/collision_map/manifest.xml
pkg/trunk/mapping/collision_map/src/collision_map_self_occ.cpp
pkg/trunk/stacks/manipulation_common/mapping_msgs/manifest.xml
Added Paths:
-----------
pkg/trunk/stacks/manipulation_common/mapping_msgs/srv/
pkg/trunk/stacks/manipulation_common/mapping_msgs/srv/Empty.srv
Modified: pkg/trunk/mapping/collision_map/manifest.xml
===================================================================
--- pkg/trunk/mapping/collision_map/manifest.xml 2009-09-03 14:40:55 UTC (rev 23764)
+++ pkg/trunk/mapping/collision_map/manifest.xml 2009-09-03 15:43:07 UTC (rev 23765)
@@ -9,12 +9,12 @@
<review status="experimental" notes="beta"/>
<depend package="roscpp" />
- <depend package="std_msgs" />
<depend package="tf" />
<depend package="visualization_msgs" />
<depend package="tabletop_msgs" />
<depend package="tabletop_srvs" />
<depend package="mapping_msgs" />
+ <depend package="std_msgs" />
<depend package="point_cloud_mapping" />
<depend package="robot_self_filter" />
</package>
Modified: pkg/trunk/mapping/collision_map/src/collision_map_self_occ.cpp
===================================================================
--- pkg/trunk/mapping/collision_map/src/collision_map_self_occ.cpp 2009-09-03 14:40:55 UTC (rev 23764)
+++ pkg/trunk/mapping/collision_map/src/collision_map_self_occ.cpp 2009-09-03 15:43:07 UTC (rev 23765)
@@ -35,6 +35,7 @@
/** \author Ioan Sucan */
#include <ros/ros.h>
+#include <mapping_msgs/Empty.h>
#include <sensor_msgs/PointCloud.h>
#include <mapping_msgs/CollisionMap.h>
#include <tf/transform_listener.h>
@@ -92,6 +93,8 @@
frames.push_back(robotFrame_);
mnCloud_->setTargetFrame(frames);
mnCloudIncremental_->setTargetFrame(frames);
+
+ resetService_ = nh_.advertiseService("~reset", &CollisionMapperOcc::reset, this);
}
~CollisionMapperOcc(void)
@@ -319,6 +322,14 @@
}
}
+ bool reset(mapping_msgs::Empty::Request &req, mapping_msgs::Empty::Response &res)
+ {
+ mapProcessing_.lock();
+ currentMap_.clear();
+ mapProcessing_.unlock();
+ return true;
+ }
+
bool transformMap(CMap &map, const roslib::Header &from, const roslib::Header &to)
{
tf::Stamped<btTransform> transf;
@@ -412,6 +423,7 @@
ros::Publisher cmapPublisher_;
ros::Publisher cmapUpdPublisher_;
ros::Publisher occPublisher_;
+ ros::ServiceServer resetService_;
roslib::Header header_;
bool publishOcclusion_;
Modified: pkg/trunk/stacks/manipulation_common/mapping_msgs/manifest.xml
===================================================================
--- pkg/trunk/stacks/manipulation_common/mapping_msgs/manifest.xml 2009-09-03 14:40:55 UTC (rev 23764)
+++ pkg/trunk/stacks/manipulation_common/mapping_msgs/manifest.xml 2009-09-03 15:43:07 UTC (rev 23765)
@@ -14,7 +14,7 @@
<depend package="geometry_msgs"/>
<export>
- <cpp cflags="-I${prefix}/msg/cpp"/>
+ <cpp cflags="-I${prefix}/msg/cpp -I${prefix}/srv/cpp"/>
</export>
</package>
Added: pkg/trunk/stacks/manipulation_common/mapping_msgs/srv/Empty.srv
===================================================================
--- pkg/trunk/stacks/manipulation_common/mapping_msgs/srv/Empty.srv (rev 0)
+++ pkg/trunk/stacks/manipulation_common/mapping_msgs/srv/Empty.srv 2009-09-03 15:43:07 UTC (rev 23765)
@@ -0,0 +1,3 @@
+std_msgs/Empty req
+---
+std_msgs/Empty res
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|