|
From: <is...@us...> - 2009-07-17 22:29:40
|
Revision: 19147
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=19147&view=rev
Author: isucan
Date: 2009-07-17 22:29:38 +0000 (Fri, 17 Jul 2009)
Log Message:
-----------
callback for finding collisions
Modified Paths:
--------------
pkg/trunk/motion_planning/planning_environment/include/planning_environment/monitors/planning_monitor.h
pkg/trunk/motion_planning/planning_environment/src/monitors/planning_monitor.cpp
Modified: pkg/trunk/motion_planning/planning_environment/include/planning_environment/monitors/planning_monitor.h
===================================================================
--- pkg/trunk/motion_planning/planning_environment/include/planning_environment/monitors/planning_monitor.h 2009-07-17 22:29:08 UTC (rev 19146)
+++ pkg/trunk/motion_planning/planning_environment/include/planning_environment/monitors/planning_monitor.h 2009-07-17 22:29:38 UTC (rev 19147)
@@ -56,11 +56,13 @@
PlanningMonitor(CollisionModels *cm, tf::TransformListener *tf, std::string frame_id) : CollisionSpaceMonitor(static_cast<CollisionModels*>(cm), tf, frame_id)
{
+ onCollisionContact_ = NULL;
loadParams();
}
PlanningMonitor(CollisionModels *cm, tf::TransformListener *tf) : CollisionSpaceMonitor(static_cast<CollisionModels*>(cm), tf)
{
+ onCollisionContact_ = NULL;
loadParams();
}
@@ -101,6 +103,12 @@
/** \brief Transform the kinematic joint to the frame requested */
bool transformJointToFrame(motion_planning_msgs::KinematicJoint &kj, const std::string &target) const;
+ /** \brief Set a callback to be called when a collision is found */
+ void setOnCollisionContactCallback(const boost::function<void(collision_space::EnvironmentModel::Contact&)> &callback)
+ {
+ onCollisionContact_ = callback;
+ }
+
protected:
/** \brief Load ROS parameters */
@@ -111,6 +119,9 @@
/** \brief Check the path assuming it is in the frame of the model */
bool isPathValidAux(const motion_planning_msgs::KinematicPath &path, bool verbose) const;
+
+ /** \brief User callback when a collision is found */
+ boost::function<void(collision_space::EnvironmentModel::Contact&)> onCollisionContact_;
motion_planning_msgs::KinematicConstraints kcPath_;
motion_planning_msgs::KinematicConstraints kcGoal_;
Modified: pkg/trunk/motion_planning/planning_environment/src/monitors/planning_monitor.cpp
===================================================================
--- pkg/trunk/motion_planning/planning_environment/src/monitors/planning_monitor.cpp 2009-07-17 22:29:08 UTC (rev 19146)
+++ pkg/trunk/motion_planning/planning_environment/src/monitors/planning_monitor.cpp 2009-07-17 22:29:38 UTC (rev 19147)
@@ -278,11 +278,16 @@
getEnvironmentModel()->updateRobotModel();
// check for collision
- bool valid = !getEnvironmentModel()->isCollision();
+ std::vector<collision_space::EnvironmentModel::Contact> contacts;
+ bool valid = !getEnvironmentModel()->getCollisionContacts(contacts, 1);
getKinematicModel()->unlock();
getEnvironmentModel()->unlock();
+ if (onCollisionContact_)
+ for (unsigned int i = 0 ; i < contacts.size() ; ++i)
+ onCollisionContact_(contacts[i]);
+
return valid;
}
@@ -297,7 +302,8 @@
getEnvironmentModel()->updateRobotModel();
// check for collision
- bool valid = !getEnvironmentModel()->isCollision();
+ std::vector<collision_space::EnvironmentModel::Contact> contacts;
+ bool valid = !getEnvironmentModel()->getCollisionContacts(contacts, 1);
if (valid)
{
@@ -309,7 +315,11 @@
getKinematicModel()->unlock();
getEnvironmentModel()->unlock();
-
+
+ if (onCollisionContact_)
+ for (unsigned int i = 0 ; i < contacts.size() ; ++i)
+ onCollisionContact_(contacts[i]);
+
return valid;
}
@@ -324,7 +334,8 @@
getEnvironmentModel()->updateRobotModel();
// check for collision
- bool valid = !getEnvironmentModel()->isCollision();
+ std::vector<collision_space::EnvironmentModel::Contact> contacts;
+ bool valid = !getEnvironmentModel()->getCollisionContacts(contacts, 1);
if (valid)
{
@@ -339,6 +350,10 @@
getKinematicModel()->unlock();
getEnvironmentModel()->unlock();
+ if (onCollisionContact_)
+ for (unsigned int i = 0 ; i < contacts.size() ; ++i)
+ onCollisionContact_(contacts[i]);
+
return valid;
}
@@ -425,8 +440,13 @@
getEnvironmentModel()->updateRobotModel();
// check for collision
- valid = !getEnvironmentModel()->isCollision();
-
+ std::vector<collision_space::EnvironmentModel::Contact> contacts;
+ valid = !getEnvironmentModel()->getCollisionContacts(contacts, 1);
+
+ if (onCollisionContact_)
+ for (unsigned int i = 0 ; i < contacts.size() ; ++i)
+ onCollisionContact_(contacts[i]);
+
if (verbose && !valid)
ROS_INFO("isPathValid: State %d is in collision", i);
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <is...@us...> - 2009-07-18 01:42:42
|
Revision: 19168
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=19168&view=rev
Author: isucan
Date: 2009-07-18 01:42:37 +0000 (Sat, 18 Jul 2009)
Log Message:
-----------
additional padding for pointclouds (option)
Modified Paths:
--------------
pkg/trunk/motion_planning/planning_environment/include/planning_environment/monitors/collision_space_monitor.h
pkg/trunk/motion_planning/planning_environment/include/planning_environment/monitors/planning_monitor.h
pkg/trunk/motion_planning/planning_environment/mainpage.dox
pkg/trunk/motion_planning/planning_environment/src/monitors/collision_space_monitor.cpp
pkg/trunk/motion_planning/planning_environment/src/tools/display_planner_collision_model.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-18 01:39:22 UTC (rev 19167)
+++ pkg/trunk/motion_planning/planning_environment/include/planning_environment/monitors/collision_space_monitor.h 2009-07-18 01:42:37 UTC (rev 19168)
@@ -115,7 +115,6 @@
/** \brief Return true if a map update has been received in the last sec seconds. If sec < 10us, this function always returns true. */
bool isMapUpdated(double sec) const;
-
/** \brief Wait until a map is received */
void waitForMap(void) const;
@@ -125,6 +124,12 @@
return lastMapUpdate_;
}
+ /** \brief Returns the padding used for pointclouds (for collision checking) */
+ double getPointCloudPadd(void) const
+ {
+ return pointcloud_padd_;
+ }
+
protected:
void setupCSM(void);
@@ -137,6 +142,7 @@
CollisionModels *cm_;
collision_space::EnvironmentModel *collisionSpace_;
boost::mutex mapUpdateLock_;
+ double pointcloud_padd_;
bool haveMap_;
ros::Time lastMapUpdate_;
Modified: pkg/trunk/motion_planning/planning_environment/include/planning_environment/monitors/planning_monitor.h
===================================================================
--- pkg/trunk/motion_planning/planning_environment/include/planning_environment/monitors/planning_monitor.h 2009-07-18 01:39:22 UTC (rev 19167)
+++ pkg/trunk/motion_planning/planning_environment/include/planning_environment/monitors/planning_monitor.h 2009-07-18 01:42:37 UTC (rev 19168)
@@ -48,8 +48,7 @@
/** \breif @b PlanningMonitor is a class which in addition to being aware
of a robot model, and the collision model is also aware of
constraints and can check the validity of states and paths.
- */
-
+ */
class PlanningMonitor : public CollisionSpaceMonitor
{
public:
Modified: pkg/trunk/motion_planning/planning_environment/mainpage.dox
===================================================================
--- pkg/trunk/motion_planning/planning_environment/mainpage.dox 2009-07-18 01:39:22 UTC (rev 19167)
+++ pkg/trunk/motion_planning/planning_environment/mainpage.dox 2009-07-18 01:42:37 UTC (rev 19168)
@@ -202,6 +202,8 @@
- @b "~bounding_planes"/string : a sequence of plane equations specified as "a1 b1 c1 d1 a2 b2 c2 d2 ..." where each plane is defined by the equation ax+by+cz+d=0
+ - @b "~pointcloud_padd"/double : additional padding to be used when collision checking agains pointclouds (the padding for the robot will still be used)
+
A robot description and its corresponding planning and collision descriptions are assumed to be loaded on the parameter server as well.
Sets the following parameters on the parameter server
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-18 01:39:22 UTC (rev 19167)
+++ pkg/trunk/motion_planning/planning_environment/src/monitors/collision_space_monitor.cpp 2009-07-18 01:42:37 UTC (rev 19168)
@@ -68,6 +68,8 @@
// a list of static planes bounding the environment
std::string planes;
nh_.param<std::string>("~bounding_planes", planes, std::string());
+ nh_.param<double>("~pointcloud_padd", pointcloud_padd_, 0.01);
+
std::stringstream ss(planes);
std::vector<double> planeValues;
if (!planes.empty())
@@ -181,7 +183,7 @@
data[i4 + 1] = pso.point.y;
data[i4 + 2] = pso.point.z;
- data[i4 + 3] = maxCoord(collisionMap->boxes[i].extents) * 0.867;
+ data[i4 + 3] = maxCoord(collisionMap->boxes[i].extents) * 0.867 + pointcloud_padd_;
}
if (err)
@@ -198,7 +200,7 @@
data[i4 + 1] = collisionMap->boxes[i].center.y;
data[i4 + 2] = collisionMap->boxes[i].center.z;
- data[i4 + 3] = maxCoord(collisionMap->boxes[i].extents) * 0.867;
+ data[i4 + 3] = maxCoord(collisionMap->boxes[i].extents) * 0.867 + pointcloud_padd_;
}
}
Modified: pkg/trunk/motion_planning/planning_environment/src/tools/display_planner_collision_model.cpp
===================================================================
--- pkg/trunk/motion_planning/planning_environment/src/tools/display_planner_collision_model.cpp 2009-07-18 01:39:22 UTC (rev 19167)
+++ pkg/trunk/motion_planning/planning_environment/src/tools/display_planner_collision_model.cpp 2009-07-18 01:42:37 UTC (rev 19168)
@@ -123,7 +123,7 @@
const robot_msgs::Point32 &point = collisionMap->boxes[i].center;
const robot_msgs::Point32 &extents = collisionMap->boxes[i].extents;
sendPoint(i, nh_.getName(), point.x, point.y, point.z,
- std::max(std::max(extents.x, extents.y), extents.z) * 0.867,
+ std::max(std::max(extents.x, extents.y), extents.z) * 0.867 + collisionSpaceMonitor_->getPointCloudPadd(),
collisionMap->header);
}
}
@@ -182,7 +182,7 @@
case mapping_msgs::Object::MESH:
mk.type = visualization_msgs::Marker::LINE_LIST;
- mk.scale.x = mk.scale.y = mk.scale.z = 0.02;
+ mk.scale.x = mk.scale.y = mk.scale.z = 0.01;
{
unsigned int nt = obj.triangles.size() / 3;
for (unsigned int i = 0 ; i < nt ; ++i)
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <is...@us...> - 2009-07-21 05:02:31
|
Revision: 19286
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=19286&view=rev
Author: isucan
Date: 2009-07-21 05:02:24 +0000 (Tue, 21 Jul 2009)
Log Message:
-----------
renaming function
Modified Paths:
--------------
pkg/trunk/motion_planning/planning_environment/include/planning_environment/monitors/planning_monitor.h
pkg/trunk/motion_planning/planning_environment/src/monitors/planning_monitor.cpp
pkg/trunk/motion_planning/planning_environment/src/tools/view_state_validity.cpp
Modified: pkg/trunk/motion_planning/planning_environment/include/planning_environment/monitors/planning_monitor.h
===================================================================
--- pkg/trunk/motion_planning/planning_environment/include/planning_environment/monitors/planning_monitor.h 2009-07-21 04:59:45 UTC (rev 19285)
+++ pkg/trunk/motion_planning/planning_environment/include/planning_environment/monitors/planning_monitor.h 2009-07-21 05:02:24 UTC (rev 19286)
@@ -73,7 +73,7 @@
bool isEnvironmentSafe(void) const;
/** \brief Check if the full state of the robot is valid (ignoring constraints) */
- bool isStateValid(const planning_models::StateParams *state) const;
+ bool isStateCollisionFree(const planning_models::StateParams *state) const;
/** \brief Check if the full state of the robot is valid (including path constraints) */
bool isStateValidOnPath(const planning_models::StateParams *state) const;
Modified: pkg/trunk/motion_planning/planning_environment/src/monitors/planning_monitor.cpp
===================================================================
--- pkg/trunk/motion_planning/planning_environment/src/monitors/planning_monitor.cpp 2009-07-21 04:59:45 UTC (rev 19285)
+++ pkg/trunk/motion_planning/planning_environment/src/monitors/planning_monitor.cpp 2009-07-21 05:02:24 UTC (rev 19286)
@@ -267,7 +267,7 @@
return true;
}
-bool planning_environment::PlanningMonitor::isStateValid(const planning_models::StateParams *state) const
+bool planning_environment::PlanningMonitor::isStateCollisionFree(const planning_models::StateParams *state) const
{
getEnvironmentModel()->lock();
getKinematicModel()->lock();
Modified: pkg/trunk/motion_planning/planning_environment/src/tools/view_state_validity.cpp
===================================================================
--- pkg/trunk/motion_planning/planning_environment/src/tools/view_state_validity.cpp 2009-07-21 04:59:45 UTC (rev 19285)
+++ pkg/trunk/motion_planning/planning_environment/src/tools/view_state_validity.cpp 2009-07-21 05:02:24 UTC (rev 19286)
@@ -83,7 +83,7 @@
void stateUpdate(void)
{
- bool valid = planningMonitor_->isStateValid(planningMonitor_->getRobotState());
+ bool valid = planningMonitor_->isStateCollisionFree(planningMonitor_->getRobotState());
std_msgs::Byte msg;
msg.data = valid ? 1 : 0;
if (last_ != msg.data)
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <is...@us...> - 2009-07-21 17:21:22
|
Revision: 19303
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=19303&view=rev
Author: isucan
Date: 2009-07-21 17:21:18 +0000 (Tue, 21 Jul 2009)
Log Message:
-----------
finding closest states on path
Modified Paths:
--------------
pkg/trunk/motion_planning/planning_environment/include/planning_environment/monitors/planning_monitor.h
pkg/trunk/motion_planning/planning_environment/src/monitors/planning_monitor.cpp
Modified: pkg/trunk/motion_planning/planning_environment/include/planning_environment/monitors/planning_monitor.h
===================================================================
--- pkg/trunk/motion_planning/planning_environment/include/planning_environment/monitors/planning_monitor.h 2009-07-21 15:07:08 UTC (rev 19302)
+++ pkg/trunk/motion_planning/planning_environment/include/planning_environment/monitors/planning_monitor.h 2009-07-21 17:21:18 UTC (rev 19303)
@@ -83,7 +83,16 @@
/** \brief Check if the path is valid. Path constraints are considered, but goal constraints are not */
bool isPathValid(const motion_planning_msgs::KinematicPath &path, bool verbose) const;
+
+ /** \brief Check if a segment of the path is valid. Path constraints are considered, but goal constraints are not */
+ bool isPathValid(const motion_planning_msgs::KinematicPath &path, unsigned int start, unsigned int end, bool verbose) const;
+ /** \brief Find the index of the state on the path that is closest to a given state */
+ int closestStateOnPath(const motion_planning_msgs::KinematicPath &path, const planning_models::StateParams *state) const;
+
+ /** \brief Find the index of the state on the path segment that is closest to a given state */
+ int closestStateOnPath(const motion_planning_msgs::KinematicPath &path, unsigned int start, unsigned int end, const planning_models::StateParams *state) const;
+
/** \brief Set the kinematic constraints the monitor should use when checking a path */
void setPathConstraints(const motion_planning_msgs::KinematicConstraints &kc);
@@ -117,8 +126,11 @@
bool transformJoint(const std::string &name, unsigned int index, std::vector<double> ¶ms, roslib::Header &header, const std::string& target) const;
/** \brief Check the path assuming it is in the frame of the model */
- bool isPathValidAux(const motion_planning_msgs::KinematicPath &path, bool verbose) const;
+ bool isPathValidAux(const motion_planning_msgs::KinematicPath &path, unsigned int start, unsigned int end, bool verbose) const;
+ /** \brief Find the index of the state on the path that is closest to a given state assuming the path is in the frame of the model */
+ int closestStateOnPathAux(const motion_planning_msgs::KinematicPath &path, unsigned int start, unsigned int end, const planning_models::StateParams *state) const;
+
/** \brief User callback when a collision is found */
boost::function<void(collision_space::EnvironmentModel::Contact&)> onCollisionContact_;
Modified: pkg/trunk/motion_planning/planning_environment/src/monitors/planning_monitor.cpp
===================================================================
--- pkg/trunk/motion_planning/planning_environment/src/monitors/planning_monitor.cpp 2009-07-21 15:07:08 UTC (rev 19302)
+++ pkg/trunk/motion_planning/planning_environment/src/monitors/planning_monitor.cpp 2009-07-21 17:21:18 UTC (rev 19303)
@@ -357,21 +357,102 @@
return valid;
}
+int planning_environment::PlanningMonitor::closestStateOnPath(const motion_planning_msgs::KinematicPath &path, const planning_models::StateParams *state) const
+{
+ return closestStateOnPath(path, 0, path.states.size() - 1, state);
+}
+
+int planning_environment::PlanningMonitor::closestStateOnPath(const motion_planning_msgs::KinematicPath &path, unsigned int start, unsigned int end, const planning_models::StateParams *state) const
+{
+ if (end >= path.states.size())
+ end = path.states.size() - 1;
+ if (start > end)
+ return -1;
+
+ if (path.header.frame_id != getFrameId())
+ {
+ motion_planning_msgs::KinematicPath pathT = path;
+ if (transformPathToFrame(pathT, getFrameId()))
+ return closestStateOnPathAux(pathT, start, end, state);
+ else
+ return -1;
+ }
+ else
+ return closestStateOnPathAux(path, start, end, state);
+}
+
+int planning_environment::PlanningMonitor::closestStateOnPathAux(const motion_planning_msgs::KinematicPath &path, unsigned int start, unsigned int end, const planning_models::StateParams *state) const
+{
+ double dist = 0.0;
+ int pos = -1;
+
+ // get the joints this path is for
+ std::vector<planning_models::KinematicModel::Joint*> joints(path.names.size());
+ for (unsigned int j = 0 ; j < joints.size() ; ++j)
+ {
+ joints[j] = getKinematicModel()->getJoint(path.names[j]);
+ if (joints[j] == NULL)
+ {
+ ROS_ERROR("Unknown joint '%s' found on path", path.names[j].c_str());
+ return -1;
+ }
+ }
+
+ for (unsigned int i = start ; i <= end ; ++i)
+ {
+ unsigned int u = 0;
+ double d = 0.0;
+ for (unsigned int j = 0 ; j < joints.size() ; ++j)
+ {
+ if (path.states[i].vals.size() < u + joints[j]->usedParams)
+ {
+ ROS_ERROR("Incorrect state specification on path");
+ return -1;
+ }
+
+ const double *jparams = state->getParamsJoint(joints[j]->name);
+ for (unsigned int k = 0 ; k < joints[j]->usedParams ; ++k)
+ {
+ double diff = fabs(path.states[i].vals[u + k] - jparams[k]);
+ d += diff * diff;
+ }
+ u += joints[j]->usedParams;
+ }
+
+ if (pos < 0 || d < dist)
+ {
+ pos = i;
+ dist = d;
+ }
+ }
+
+ return pos;
+}
+
bool planning_environment::PlanningMonitor::isPathValid(const motion_planning_msgs::KinematicPath &path, bool verbose) const
{
+ return isPathValid(path, 0, path.states.size() - 1, verbose);
+}
+
+bool planning_environment::PlanningMonitor::isPathValid(const motion_planning_msgs::KinematicPath &path, unsigned int start, unsigned int end, bool verbose) const
+{
+ if (end >= path.states.size())
+ end = path.states.size() - 1;
+ if (start > end)
+ return true;
if (path.header.frame_id != getFrameId())
{
motion_planning_msgs::KinematicPath pathT = path;
if (transformPathToFrame(pathT, getFrameId()))
- return isPathValidAux(pathT, verbose);
+ return isPathValidAux(pathT, start, end, verbose);
else
return false;
}
else
- return isPathValidAux(path, verbose);
+ return isPathValidAux(path, start, end, verbose);
}
-bool planning_environment::PlanningMonitor::isPathValidAux(const motion_planning_msgs::KinematicPath &path, bool verbose) const
+bool planning_environment::PlanningMonitor::isPathValidAux(const motion_planning_msgs::KinematicPath &path, unsigned int start, unsigned int end, bool verbose) const
{
boost::scoped_ptr<planning_models::StateParams> sp(getKinematicModel()->newStateParams());
@@ -415,7 +496,7 @@
}
// check every state
- for (unsigned int i = 0 ; valid && i < path.states.size() ; ++i)
+ for (unsigned int i = start ; valid && i <= end ; ++i)
{
unsigned int u = 0;
for (unsigned int j = 0 ; j < joints.size() ; ++j)
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <is...@us...> - 2009-07-22 02:07:47
|
Revision: 19367
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=19367&view=rev
Author: isucan
Date: 2009-07-22 02:07:42 +0000 (Wed, 22 Jul 2009)
Log Message:
-----------
getter for int param
Modified Paths:
--------------
pkg/trunk/motion_planning/planning_environment/include/planning_environment/models/robot_models.h
pkg/trunk/motion_planning/planning_environment/src/models/robot_models.cpp
Modified: pkg/trunk/motion_planning/planning_environment/include/planning_environment/models/robot_models.h
===================================================================
--- pkg/trunk/motion_planning/planning_environment/include/planning_environment/models/robot_models.h 2009-07-22 01:59:56 UTC (rev 19366)
+++ pkg/trunk/motion_planning/planning_environment/include/planning_environment/models/robot_models.h 2009-07-22 02:07:42 UTC (rev 19367)
@@ -72,7 +72,8 @@
bool hasParam(const std::string ¶m);
std::string getParamString(const std::string ¶m, const std::string &def = "");
double getParamDouble(const std::string ¶m, double def);
-
+ int getParamInt(const std::string ¶m, int def);
+
private:
std::string description_;
Modified: pkg/trunk/motion_planning/planning_environment/src/models/robot_models.cpp
===================================================================
--- pkg/trunk/motion_planning/planning_environment/src/models/robot_models.cpp 2009-07-22 01:59:56 UTC (rev 19366)
+++ pkg/trunk/motion_planning/planning_environment/src/models/robot_models.cpp 2009-07-22 02:07:42 UTC (rev 19367)
@@ -185,6 +185,13 @@
return value;
}
+int planning_environment::RobotModels::PlannerConfig::getParamInt(const std::string ¶m, int def)
+{
+ int value;
+ nh_.param(description_ + "_planning/planner_configs/" + config_ + "/" + param, value, def);
+ return value;
+}
+
std::vector< boost::shared_ptr<planning_environment::RobotModels::PlannerConfig> > planning_environment::RobotModels::getGroupPlannersConfig(const std::string &group)
{
std::string configs_list;
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <is...@us...> - 2009-07-28 21:36:18
|
Revision: 19899
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=19899&view=rev
Author: isucan
Date: 2009-07-28 21:36:05 +0000 (Tue, 28 Jul 2009)
Log Message:
-----------
start/stop possible for available monitors
Modified Paths:
--------------
pkg/trunk/motion_planning/planning_environment/include/planning_environment/models/collision_models.h
pkg/trunk/motion_planning/planning_environment/include/planning_environment/monitors/collision_space_monitor.h
pkg/trunk/motion_planning/planning_environment/include/planning_environment/monitors/kinematic_model_state_monitor.h
pkg/trunk/motion_planning/planning_environment/src/models/collision_models.cpp
pkg/trunk/motion_planning/planning_environment/src/monitors/collision_space_monitor.cpp
pkg/trunk/motion_planning/planning_environment/src/monitors/kinematic_model_state_monitor.cpp
Modified: pkg/trunk/motion_planning/planning_environment/include/planning_environment/models/collision_models.h
===================================================================
--- pkg/trunk/motion_planning/planning_environment/include/planning_environment/models/collision_models.h 2009-07-28 21:12:29 UTC (rev 19898)
+++ pkg/trunk/motion_planning/planning_environment/include/planning_environment/models/collision_models.h 2009-07-28 21:36:05 UTC (rev 19899)
@@ -96,11 +96,13 @@
return bullet_collision_model_;
}
+ /** \brief Get the scaling to be used for the robot parts when inserted in the collision space */
double getScale(void)
{
return scale_;
}
+ /** \brief Get the padding to be used for the robot parts when inserted in the collision space */
double getPadding(void)
{
return padd_;
@@ -117,6 +119,7 @@
double scale_;
double padd_;
+ std::vector<double> boundingPlanes_;
};
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-28 21:12:29 UTC (rev 19898)
+++ pkg/trunk/motion_planning/planning_environment/include/planning_environment/monitors/collision_space_monitor.h 2009-07-28 21:36:05 UTC (rev 19899)
@@ -76,6 +76,18 @@
delete collisionMapUpdateNotifier_;
}
+ /** \brief Start the environment monitor. By default, the monitor is started after creation */
+ void startEnvironmentMonitor(void);
+
+ /** \brief Stop the environment monitor. */
+ void stopEnvironmentMonitor(void);
+
+ /** \brief Check if the environment monitor is currently started */
+ bool isEnvironmentMonitorStarted(void) const
+ {
+ return envMonitorStarted_;
+ }
+
/** \brief Return the instance of the environment model maintained */
collision_space::EnvironmentModel* getEnvironmentModel(void) const
{
@@ -144,6 +156,8 @@
boost::mutex mapUpdateLock_;
double pointcloud_padd_;
+ bool envMonitorStarted_;
+
bool haveMap_;
ros::Time lastMapUpdate_;
tf::MessageNotifier<mapping_msgs::CollisionMap> *collisionMapNotifier_;
Modified: pkg/trunk/motion_planning/planning_environment/include/planning_environment/monitors/kinematic_model_state_monitor.h
===================================================================
--- pkg/trunk/motion_planning/planning_environment/include/planning_environment/monitors/kinematic_model_state_monitor.h 2009-07-28 21:12:29 UTC (rev 19898)
+++ pkg/trunk/motion_planning/planning_environment/include/planning_environment/monitors/kinematic_model_state_monitor.h 2009-07-28 21:36:05 UTC (rev 19899)
@@ -83,6 +83,18 @@
delete attachedBodyNotifier_;
}
+ /** \brief Start the state monitor. By default, the monitor is started after creation */
+ void startStateMonitor(void);
+
+ /** \brief Stop the state monitor. */
+ void stopStateMonitor(void);
+
+ /** \brief Check if the state monitor is currently started */
+ bool isStateMonitorStarted(void) const
+ {
+ return stateMonitorStarted_;
+ }
+
/** \brief Define a callback for when the state is changed */
void setOnStateUpdateCallback(const boost::function<void(void)> &callback)
{
@@ -182,6 +194,8 @@
std::string planarJoint_;
std::string floatingJoint_;
+ bool stateMonitorStarted_;
+
ros::NodeHandle nh_;
ros::Subscriber mechanismStateSubscriber_;
tf::TransformListener *tf_;
Modified: pkg/trunk/motion_planning/planning_environment/src/models/collision_models.cpp
===================================================================
--- pkg/trunk/motion_planning/planning_environment/src/models/collision_models.cpp 2009-07-28 21:12:29 UTC (rev 19898)
+++ pkg/trunk/motion_planning/planning_environment/src/models/collision_models.cpp 2009-07-28 21:36:05 UTC (rev 19899)
@@ -37,6 +37,8 @@
#include "planning_environment/models/collision_models.h"
#include <collision_space/environmentODE.h>
#include <collision_space/environmentBullet.h>
+#include <sstream>
+#include <vector>
void planning_environment::CollisionModels::setupModel(boost::shared_ptr<collision_space::EnvironmentModel> &model, const std::vector<std::string> &links)
{
@@ -54,6 +56,13 @@
model->addSelfCollisionGroup(scg);
}
model->updateRobotModel();
+
+ for (unsigned int i = 0 ; i < boundingPlanes_.size() / 4 ; ++i)
+ {
+ model->addPlane("bounds", boundingPlanes_[i * 4], boundingPlanes_[i * 4 + 1], boundingPlanes_[i * 4 + 2], boundingPlanes_[i * 4 + 3]);
+ ROS_INFO("Added static plane %fx + %fy + %fz + %f = 0 for model %p", boundingPlanes_[i * 4], boundingPlanes_[i * 4 + 1], boundingPlanes_[i * 4 + 2], boundingPlanes_[i * 4 + 3], model.get());
+ }
+
model->unlock();
}
@@ -65,6 +74,26 @@
void planning_environment::CollisionModels::loadCollision(const std::vector<std::string> &links)
{
+ // a list of static planes bounding the environment
+ boundingPlanes_.clear();
+
+ std::string planes;
+ nh_.param<std::string>("~bounding_planes", planes, std::string());
+
+ std::stringstream ss(planes);
+ if (!planes.empty())
+ while (ss.good() && !ss.eof())
+ {
+ double value;
+ ss >> value;
+ boundingPlanes_.push_back(value);
+ }
+ if (boundingPlanes_.size() % 4 != 0)
+ {
+ ROS_WARN("~bounding_planes must be a list of 4-tuples (a b c d) that define planes ax+by+cz+d=0");
+ boundingPlanes_.resize(boundingPlanes_.size() - (boundingPlanes_.size() % 4));
+ }
+
if (loadedModels())
{
ode_collision_model_ = boost::shared_ptr<collision_space::EnvironmentModel>(new collision_space::EnvironmentModelODE());
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-28 21:12:29 UTC (rev 19898)
+++ pkg/trunk/motion_planning/planning_environment/src/monitors/collision_space_monitor.cpp 2009-07-28 21:36:05 UTC (rev 19899)
@@ -53,6 +53,7 @@
void planning_environment::CollisionSpaceMonitor::setupCSM(void)
{
+ envMonitorStarted_ = false;
onBeforeMapUpdate_ = NULL;
onAfterMapUpdate_ = NULL;
onObjectInMapUpdate_ = NULL;
@@ -64,29 +65,15 @@
haveMap_ = false;
collisionSpace_ = cm_->getODECollisionModel().get();
+ nh_.param<double>("~pointcloud_padd", pointcloud_padd_, 0.01);
- // a list of static planes bounding the environment
- std::string planes;
- nh_.param<std::string>("~bounding_planes", planes, std::string());
- nh_.param<double>("~pointcloud_padd", pointcloud_padd_, 0.01);
+ startEnvironmentMonitor();
+}
- std::stringstream ss(planes);
- std::vector<double> planeValues;
- if (!planes.empty())
- while (ss.good() && !ss.eof())
- {
- double value;
- ss >> value;
- planeValues.push_back(value);
- }
- if (planeValues.size() % 4 != 0)
- ROS_WARN("~bounding_planes must be a list of 4-tuples (a b c d) that define planes ax+by+cz+d=0");
- else
- for (unsigned int i = 0 ; i < planeValues.size() / 4 ; ++i)
- {
- collisionSpace_->addPlane("bounds", planeValues[i * 4], planeValues[i * 4 + 1], planeValues[i * 4 + 2], planeValues[i * 4 + 3]);
- 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]);
- }
+void planning_environment::CollisionSpaceMonitor::startEnvironmentMonitor(void)
+{
+ if (envMonitorStarted_)
+ return;
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());
@@ -96,8 +83,29 @@
objectInMapNotifier_ = new tf::MessageNotifier<mapping_msgs::ObjectInMap>(*tf_, boost::bind(&CollisionSpaceMonitor::objectInMapCallback, this, _1), "object_in_map", getFrameId(), 1024);
ROS_DEBUG("Listening to object_in_map using message notifier with target frame %s", collisionMapUpdateNotifier_->getTargetFramesString().c_str());
+
+ envMonitorStarted_ = true;
}
+void planning_environment::CollisionSpaceMonitor::stopEnvironmentMonitor(void)
+{
+ if (!envMonitorStarted_)
+ return;
+
+ delete collisionMapUpdateNotifier_;
+ collisionMapUpdateNotifier_ = NULL;
+
+ delete collisionMapNotifier_;
+ collisionMapNotifier_ = NULL;
+
+ delete objectInMapNotifier_;
+ objectInMapNotifier_ = NULL;
+
+ ROS_DEBUG("Environment state is no longer being monitored");
+
+ envMonitorStarted_ = false;
+}
+
bool planning_environment::CollisionSpaceMonitor::isMapUpdated(double sec) const
{
if (!haveMap_)
Modified: pkg/trunk/motion_planning/planning_environment/src/monitors/kinematic_model_state_monitor.cpp
===================================================================
--- pkg/trunk/motion_planning/planning_environment/src/monitors/kinematic_model_state_monitor.cpp 2009-07-28 21:12:29 UTC (rev 19898)
+++ pkg/trunk/motion_planning/planning_environment/src/monitors/kinematic_model_state_monitor.cpp 2009-07-28 21:36:05 UTC (rev 19899)
@@ -41,6 +41,7 @@
void planning_environment::KinematicModelStateMonitor::setupRSM(void)
{
+ stateMonitorStarted_ = false;
pose_.setIdentity();
kmodel_ = NULL;
robotState_ = NULL;
@@ -76,16 +77,43 @@
else
frame_id_ = robot_frame_;
}
+ }
+
+ startStateMonitor();
+}
+void planning_environment::KinematicModelStateMonitor::startStateMonitor(void)
+{
+ if (stateMonitorStarted_)
+ return;
+
+ if (rm_->loadedModels())
+ {
mechanismStateSubscriber_ = nh_.subscribe("mechanism_state", 1, &KinematicModelStateMonitor::mechanismStateCallback, this);
ROS_DEBUG("Listening to mechanism state");
-
+
attachedBodyNotifier_ = new tf::MessageNotifier<mapping_msgs::AttachedObject>(*tf_, boost::bind(&KinematicModelStateMonitor::attachObjectCallback, this, _1), "attach_object", "", 1);
attachedBodyNotifier_->setTargetFrame(rm_->getCollisionCheckLinks());
ROS_DEBUG("Listening to attach_object using message notifier with target frame %s", attachedBodyNotifier_->getTargetFramesString().c_str());
}
+ stateMonitorStarted_ = true;
}
+void planning_environment::KinematicModelStateMonitor::stopStateMonitor(void)
+{
+ if (!stateMonitorStarted_)
+ return;
+
+ delete attachedBodyNotifier_;
+ attachedBodyNotifier_ = NULL;
+
+ mechanismStateSubscriber_.shutdown();
+
+ ROS_DEBUG("Kinematic state is no longer being monitored");
+
+ stateMonitorStarted_ = false;
+}
+
void planning_environment::KinematicModelStateMonitor::mechanismStateCallback(const mechanism_msgs::MechanismStateConstPtr &mechanismState)
{
bool change = !haveMechanismState_;
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <is...@us...> - 2009-07-31 21:02:42
|
Revision: 20312
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=20312&view=rev
Author: isucan
Date: 2009-07-31 21:02:32 +0000 (Fri, 31 Jul 2009)
Log Message:
-----------
no longer using deprecated canTransform
Modified Paths:
--------------
pkg/trunk/motion_planning/planning_environment/include/planning_environment/monitors/kinematic_model_state_monitor.h
pkg/trunk/motion_planning/planning_environment/src/monitors/kinematic_model_state_monitor.cpp
pkg/trunk/motion_planning/planning_environment/src/monitors/planning_monitor.cpp
Modified: pkg/trunk/motion_planning/planning_environment/include/planning_environment/monitors/kinematic_model_state_monitor.h
===================================================================
--- pkg/trunk/motion_planning/planning_environment/include/planning_environment/monitors/kinematic_model_state_monitor.h 2009-07-31 20:52:46 UTC (rev 20311)
+++ pkg/trunk/motion_planning/planning_environment/include/planning_environment/monitors/kinematic_model_state_monitor.h 2009-07-31 21:02:32 UTC (rev 20312)
@@ -203,9 +203,6 @@
tf::MessageNotifier<mapping_msgs::AttachedObject>
*attachedBodyNotifier_;
- /** \brief How long to wait for a TF if it is not yet available, before failing */
- ros::Duration tfWait_;
-
planning_models::StateParams *robotState_;
tf::Pose pose_;
std::string robot_frame_;
Modified: pkg/trunk/motion_planning/planning_environment/src/monitors/kinematic_model_state_monitor.cpp
===================================================================
--- pkg/trunk/motion_planning/planning_environment/src/monitors/kinematic_model_state_monitor.cpp 2009-07-31 20:52:46 UTC (rev 20311)
+++ pkg/trunk/motion_planning/planning_environment/src/monitors/kinematic_model_state_monitor.cpp 2009-07-31 21:02:32 UTC (rev 20312)
@@ -48,7 +48,6 @@
onStateUpdate_ = NULL;
onAfterAttachBody_ = NULL;
attachedBodyNotifier_ = NULL;
- tfWait_ = ros::Duration(0.1);
havePose_ = haveMechanismState_ = false;
if (rm_->loadedModels())
Modified: pkg/trunk/motion_planning/planning_environment/src/monitors/planning_monitor.cpp
===================================================================
--- pkg/trunk/motion_planning/planning_environment/src/monitors/planning_monitor.cpp 2009-07-31 20:52:46 UTC (rev 20311)
+++ pkg/trunk/motion_planning/planning_environment/src/monitors/planning_monitor.cpp 2009-07-31 21:02:32 UTC (rev 20312)
@@ -94,17 +94,23 @@
for (unsigned int i = 0; i < kc.pose_constraint.size() ; ++i)
{
bool ok = false;
- if (tf_->canTransform(target, kc.pose_constraint[i].pose.header.frame_id, kc.pose_constraint[i].pose.header.stamp, tfWait_))
+
+ unsigned int steps = 0;
+ while (!tf_->canTransform(target, kc.pose_constraint[i].pose.header.frame_id, kc.pose_constraint[i].pose.header.stamp) && steps < 10)
{
- try
- {
- tf_->transformPose(target, kc.pose_constraint[i].pose, kc.pose_constraint[i].pose);
- ok = true;
- }
- catch(...)
- {
- }
+ ros::Duration(0.01).sleep();
+ steps++;
}
+
+ try
+ {
+ tf_->transformPose(target, kc.pose_constraint[i].pose, kc.pose_constraint[i].pose);
+ ok = true;
+ }
+ catch(...)
+ {
+ }
+
if (!ok)
{
ROS_ERROR("Unable to transform pose constraint on link '%s' to frame '%s'", kc.pose_constraint[i].link_name.c_str(), target.c_str());
@@ -202,17 +208,23 @@
pose.stamp_ = header.stamp;
pose.frame_id_ = header.frame_id;
bool ok = false;
- if (tf_->canTransform(target, pose.frame_id_, pose.stamp_, tfWait_))
+
+ unsigned int steps = 0;
+ while (!tf_->canTransform(target, pose.frame_id_, pose.stamp_) && steps < 10)
{
- try
- {
- tf_->transformPose(target, pose, pose);
- ok = true;
- }
- catch(...)
- {
- }
+ ros::Duration(0.01).sleep();
+ steps++;
}
+
+ try
+ {
+ tf_->transformPose(target, pose, pose);
+ ok = true;
+ }
+ catch(...)
+ {
+ }
+
if (!ok)
{
ROS_ERROR("Unable to transform planar joint '%s' to frame '%s'", name.c_str(), target.c_str());
@@ -235,22 +247,29 @@
pose.stamp_ = header.stamp;
pose.frame_id_ = header.frame_id;
bool ok = false;
- if (tf_->canTransform(target, pose.frame_id_, pose.stamp_, tfWait_))
+
+ unsigned int steps = 0;
+ while (!tf_->canTransform(target, pose.frame_id_, pose.stamp_) && steps < 10)
{
- try
- {
- tf_->transformPose(target, pose, pose);
- ok = true;
- }
- catch(...)
- {
- }
+ ros::Duration(0.01).sleep();
+ steps++;
}
+
+ try
+ {
+ tf_->transformPose(target, pose, pose);
+ ok = true;
+ }
+ catch(...)
+ {
+ }
+
if (!ok)
{
ROS_ERROR("Unable to transform floating joint '%s' to frame '%s'", name.c_str(), target.c_str());
return false;
}
+
params[index + 0] = pose.getOrigin().getX();
params[index + 1] = pose.getOrigin().getY();
params[index + 2] = pose.getOrigin().getZ();
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <is...@us...> - 2009-08-04 18:14:52
|
Revision: 20667
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=20667&view=rev
Author: isucan
Date: 2009-08-04 18:14:43 +0000 (Tue, 04 Aug 2009)
Log Message:
-----------
reconstructing objects in map (in addition to collision map)
Modified Paths:
--------------
pkg/trunk/motion_planning/planning_environment/include/planning_environment/monitors/collision_space_monitor.h
pkg/trunk/motion_planning/planning_environment/include/planning_environment/util/construct_object.h
pkg/trunk/motion_planning/planning_environment/src/monitors/collision_space_monitor.cpp
pkg/trunk/motion_planning/planning_environment/src/monitors/kinematic_model_state_monitor.cpp
pkg/trunk/motion_planning/planning_environment/src/tools/clear_known_objects.cpp
pkg/trunk/motion_planning/planning_environment/src/util/construct_object.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-08-04 18:12:57 UTC (rev 20666)
+++ pkg/trunk/motion_planning/planning_environment/include/planning_environment/monitors/collision_space_monitor.h 2009-08-04 18:14:43 UTC (rev 20667)
@@ -145,6 +145,12 @@
/** \brief If the used modified some instance of an environment model, this function provides the means to obtain a collision map (the set of boxes)
* from that environment model */
void recoverCollisionMap(const collision_space::EnvironmentModel *env, mapping_msgs::CollisionMap &cmap);
+
+ /** \brief If the used modified some instance of an
+ environment model, this function provides the means to
+ obtain a set of objects in map (all objects that are not
+ in the namespace the collision map was added to) */
+ void recoverObjectsInMap(const collision_space::EnvironmentModel *env, std::vector<mapping_msgs::ObjectInMap> &omap);
protected:
Modified: pkg/trunk/motion_planning/planning_environment/include/planning_environment/util/construct_object.h
===================================================================
--- pkg/trunk/motion_planning/planning_environment/include/planning_environment/util/construct_object.h 2009-08-04 18:12:57 UTC (rev 20666)
+++ pkg/trunk/motion_planning/planning_environment/include/planning_environment/util/construct_object.h 2009-08-04 18:14:43 UTC (rev 20667)
@@ -43,7 +43,8 @@
namespace planning_environment
{
- shapes::Shape* construct_object(const mapping_msgs::Object &obj);
+ shapes::Shape* constructObject(const mapping_msgs::Object &obj);
+ bool constructObjectMsg(const shapes::Shape* shape, mapping_msgs::Object &obj);
}
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-08-04 18:12:57 UTC (rev 20666)
+++ pkg/trunk/motion_planning/planning_environment/src/monitors/collision_space_monitor.cpp 2009-08-04 18:14:43 UTC (rev 20667)
@@ -40,6 +40,7 @@
#include <geometry_msgs/PoseStamped.h>
#include <boost/bind.hpp>
#include <climits>
+#include <sstream>
namespace planning_environment
{
@@ -296,7 +297,7 @@
if (objectInMap->action == mapping_msgs::ObjectInMap::ADD)
{
// add the object to the map
- shapes::Shape *shape = construct_object(objectInMap->object);
+ shapes::Shape *shape = constructObject(objectInMap->object);
if (shape)
{
bool err = false;
@@ -396,3 +397,40 @@
cmap.boxes.push_back(obb);
}
}
+
+void planning_environment::CollisionSpaceMonitor::recoverObjectsInMap(const collision_space::EnvironmentModel *env, std::vector<mapping_msgs::ObjectInMap> &omap)
+{
+ omap.clear();
+ const collision_space::EnvironmentObjects *eo = env->getObjects();
+ std::vector<std::string> ns = eo->getNamespaces();
+ for (unsigned int i = 0 ; i < ns.size() ; ++i)
+ {
+ if (ns[i] == "points")
+ continue;
+ const collision_space::EnvironmentObjects::NamespaceObjects &no = eo->getObjects(ns[i]);
+ const unsigned int n = no.shape.size();
+
+ for (unsigned int j = 0 ; j < n ; ++j)
+ {
+ mapping_msgs::Object obj;
+ if (constructObjectMsg(no.shape[j], obj))
+ {
+ mapping_msgs::ObjectInMap o;
+ o.header.frame_id = getFrameId();
+ o.header.stamp = lastMapUpdate();
+ if (n == 1)
+ o.id = ns[i];
+ else
+ {
+ std::stringstream ss(ns[i]);
+ ss << "-" << j;
+ o.id = ss.str();
+ }
+ o.action = mapping_msgs::ObjectInMap::ADD;
+ o.object = obj;
+ tf::poseTFToMsg(no.shapePose[j], o.pose);
+ omap.push_back(o);
+ }
+ }
+ }
+}
Modified: pkg/trunk/motion_planning/planning_environment/src/monitors/kinematic_model_state_monitor.cpp
===================================================================
--- pkg/trunk/motion_planning/planning_environment/src/monitors/kinematic_model_state_monitor.cpp 2009-08-04 18:12:57 UTC (rev 20666)
+++ pkg/trunk/motion_planning/planning_environment/src/monitors/kinematic_model_state_monitor.cpp 2009-08-04 18:14:43 UTC (rev 20667)
@@ -257,7 +257,7 @@
if (err)
continue;
- shapes::Shape *shape = construct_object(attachedObject->objects[i]);
+ shapes::Shape *shape = constructObject(attachedObject->objects[i]);
if (!shape)
continue;
Modified: pkg/trunk/motion_planning/planning_environment/src/tools/clear_known_objects.cpp
===================================================================
--- pkg/trunk/motion_planning/planning_environment/src/tools/clear_known_objects.cpp 2009-08-04 18:12:57 UTC (rev 20666)
+++ pkg/trunk/motion_planning/planning_environment/src/tools/clear_known_objects.cpp 2009-08-04 18:14:43 UTC (rev 20667)
@@ -268,7 +268,7 @@
if (objectInMap->action == mapping_msgs::ObjectInMap::ADD)
{
// add the object to the map
- shapes::Shape *shape = planning_environment::construct_object(objectInMap->object);
+ shapes::Shape *shape = planning_environment::constructObject(objectInMap->object);
if (shape)
{
bool err = false;
Modified: pkg/trunk/motion_planning/planning_environment/src/util/construct_object.cpp
===================================================================
--- pkg/trunk/motion_planning/planning_environment/src/util/construct_object.cpp 2009-08-04 18:12:57 UTC (rev 20666)
+++ pkg/trunk/motion_planning/planning_environment/src/util/construct_object.cpp 2009-08-04 18:14:43 UTC (rev 20667)
@@ -37,7 +37,7 @@
#include "planning_environment/util/construct_object.h"
#include <ros/console.h>
-shapes::Shape* planning_environment::construct_object(const mapping_msgs::Object &obj)
+shapes::Shape* planning_environment::constructObject(const mapping_msgs::Object &obj)
{
shapes::Shape *shape = NULL;
if (obj.type == mapping_msgs::Object::SPHERE)
@@ -96,3 +96,58 @@
return shape;
}
+bool planning_environment::constructObjectMsg(const shapes::Shape* shape, mapping_msgs::Object &obj)
+{
+ obj.dimensions.clear();
+ obj.vertices.clear();
+ obj.triangles.clear();
+ if (shape->type == shapes::SPHERE)
+ {
+ obj.type = mapping_msgs::Object::SPHERE;
+ obj.dimensions.push_back(static_cast<const shapes::Sphere*>(shape)->radius);
+ }
+ else
+ if (shape->type == shapes::BOX)
+ {
+ obj.type = mapping_msgs::Object::BOX;
+ const double* sz = static_cast<const shapes::Box*>(shape)->size;
+ obj.dimensions.push_back(sz[0]);
+ obj.dimensions.push_back(sz[1]);
+ obj.dimensions.push_back(sz[2]);
+ }
+ else
+ if (shape->type == shapes::CYLINDER)
+ {
+ obj.type = mapping_msgs::Object::CYLINDER;
+ obj.dimensions.push_back(static_cast<const shapes::Cylinder*>(shape)->radius);
+ obj.dimensions.push_back(static_cast<const shapes::Cylinder*>(shape)->length);
+ }
+ else
+ if (shape->type == shapes::MESH)
+ {
+ const shapes::Mesh *mesh = static_cast<const shapes::Mesh*>(shape);
+ const unsigned int t3 = mesh->triangleCount * 3;
+
+ obj.vertices.resize(mesh->vertexCount);
+ obj.triangles.resize(t3);
+
+ for (unsigned int i = 0 ; i < mesh->vertexCount ; ++i)
+ {
+ obj.vertices[i].x = mesh->vertices[3 * i ];
+ obj.vertices[i].y = mesh->vertices[3 * i + 1];
+ obj.vertices[i].z = mesh->vertices[3 * i + 2];
+ }
+
+ for (unsigned int i = 0 ; i < t3 ; ++i)
+ obj.triangles[i] = mesh->triangles[i];
+ }
+ else
+ {
+ ROS_ERROR("Unable to construct object message for shape of type %d", (int)shape->type);
+ return false;
+ }
+
+ return true;
+}
+
+
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <mr...@us...> - 2009-08-07 00:40:51
|
Revision: 20965
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=20965&view=rev
Author: mrinal
Date: 2009-08-07 00:40:42 +0000 (Fri, 07 Aug 2009)
Log Message:
-----------
printing routines (ioan)
Modified Paths:
--------------
pkg/trunk/motion_planning/planning_environment/include/planning_environment/monitors/planning_monitor.h
pkg/trunk/motion_planning/planning_environment/src/monitors/planning_monitor.cpp
Modified: pkg/trunk/motion_planning/planning_environment/include/planning_environment/monitors/planning_monitor.h
===================================================================
--- pkg/trunk/motion_planning/planning_environment/include/planning_environment/monitors/planning_monitor.h 2009-08-07 00:38:30 UTC (rev 20964)
+++ pkg/trunk/motion_planning/planning_environment/include/planning_environment/monitors/planning_monitor.h 2009-08-07 00:40:42 UTC (rev 20965)
@@ -41,6 +41,7 @@
#include <motion_planning_msgs/KinematicJoint.h>
#include <motion_planning_msgs/KinematicPath.h>
#include <motion_planning_msgs/KinematicConstraints.h>
+#include <iostream>
namespace planning_environment
{
@@ -121,6 +122,9 @@
return kcGoal_;
}
+ /** \brief Print active constraints */
+ void printConstraints(std::ostream &out = std::cout);
+
/** \brief Clear previously set constraints */
void clearConstraints(void);
@@ -141,6 +145,9 @@
/** \brief Get the set of contacts allowed when collision checking */
const std::vector<collision_space::EnvironmentModel::AllowedContact>& getAllowedContacts(void) const;
+
+ /** \brief Print allowed contacts */
+ void printAllowedContacts(std::ostream &out = std::cout);
/** \brief Clear the set of allowed contacts */
void clearAllowedContacts(void);
Modified: pkg/trunk/motion_planning/planning_environment/src/monitors/planning_monitor.cpp
===================================================================
--- pkg/trunk/motion_planning/planning_environment/src/monitors/planning_monitor.cpp 2009-08-07 00:38:30 UTC (rev 20964)
+++ pkg/trunk/motion_planning/planning_environment/src/monitors/planning_monitor.cpp 2009-08-07 00:40:42 UTC (rev 20965)
@@ -575,6 +575,34 @@
return allowedContacts_;
}
+void planning_environment::PlanningMonitor::printAllowedContacts(std::ostream &out)
+{
+ out << allowedContacts_.size() << " allowed contacts" << std::endl;
+ for (unsigned int i = 0 ; i < allowedContacts_.size() ; ++i)
+ {
+ out << " - allowing contacts up to depth " << allowedContacts_[i].depth << " between links: [";
+ for (unsigned int j = 0 ; j < allowedContacts_[i].links.size() ; ++j)
+ out << allowedContacts_[i].links[j];
+ out << "] and bound " << allowedContacts_[i].bound.get() << std::endl;
+ }
+}
+
+void planning_environment::PlanningMonitor::printConstraints(std::ostream &out)
+{
+ out << "Path constraints:" << std::endl;
+
+ KinematicConstraintEvaluatorSet ks;
+ ks.add(getKinematicModel(), kcPath_.joint_constraint);
+ ks.add(getKinematicModel(), kcPath_.pose_constraint);
+ ks.print(out);
+
+ out << "Goal constraints:" << std::endl;
+ ks.clear();
+ ks.add(getKinematicModel(), kcGoal_.joint_constraint);
+ ks.add(getKinematicModel(), kcGoal_.pose_constraint);
+ ks.print(out);
+}
+
void planning_environment::PlanningMonitor::clearAllowedContacts(void)
{
allowedContacts_.clear();
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <bc...@us...> - 2009-09-01 05:31:12
|
Revision: 23483
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=23483&view=rev
Author: bcohen1
Date: 2009-09-01 05:31:04 +0000 (Tue, 01 Sep 2009)
Log Message:
-----------
added remove_object_example.launch and changed the name of the node in remove_object_example.cpp
Modified Paths:
--------------
pkg/trunk/motion_planning/planning_environment/src/examples/remove_object_example.cpp
Added Paths:
-----------
pkg/trunk/motion_planning/planning_environment/launch/remove_object_example.launch
Added: pkg/trunk/motion_planning/planning_environment/launch/remove_object_example.launch
===================================================================
--- pkg/trunk/motion_planning/planning_environment/launch/remove_object_example.launch (rev 0)
+++ pkg/trunk/motion_planning/planning_environment/launch/remove_object_example.launch 2009-09-01 05:31:04 UTC (rev 23483)
@@ -0,0 +1,10 @@
+<launch>
+ <node pkg="planning_environment" type="remove_object_example" respawn="false" output="screen">
+ <remap from="collision_map" to="collision_map_occ" />
+ <remap from="collision_map_update" to="collision_map_occ_update" />
+ <param name="refresh_interval_collision_map" type="double" value="5.0" />
+ <param name="refresh_interval_kinematic_state" type="double" value="1.0" />
+ <param name="refresh_interval_pose" type="double" value="1.0" />
+ <param name="bounding_planes" type="string" value="0 0 1 -0.01" />
+ </node>
+</launch>
Modified: pkg/trunk/motion_planning/planning_environment/src/examples/remove_object_example.cpp
===================================================================
--- pkg/trunk/motion_planning/planning_environment/src/examples/remove_object_example.cpp 2009-09-01 05:30:18 UTC (rev 23482)
+++ pkg/trunk/motion_planning/planning_environment/src/examples/remove_object_example.cpp 2009-09-01 05:31:04 UTC (rev 23483)
@@ -38,6 +38,8 @@
@b RemoveObjectExample is a node that forwards a collision map after it removes a box from it
+note: remember to remap "collision_map" to the desired collision map to be used by the planning environment. To run this, launch "launch/remove_object_example.launch"
+
**/
#include "planning_environment/monitors/planning_monitor.h"
@@ -125,7 +127,7 @@
int main(int argc, char **argv)
{
- ros::init(argc, argv, "view_state_validity");
+ ros::init(argc, argv, "remove_object_example");
RemoveObjectExample example;
ros::spin();
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <is...@us...> - 2009-09-04 03:09:05
|
Revision: 23810
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=23810&view=rev
Author: isucan
Date: 2009-09-04 03:08:58 +0000 (Fri, 04 Sep 2009)
Log Message:
-----------
switching to message filters instead of message notifier
Modified Paths:
--------------
pkg/trunk/motion_planning/planning_environment/include/planning_environment/monitors/collision_space_monitor.h
pkg/trunk/motion_planning/planning_environment/include/planning_environment/monitors/kinematic_model_state_monitor.h
pkg/trunk/motion_planning/planning_environment/manifest.xml
pkg/trunk/motion_planning/planning_environment/src/monitors/collision_space_monitor.cpp
pkg/trunk/motion_planning/planning_environment/src/monitors/kinematic_model_state_monitor.cpp
pkg/trunk/motion_planning/planning_environment/src/tools/clear_known_objects.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-09-04 02:26:34 UTC (rev 23809)
+++ pkg/trunk/motion_planning/planning_environment/include/planning_environment/monitors/collision_space_monitor.h 2009-09-04 03:08:58 UTC (rev 23810)
@@ -69,12 +69,18 @@
virtual ~CollisionSpaceMonitor(void)
{
- if (objectInMapNotifier_)
- delete objectInMapNotifier_;
- if (collisionMapNotifier_)
- delete collisionMapNotifier_;
- if (collisionMapUpdateNotifier_)
- delete collisionMapUpdateNotifier_;
+ if (objectInMapFilter_)
+ delete objectInMapFilter_;
+ if (objectInMapSubscriber_)
+ delete objectInMapSubscriber_;
+ if (collisionMapFilter_)
+ delete collisionMapFilter_;
+ if (collisionMapSubscriber_)
+ delete collisionMapSubscriber_;
+ if (collisionMapUpdateFilter_)
+ delete collisionMapUpdateFilter_;
+ if (collisionMapUpdateSubscriber_)
+ delete collisionMapUpdateSubscriber_;
}
/** \brief Start the environment monitor. By default, the monitor is started after creation */
@@ -188,10 +194,14 @@
bool haveMap_;
ros::Time lastMapUpdate_;
- tf::MessageNotifier<mapping_msgs::CollisionMap> *collisionMapNotifier_;
- tf::MessageNotifier<mapping_msgs::CollisionMap> *collisionMapUpdateNotifier_;
- tf::MessageNotifier<mapping_msgs::ObjectInMap> *objectInMapNotifier_;
+ message_filters::Subscriber<mapping_msgs::CollisionMap> *collisionMapSubscriber_;
+ tf::MessageFilter<mapping_msgs::CollisionMap> *collisionMapFilter_;
+ message_filters::Subscriber<mapping_msgs::CollisionMap> *collisionMapUpdateSubscriber_;
+ tf::MessageFilter<mapping_msgs::CollisionMap> *collisionMapUpdateFilter_;
+ message_filters::Subscriber<mapping_msgs::ObjectInMap> *objectInMapSubscriber_;
+ tf::MessageFilter<mapping_msgs::ObjectInMap> *objectInMapFilter_;
+
boost::function<void(const mapping_msgs::CollisionMapConstPtr, bool)> onBeforeMapUpdate_;
boost::function<void(const mapping_msgs::CollisionMapConstPtr, bool)> onAfterMapUpdate_;
boost::function<void(const mapping_msgs::ObjectInMapConstPtr)> onObjectInMapUpdate_;
Modified: pkg/trunk/motion_planning/planning_environment/include/planning_environment/monitors/kinematic_model_state_monitor.h
===================================================================
--- pkg/trunk/motion_planning/planning_environment/include/planning_environment/monitors/kinematic_model_state_monitor.h 2009-09-04 02:26:34 UTC (rev 23809)
+++ pkg/trunk/motion_planning/planning_environment/include/planning_environment/monitors/kinematic_model_state_monitor.h 2009-09-04 03:08:58 UTC (rev 23810)
@@ -41,7 +41,8 @@
#include "planning_models/kinematic_state.h"
#include <tf/transform_datatypes.h>
#include <tf/transform_listener.h>
-#include <tf/message_notifier.h>
+#include <tf/message_filter.h>
+#include <message_filters/subscriber.h>
#include <sensor_msgs/JointState.h>
#include <mapping_msgs/AttachedObject.h>
#include <boost/bind.hpp>
@@ -81,8 +82,10 @@
{
if (robotState_)
delete robotState_;
- if (attachedBodyNotifier_)
- delete attachedBodyNotifier_;
+ if (attachedBodyFilter_)
+ delete attachedBodyFilter_;
+ if (attachedBodySubscriber_)
+ delete attachedBodySubscriber_;
}
/** \brief Start the state monitor. By default, the monitor is started after creation */
@@ -208,8 +211,11 @@
ros::Subscriber jointStateSubscriber_;
tf::TransformListener *tf_;
- tf::MessageNotifier<mapping_msgs::AttachedObject>
- *attachedBodyNotifier_;
+ message_filters::Subscriber<mapping_msgs::AttachedObject>
+ *attachedBodySubscriber_;
+
+ tf::MessageFilter<mapping_msgs::AttachedObject>
+ *attachedBodyFilter_;
planning_models::KinematicState *robotState_;
double robotVelocity_;
Modified: pkg/trunk/motion_planning/planning_environment/manifest.xml
===================================================================
--- pkg/trunk/motion_planning/planning_environment/manifest.xml 2009-09-04 02:26:34 UTC (rev 23809)
+++ pkg/trunk/motion_planning/planning_environment/manifest.xml 2009-09-04 03:08:58 UTC (rev 23810)
@@ -12,6 +12,7 @@
<depend package="roscpp" />
<depend package="rosconsole" />
<depend package="tf" />
+ <depend package="message_filters" />
<depend package="angles" />
<depend package="sensor_msgs" />
<depend package="motion_planning_msgs" />
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-09-04 02:26:34 UTC (rev 23809)
+++ pkg/trunk/motion_planning/planning_environment/src/monitors/collision_space_monitor.cpp 2009-09-04 03:08:58 UTC (rev 23810)
@@ -58,10 +58,14 @@
onAfterMapUpdate_ = NULL;
onObjectInMapUpdate_ = NULL;
- collisionMapNotifier_ = NULL;
- collisionMapUpdateNotifier_ = NULL;
- objectInMapNotifier_ = NULL;
+ collisionMapFilter_ = NULL;
+ collisionMapUpdateFilter_ = NULL;
+ objectInMapFilter_ = NULL;
+ collisionMapSubscriber_ = NULL;
+ collisionMapUpdateSubscriber_ = NULL;
+ objectInMapSubscriber_ = NULL;
+
haveMap_ = false;
collisionSpace_ = cm_->getODECollisionModel().get();
@@ -74,15 +78,21 @@
{
if (envMonitorStarted_)
return;
-
- 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<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());
+ collisionMapSubscriber_ = new message_filters::Subscriber<mapping_msgs::CollisionMap>(nh_, "collision_map", 1);
+ collisionMapFilter_ = new tf::MessageFilter<mapping_msgs::CollisionMap>(*collisionMapSubscriber_, *tf_, getFrameId(), 1);
+ collisionMapFilter_->registerCallback(boost::bind(&CollisionSpaceMonitor::collisionMapCallback, this, _1));
+ ROS_DEBUG("Listening to collision_map using message notifier with target frame %s", collisionMapFilter_->getTargetFramesString().c_str());
- objectInMapNotifier_ = new tf::MessageNotifier<mapping_msgs::ObjectInMap>(*tf_, boost::bind(&CollisionSpaceMonitor::objectInMapCallback, this, _1), "object_in_map", getFrameId(), 1024);
- ROS_DEBUG("Listening to object_in_map using message notifier with target frame %s", collisionMapUpdateNotifier_->getTargetFramesString().c_str());
+ collisionMapUpdateSubscriber_ = new message_filters::Subscriber<mapping_msgs::CollisionMap>(nh_, "collision_map_update", 1);
+ collisionMapUpdateFilter_ = new tf::MessageFilter<mapping_msgs::CollisionMap>(*collisionMapUpdateSubscriber_, *tf_, getFrameId(), 1);
+ collisionMapUpdateFilter_->registerCallback(boost::bind(&CollisionSpaceMonitor::collisionMapUpdateCallback, this, _1));
+ ROS_DEBUG("Listening to collision_map_update using message notifier with target frame %s", collisionMapUpdateFilter_->getTargetFramesString().c_str());
+
+ objectInMapSubscriber_ = new message_filters::Subscriber<mapping_msgs::ObjectInMap>(nh_, "object_in_map", 1024);
+ objectInMapFilter_ = new tf::MessageFilter<mapping_msgs::ObjectInMap>(*objectInMapSubscriber_, *tf_, getFrameId(), 1024);
+ objectInMapFilter_->registerCallback(boost::bind(&CollisionSpaceMonitor::objectInMapCallback, this, _1));
+ ROS_DEBUG("Listening to object_in_map using message notifier with target frame %s", collisionMapUpdateFilter_->getTargetFramesString().c_str());
envMonitorStarted_ = true;
}
@@ -92,14 +102,20 @@
if (!envMonitorStarted_)
return;
- delete collisionMapUpdateNotifier_;
- collisionMapUpdateNotifier_ = NULL;
+ delete collisionMapUpdateFilter_;
+ collisionMapUpdateFilter_ = NULL;
+ delete collisionMapUpdateSubscriber_;
+ collisionMapUpdateSubscriber_ = NULL;
- delete collisionMapNotifier_;
- collisionMapNotifier_ = NULL;
+ delete collisionMapFilter_;
+ collisionMapFilter_ = NULL;
+ delete collisionMapSubscriber_;
+ collisionMapSubscriber_ = NULL;
- delete objectInMapNotifier_;
- objectInMapNotifier_ = NULL;
+ delete objectInMapFilter_;
+ objectInMapFilter_ = NULL;
+ delete objectInMapSubscriber_;
+ objectInMapSubscriber_ = NULL;
ROS_DEBUG("Environment state is no longer being monitored");
Modified: pkg/trunk/motion_planning/planning_environment/src/monitors/kinematic_model_state_monitor.cpp
===================================================================
--- pkg/trunk/motion_planning/planning_environment/src/monitors/kinematic_model_state_monitor.cpp 2009-09-04 02:26:34 UTC (rev 23809)
+++ pkg/trunk/motion_planning/planning_environment/src/monitors/kinematic_model_state_monitor.cpp 2009-09-04 03:08:58 UTC (rev 23810)
@@ -47,7 +47,8 @@
robotState_ = NULL;
onStateUpdate_ = NULL;
onAfterAttachBody_ = NULL;
- attachedBodyNotifier_ = NULL;
+ attachedBodyFilter_ = NULL;
+ attachedBodySubscriber_ = NULL;
havePose_ = haveJointState_ = false;
robotVelocity_ = 0.0;
@@ -94,9 +95,12 @@
jointStateSubscriber_ = nh_.subscribe("joint_states", 1, &KinematicModelStateMonitor::jointStateCallback, this);
ROS_DEBUG("Listening to joint states");
- attachedBodyNotifier_ = new tf::MessageNotifier<mapping_msgs::AttachedObject>(*tf_, boost::bind(&KinematicModelStateMonitor::attachObjectCallback, this, _1), "attach_object", "", 1);
- attachedBodyNotifier_->setTargetFrame(rm_->getCollisionCheckLinks());
- ROS_DEBUG("Listening to attach_object using message notifier with target frame %s", attachedBodyNotifier_->getTargetFramesString().c_str());
+ attachedBodySubscriber_ = new message_filters::Subscriber<mapping_msgs::AttachedObject>(nh_, "attach_object", 1);
+ attachedBodyFilter_ = new tf::MessageFilter<mapping_msgs::AttachedObject>(*attachedBodySubscriber_, *tf_, "", 1);
+ attachedBodyFilter_->setTargetFrames(rm_->getCollisionCheckLinks());
+ attachedBodyFilter_->registerCallback(boost::bind(&KinematicModelStateMonitor::attachObjectCallback, this, _1));
+
+ ROS_DEBUG("Listening to attach_object using message notifier with target frame %s", attachedBodyFilter_->getTargetFramesString().c_str());
}
stateMonitorStarted_ = true;
}
@@ -106,8 +110,11 @@
if (!stateMonitorStarted_)
return;
- delete attachedBodyNotifier_;
- attachedBodyNotifier_ = NULL;
+ delete attachedBodyFilter_;
+ attachedBodyFilter_ = NULL;
+
+ delete attachedBodySubscriber_;
+ attachedBodySubscriber_ = NULL;
jointStateSubscriber_.shutdown();
Modified: pkg/trunk/motion_planning/planning_environment/src/tools/clear_known_objects.cpp
===================================================================
--- pkg/trunk/motion_planning/planning_environment/src/tools/clear_known_objects.cpp 2009-09-04 02:26:34 UTC (rev 23809)
+++ pkg/trunk/motion_planning/planning_environment/src/tools/clear_known_objects.cpp 2009-09-04 03:08:58 UTC (rev 23810)
@@ -46,7 +46,8 @@
#include "planning_environment/util/construct_object.h"
#include <geometric_shapes/bodies.h>
-#include <tf/message_notifier.h>
+#include <tf/message_filter.h>
+#include <message_filters/subscriber.h>
#include <sensor_msgs/PointCloud.h>
#include <geometry_msgs/PoseStamped.h>
#include <mapping_msgs/AttachedObject.h>
@@ -71,23 +72,35 @@
cloudPublisher_ = nh_.advertise<sensor_msgs::PointCloud>("cloud_out", 1);
kmsm_->setOnAfterAttachBodyCallback(boost::bind(&ClearKnownObjects::attachObjectEvent, this, _1));
- cloudNotifier_ = new tf::MessageNotifier<sensor_msgs::PointCloud>(tf_, boost::bind(&ClearKnownObjects::cloudCallback, this, _1), "cloud_in", fixed_frame_, 1);
- objectInMapNotifier_ = new tf::MessageNotifier<mapping_msgs::ObjectInMap>(tf_, boost::bind(&ClearKnownObjects::objectInMapCallback, this, _1), "object_in_map", fixed_frame_, 1024);
+
+ cloudSubscriber_ = new message_filters::Subscriber<sensor_msgs::PointCloud>(nh_, "cloud_in", 1);
+ cloudFilter_ = new tf::MessageFilter<sensor_msgs::PointCloud>(*cloudSubscriber_, tf_, fixed_frame_, 1);
+ cloudFilter_->registerCallback(boost::bind(&ClearKnownObjects::cloudCallback, this, _1));
+
+ objectInMapSubscriber_ = new message_filters::Subscriber<mapping_msgs::ObjectInMap>(nh_, "object_in_map", 1024);
+ objectInMapFilter_ = new tf::MessageFilter<mapping_msgs::ObjectInMap>(*objectInMapSubscriber_, tf_, fixed_frame_, 1024);
+ objectInMapFilter_->registerCallback(boost::bind(&ClearKnownObjects::objectInMapCallback, this, _1));
}
else
{
kmsm_ = NULL;
- cloudNotifier_ = NULL;
- objectInMapNotifier_ = NULL;
+ cloudFilter_ = NULL;
+ cloudSubscriber_ = NULL;
+ objectInMapFilter_ = NULL;
+ objectInMapSubscriber_ = NULL;
}
}
~ClearKnownObjects(void)
{
- if (cloudNotifier_)
- delete cloudNotifier_;
- if (objectInMapNotifier_)
- delete objectInMapNotifier_;
+ if (cloudFilter_)
+ delete cloudFilter_;
+ if (cloudSubscriber_)
+ delete cloudSubscriber_;
+ if (objectInMapFilter_)
+ delete objectInMapFilter_;
+ if (objectInMapSubscriber_)
+ delete objectInMapSubscriber_;
if (kmsm_)
delete kmsm_;
if (rm_)
@@ -361,8 +374,12 @@
tf::TransformListener tf_;
planning_environment::RobotModels *rm_;
planning_environment::KinematicModelStateMonitor *kmsm_;
- tf::MessageNotifier<sensor_msgs::PointCloud> *cloudNotifier_;
- tf::MessageNotifier<mapping_msgs::ObjectInMap> *objectInMapNotifier_;
+
+ message_filters::Subscriber<mapping_msgs::ObjectInMap> *objectInMapSubscriber_;
+ tf::MessageFilter<mapping_msgs::ObjectInMap> *objectInMapFilter_;
+ message_filters::Subscriber<sensor_msgs::PointCloud> *cloudSubscriber_;
+ tf::MessageFilter<sensor_msgs::PointCloud> *cloudFilter_;
+
std::string fixed_frame_;
boost::mutex updateObjects_;
ros::Publisher cloudPublisher_;
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|