|
From: <is...@us...> - 2009-07-14 20:33:25
|
Revision: 18779
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=18779&view=rev
Author: isucan
Date: 2009-07-14 20:33:19 +0000 (Tue, 14 Jul 2009)
Log Message:
-----------
callback for objects in map
Modified Paths:
--------------
pkg/trunk/motion_planning/planning_environment/include/planning_environment/monitors/collision_space_monitor.h
pkg/trunk/motion_planning/planning_environment/src/monitors/collision_space_monitor.cpp
Modified: pkg/trunk/motion_planning/planning_environment/include/planning_environment/monitors/collision_space_monitor.h
===================================================================
--- pkg/trunk/motion_planning/planning_environment/include/planning_environment/monitors/collision_space_monitor.h 2009-07-14 20:24:30 UTC (rev 18778)
+++ pkg/trunk/motion_planning/planning_environment/include/planning_environment/monitors/collision_space_monitor.h 2009-07-14 20:33:19 UTC (rev 18779)
@@ -100,6 +100,12 @@
onAfterMapUpdate_ = callback;
}
+ /** \brief Define a callback for updates to the objects in the map */
+ void setOnObjectInMapUpdateCallback(const boost::function<void(const mapping_msgs::ObjectInMapConstPtr)> &callback)
+ {
+ onObjectInMapUpdate_ = callback;
+ }
+
/** \brief Return true if map has been received */
bool haveMap(void) const
{
@@ -140,6 +146,7 @@
boost::function<void(const mapping_msgs::CollisionMapConstPtr)> onBeforeMapUpdate_;
boost::function<void(const mapping_msgs::CollisionMapConstPtr)> onAfterMapUpdate_;
+ boost::function<void(const mapping_msgs::ObjectInMapConstPtr)> onObjectInMapUpdate_;
};
Modified: pkg/trunk/motion_planning/planning_environment/src/monitors/collision_space_monitor.cpp
===================================================================
--- pkg/trunk/motion_planning/planning_environment/src/monitors/collision_space_monitor.cpp 2009-07-14 20:24:30 UTC (rev 18778)
+++ pkg/trunk/motion_planning/planning_environment/src/monitors/collision_space_monitor.cpp 2009-07-14 20:33:19 UTC (rev 18779)
@@ -55,7 +55,8 @@
{
onBeforeMapUpdate_ = NULL;
onAfterMapUpdate_ = NULL;
-
+ onObjectInMapUpdate_ = NULL;
+
collisionMapNotifier_ = NULL;
collisionMapUpdateNotifier_ = NULL;
objectInMapNotifier_ = NULL;
@@ -265,6 +266,9 @@
collisionSpace_->clearObstacles(objectInMap->id);
collisionSpace_->unlock();
}
+
+ if (onObjectInMapUpdate_)
+ onObjectInMapUpdate_(objectInMap);
}
bool planning_environment::CollisionSpaceMonitor::attachObject(const mapping_msgs::AttachedObjectConstPtr &attachedObject)
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|