|
From: <is...@us...> - 2009-06-05 06:14:50
|
Revision: 16761
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=16761&view=rev
Author: isucan
Date: 2009-06-05 06:14:48 +0000 (Fri, 05 Jun 2009)
Log Message:
-----------
moved some code
Modified Paths:
--------------
pkg/trunk/motion_planning/planning_environment/collision_checks.yaml
pkg/trunk/motion_planning/planning_environment/include/planning_environment/collision_models.h
pkg/trunk/motion_planning/planning_environment/include/planning_environment/robot_models.h
pkg/trunk/motion_planning/planning_environment/src/collision_models.cpp
pkg/trunk/motion_planning/planning_environment/src/robot_models.cpp
Modified: pkg/trunk/motion_planning/planning_environment/collision_checks.yaml
===================================================================
--- pkg/trunk/motion_planning/planning_environment/collision_checks.yaml 2009-06-05 04:34:04 UTC (rev 16760)
+++ pkg/trunk/motion_planning/planning_environment/collision_checks.yaml 2009-06-05 06:14:48 UTC (rev 16761)
@@ -74,3 +74,9 @@
torso_lift_link
base_link
+
+## The padding to be added for the body parts the robot can see
+self_see_padd: 0.1
+
+## The scaling to be considered for the body parts the robot can see
+self_see_scale: 1.0
Modified: pkg/trunk/motion_planning/planning_environment/include/planning_environment/collision_models.h
===================================================================
--- pkg/trunk/motion_planning/planning_environment/include/planning_environment/collision_models.h 2009-06-05 04:34:04 UTC (rev 16760)
+++ pkg/trunk/motion_planning/planning_environment/include/planning_environment/collision_models.h 2009-06-05 06:14:48 UTC (rev 16761)
@@ -69,9 +69,6 @@
{
RobotModels::reload();
ode_collision_model_.reset();
- self_see_links_.clear();
- collision_check_links_.clear();
- self_collision_check_groups_.clear();
loadCollision();
}
@@ -81,32 +78,10 @@
return ode_collision_model_;
}
- const std::vector<std::string> &getCollisionCheckLinks(void) const
- {
- return collision_check_links_;
- }
-
- const std::vector<std::string> &getSelfSeeLinks(void) const
- {
- return self_see_links_;
- }
-
- const std::vector< std::vector<std::string> > &getSelfCollisionGroups(void) const
- {
- return self_collision_check_groups_;
- }
-
protected:
void loadCollision(void);
- void getSelfSeeLinks(std::vector<std::string> &links);
- void getCollisionCheckLinks(std::vector<std::string> &links);
- void getSelfCollisionGroups(std::vector< std::vector<std::string> > &groups);
- std::vector<std::string> self_see_links_;
- std::vector<std::string> collision_check_links_;
- std::vector< std::vector<std::string> > self_collision_check_groups_;
-
boost::shared_ptr<collision_space::EnvironmentModel> ode_collision_model_;
double scale_;
Modified: pkg/trunk/motion_planning/planning_environment/include/planning_environment/robot_models.h
===================================================================
--- pkg/trunk/motion_planning/planning_environment/include/planning_environment/robot_models.h 2009-06-05 04:34:04 UTC (rev 16760)
+++ pkg/trunk/motion_planning/planning_environment/include/planning_environment/robot_models.h 2009-06-05 06:14:48 UTC (rev 16761)
@@ -112,14 +112,35 @@
return planning_groups_;
}
+ const std::vector<std::string> &getCollisionCheckLinks(void) const
+ {
+ return collision_check_links_;
+ }
+
+ const std::vector<std::string> &getSelfSeeLinks(void) const
+ {
+ return self_see_links_;
+ }
+
+ const std::vector< std::vector<std::string> > &getSelfCollisionGroups(void) const
+ {
+ return self_collision_check_groups_;
+ }
+
+ double getSelfSeePadding(void);
+ double getSelfSeeScale(void);
+
std::vector< boost::shared_ptr<PlannerConfig> > getGroupPlannersConfig(const std::string &group);
/** Reload the robot description and recreate the model */
virtual void reload(void)
{
- planning_groups_.clear();
kmodel_.reset();
urdf_.reset();
+ planning_groups_.clear();
+ self_see_links_.clear();
+ collision_check_links_.clear();
+ self_collision_check_groups_.clear();
loadRobot();
}
@@ -128,14 +149,23 @@
void loadRobot(void);
void getPlanningGroups(std::map< std::string, std::vector<std::string> > &groups);
+ void getSelfSeeLinks(std::vector<std::string> &links);
+ void getCollisionCheckLinks(std::vector<std::string> &links);
+ void getSelfCollisionGroups(std::vector< std::vector<std::string> > &groups);
+
+
ros::NodeHandle nh_;
std::string description_;
- std::map< std::string, std::vector<std::string> > planning_groups_;
-
boost::shared_ptr<planning_models::KinematicModel> kmodel_;
boost::shared_ptr<robot_desc::URDF> urdf_;
+
+ std::map< std::string, std::vector<std::string> > planning_groups_;
+ std::vector<std::string> self_see_links_;
+ std::vector<std::string> collision_check_links_;
+ std::vector< std::vector<std::string> > self_collision_check_groups_;
+
};
Modified: pkg/trunk/motion_planning/planning_environment/src/collision_models.cpp
===================================================================
--- pkg/trunk/motion_planning/planning_environment/src/collision_models.cpp 2009-06-05 04:34:04 UTC (rev 16760)
+++ pkg/trunk/motion_planning/planning_environment/src/collision_models.cpp 2009-06-05 06:14:48 UTC (rev 16761)
@@ -55,72 +55,3 @@
ode_collision_model_->unlock();
}
}
-
-void planning_environment::CollisionModels::getSelfSeeLinks(std::vector<std::string> &links)
-{
- std::string link_list;
- nh_.param(description_ + "_collision/self_see", link_list, std::string(""));
- std::stringstream link_list_stream(link_list);
-
- while (link_list_stream.good() && !link_list_stream.eof())
- {
- std::string name;
- link_list_stream >> name;
- if (name.size() == 0)
- continue;
- if (urdf_->getLink(name))
- links.push_back(name);
- else
- ROS_ERROR("Unknown link: '%s'", name.c_str());
- }
-}
-
-void planning_environment::CollisionModels::getCollisionCheckLinks(std::vector<std::string> &links)
-{
- std::string link_list;
- nh_.param(description_ + "_collision/collision_links", link_list, std::string(""));
- std::stringstream link_list_stream(link_list);
-
- while (link_list_stream.good() && !link_list_stream.eof())
- {
- std::string name;
- link_list_stream >> name;
- if (name.size() == 0)
- continue;
- if (urdf_->getLink(name))
- links.push_back(name);
- else
- ROS_ERROR("Unknown link: '%s'", name.c_str());
- }
-}
-
-void planning_environment::CollisionModels::getSelfCollisionGroups(std::vector< std::vector<std::string> > &groups)
-{
- std::string group_list;
- nh_.param(description_ + "_collision/self_collision_groups", group_list, std::string(""));
- std::stringstream group_list_stream(group_list);
- while (group_list_stream.good() && !group_list_stream.eof())
- {
- std::string name;
- std::string group_elems;
- group_list_stream >> name;
- if (name.size() == 0)
- continue;
- nh_.param(description_ + "_collision/" + name, group_elems, std::string(""));
- std::stringstream group_elems_stream(group_elems);
- std::vector<std::string> this_group;
- while (group_elems_stream.good() && !group_elems_stream.eof())
- {
- std::string link_name;
- group_elems_stream >> link_name;
- if (link_name.size() == 0)
- continue;
- if (urdf_->getLink(link_name))
- this_group.push_back(link_name);
- else
- ROS_ERROR("Unknown link: '%s'", link_name.c_str());
- }
- if (this_group.size() > 0)
- groups.push_back(this_group);
- }
-}
Modified: pkg/trunk/motion_planning/planning_environment/src/robot_models.cpp
===================================================================
--- pkg/trunk/motion_planning/planning_environment/src/robot_models.cpp 2009-06-05 04:34:04 UTC (rev 16760)
+++ pkg/trunk/motion_planning/planning_environment/src/robot_models.cpp 2009-06-05 06:14:48 UTC (rev 16761)
@@ -125,3 +125,86 @@
}
return configs;
}
+
+void planning_environment::RobotModels::getSelfSeeLinks(std::vector<std::string> &links)
+{
+ std::string link_list;
+ nh_.param(description_ + "_collision/self_see", link_list, std::string(""));
+ std::stringstream link_list_stream(link_list);
+
+ while (link_list_stream.good() && !link_list_stream.eof())
+ {
+ std::string name;
+ link_list_stream >> name;
+ if (name.size() == 0)
+ continue;
+ if (urdf_->getLink(name))
+ links.push_back(name);
+ else
+ ROS_ERROR("Unknown link: '%s'", name.c_str());
+ }
+}
+
+void planning_environment::RobotModels::getCollisionCheckLinks(std::vector<std::string> &links)
+{
+ std::string link_list;
+ nh_.param(description_ + "_collision/collision_links", link_list, std::string(""));
+ std::stringstream link_list_stream(link_list);
+
+ while (link_list_stream.good() && !link_list_stream.eof())
+ {
+ std::string name;
+ link_list_stream >> name;
+ if (name.size() == 0)
+ continue;
+ if (urdf_->getLink(name))
+ links.push_back(name);
+ else
+ ROS_ERROR("Unknown link: '%s'", name.c_str());
+ }
+}
+
+void planning_environment::RobotModels::getSelfCollisionGroups(std::vector< std::vector<std::string> > &groups)
+{
+ std::string group_list;
+ nh_.param(description_ + "_collision/self_collision_groups", group_list, std::string(""));
+ std::stringstream group_list_stream(group_list);
+ while (group_list_stream.good() && !group_list_stream.eof())
+ {
+ std::string name;
+ std::string group_elems;
+ group_list_stream >> name;
+ if (name.size() == 0)
+ continue;
+ nh_.param(description_ + "_collision/" + name, group_elems, std::string(""));
+ std::stringstream group_elems_stream(group_elems);
+ std::vector<std::string> this_group;
+ while (group_elems_stream.good() && !group_elems_stream.eof())
+ {
+ std::string link_name;
+ group_elems_stream >> link_name;
+ if (link_name.size() == 0)
+ continue;
+ if (urdf_->getLink(link_name))
+ this_group.push_back(link_name);
+ else
+ ROS_ERROR("Unknown link: '%s'", link_name.c_str());
+ }
+ if (this_group.size() > 0)
+ groups.push_back(this_group);
+ }
+}
+
+double planning_environment::RobotModels::getSelfSeePadding(void)
+{
+ double value;
+ nh_.param(description_ + "_collision/self_see_padd", value, 0.0);
+ return value;
+}
+
+double planning_environment::RobotModels::getSelfSeeScale(void)
+{
+ double value;
+ nh_.param(description_ + "_collision/self_see_scale", value, 1.0);
+ return value;
+}
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <is...@us...> - 2009-06-05 20:00:19
|
Revision: 16777
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=16777&view=rev
Author: isucan
Date: 2009-06-05 19:59:14 +0000 (Fri, 05 Jun 2009)
Log Message:
-----------
added runtime test
Modified Paths:
--------------
pkg/trunk/motion_planning/planning_environment/CMakeLists.txt
pkg/trunk/motion_planning/planning_environment/test/test_robot_models.cpp
Modified: pkg/trunk/motion_planning/planning_environment/CMakeLists.txt
===================================================================
--- pkg/trunk/motion_planning/planning_environment/CMakeLists.txt 2009-06-05 19:59:01 UTC (rev 16776)
+++ pkg/trunk/motion_planning/planning_environment/CMakeLists.txt 2009-06-05 19:59:14 UTC (rev 16777)
@@ -3,6 +3,8 @@
rospack(planning_environment)
+set(ROS_BUILD_TYPE Release)
+
rospack_add_library(planning_environment src/robot_models.cpp
src/collision_models.cpp)
Modified: pkg/trunk/motion_planning/planning_environment/test/test_robot_models.cpp
===================================================================
--- pkg/trunk/motion_planning/planning_environment/test/test_robot_models.cpp 2009-06-05 19:59:01 UTC (rev 16776)
+++ pkg/trunk/motion_planning/planning_environment/test/test_robot_models.cpp 2009-06-05 19:59:14 UTC (rev 16777)
@@ -35,18 +35,39 @@
/** \author Ioan Sucan */
#include <planning_environment/robot_models.h>
+#include <ros/time.h>
#include <gtest/gtest.h>
#include <iostream>
#include <sstream>
-TEST(Loading, EmptyRobot)
+TEST(Loading, Simple)
{
planning_environment::RobotModels m("robotdesc/pr2");
EXPECT_TRUE(m.getKinematicModel().get() != NULL);
}
+TEST(ForwardKinematics, RuntimeArm)
+{
+ planning_environment::RobotModels m("robotdesc/pr2");
+ planning_models::KinematicModel* kmodel = m.getKinematicModel().get();
+
+ int gid = kmodel->getGroupID("pr2::right_arm");
+ unsigned int dim = kmodel->getGroupDimension(gid);
+ double params[dim];
+ for (unsigned int i = 0 ; i < dim ; ++i)
+ params[dim] = 0.1;
+ ros::WallTime tm = ros::WallTime::now();
+ const unsigned int NT = 100000;
+ for (unsigned int i = 0 ; i < NT ; ++i)
+ kmodel->computeTransformsGroup(params, gid);
+ double fps = (double)NT / (ros::WallTime::now() - tm).toSec();
+ ROS_ERROR("%f forward kinematics steps per second", fps);
+
+ EXPECT_TRUE(fps > 10000.0);
+}
+
int main(int argc, char **argv)
{
testing::InitGoogleTest(&argc, argv);
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <is...@us...> - 2009-06-09 02:22:57
|
Revision: 16851
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=16851&view=rev
Author: isucan
Date: 2009-06-09 01:41:58 +0000 (Tue, 09 Jun 2009)
Log Message:
-----------
better handling of frame_id
Modified Paths:
--------------
pkg/trunk/motion_planning/planning_environment/include/planning_environment/kinematic_model_state_monitor.h
pkg/trunk/motion_planning/planning_environment/src/kinematic_model_state_monitor.cpp
pkg/trunk/motion_planning/planning_environment/src/robot_models.cpp
Modified: pkg/trunk/motion_planning/planning_environment/include/planning_environment/kinematic_model_state_monitor.h
===================================================================
--- pkg/trunk/motion_planning/planning_environment/include/planning_environment/kinematic_model_state_monitor.h 2009-06-09 01:36:55 UTC (rev 16850)
+++ pkg/trunk/motion_planning/planning_environment/include/planning_environment/kinematic_model_state_monitor.h 2009-06-09 01:41:58 UTC (rev 16851)
@@ -49,7 +49,8 @@
{
/** @b KinematicModelStateMonitor is a class that monitors the robot state for the kinematic model defined in @b RobotModels
-
+ If the pose is not included, the robot state is the frame of the link it attaches to the world. If the pose is included,
+ the frame of the robot is the one in which the pose is published.
<hr>
@section topic ROS topics
@@ -98,6 +99,12 @@
return robotState_;
}
+ /** Return the frame id of the state */
+ const std::string& getFrameId(void) const
+ {
+ return frame_id_;
+ }
+
/** Return true if a pose has been received */
bool havePose(void) const
{
@@ -110,6 +117,18 @@
return haveMechanismState_;
}
+ /** Return the time of the last pose update */
+ const ros::Time& lastPoseUpdate(void) const
+ {
+ return lastPoseUpdate_;
+ }
+
+ /** Return the time of the last state update */
+ const ros::Time& lastStateUpdate(void) const
+ {
+ return lastStateUpdate_;
+ }
+
/** Wait until a pose is received */
void waitForPose(void) const;
@@ -135,8 +154,8 @@
RobotModels *rm_;
bool includePose_;
planning_models::KinematicModel *kmodel_;
- std::vector<std::string> planarJoints_;
- std::vector<std::string> floatingJoints_;
+ std::string planarJoint_;
+ std::string floatingJoint_;
ros::NodeHandle nh_;
ros::Subscriber mechanismStateSubscriber_;
@@ -144,6 +163,8 @@
planning_models::KinematicModel::StateParams *robotState_;
tf::Pose pose_;
+ std::string frame_id_;
+
boost::function<void(void)> onStateUpdate_;
bool havePose_;
Modified: pkg/trunk/motion_planning/planning_environment/src/kinematic_model_state_monitor.cpp
===================================================================
--- pkg/trunk/motion_planning/planning_environment/src/kinematic_model_state_monitor.cpp 2009-06-09 01:36:55 UTC (rev 16850)
+++ pkg/trunk/motion_planning/planning_environment/src/kinematic_model_state_monitor.cpp 2009-06-09 01:41:58 UTC (rev 16851)
@@ -48,16 +48,23 @@
{
kmodel_ = rm_->getKinematicModel().get();
robotState_ = kmodel_->newStateParams();
- robotState_->setInRobotFrame();
- for (unsigned int i = 0 ; i < kmodel_->getModelInfo().floatingJoints.size() ; ++i)
- floatingJoints_.push_back(kmodel_->getModelInfo().parameterName[kmodel_->getModelInfo().floatingJoints[i]]);
- for (unsigned int i = 0 ; i < kmodel_->getModelInfo().planarJoints.size() ; ++i)
- planarJoints_.push_back(kmodel_->getModelInfo().parameterName[kmodel_->getModelInfo().planarJoints[i]]);
-
+ if (kmodel_->getRobotCount() > 1)
+ ROS_WARN("Using more than one robot. A frame_id cannot be set (there multiple frames) and pose cannot be maintained");
+ else
+ {
+ // joints to update based on received pose
+ if (dynamic_cast<planning_models::KinematicModel::PlanarJoint*>(kmodel_->getRobot(0)->chain))
+ planarJoint_ = kmodel_->getRobot(0)->chain->name;
+ if (dynamic_cast<planning_models::KinematicModel::FloatingJoint*>(kmodel_->getRobot(0)->chain))
+ floatingJoint_ = kmodel_->getRobot(0)->chain->name;
+
+ if (includePose_)
+ localizedPoseSubscriber_ = nh_.subscribe("localized_pose", 1, &KinematicModelStateMonitor::localizedPoseCallback, this);
+ else
+ frame_id_ = kmodel_->getRobot(0)->chain->after->name;
+ }
mechanismStateSubscriber_ = nh_.subscribe("mechanism_state", 1, &KinematicModelStateMonitor::mechanismStateCallback, this);
- if (includePose_)
- localizedPoseSubscriber_ = nh_.subscribe("localized_pose", 1, &KinematicModelStateMonitor::localizedPoseCallback, this);
}
}
@@ -94,7 +101,7 @@
first_time = false;
- lastStateUpdate_ = ros::Time::now();
+ lastStateUpdate_ = mechanismState->header.stamp;
if (!haveMechanismState_)
haveMechanismState_ = robotState_->seenAll();
@@ -105,12 +112,13 @@
void planning_environment::KinematicModelStateMonitor::localizedPoseCallback(const robot_msgs::PoseWithCovarianceConstPtr &localizedPose)
{
tf::PoseMsgToTF(localizedPose->pose, pose_);
- lastPoseUpdate_ = ros::Time::now();
-
+ lastPoseUpdate_ = localizedPose->header.stamp;
+ frame_id_ = localizedPose->header.frame_id;
+
bool change = !havePose_;
havePose_ = true;
- if (!planarJoints_.empty())
+ if (!planarJoint_.empty())
{
double planar_joint[3];
planar_joint[0] = pose_.getOrigin().x();
@@ -120,14 +128,11 @@
pose_.getBasis().getEulerZYX(yaw, pitch, roll);
planar_joint[2] = yaw;
- for (unsigned int i = 0 ; i < planarJoints_.size() ; ++i)
- {
- bool this_changed = robotState_->setParamsJoint(planar_joint, planarJoints_[i]);
- change = change || this_changed;
- }
+ bool this_changed = robotState_->setParamsJoint(planar_joint, planarJoint_);
+ change = change || this_changed;
}
- if (!floatingJoints_.empty())
+ if (!floatingJoint_.empty())
{
double floating_joint[7];
floating_joint[0] = pose_.getOrigin().x();
@@ -139,11 +144,8 @@
floating_joint[5] = q.z();
floating_joint[6] = q.w();
- for (unsigned int i = 0 ; i < floatingJoints_.size() ; ++i)
- {
- bool this_changed = robotState_->setParamsJoint(floating_joint, floatingJoints_[i]);
- change = change || this_changed;
- }
+ bool this_changed = robotState_->setParamsJoint(floating_joint, floatingJoint_);
+ change = change || this_changed;
}
if (change && onStateUpdate_ != NULL)
Modified: pkg/trunk/motion_planning/planning_environment/src/robot_models.cpp
===================================================================
--- pkg/trunk/motion_planning/planning_environment/src/robot_models.cpp 2009-06-09 01:36:55 UTC (rev 16850)
+++ pkg/trunk/motion_planning/planning_environment/src/robot_models.cpp 2009-06-09 01:41:58 UTC (rev 16851)
@@ -63,7 +63,7 @@
kmodel_->setVerbose(false);
kmodel_->build(*urdf_, planning_groups_);
- // make sure the kinematic model is in its own frame
+ // make sure the kinematic model is in the frame of the link that connects it to the environment
// (remove all transforms caused by planar or floating
// joints)
kmodel_->reduceToRobotFrame();
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <is...@us...> - 2009-06-09 17:35:37
|
Revision: 16865
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=16865&view=rev
Author: isucan
Date: 2009-06-09 17:35:35 +0000 (Tue, 09 Jun 2009)
Log Message:
-----------
properly dealing with frames for collision maps
Modified Paths:
--------------
pkg/trunk/motion_planning/planning_environment/include/planning_environment/robot_models.h
pkg/trunk/motion_planning/planning_environment/src/collision_space_monitor.cpp
pkg/trunk/motion_planning/planning_environment/src/robot_models.cpp
Modified: pkg/trunk/motion_planning/planning_environment/include/planning_environment/robot_models.h
===================================================================
--- pkg/trunk/motion_planning/planning_environment/include/planning_environment/robot_models.h 2009-06-09 17:34:31 UTC (rev 16864)
+++ pkg/trunk/motion_planning/planning_environment/include/planning_environment/robot_models.h 2009-06-09 17:35:35 UTC (rev 16865)
@@ -68,7 +68,8 @@
}
bool hasParam(const std::string ¶m);
- std::string getParam(const std::string ¶m);
+ std::string getParamString(const std::string ¶m, const std::string &def = "");
+ double getParamDouble(const std::string ¶m, double def);
private:
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-09 17:34:31 UTC (rev 16864)
+++ pkg/trunk/motion_planning/planning_environment/src/collision_space_monitor.cpp 2009-06-09 17:35:35 UTC (rev 16865)
@@ -35,6 +35,7 @@
/** \author Ioan Sucan */
#include "planning_environment/collision_space_monitor.h"
+#include <robot_msgs/PointStamped.h>
namespace planning_environment
{
@@ -73,23 +74,55 @@
void planning_environment::CollisionSpaceMonitor::collisionMapCallback(const robot_msgs::CollisionMapConstPtr &collisionMap)
{
- unsigned int n = collisionMap->get_boxes_size();
- ROS_DEBUG("Received %u points (collision map)", n);
+ int n = collisionMap->get_boxes_size();
+ ROS_DEBUG("Received %d points (collision map)", n);
if (onBeforeMapUpdate_ != NULL)
onBeforeMapUpdate_(collisionMap);
+
+ // we want to make sure the frame the robot model is kept in is the same as the frame of the collisionMap
+ bool transform = !frame_id_.empty() && collisionMap->header.frame_id != frame_id_;
ros::WallTime startTime = ros::WallTime::now();
double *data = new double[4 * n];
- for (unsigned int i = 0 ; i < n ; ++i)
+
+ if (transform)
{
- unsigned int i4 = i * 4;
- data[i4 ] = collisionMap->boxes[i].center.x;
- data[i4 + 1] = collisionMap->boxes[i].center.y;
- data[i4 + 2] = collisionMap->boxes[i].center.z;
+ std::string target = frame_id_;
- data[i4 + 3] = radiusOfBox(collisionMap->boxes[i].extents);
+#pragma omp parallel for
+ for (int i = 0 ; i < n ; ++i)
+ {
+ int i4 = i * 4;
+ robot_msgs::PointStamped psi;
+ psi.header = collisionMap->header;
+ psi.point.x = collisionMap->boxes[i].center.x;
+ psi.point.y = collisionMap->boxes[i].center.y;
+ psi.point.z = collisionMap->boxes[i].center.z;
+
+ robot_msgs::PointStamped pso;
+ tf_.transformPoint(target, psi, pso);
+
+ data[i4 ] = pso.point.x;
+ data[i4 + 1] = pso.point.y;
+ data[i4 + 2] = pso.point.z;
+
+ data[i4 + 3] = radiusOfBox(collisionMap->boxes[i].extents);
+ }
}
+ else
+ {
+#pragma omp parallel for
+ for (int i = 0 ; i < n ; ++i)
+ {
+ int i4 = i * 4;
+ data[i4 ] = collisionMap->boxes[i].center.x;
+ data[i4 + 1] = collisionMap->boxes[i].center.y;
+ data[i4 + 2] = collisionMap->boxes[i].center.z;
+
+ data[i4 + 3] = radiusOfBox(collisionMap->boxes[i].extents);
+ }
+ }
collisionSpace_->lock();
collisionSpace_->clearObstacles();
Modified: pkg/trunk/motion_planning/planning_environment/src/robot_models.cpp
===================================================================
--- pkg/trunk/motion_planning/planning_environment/src/robot_models.cpp 2009-06-09 17:34:31 UTC (rev 16864)
+++ pkg/trunk/motion_planning/planning_environment/src/robot_models.cpp 2009-06-09 17:35:35 UTC (rev 16865)
@@ -37,6 +37,8 @@
#include "planning_environment/robot_models.h"
#include <planning_models/output.h>
#include <ros/console.h>
+
+#include <boost/algorithm/string.hpp>
#include <sstream>
// make sure messages from planning_environments & collision_space go to ROS console
@@ -162,13 +164,21 @@
return nh_.hasParam(description_ + "_planning/planner_configs/" + config_ + "/" + param);
}
-std::string planning_environment::RobotModels::PlannerConfig::getParam(const std::string ¶m)
+std::string planning_environment::RobotModels::PlannerConfig::getParamString(const std::string ¶m, const std::string& def)
{
std::string value;
- nh_.param(description_ + "_planning/planner_configs/" + config_ + "/" + param, value, std::string(""));
+ nh_.param(description_ + "_planning/planner_configs/" + config_ + "/" + param, value, def);
+ boost::trim(value);
return value;
}
+double planning_environment::RobotModels::PlannerConfig::getParamDouble(const std::string ¶m, double def)
+{
+ double 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-06-13 04:43:54
|
Revision: 17061
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=17061&view=rev
Author: isucan
Date: 2009-06-13 04:43:52 +0000 (Sat, 13 Jun 2009)
Log Message:
-----------
checking of paths and states for validity; this does not depend on any type of planning
Modified Paths:
--------------
pkg/trunk/motion_planning/planning_environment/CMakeLists.txt
pkg/trunk/motion_planning/planning_environment/include/planning_environment/kinematic_state_constraint_evaluator.h
pkg/trunk/motion_planning/planning_environment/src/kinematic_state_constraint_evaluator.cpp
Added Paths:
-----------
pkg/trunk/motion_planning/planning_environment/include/planning_environment/planning_monitor.h
pkg/trunk/motion_planning/planning_environment/src/planning_monitor.cpp
Modified: pkg/trunk/motion_planning/planning_environment/CMakeLists.txt
===================================================================
--- pkg/trunk/motion_planning/planning_environment/CMakeLists.txt 2009-06-13 02:30:38 UTC (rev 17060)
+++ pkg/trunk/motion_planning/planning_environment/CMakeLists.txt 2009-06-13 04:43:52 UTC (rev 17061)
@@ -9,7 +9,8 @@
src/collision_models.cpp
src/kinematic_model_state_monitor.cpp
src/collision_space_monitor.cpp
- src/kinematic_state_constraint_evaluator.cpp)
+ src/kinematic_state_constraint_evaluator.cpp
+ src/planning_monitor.cpp)
#rospack_add_openmp_flags(planning_environment)
# Tests
Modified: pkg/trunk/motion_planning/planning_environment/include/planning_environment/kinematic_state_constraint_evaluator.h
===================================================================
--- pkg/trunk/motion_planning/planning_environment/include/planning_environment/kinematic_state_constraint_evaluator.h 2009-06-13 02:30:38 UTC (rev 17060)
+++ pkg/trunk/motion_planning/planning_environment/include/planning_environment/kinematic_state_constraint_evaluator.h 2009-06-13 04:43:52 UTC (rev 17061)
@@ -68,6 +68,9 @@
/** Decide whether the constraint is satisfied. The kinematic model is assumed to be at the state we want to decide. */
virtual bool decide(const double *params, const int groupID) const = 0;
+ /** Decide whether the constraint is satisfied. The kinematic model is assumed to be at the state we want to decide. */
+ virtual bool decide(const double *params) const;
+
/** Print the constraint data */
virtual void print(std::ostream &out = std::cout) const
{
@@ -183,6 +186,9 @@
/** Decide whether the set of constraints is satisfied */
bool decide(const double *params, int groupID) const;
+ /** Decide whether the set of constraints is satisfied */
+ bool decide(const double *params) const;
+
/** Print the constraint data */
void print(std::ostream &out = std::cout) const;
Added: pkg/trunk/motion_planning/planning_environment/include/planning_environment/planning_monitor.h
===================================================================
--- pkg/trunk/motion_planning/planning_environment/include/planning_environment/planning_monitor.h (rev 0)
+++ pkg/trunk/motion_planning/planning_environment/include/planning_environment/planning_monitor.h 2009-06-13 04:43:52 UTC (rev 17061)
@@ -0,0 +1,94 @@
+/*********************************************************************
+* Software License Agreement (BSD License)
+*
+* Copyright (c) 2008, Willow Garage, Inc.
+* All rights reserved.
+*
+* Redistribution and use in source and binary forms, with or without
+* modification, are permitted provided that the following conditions
+* are met:
+*
+* * Redistributions of source code must retain the above copyright
+* notice, this list of conditions and the following disclaimer.
+* * Redistributions in binary form must reproduce the above
+* copyright notice, this list of conditions and the following
+* disclaimer in the documentation and/or other materials provided
+* with the distribution.
+* * Neither the name of the Willow Garage nor the names of its
+* contributors may be used to endorse or promote products derived
+* from this software without specific prior written permission.
+*
+* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
+* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
+* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+* POSSIBILITY OF SUCH DAMAGE.
+*********************************************************************/
+
+/** \author Ioan Sucan */
+
+#ifndef PLANNING_ENVIRONMENT_PLANNING_MONITOR_
+#define PLANNING_ENVIRONMENT_PLANNING_MONITOR_
+
+#include "planning_environment/collision_space_monitor.h"
+#include <motion_planning_msgs/KinematicPath.h>
+#include <motion_planning_msgs/KinematicConstraints.h>
+
+namespace planning_environment
+{
+
+ /** @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:
+
+ PlanningMonitor(CollisionModels *cm, std::string frame_id) : CollisionSpaceMonitor(static_cast<CollisionModels*>(cm), frame_id)
+ {
+ }
+
+ PlanningMonitor(CollisionModels *cm) : CollisionSpaceMonitor(static_cast<CollisionModels*>(cm))
+ {
+ }
+
+ virtual ~PlanningMonitor(void)
+ {
+ }
+
+ /** Check if the full state of the robot is valid */
+ bool isStateValidOnPath(const planning_models::KinematicModel::StateParams *state) const;
+
+ /** Check if the full state of the robot is valid */
+ bool isStateValidAtGoal(const planning_models::KinematicModel::StateParams *state) const;
+
+ /** Check if the path is valid */
+ bool isPathValid(const motion_planning_msgs::KinematicPath &path);
+
+ /** Set the kinematic constraints the monitor should use when checking a path */
+ void setPathConstraints(const motion_planning_msgs::KinematicConstraints &kc);
+
+ /** Set the kinematic constraints the monitor should use when checking a path's last state (the goal) */
+ void setGoalConstraints(const motion_planning_msgs::KinematicConstraints &kc);
+
+ protected:
+
+ void bringConstraintsToModelFrame(motion_planning_msgs::KinematicConstraints &kc);
+
+ motion_planning_msgs::KinematicConstraints kcPath_;
+ motion_planning_msgs::KinematicConstraints kcGoal_;
+ };
+
+
+}
+
+#endif
Modified: pkg/trunk/motion_planning/planning_environment/src/kinematic_state_constraint_evaluator.cpp
===================================================================
--- pkg/trunk/motion_planning/planning_environment/src/kinematic_state_constraint_evaluator.cpp 2009-06-13 02:30:38 UTC (rev 17060)
+++ pkg/trunk/motion_planning/planning_environment/src/kinematic_state_constraint_evaluator.cpp 2009-06-13 04:43:52 UTC (rev 17061)
@@ -38,6 +38,11 @@
#include <tf/transform_datatypes.h>
#include <cassert>
+bool planning_environment::KinematicConstraintEvaluator::decide(const double *params) const
+{
+ return decide(params, -1);
+}
+
bool planning_environment::JointConstraintEvaluator::use(const planning_models::KinematicModel *kmodel, const ros::Message *kc)
{
const motion_planning_msgs::JointConstraint *jc = dynamic_cast<const motion_planning_msgs::JointConstraint*>(kc);
@@ -54,10 +59,10 @@
m_jc = jc;
return true;
}
-
+
bool planning_environment::JointConstraintEvaluator::decide(const double *params, const int groupID) const
{
- const double *val = params + m_kmodel->getJointIndexInGroup(m_joint->name, groupID);
+ const double *val = params + (groupID >= 0 ? m_kmodel->getJointIndexInGroup(m_joint->name, groupID) : m_kmodel->getJointIndex(m_joint->name));
assert(m_jc.value.size() == m_jc.toleranceBelow.size() && m_jc.value.size() == m_jc.toleranceAbove.size());
for (unsigned int i = 0 ; i < m_jc.value.size() ; ++i)
@@ -385,6 +390,11 @@
return true;
}
+bool planning_environment::KinematicConstraintEvaluatorSet::decide(const double *params) const
+{
+ return decide(params, -1);
+}
+
void planning_environment::KinematicConstraintEvaluatorSet::print(std::ostream &out) const
{
out << m_kce.size() << " kinematic constraints" << std::endl;
Added: pkg/trunk/motion_planning/planning_environment/src/planning_monitor.cpp
===================================================================
--- pkg/trunk/motion_planning/planning_environment/src/planning_monitor.cpp (rev 0)
+++ pkg/trunk/motion_planning/planning_environment/src/planning_monitor.cpp 2009-06-13 04:43:52 UTC (rev 17061)
@@ -0,0 +1,177 @@
+/*********************************************************************
+* Software License Agreement (BSD License)
+*
+* Copyright (c) 2008, Willow Garage, Inc.
+* All rights reserved.
+*
+* Redistribution and use in source and binary forms, with or without
+* modification, are permitted provided that the following conditions
+* are met:
+*
+* * Redistributions of source code must retain the above copyright
+* notice, this list of conditions and the following disclaimer.
+* * Redistributions in binary form must reproduce the above
+* copyright notice, this list of conditions and the following
+* disclaimer in the documentation and/or other materials provided
+* with the distribution.
+* * Neither the name of the Willow Garage nor the names of its
+* contributors may be used to endorse or promote products derived
+* from this software without specific prior written permission.
+*
+* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
+* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
+* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+* POSSIBILITY OF SUCH DAMAGE.
+*********************************************************************/
+
+/** \author Ioan Sucan */
+
+#include "planning_environment/planning_monitor.h"
+#include "planning_environment/kinematic_state_constraint_evaluator.h"
+
+void planning_environment::PlanningMonitor::setPathConstraints(const motion_planning_msgs::KinematicConstraints &kc)
+{
+ kcPath_ = kc;
+ bringConstraintsToModelFrame(kcPath_);
+}
+
+void planning_environment::PlanningMonitor::setGoalConstraints(const motion_planning_msgs::KinematicConstraints &kc)
+{
+ kcGoal_ = kc;
+ bringConstraintsToModelFrame(kcPath_);
+}
+
+void planning_environment::PlanningMonitor::bringConstraintsToModelFrame(motion_planning_msgs::KinematicConstraints &kc)
+{
+ for (unsigned int i = 0; i < kc.pose.size() ; ++i)
+ tf_->transformPose(getFrameId(), kc.pose[i].pose, kc.pose[i].pose);
+}
+
+bool planning_environment::PlanningMonitor::isStateValidOnPath(const planning_models::KinematicModel::StateParams *state) const
+{
+ getEnvironmentModel()->lock();
+ getKinematicModel()->lock();
+
+ // figure out the poses of the robot model
+ getKinematicModel()->computeTransforms(state->getParams());
+ // update the collision space
+ getEnvironmentModel()->updateRobotModel();
+
+ // check for collision
+ bool valid = !getEnvironmentModel()->isCollision();
+
+ if (valid)
+ {
+ KinematicConstraintEvaluatorSet ks;
+ ks.add(getKinematicModel(), kcPath_.joint);
+ ks.add(getKinematicModel(), kcPath_.pose);
+ valid = ks.decide(state->getParams());
+ }
+
+ getKinematicModel()->unlock();
+ getEnvironmentModel()->unlock();
+
+ return valid;
+}
+
+bool planning_environment::PlanningMonitor::isStateValidAtGoal(const planning_models::KinematicModel::StateParams *state) const
+{
+ getEnvironmentModel()->lock();
+ getKinematicModel()->lock();
+
+ // figure out the poses of the robot model
+ getKinematicModel()->computeTransforms(state->getParams());
+ // update the collision space
+ getEnvironmentModel()->updateRobotModel();
+
+ // check for collision
+ bool valid = !getEnvironmentModel()->isCollision();
+
+ if (valid)
+ {
+ KinematicConstraintEvaluatorSet ks;
+ ks.add(getKinematicModel(), kcPath_.joint);
+ ks.add(getKinematicModel(), kcPath_.pose);
+ ks.add(getKinematicModel(), kcGoal_.joint);
+ ks.add(getKinematicModel(), kcGoal_.pose);
+ valid = ks.decide(state->getParams());
+ }
+
+ getKinematicModel()->unlock();
+ getEnvironmentModel()->unlock();
+
+ return valid;
+}
+
+bool planning_environment::PlanningMonitor::isPathValid(const motion_planning_msgs::KinematicPath &path)
+{
+ planning_models::KinematicModel::StateParams *sp = getKinematicModel()->newStateParams();
+ sp->setParams(path.start_state.vals);
+
+ KinematicConstraintEvaluatorSet ks;
+ ks.add(getKinematicModel(), kcPath_.joint);
+ ks.add(getKinematicModel(), kcPath_.pose);
+
+ getEnvironmentModel()->lock();
+ getKinematicModel()->lock();
+
+ // figure out the poses of the robot model
+ getKinematicModel()->computeTransforms(sp->getParams());
+ // update the collision space
+ getEnvironmentModel()->updateRobotModel();
+
+ bool valid = true;
+
+ // 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]);
+
+ // check every state
+ for (unsigned int i = 0 ; valid && i < path.states.size() ; ++i)
+ {
+ unsigned int u = 0;
+ for (unsigned int j = 0 ; j < joints.size() ; ++j)
+ {
+ /* copy the parameters that describe the joint */
+ std::vector<double> params;
+ for (unsigned int k = 0 ; k < joints[j]->usedParams ; ++k)
+ params.push_back(path.states[i].vals[u + k]);
+ u += joints[j]->usedParams;
+
+ /* set the parameters */
+ sp->setParamsJoint(params, joints[j]->name);
+ }
+ getKinematicModel()->computeTransforms(sp->getParams());
+ getEnvironmentModel()->updateRobotModel();
+
+ // check for collision
+ valid = !getEnvironmentModel()->isCollision();
+
+ // check for validity
+ if (valid)
+ valid = ks.decide(sp->getParams());
+ }
+
+ // if we got to the last state, we also check the goal constraints
+ if (valid)
+ {
+ ks.add(getKinematicModel(), kcGoal_.joint);
+ ks.add(getKinematicModel(), kcGoal_.pose);
+ valid = ks.decide(sp->getParams());
+ }
+
+ getKinematicModel()->unlock();
+ getEnvironmentModel()->unlock();
+
+ delete sp;
+ return valid;
+}
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <is...@us...> - 2009-06-14 05:43:25
|
Revision: 17067
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=17067&view=rev
Author: isucan
Date: 2009-06-14 05:43:22 +0000 (Sun, 14 Jun 2009)
Log Message:
-----------
monitor position on path
Modified Paths:
--------------
pkg/trunk/motion_planning/planning_environment/include/planning_environment/planning_monitor.h
pkg/trunk/motion_planning/planning_environment/src/planning_monitor.cpp
Modified: pkg/trunk/motion_planning/planning_environment/include/planning_environment/planning_monitor.h
===================================================================
--- pkg/trunk/motion_planning/planning_environment/include/planning_environment/planning_monitor.h 2009-06-14 01:14:02 UTC (rev 17066)
+++ pkg/trunk/motion_planning/planning_environment/include/planning_environment/planning_monitor.h 2009-06-14 05:43:22 UTC (rev 17067)
@@ -72,8 +72,11 @@
bool isStateValidAtGoal(const planning_models::KinematicModel::StateParams *state) const;
/** Check if the path is valid */
- bool isPathValid(const motion_planning_msgs::KinematicPath &path);
+ bool isPathValid(const motion_planning_msgs::KinematicPath &path) const;
+ /** Return the index of the state on the path that is closest to the current state */
+ unsigned int positionOnPath(const motion_planning_msgs::KinematicPath &path) const;
+
/** Set the kinematic constraints the monitor should use when checking a path */
void setPathConstraints(const motion_planning_msgs::KinematicConstraints &kc);
@@ -81,18 +84,18 @@
void setGoalConstraints(const motion_planning_msgs::KinematicConstraints &kc);
/** Transform the frames in which constraints are specified to the one requested */
- void transformConstraintsToFrame(motion_planning_msgs::KinematicConstraints &kc, const std::string &target);
+ void transformConstraintsToFrame(motion_planning_msgs::KinematicConstraints &kc, const std::string &target) const;
/** Transform the kinematic path to the frame requested */
- void transformPathToFrame(motion_planning_msgs::KinematicPath &kp, const std::string &target);
+ void transformPathToFrame(motion_planning_msgs::KinematicPath &kp, const std::string &target) const;
protected:
/** Transform the joint parameters (if needed) to a target frame */
- void transformJoint(const std::string &name, unsigned int index, std::vector<double> ¶ms, roslib::Header &header, const std::string& target);
+ void transformJoint(const std::string &name, unsigned int index, std::vector<double> ¶ms, roslib::Header &header, const std::string& target) const;
/** Check the path assuming it is in the frame of the model */
- bool isPathValidAux(const motion_planning_msgs::KinematicPath &path);
+ bool isPathValidAux(const motion_planning_msgs::KinematicPath &path) const;
motion_planning_msgs::KinematicConstraints kcPath_;
motion_planning_msgs::KinematicConstraints kcGoal_;
Modified: pkg/trunk/motion_planning/planning_environment/src/planning_monitor.cpp
===================================================================
--- pkg/trunk/motion_planning/planning_environment/src/planning_monitor.cpp 2009-06-14 01:14:02 UTC (rev 17066)
+++ pkg/trunk/motion_planning/planning_environment/src/planning_monitor.cpp 2009-06-14 05:43:22 UTC (rev 17067)
@@ -49,7 +49,7 @@
transformConstraintsToFrame(kcPath_, getFrameId());
}
-void planning_environment::PlanningMonitor::transformConstraintsToFrame(motion_planning_msgs::KinematicConstraints &kc, const std::string &target)
+void planning_environment::PlanningMonitor::transformConstraintsToFrame(motion_planning_msgs::KinematicConstraints &kc, const std::string &target) const
{
for (unsigned int i = 0; i < kc.pose.size() ; ++i)
tf_->transformPose(target, kc.pose[i].pose, kc.pose[i].pose);
@@ -62,7 +62,7 @@
}
}
-void planning_environment::PlanningMonitor::transformPathToFrame(motion_planning_msgs::KinematicPath &kp, const std::string &target)
+void planning_environment::PlanningMonitor::transformPathToFrame(motion_planning_msgs::KinematicPath &kp, const std::string &target) const
{
// if there are no planar of floating transforms, there is nothing to do
if (getKinematicModel()->getModelInfo().planarJoints.empty() && getKinematicModel()->getModelInfo().floatingJoints.empty())
@@ -107,7 +107,7 @@
kp.header = updatedHeader;
}
-void planning_environment::PlanningMonitor::transformJoint(const std::string &name, unsigned int index, std::vector<double> ¶ms, roslib::Header &header, const std::string& target)
+void planning_environment::PlanningMonitor::transformJoint(const std::string &name, unsigned int index, std::vector<double> ¶ms, roslib::Header &header, const std::string& target) const
{
// planar joints and floating joints may need to be transformed
planning_models::KinematicModel::Joint *joint = getKinematicModel()->getJoint(name);
@@ -206,10 +206,54 @@
return valid;
}
-bool planning_environment::PlanningMonitor::isPathValid(const motion_planning_msgs::KinematicPath &path)
+unsigned int planning_environment::PlanningMonitor::positionOnPath(const motion_planning_msgs::KinematicPath &path) const
{
+ std::vector<double> current;
+ getRobotState()->copyParamsGroup(current, path.model_id);
+
+ // convert current state to path frame
if (path.header.frame_id != getFrameId())
{
+ roslib::Header header;
+ header.stamp = lastStateUpdate();
+ header.frame_id = getFrameId();
+
+ std::vector<planning_models::KinematicModel::Joint*> joints;
+ joints.resize(path.names.size());
+ for (unsigned int j = 0 ; j < joints.size() ; ++j)
+ joints[j] = getKinematicModel()->getJoint(path.names[j]);
+
+ unsigned int u = 0;
+ for (unsigned int j = 0 ; j < joints.size() ; ++j)
+ {
+ roslib::Header h = header;
+ transformJoint(joints[j]->name, u, current, h, path.header.frame_id);
+ u += joints[j]->usedParams;
+ }
+ }
+
+ unsigned int p = 0;
+ double bestDif = -1.0;
+
+ for (unsigned int i = 0 ; i < path.states.size() ; ++i)
+ {
+ double sum = 0.0;
+ for (unsigned int j = 0 ; j < current.size() ; ++j)
+ sum += fabs(path.states[i].vals[j] - current[j]);
+ if (sum < bestDif || bestDif < 0.0)
+ {
+ p = i;
+ bestDif = sum;
+ }
+ }
+
+ return p;
+}
+
+bool planning_environment::PlanningMonitor::isPathValid(const motion_planning_msgs::KinematicPath &path) const
+{
+ if (path.header.frame_id != getFrameId())
+ {
motion_planning_msgs::KinematicPath pathT = path;
transformPathToFrame(pathT, getFrameId());
return isPathValidAux(pathT);
@@ -218,7 +262,7 @@
return isPathValidAux(path);
}
-bool planning_environment::PlanningMonitor::isPathValidAux(const motion_planning_msgs::KinematicPath &path)
+bool planning_environment::PlanningMonitor::isPathValidAux(const motion_planning_msgs::KinematicPath &path) const
{
planning_models::KinematicModel::StateParams *sp = getKinematicModel()->newStateParams();
sp->setParams(path.start_state.vals);
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <is...@us...> - 2009-06-17 18:31:57
|
Revision: 17231
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=17231&view=rev
Author: isucan
Date: 2009-06-17 18:30:56 +0000 (Wed, 17 Jun 2009)
Log Message:
-----------
check path safety
Modified Paths:
--------------
pkg/trunk/motion_planning/planning_environment/include/planning_environment/planning_monitor.h
pkg/trunk/motion_planning/planning_environment/src/planning_monitor.cpp
Modified: pkg/trunk/motion_planning/planning_environment/include/planning_environment/planning_monitor.h
===================================================================
--- pkg/trunk/motion_planning/planning_environment/include/planning_environment/planning_monitor.h 2009-06-17 18:30:25 UTC (rev 17230)
+++ pkg/trunk/motion_planning/planning_environment/include/planning_environment/planning_monitor.h 2009-06-17 18:30:56 UTC (rev 17231)
@@ -56,6 +56,8 @@
PlanningMonitor(CollisionModels *cm, std::string frame_id) : CollisionSpaceMonitor(static_cast<CollisionModels*>(cm), frame_id)
{
+ nh_.param("~refresh_interval_collision_map", intervalCollisionMap_, 3.0);
+ nh_.param("~refresh_interval_kinematic_state", intervalState_, 0.5);
}
PlanningMonitor(CollisionModels *cm) : CollisionSpaceMonitor(static_cast<CollisionModels*>(cm))
@@ -66,6 +68,9 @@
{
}
+ /** Return true if recent enough data is available so that planning is considered safe */
+ bool isEnvironmentSafe(void) const;
+
/** Check if the full state of the robot is valid */
bool isStateValidOnPath(const planning_models::KinematicModel::StateParams *state) const;
@@ -100,6 +105,9 @@
motion_planning_msgs::KinematicConstraints kcPath_;
motion_planning_msgs::KinematicConstraints kcGoal_;
+
+ double intervalCollisionMap_;
+ double intervalState_;
};
Modified: pkg/trunk/motion_planning/planning_environment/src/planning_monitor.cpp
===================================================================
--- pkg/trunk/motion_planning/planning_environment/src/planning_monitor.cpp 2009-06-17 18:30:25 UTC (rev 17230)
+++ pkg/trunk/motion_planning/planning_environment/src/planning_monitor.cpp 2009-06-17 18:30:56 UTC (rev 17231)
@@ -37,6 +37,22 @@
#include "planning_environment/planning_monitor.h"
#include "planning_environment/kinematic_state_constraint_evaluator.h"
+bool planning_environment::PlanningMonitor::isEnvironmentSafe(void) const
+{
+ if (isMapUpdated(intervalCollisionMap_))
+ {
+ ROS_WARN("Planning is not safe: map is not up to date");
+ return false;
+ }
+
+ if (isStateUpdated(intervalState_))
+ {
+ ROS_WARN("Planning is not safe: robot state is not up to date");
+ return false;
+ }
+ return true;
+}
+
void planning_environment::PlanningMonitor::setPathConstraints(const motion_planning_msgs::KinematicConstraints &kc)
{
kcPath_ = kc;
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <is...@us...> - 2009-06-18 18:29:12
|
Revision: 17295
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=17295&view=rev
Author: isucan
Date: 2009-06-18 18:29:08 +0000 (Thu, 18 Jun 2009)
Log Message:
-----------
changed defaults
Modified Paths:
--------------
pkg/trunk/motion_planning/planning_environment/include/planning_environment/planning_monitor.h
pkg/trunk/motion_planning/planning_environment/src/planning_monitor.cpp
Modified: pkg/trunk/motion_planning/planning_environment/include/planning_environment/planning_monitor.h
===================================================================
--- pkg/trunk/motion_planning/planning_environment/include/planning_environment/planning_monitor.h 2009-06-18 18:28:30 UTC (rev 17294)
+++ pkg/trunk/motion_planning/planning_environment/include/planning_environment/planning_monitor.h 2009-06-18 18:29:08 UTC (rev 17295)
@@ -56,8 +56,8 @@
PlanningMonitor(CollisionModels *cm, std::string frame_id) : CollisionSpaceMonitor(static_cast<CollisionModels*>(cm), frame_id)
{
- nh_.param("~refresh_interval_collision_map", intervalCollisionMap_, 3.0);
- nh_.param("~refresh_interval_kinematic_state", intervalState_, 0.5);
+ nh_.param("~refresh_interval_collision_map", intervalCollisionMap_, 0.0);
+ nh_.param("~refresh_interval_kinematic_state", intervalState_, 0.0);
}
PlanningMonitor(CollisionModels *cm) : CollisionSpaceMonitor(static_cast<CollisionModels*>(cm))
Modified: pkg/trunk/motion_planning/planning_environment/src/planning_monitor.cpp
===================================================================
--- pkg/trunk/motion_planning/planning_environment/src/planning_monitor.cpp 2009-06-18 18:28:30 UTC (rev 17294)
+++ pkg/trunk/motion_planning/planning_environment/src/planning_monitor.cpp 2009-06-18 18:29:08 UTC (rev 17295)
@@ -41,13 +41,13 @@
{
if (!isMapUpdated(intervalCollisionMap_))
{
- ROS_WARN("Planning is not safe: map is not up to date");
+ ROS_WARN("Planning is not safe: map not updated in the last %f seconds", intervalCollisionMap_);
return false;
}
if (!isStateUpdated(intervalState_))
{
- ROS_WARN("Planning is not safe: robot state is not up to date");
+ ROS_WARN("Planning is not safe: robot state not updated in the last %f seconds", intervalState_);
return false;
}
return true;
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <is...@us...> - 2009-06-21 20:57:45
|
Revision: 17428
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=17428&view=rev
Author: isucan
Date: 2009-06-21 20:57:42 +0000 (Sun, 21 Jun 2009)
Log Message:
-----------
using message notifier for collision maps
Modified Paths:
--------------
pkg/trunk/motion_planning/planning_environment/include/planning_environment/collision_space_monitor.h
pkg/trunk/motion_planning/planning_environment/src/collision_space_monitor.cpp
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-21 19:27:22 UTC (rev 17427)
+++ pkg/trunk/motion_planning/planning_environment/include/planning_environment/collision_space_monitor.h 2009-06-21 20:57:42 UTC (rev 17428)
@@ -40,6 +40,7 @@
#include "planning_environment/collision_models.h"
#include "planning_environment/kinematic_model_state_monitor.h"
+#include <tf/message_notifier.h>
#include <robot_msgs/CollisionMap.h>
#include <robot_msgs/AttachedObject.h>
@@ -75,6 +76,10 @@
virtual ~CollisionSpaceMonitor(void)
{
+ if (collisionMapNotifier_)
+ delete collisionMapNotifier_;
+ if (attachedBodyNotifier_)
+ delete attachedBodyNotifier_;
}
collision_space::EnvironmentModel* getEnvironmentModel(void) const
@@ -142,8 +147,8 @@
bool haveMap_;
ros::Time lastMapUpdate_;
- ros::Subscriber attachBodySubscriber_;
- ros::Subscriber collisionMapSubscriber_;
+ tf::MessageNotifier<robot_msgs::CollisionMap> *collisionMapNotifier_;
+ tf::MessageNotifier<robot_msgs::AttachedObject> *attachedBodyNotifier_;
boost::function<void(const robot_msgs::CollisionMapConstPtr)> onBeforeMapUpdate_;
boost::function<void(const robot_msgs::CollisionMapConstPtr)> onAfterMapUpdate_;
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-21 19:27:22 UTC (rev 17427)
+++ pkg/trunk/motion_planning/planning_environment/src/collision_space_monitor.cpp 2009-06-21 20:57:42 UTC (rev 17428)
@@ -36,6 +36,7 @@
#include "planning_environment/collision_space_monitor.h"
#include <robot_msgs/PointStamped.h>
+#include <boost/bind.hpp>
#include <climits>
namespace planning_environment
@@ -52,6 +53,10 @@
onBeforeMapUpdate_ = NULL;
onAfterMapUpdate_ = NULL;
onAfterAttachBody_ = NULL;
+
+ attachedBodyNotifier_ = NULL;
+ collisionMapNotifier_ = NULL;
+
haveMap_ = false;
if (!tf_)
@@ -59,12 +64,13 @@
collisionSpace_ = cm_->getODECollisionModel().get();
- collisionMapSubscriber_ = nh_.subscribe("collision_map", 1, &CollisionSpaceMonitor::collisionMapCallback, this);
+ collisionMapNotifier_ = new tf::MessageNotifier<robot_msgs::CollisionMap>(*tf_, boost::bind(&CollisionSpaceMonitor::collisionMapCallback, this, _1), "collision_map", getFrameId(), 1);
ROS_DEBUG("Listening to collision_map");
if (cm_->loadedModels())
{
- attachBodySubscriber_ = nh_.subscribe("attach_object", 1, &CollisionSpaceMonitor::attachObjectCallback, this);
+ attachedBodyNotifier_ = new tf::MessageNotifier<robot_msgs::AttachedObject>(*tf_, boost::bind(&CollisionSpaceMonitor::attachObjectCallback, this, _1), "attach_object", "", 1);
+ attachedBodyNotifier_->setTargetFrame(cm_->getCollisionCheckLinks());
ROS_DEBUG("Listening to attach_object");
}
}
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <is...@us...> - 2009-06-27 17:54:20
|
Revision: 17816
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=17816&view=rev
Author: isucan
Date: 2009-06-27 17:54:19 +0000 (Sat, 27 Jun 2009)
Log Message:
-----------
support for map updates + a bit more documentation
Modified Paths:
--------------
pkg/trunk/motion_planning/planning_environment/include/planning_environment/collision_space_monitor.h
pkg/trunk/motion_planning/planning_environment/include/planning_environment/planning_monitor.h
pkg/trunk/motion_planning/planning_environment/mainpage.dox
pkg/trunk/motion_planning/planning_environment/src/collision_space_monitor.cpp
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-27 17:51:48 UTC (rev 17815)
+++ pkg/trunk/motion_planning/planning_environment/include/planning_environment/collision_space_monitor.h 2009-06-27 17:54:19 UTC (rev 17816)
@@ -78,6 +78,8 @@
{
if (collisionMapNotifier_)
delete collisionMapNotifier_;
+ if (collisionMapUpdateNotifier_)
+ delete collisionMapUpdateNotifier_;
if (attachedBodyNotifier_)
delete attachedBodyNotifier_;
}
@@ -139,7 +141,9 @@
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 attachObjectCallback(const robot_msgs::AttachedObjectConstPtr &attachedObject);
CollisionModels *cm_;
@@ -148,6 +152,7 @@
bool haveMap_;
ros::Time lastMapUpdate_;
tf::MessageNotifier<robot_msgs::CollisionMap> *collisionMapNotifier_;
+ tf::MessageNotifier<robot_msgs::CollisionMap> *collisionMapUpdateNotifier_;
tf::MessageNotifier<robot_msgs::AttachedObject> *attachedBodyNotifier_;
boost::function<void(const robot_msgs::CollisionMapConstPtr)> onBeforeMapUpdate_;
Modified: pkg/trunk/motion_planning/planning_environment/include/planning_environment/planning_monitor.h
===================================================================
--- pkg/trunk/motion_planning/planning_environment/include/planning_environment/planning_monitor.h 2009-06-27 17:51:48 UTC (rev 17815)
+++ pkg/trunk/motion_planning/planning_environment/include/planning_environment/planning_monitor.h 2009-06-27 17:54:19 UTC (rev 17816)
@@ -68,39 +68,39 @@
{
}
- /** Return true if recent enough data is available so that planning is considered safe */
+ /** \brief Return true if recent enough data is available so that planning is considered safe */
bool isEnvironmentSafe(void) const;
- /** Check if the full state of the robot is valid */
+ /** \brief Check if the full state of the robot is valid */
bool isStateValidOnPath(const planning_models::StateParams *state) const;
- /** Check if the full state of the robot is valid */
+ /** \brief Check if the full state of the robot is valid */
bool isStateValidAtGoal(const planning_models::StateParams *state) const;
- /** Check if the path is valid */
+ /** \brief Check if the path is valid */
bool isPathValid(const motion_planning_msgs::KinematicPath &path) const;
- /** Set the kinematic constraints the monitor should use when checking a path */
+ /** \brief Set the kinematic constraints the monitor should use when checking a path */
void setPathConstraints(const motion_planning_msgs::KinematicConstraints &kc);
- /** Set the kinematic constraints the monitor should use when checking a path's last state (the goal) */
+ /** \brief Set the kinematic constraints the monitor should use when checking a path's last state (the goal) */
void setGoalConstraints(const motion_planning_msgs::KinematicConstraints &kc);
- /** Transform the frames in which constraints are specified to the one requested */
+ /** \brief Transform the frames in which constraints are specified to the one requested */
bool transformConstraintsToFrame(motion_planning_msgs::KinematicConstraints &kc, const std::string &target) const;
- /** Transform the kinematic path to the frame requested */
+ /** \brief Transform the kinematic path to the frame requested */
bool transformPathToFrame(motion_planning_msgs::KinematicPath &kp, const std::string &target) const;
- /** Transform the kinematic joint to the frame requested */
+ /** \brief Transform the kinematic joint to the frame requested */
bool transformJointToFrame(motion_planning_msgs::KinematicJoint &kj, const std::string &target) const;
protected:
- /** Transform the joint parameters (if needed) to a target frame */
+ /** \brief Transform the joint parameters (if needed) to a target frame */
bool transformJoint(const std::string &name, unsigned int index, std::vector<double> ¶ms, roslib::Header &header, const std::string& target) const;
- /** Check the path assuming it is in the frame of the model */
+ /** \brief Check the path assuming it is in the frame of the model */
bool isPathValidAux(const motion_planning_msgs::KinematicPath &path) const;
motion_planning_msgs::KinematicConstraints kcPath_;
Modified: pkg/trunk/motion_planning/planning_environment/mainpage.dox
===================================================================
--- pkg/trunk/motion_planning/planning_environment/mainpage.dox 2009-06-27 17:51:48 UTC (rev 17815)
+++ pkg/trunk/motion_planning/planning_environment/mainpage.dox 2009-06-27 17:54:19 UTC (rev 17816)
@@ -18,20 +18,33 @@
\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.
+The intended use for this package is to instantiante one of the two
+model classes and potentially one of the monitor classes.
+The model classes are:
+- \b RobotModels : allows the instantiation of various robot models (for example, a kinematic one) based on data from the parameter server. The URDF robot description and the .yaml files describing collision and planning information are assumed to be loaded.
+
+- \b CollisionModels : allows the instantiation of various robot models (for example, a kinematic one) and various collision spaces, based on data from the parameter server. This class inherits from \b RobotModels. The URDF robot description and the .yaml files describing collision and planning information are assumed to be loaded.
+
+<hr>
+
+The monitor classes are:
+- \b KinematicModelStateMonitor : monitors the kinematic state of the robot. Optionally, monitors the base location. It uses the 'mechanism_state' topic.
+- \b CollisionSpaceMonitor : same as \b KinematicModelStateMonitor except it also monitors the state of the collision environment. It uses the 'collision_map' topic to receive new full maps and the 'collision_map_update' to receive updates. Attaching objects to robot links is possible using the 'attach_object' topic.
+- \b PlanningMonitor : same as \b CollisionSpaceMonitor except it also offers the ability to evaluate kinematic constraints and check paths and states for validity.
+
+ <!-- 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
+<!-- \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
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-27 17:51:48 UTC (rev 17815)
+++ pkg/trunk/motion_planning/planning_environment/src/collision_space_monitor.cpp 2009-06-27 17:54:19 UTC (rev 17816)
@@ -67,6 +67,9 @@
collisionMapNotifier_ = new tf::MessageNotifier<robot_msgs::CollisionMap>(*tf_, boost::bind(&CollisionSpaceMonitor::collisionMapCallback, this, _1), "collision_map", getFrameId(), 1);
ROS_DEBUG("Listening to collision_map");
+ collisionMapUpdateNotifier_ = new tf::MessageNotifier<robot_msgs::CollisionMap>(*tf_, boost::bind(&CollisionSpaceMonitor::collisionMapUpdateCallback, this, _1), "collision_map_update", getFrameId(), 1);
+ ROS_DEBUG("Listening to collision_map_update");
+
if (cm_->loadedModels())
{
attachedBodyNotifier_ = new tf::MessageNotifier<robot_msgs::AttachedObject>(*tf_, boost::bind(&CollisionSpaceMonitor::attachObjectCallback, this, _1), "attach_object", "", 1);
@@ -99,8 +102,18 @@
ROS_INFO("Map received!");
}
+void planning_environment::CollisionSpaceMonitor::collisionMapUpdateCallback(const robot_msgs::CollisionMapConstPtr &collisionMap)
+{
+ updateCollisionSpace(collisionMap, false);
+}
+
void planning_environment::CollisionSpaceMonitor::collisionMapCallback(const robot_msgs::CollisionMapConstPtr &collisionMap)
{
+ updateCollisionSpace(collisionMap, true);
+}
+
+void planning_environment::CollisionSpaceMonitor::updateCollisionSpace(const robot_msgs::CollisionMapConstPtr &collisionMap, bool clear)
+{
int n = collisionMap->get_boxes_size();
ROS_DEBUG("Received %d points (collision map)", n);
@@ -164,7 +177,8 @@
}
collisionSpace_->lock();
- collisionSpace_->clearObstacles();
+ if (clear)
+ collisionSpace_->clearObstacles();
collisionSpace_->addPointCloud(n, data);
collisionSpace_->unlock();
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <is...@us...> - 2009-06-27 21:45:17
|
Revision: 17824
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=17824&view=rev
Author: isucan
Date: 2009-06-27 21:45:10 +0000 (Sat, 27 Jun 2009)
Log Message:
-----------
fixed parameter loading
Modified Paths:
--------------
pkg/trunk/motion_planning/planning_environment/include/planning_environment/planning_monitor.h
pkg/trunk/motion_planning/planning_environment/src/planning_monitor.cpp
Modified: pkg/trunk/motion_planning/planning_environment/include/planning_environment/planning_monitor.h
===================================================================
--- pkg/trunk/motion_planning/planning_environment/include/planning_environment/planning_monitor.h 2009-06-27 21:37:12 UTC (rev 17823)
+++ pkg/trunk/motion_planning/planning_environment/include/planning_environment/planning_monitor.h 2009-06-27 21:45:10 UTC (rev 17824)
@@ -56,12 +56,12 @@
PlanningMonitor(CollisionModels *cm, std::string frame_id) : CollisionSpaceMonitor(static_cast<CollisionModels*>(cm), frame_id)
{
- nh_.param<double>("~refresh_interval_collision_map", intervalCollisionMap_, 0.0);
- nh_.param<double>("~refresh_interval_kinematic_state", intervalState_, 0.0);
+ loadParams();
}
PlanningMonitor(CollisionModels *cm) : CollisionSpaceMonitor(static_cast<CollisionModels*>(cm))
{
+ loadParams();
}
virtual ~PlanningMonitor(void)
@@ -96,7 +96,10 @@
bool transformJointToFrame(motion_planning_msgs::KinematicJoint &kj, const std::string &target) const;
protected:
-
+
+ /** \brief Load ROS parameters */
+ void loadParams(void);
+
/** \brief Transform the joint parameters (if needed) to a target frame */
bool transformJoint(const std::string &name, unsigned int index, std::vector<double> ¶ms, roslib::Header &header, const std::string& target) const;
Modified: pkg/trunk/motion_planning/planning_environment/src/planning_monitor.cpp
===================================================================
--- pkg/trunk/motion_planning/planning_environment/src/planning_monitor.cpp 2009-06-27 21:37:12 UTC (rev 17823)
+++ pkg/trunk/motion_planning/planning_environment/src/planning_monitor.cpp 2009-06-27 21:45:10 UTC (rev 17824)
@@ -38,6 +38,12 @@
#include "planning_environment/kinematic_state_constraint_evaluator.h"
#include <boost/scoped_ptr.hpp>
+void planning_environment::PlanningMonitor::loadParams(void)
+{
+ nh_.param<double>("~refresh_interval_collision_map", intervalCollisionMap_, 0.0);
+ nh_.param<double>("~refresh_interval_kinematic_state", intervalState_, 0.0);
+}
+
bool planning_environment::PlanningMonitor::isEnvironmentSafe(void) const
{
if (!isMapUpdated(intervalCollisionMap_))
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <is...@us...> - 2009-06-29 01:22:16
|
Revision: 17846
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=17846&view=rev
Author: isucan
Date: 2009-06-29 01:08:31 +0000 (Mon, 29 Jun 2009)
Log Message:
-----------
fix locking issues
Modified Paths:
--------------
pkg/trunk/motion_planning/planning_environment/CMakeLists.txt
pkg/trunk/motion_planning/planning_environment/include/planning_environment/collision_space_monitor.h
pkg/trunk/motion_planning/planning_environment/mainpage.dox
pkg/trunk/motion_planning/planning_environment/src/collision_space_monitor.cpp
Modified: pkg/trunk/motion_planning/planning_environment/CMakeLists.txt
===================================================================
--- pkg/trunk/motion_planning/planning_environment/CMakeLists.txt 2009-06-29 01:07:52 UTC (rev 17845)
+++ pkg/trunk/motion_planning/planning_environment/CMakeLists.txt 2009-06-29 01:08:31 UTC (rev 17846)
@@ -12,7 +12,8 @@
src/kinematic_state_constraint_evaluator.cpp
src/planning_monitor.cpp)
rospack_add_openmp_flags(planning_environment)
-
+rospack_link_boost(planning_environment thread)
+
# Tests
# Create a model of the PR2
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-29 01:07:52 UTC (rev 17845)
+++ pkg/trunk/motion_planning/planning_environment/include/planning_environment/collision_space_monitor.h 2009-06-29 01:08:31 UTC (rev 17846)
@@ -44,6 +44,8 @@
#include <robot_msgs/CollisionMap.h>
#include <robot_msgs/AttachedObject.h>
+#include <boost/thread/mutex.hpp>
+
namespace planning_environment
{
@@ -148,6 +150,8 @@
CollisionModels *cm_;
collision_space::EnvironmentModel *collisionSpace_;
+ double boxScale_;
+ boost::mutex mapUpdateLock_;
bool haveMap_;
ros::Time lastMapUpdate_;
Modified: pkg/trunk/motion_planning/planning_environment/mainpage.dox
===================================================================
--- pkg/trunk/motion_planning/planning_environment/mainpage.dox 2009-06-29 01:07:52 UTC (rev 17845)
+++ pkg/trunk/motion_planning/planning_environment/mainpage.dox 2009-06-29 01:08:31 UTC (rev 17846)
@@ -30,7 +30,7 @@
The monitor classes are:
- \b KinematicModelStateMonitor : monitors the kinematic state of the robot. Optionally, monitors the base location. It uses the 'mechanism_state' topic.
-- \b CollisionSpaceMonitor : same as \b KinematicModelStateMonitor except it also monitors the state of the collision environment. It uses the 'collision_map' topic to receive new full maps and the 'collision_map_update' to receive updates. Attaching objects to robot links is possible using the 'attach_object' topic.
+- \b CollisionSpaceMonitor : same as \b KinematicModelStateMonitor except it also monitors the state of the collision environment. It uses the 'collision_map' topic to receive new full maps and the 'collision_map_update' to receive updates. Attaching objects to robot links is possible using the 'attach_object' topic. The '~box_scale' parameter is used as the constant that gets multiplied to a box's maximum extent to obtain the radius of the sphere used in collision checking.
- \b PlanningMonitor : same as \b CollisionSpaceMonitor except it also offers the ability to evaluate kinematic constraints and check paths and states for validity.
<!-- Provide links to specific auto-generated API
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-29 01:07:52 UTC (rev 17845)
+++ pkg/trunk/motion_planning/planning_environment/src/collision_space_monitor.cpp 2009-06-29 01:08:31 UTC (rev 17846)
@@ -42,9 +42,9 @@
namespace planning_environment
{
- static inline double radiusOfBox(const robot_msgs::Point32 &point)
+ static inline double maxCoord(const robot_msgs::Point32 &point)
{
- return std::max(std::max(point.x, point.y), point.z) * 1.73;
+ return std::max(std::max(point.x, point.y), point.z);
}
}
@@ -62,19 +62,22 @@
if (!tf_)
tf_ = new tf::TransformListener();
+ // the factor by which a boxes maximum extent is multiplied to get the radius of the sphere to be placed in the collision space
+ nh_.param<double>("~box_scale", boxScale_, 2.0);
+
collisionSpace_ = cm_->getODECollisionModel().get();
collisionMapNotifier_ = new tf::MessageNotifier<robot_msgs::CollisionMap>(*tf_, boost::bind(&CollisionSpaceMonitor::collisionMapCallback, this, _1), "collision_map", getFrameId(), 1);
- ROS_DEBUG("Listening to collision_map");
+ 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);
- ROS_DEBUG("Listening to collision_map_update");
+ ROS_DEBUG("Listening to collision_map_update using message notifier with target frame %s", collisionMapUpdateNotifier_->getTargetFramesString().c_str());
if (cm_->loadedModels())
{
attachedBodyNotifier_ = new tf::MessageNotifier<robot_msgs::AttachedObject>(*tf_, boost::bind(&CollisionSpaceMonitor::attachObjectCallback, this, _1), "attach_object", "", 1);
attachedBodyNotifier_->setTargetFrame(cm_->getCollisionCheckLinks());
- ROS_DEBUG("Listening to attach_object");
+ ROS_DEBUG("Listening to attach_object using message notifier with target frame %s", attachedBodyNotifier_->getTargetFramesString().c_str());
}
}
@@ -115,6 +118,8 @@
void planning_environment::CollisionSpaceMonitor::updateCollisionSpace(const robot_msgs::CollisionMapConstPtr &collisionMap, bool clear)
{
+ boost::mutex::scoped_lock lock(mapUpdateLock_);
+
int n = collisionMap->get_boxes_size();
ROS_DEBUG("Received %d points (collision map)", n);
@@ -124,7 +129,7 @@
// we want to make sure the frame the robot model is kept in is the same as the frame of the collisionMap
bool transform = !frame_id_.empty() && collisionMap->header.frame_id != frame_id_;
-
+
ros::WallTime startTime = ros::WallTime::now();
double *data = n > 0 ? new double[4 * n] : NULL;
@@ -158,7 +163,7 @@
data[i4 + 1] = pso.point.y;
data[i4 + 2] = pso.point.z;
- data[i4 + 3] = radiusOfBox(collisionMap->boxes[i].extents);
+ data[i4 + 3] = maxCoord(collisionMap->boxes[i].extents) * boxScale_;
}
if (err)
@@ -166,6 +171,7 @@
}
else
{
+
#pragma omp parallel for
for (int i = 0 ; i < n ; ++i)
{
@@ -174,15 +180,17 @@
data[i4 + 1] = collisionMap->boxes[i].center.y;
data[i4 + 2] = collisionMap->boxes[i].center.z;
- data[i4 + 3] = radiusOfBox(collisionMap->boxes[i].extents);
+ data[i4 + 3] = maxCoord(collisionMap->boxes[i].extents) * boxScale_;
}
}
collisionSpace_->lock();
+
if (clear)
collisionSpace_->clearObstacles();
if (n > 0)
collisionSpace_->addPointCloud(n, data);
+
collisionSpace_->unlock();
if (data)
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <is...@us...> - 2009-06-29 02:15:44
|
Revision: 17850
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=17850&view=rev
Author: isucan
Date: 2009-06-29 02:02:36 +0000 (Mon, 29 Jun 2009)
Log Message:
-----------
a getter for the box scale + another check
Modified Paths:
--------------
pkg/trunk/motion_planning/planning_environment/include/planning_environment/collision_space_monitor.h
pkg/trunk/motion_planning/planning_environment/src/collision_space_monitor.cpp
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-29 01:48:17 UTC (rev 17849)
+++ pkg/trunk/motion_planning/planning_environment/include/planning_environment/collision_space_monitor.h 2009-06-29 02:02:36 UTC (rev 17850)
@@ -86,6 +86,7 @@
delete attachedBodyNotifier_;
}
+ /** \brief Return the instance of the environment model maintained */
collision_space::EnvironmentModel* getEnvironmentModel(void) const
{
return collisionSpace_;
@@ -102,6 +103,14 @@
{
return tf_;
}
+
+ /** \brief Return the scaling employed when creating spheres
+ from boxes in a collision map. The radius of a sphere is
+ this scaling multiplied by the largest extent of the box */
+ double getBoxScale(void) const
+ {
+ return boxScale_;
+ }
/** \brief Define a callback for before updating a map */
void setOnBeforeMapUpdateCallback(const boost::function<void(const robot_msgs::CollisionMapConstPtr)> &callback)
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-29 01:48:17 UTC (rev 17849)
+++ pkg/trunk/motion_planning/planning_environment/src/collision_space_monitor.cpp 2009-06-29 02:02:36 UTC (rev 17850)
@@ -73,12 +73,13 @@
nh_.param<std::string>("~bounding_planes", planes, std::string());
std::stringstream ss(planes);
std::vector<double> planeValues;
- while (ss.good() && !ss.eof())
- {
- double value;
- ss >> value;
- planeValues.push_back(value);
- }
+ 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
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <is...@us...> - 2009-07-01 04:53:43
|
Revision: 18073
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=18073&view=rev
Author: isucan
Date: 2009-07-01 04:53:37 +0000 (Wed, 01 Jul 2009)
Log Message:
-----------
clearing constraints
Modified Paths:
--------------
pkg/trunk/motion_planning/planning_environment/include/planning_environment/planning_monitor.h
pkg/trunk/motion_planning/planning_environment/src/planning_monitor.cpp
Modified: pkg/trunk/motion_planning/planning_environment/include/planning_environment/planning_monitor.h
===================================================================
--- pkg/trunk/motion_planning/planning_environment/include/planning_environment/planning_monitor.h 2009-07-01 04:45:25 UTC (rev 18072)
+++ pkg/trunk/motion_planning/planning_environment/include/planning_environment/planning_monitor.h 2009-07-01 04:53:37 UTC (rev 18073)
@@ -77,7 +77,7 @@
/** \brief Check if the full state of the robot is valid */
bool isStateValidAtGoal(const planning_models::StateParams *state) const;
- /** \brief Check if the path is valid */
+ /** \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 Set the kinematic constraints the monitor should use when checking a path */
@@ -86,6 +86,9 @@
/** \brief Set the kinematic constraints the monitor should use when checking a path's last state (the goal) */
void setGoalConstraints(const motion_planning_msgs::KinematicConstraints &kc);
+ /** \brief Clear previously set constraints */
+ void clearConstraints(void);
+
/** \brief Transform the frames in which constraints are specified to the one requested */
bool transformConstraintsToFrame(motion_planning_msgs::KinematicConstraints &kc, const std::string &target) const;
Modified: pkg/trunk/motion_planning/planning_environment/src/planning_monitor.cpp
===================================================================
--- pkg/trunk/motion_planning/planning_environment/src/planning_monitor.cpp 2009-07-01 04:45:25 UTC (rev 18072)
+++ pkg/trunk/motion_planning/planning_environment/src/planning_monitor.cpp 2009-07-01 04:53:37 UTC (rev 18073)
@@ -60,6 +60,14 @@
return true;
}
+void planning_environment::PlanningMonitor::clearConstraints(void)
+{
+ kcPath_.joint_constraint.clear();
+ kcPath_.pose_constraint.clear();
+ kcGoal_.joint_constraint.clear();
+ kcGoal_.pose_constraint.clear();
+}
+
void planning_environment::PlanningMonitor::setPathConstraints(const motion_planning_msgs::KinematicConstraints &kc)
{
kcPath_ = kc;
@@ -355,16 +363,6 @@
}
}
- // if we got to the last state, we also check the goal constraints
- if (valid)
- {
- ks.add(getKinematicModel(), kcGoal_.joint_constraint);
- ks.add(getKinematicModel(), kcGoal_.pose_constraint);
- valid = ks.decide(sp->getParams());
- if (verbose && !valid)
- ROS_INFO("isPathValid: Goal state does not satisfy constraints");
- }
-
getEnvironmentModel()->setVerbose(vlevel);
getKinematicModel()->unlock();
getEnvironmentModel()->unlock();
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <is...@us...> - 2009-07-02 17:39:21
|
Revision: 18188
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=18188&view=rev
Author: isucan
Date: 2009-07-02 17:39:19 +0000 (Thu, 02 Jul 2009)
Log Message:
-----------
added getter for config name
Modified Paths:
--------------
pkg/trunk/motion_planning/planning_environment/include/planning_environment/robot_models.h
pkg/trunk/motion_planning/planning_environment/src/robot_models.cpp
Modified: pkg/trunk/motion_planning/planning_environment/include/planning_environment/robot_models.h
===================================================================
--- pkg/trunk/motion_planning/planning_environment/include/planning_environment/robot_models.h 2009-07-02 17:29:45 UTC (rev 18187)
+++ pkg/trunk/motion_planning/planning_environment/include/planning_environment/robot_models.h 2009-07-02 17:39:19 UTC (rev 18188)
@@ -68,6 +68,7 @@
{
}
+ std::string getName(void);
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);
Modified: pkg/trunk/motion_planning/planning_environment/src/robot_models.cpp
===================================================================
--- pkg/trunk/motion_planning/planning_environment/src/robot_models.cpp 2009-07-02 17:29:45 UTC (rev 18187)
+++ pkg/trunk/motion_planning/planning_environment/src/robot_models.cpp 2009-07-02 17:39:19 UTC (rev 18188)
@@ -160,6 +160,11 @@
}
}
+std::string planning_environment::RobotModels::PlannerConfig::getName(void)
+{
+ return config_;
+}
+
bool planning_environment::RobotModels::PlannerConfig::hasParam(const std::string ¶m)
{
return nh_.hasParam(description_ + "_planning/planner_configs/" + config_ + "/" + param);
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <is...@us...> - 2009-07-06 04:07:01
|
Revision: 18307
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=18307&view=rev
Author: isucan
Date: 2009-07-06 04:06:59 +0000 (Mon, 06 Jul 2009)
Log Message:
-----------
more robust transform handling
Modified Paths:
--------------
pkg/trunk/motion_planning/planning_environment/include/planning_environment/kinematic_model_state_monitor.h
pkg/trunk/motion_planning/planning_environment/include/planning_environment/planning_monitor.h
pkg/trunk/motion_planning/planning_environment/src/kinematic_model_state_monitor.cpp
pkg/trunk/motion_planning/planning_environment/src/planning_monitor.cpp
Modified: pkg/trunk/motion_planning/planning_environment/include/planning_environment/kinematic_model_state_monitor.h
===================================================================
--- pkg/trunk/motion_planning/planning_environment/include/planning_environment/kinematic_model_state_monitor.h 2009-07-06 03:18:49 UTC (rev 18306)
+++ pkg/trunk/motion_planning/planning_environment/include/planning_environment/kinematic_model_state_monitor.h 2009-07-06 04:06:59 UTC (rev 18307)
@@ -158,6 +158,9 @@
ros::Subscriber mechanismStateSubscriber_;
tf::TransformListener *tf_;
+ /** \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/include/planning_environment/planning_monitor.h
===================================================================
--- pkg/trunk/motion_planning/planning_environment/include/planning_environment/planning_monitor.h 2009-07-06 03:18:49 UTC (rev 18306)
+++ pkg/trunk/motion_planning/planning_environment/include/planning_environment/planning_monitor.h 2009-07-06 04:06:59 UTC (rev 18307)
@@ -114,6 +114,7 @@
double intervalCollisionMap_;
double intervalState_;
+
};
Modified: pkg/trunk/motion_planning/planning_environment/src/kinematic_model_state_monitor.cpp
===================================================================
--- pkg/trunk/motion_planning/planning_environment/src/kinematic_model_state_monitor.cpp 2009-07-06 03:18:49 UTC (rev 18306)
+++ pkg/trunk/motion_planning/planning_environment/src/kinematic_model_state_monitor.cpp 2009-07-06 04:06:59 UTC (rev 18307)
@@ -44,6 +44,7 @@
robotState_ = NULL;
onStateUpdate_ = NULL;
tf_ = NULL;
+ tfWait_ = ros::Duration(0.1);
havePose_ = haveMechanismState_ = false;
if (rm_->loadedModels())
{
@@ -123,43 +124,57 @@
if (tf_->canTransform(frame_id_, robot_frame_, mechanismState->header.stamp))
{
tf::Stamped<tf::Pose> transf;
- tf_->lookupTransform(frame_id_, robot_frame_, mechanismState->header.stamp, transf);
- pose_ = transf;
-
- if (!planarJoint_.empty())
+ bool ok = true;
+ try
{
- double planar_joint[3];
- planar_joint[0] = pose_.getOrigin().x();
- planar_joint[1] = pose_.getOrigin().y();
-
- double yaw, pitch, roll;
- pose_.getBasis().getEulerZYX(yaw, pitch, roll);
- planar_joint[2] = yaw;
-
- bool this_changed = robotState_->setParamsJoint(planar_joint, planarJoint_);
- change = change || this_changed;
+ tf_->lookupTransform(frame_id_, robot_frame_, mechanismState->header.stamp, transf);
}
-
- if (!floatingJoint_.empty())
+ catch(...)
{
- double floating_joint[7];
- floating_joint[0] = pose_.getOrigin().x();
- floating_joint[1] = pose_.getOrigin().y();
- floating_joint[2] = pose_.getOrigin().z();
- btQuaternion q = pose_.getRotation();
- floating_joint[3] = q.x();
- floating_joint[4] = q.y();
- floating_joint[5] = q.z();
- floating_joint[6] = q.w();
-
- bool this_changed = robotState_->setParamsJoint(floating_joint, floatingJoint_);
- change = change || this_changed;
+ ok = false;
}
-
- havePose_ = true;
+
+ if (ok)
+ {
+ pose_ = transf;
+
+ if (!planarJoint_.empty())
+ {
+ double planar_joint[3];
+ planar_joint[0] = pose_.getOrigin().x();
+ planar_joint[1] = pose_.getOrigin().y();
+
+ double yaw, pitch, roll;
+ pose_.getBasis().getEulerZYX(yaw, pitch, roll);
+ planar_joint[2] = yaw;
+
+ bool this_changed = robotState_->setParamsJoint(planar_joint, planarJoint_);
+ change = change || this_changed;
+ }
+
+ if (!floatingJoint_.empty())
+ {
+ double floating_joint[7];
+ floating_joint[0] = pose_.getOrigin().x();
+ floating_joint[1] = pose_.getOrigin().y();
+ floating_joint[2] = pose_.getOrigin().z();
+ btQuaternion q = pose_.getRotation();
+ floating_joint[3] = q.x();
+ floating_joint[4] = q.y();
+ floating_joint[5] = q.z();
+ floating_joint[6] = q.w();
+
+ bool this_changed = robotState_->setParamsJoint(floating_joint, floatingJoint_);
+ change = change || this_changed;
+ }
+
+ havePose_ = true;
+ }
+ else
+ ROS_ERROR("Transforming from link '%s' to link '%s' failed", robot_frame_.c_str(), frame_id_.c_str());
}
else
- ROS_WARN("Unable fo find transform from link '%s' to link '%s'", robot_frame_.c_str(), frame_id_.c_str());
+ ROS_WARN("Unable to find transform from link '%s' to link '%s'", robot_frame_.c_str(), frame_id_.c_str());
}
if (change && onStateUpdate_ != NULL)
Modified: pkg/trunk/motion_planning/planning_environment/src/planning_monitor.cpp
===================================================================
--- pkg/trunk/motion_planning/planning_environment/src/planning_monitor.cpp 2009-07-06 03:18:49 UTC (rev 18306)
+++ pkg/trunk/motion_planning/planning_environment/src/planning_monitor.cpp 2009-07-06 04:06:59 UTC (rev 18307)
@@ -84,7 +84,25 @@
{
bool res = true;
for (unsigned int i = 0; i < kc.pose_constraint.size() ; ++i)
- tf_->transformPose(target, kc.pose_constraint[i].pose, kc.pose_constraint[i].pose);
+ {
+ bool ok = false;
+ if (tf_->canTransform(target, kc.pose_constraint[i].pose.header.frame_id, kc.pose_constraint[i].pose.header.stamp, tfWait_))
+ {
+ 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());
+ res = false;
+ }
+ }
// if there are any floating or planar joints, transform them
if (getKinematicModel()->getModelInfo().planarJoints.size() > 0 || getKinematicModel()->getModelInfo().floatingJoints.size() > 0)
@@ -175,7 +193,23 @@
pose.getBasis().setEulerYPR(params[index + 2], 0.0, 0.0);
pose.stamp_ = header.stamp;
pose.frame_id_ = header.frame_id;
- tf_->transformPose(target, pose, pose);
+ bool ok = false;
+ if (tf_->canTransform(target, pose.frame_id_, pose.stamp_, tfWait_))
+ {
+ 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());
+ return false;
+ }
params[index + 0] = pose.getOrigin().getX();
params[index + 1] = pose.getOrigin().getY();
btScalar dummy;
@@ -192,7 +226,23 @@
pose.setRotation(q);
pose.stamp_ = header.stamp;
pose.frame_id_ = header.frame_id;
- tf_->transformPose(target, pose, pose);
+ bool ok = false;
+ if (tf_->canTransform(target, pose.frame_id_, pose.stamp_, tfWait_))
+ {
+ 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();
@@ -265,7 +315,6 @@
return valid;
}
-
bool planning_environment::PlanningMonitor::isPathValid(const motion_planning_msgs::KinematicPath &path, bool verbose) const
{
if (path.header.frame_id != getFrameId())
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <is...@us...> - 2009-07-07 22:03:02
|
Revision: 18422
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=18422&view=rev
Author: isucan
Date: 2009-07-07 22:02:57 +0000 (Tue, 07 Jul 2009)
Log Message:
-----------
update for ben
Modified Paths:
--------------
pkg/trunk/motion_planning/planning_environment/include/planning_environment/collision_models.h
pkg/trunk/motion_planning/planning_environment/src/collision_models.cpp
Modified: pkg/trunk/motion_planning/planning_environment/include/planning_environment/collision_models.h
===================================================================
--- pkg/trunk/motion_planning/planning_environment/include/planning_environment/collision_models.h 2009-07-07 21:56:07 UTC (rev 18421)
+++ pkg/trunk/motion_planning/planning_environment/include/planning_environment/collision_models.h 2009-07-07 22:02:57 UTC (rev 18422)
@@ -51,8 +51,13 @@
CollisionModels(const std::string &description, double scale = 1.0, double padd = 0.0) : RobotModels(description), scale_(scale), padd_(padd)
{
- loadCollision();
+ loadCollision(collision_check_links_);
}
+
+ CollisionModels(const std::string &description, const std::vector<std::string> &links, double scale = 1.0, double padd = 0.0) : RobotModels(description), scale_(scale), padd_(padd)
+ {
+ loadCollision(links);
+ }
virtual ~CollisionModels(void)
{
@@ -63,7 +68,7 @@
{
RobotModels::reload();
ode_collision_model_.reset();
- loadCollision();
+ loadCollision(collision_check_links_);
}
/** \brief Return the instance of the constructed ODE collision model */
@@ -74,7 +79,7 @@
protected:
- void loadCollision(void);
+ void loadCollision(const std::vector<std::string> &links);
boost::shared_ptr<collision_space::EnvironmentModel> ode_collision_model_;
Modified: pkg/trunk/motion_planning/planning_environment/src/collision_models.cpp
===================================================================
--- pkg/trunk/motion_planning/planning_environment/src/collision_models.cpp 2009-07-07 21:56:07 UTC (rev 18421)
+++ pkg/trunk/motion_planning/planning_environment/src/collision_models.cpp 2009-07-07 22:02:57 UTC (rev 18422)
@@ -36,13 +36,13 @@
#include "planning_environment/collision_models.h"
-void planning_environment::CollisionModels::loadCollision(void)
+void planning_environment::CollisionModels::loadCollision(const std::vector<std::string> &links)
{
if (loadedModels())
{
ode_collision_model_ = boost::shared_ptr<collision_space::EnvironmentModel>(new collision_space::EnvironmentModelODE());
ode_collision_model_->lock();
- ode_collision_model_->addRobotModel(kmodel_, collision_check_links_, scale_, padd_);
+ ode_collision_model_->addRobotModel(kmodel_, links, scale_, padd_);
// form all pairs of links that can collide and add them as self-collision groups
for (unsigned int i = 0 ; i < self_collision_check_groups_.size() ; ++i)
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <is...@us...> - 2009-07-09 01:26:35
|
Revision: 18531
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=18531&view=rev
Author: isucan
Date: 2009-07-09 01:26:32 +0000 (Thu, 09 Jul 2009)
Log Message:
-----------
instantiating a Bullet collision model as well
Modified Paths:
--------------
pkg/trunk/motion_planning/planning_environment/include/planning_environment/collision_models.h
pkg/trunk/motion_planning/planning_environment/src/collision_models.cpp
Modified: pkg/trunk/motion_planning/planning_environment/include/planning_environment/collision_models.h
===================================================================
--- pkg/trunk/motion_planning/planning_environment/include/planning_environment/collision_models.h 2009-07-09 01:25:49 UTC (rev 18530)
+++ pkg/trunk/motion_planning/planning_environment/include/planning_environment/collision_models.h 2009-07-09 01:26:32 UTC (rev 18531)
@@ -38,7 +38,7 @@
#define PLANNING_ENVIRONMENT_COLLISION_MODELS_
#include "planning_environment/robot_models.h"
-#include <collision_space/environmentODE.h>
+#include <collision_space/environment.h>
namespace planning_environment
{
@@ -68,6 +68,7 @@
{
RobotModels::reload();
ode_collision_model_.reset();
+ bullet_collision_model_.reset();
loadCollision(collision_check_links_);
}
@@ -77,11 +78,19 @@
return ode_collision_model_;
}
+ /** \brief Return the instance of the constructed Bullet collision model */
+ const boost::shared_ptr<collision_space::EnvironmentModel> &getBulletCollisionModel(void) const
+ {
+ return bullet_collision_model_;
+ }
+
protected:
void loadCollision(const std::vector<std::string> &links);
+ void setupModel(boost::shared_ptr<collision_space::EnvironmentModel> &model, const std::vector<std::string> &links);
boost::shared_ptr<collision_space::EnvironmentModel> ode_collision_model_;
+ boost::shared_ptr<collision_space::EnvironmentModel> bullet_collision_model_;
double scale_;
double padd_;
Modified: pkg/trunk/motion_planning/planning_environment/src/collision_models.cpp
===================================================================
--- pkg/trunk/motion_planning/planning_environment/src/collision_models.cpp 2009-07-09 01:25:49 UTC (rev 18530)
+++ pkg/trunk/motion_planning/planning_environment/src/collision_models.cpp 2009-07-09 01:26:32 UTC (rev 18531)
@@ -35,26 +35,36 @@
/** \author Ioan Sucan */
#include "planning_environment/collision_models.h"
+#include <collision_space/environmentODE.h>
+#include <collision_space/environmentBullet.h>
+void planning_environment::CollisionModels::setupModel(boost::shared_ptr<collision_space::EnvironmentModel> &model, const std::vector<std::string> &links)
+{
+ model->lock();
+ model->addRobotModel(kmodel_, links, scale_, padd_);
+
+ // form all pairs of links that can collide and add them as self-collision groups
+ for (unsigned int i = 0 ; i < self_collision_check_groups_.size() ; ++i)
+ for (unsigned int g1 = 0 ; g1 < self_collision_check_groups_[i].first.size() ; ++g1)
+ for (unsigned int g2 = 0 ; g2 < self_collision_check_groups_[i].second.size() ; ++g2)
+ {
+ std::vector<std::string> scg;
+ scg.push_back(self_collision_check_groups_[i].first[g1]);
+ scg.push_back(self_collision_check_groups_[i].second[g2]);
+ model->addSelfCollisionGroup(scg);
+ }
+ model->updateRobotModel();
+ model->unlock();
+}
+
void planning_environment::CollisionModels::loadCollision(const std::vector<std::string> &links)
{
if (loadedModels())
{
ode_collision_model_ = boost::shared_ptr<collision_space::EnvironmentModel>(new collision_space::EnvironmentModelODE());
- ode_collision_model_->lock();
- ode_collision_model_->addRobotModel(kmodel_, links, scale_, padd_);
-
- // form all pairs of links that can collide and add them as self-collision groups
- for (unsigned int i = 0 ; i < self_collision_check_groups_.size() ; ++i)
- for (unsigned int g1 = 0 ; g1 < self_collision_check_groups_[i].first.size() ; ++g1)
- for (unsigned int g2 = 0 ; g2 < self_collision_check_groups_[i].second.size() ; ++g2)
- {
- std::vector<std::string> scg;
- scg.push_back(self_collision_check_groups_[i].first[g1]);
- scg.push_back(self_collision_check_groups_[i].second[g2]);
- ode_collision_model_->addSelfCollisionGroup(scg);
- }
- ode_collision_model_->updateRobotModel();
- ode_collision_model_->unlock();
+ setupModel(ode_collision_model_, links);
+
+ bullet_collision_model_ = boost::shared_ptr<collision_space::EnvironmentModel>(new collision_space::EnvironmentModelBullet());
+ setupModel(bullet_collision_model_, links);
}
}
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <is...@us...> - 2009-07-12 03:10:10
|
Revision: 18675
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=18675&view=rev
Author: isucan
Date: 2009-07-12 03:10:08 +0000 (Sun, 12 Jul 2009)
Log Message:
-----------
added a state validity checker
Modified Paths:
--------------
pkg/trunk/motion_planning/planning_environment/CMakeLists.txt
Added Paths:
-----------
pkg/trunk/motion_planning/planning_environment/src/view_state_validity.cpp
pkg/trunk/motion_planning/planning_environment/view_state_validity.launch
Modified: pkg/trunk/motion_planning/planning_environment/CMakeLists.txt
===================================================================
--- pkg/trunk/motion_planning/planning_environment/CMakeLists.txt 2009-07-12 02:50:16 UTC (rev 18674)
+++ pkg/trunk/motion_planning/planning_environment/CMakeLists.txt 2009-07-12 03:10:08 UTC (rev 18675)
@@ -14,10 +14,14 @@
rospack_add_openmp_flags(planning_environment)
rospack_link_boost(planning_environment thread)
+# Utility apps
+rospack_add_executable(view_state_validity src/view_state_validity.cpp)
+target_link_libraries(view_state_validity planning_environment)
+
# Tests
# Create a model of the PR2
-rospack_add_executable(test_robot_models test/test_robot_models.cpp)
+rospack_add_executable(test_robot_models test/test_robot_models.cpp)
rospack_declare_test(test_robot_models)
rospack_add_gtest_build_flags(test_robot_models)
target_link_libraries(test_robot_models planning_environment)
Copied: pkg/trunk/motion_planning/planning_environment/src/view_state_validity.cpp (from rev 18643, pkg/trunk/motion_planning/ompl_planning/src/state_validity_monitor.cpp)
===================================================================
--- pkg/trunk/motion_planning/planning_environment/src/view_state_validity.cpp (rev 0)
+++ pkg/trunk/motion_planning/planning_environment/src/view_state_validity.cpp 2009-07-12 03:10:08 UTC (rev 18675)
@@ -0,0 +1,122 @@
+/*********************************************************************
+* Software License Agreement (BSD License)
+*
+* Copyright (c) 2008, Willow Garage, Inc.
+* All rights reserved.
+*
+* Redistribution and use in source and binary forms, with or without
+* modification, are permitted provided that the following conditions
+* are met:
+*
+* * Redistributions of source code must retain the above copyright
+* notice, this list of conditions and the following disclaimer.
+* * Redistributions in binary form must reproduce the above
+* copyright notice, this list of conditions and the following
+* disclaimer in the documentation and/or other materials provided
+* with the distribution.
+* * Neither the name of the Willow Garage nor the names of its
+* contributors may be used to endorse or promote products derived
+* from this software without specific prior written permission.
+*
+* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
+* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
+* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+* POSSIBILITY OF SUCH DAMAGE.
+*********************************************************************/
+
+/** \author Ioan Sucan */
+
+/**
+
+@b ViewStateValidity is a node capable of verifying if the current
+state of the robot is valid or not.
+
+**/
+
+#include "planning_environment/collision_space_monitor.h"
+#include <std_msgs/Byte.h>
+
+#include <iostream>
+#include <sstream>
+#include <string>
+#include <map>
+
+class ViewStateValidity
+{
+public:
+
+ ViewStateValidity(void) : last_(-1)
+ {
+ collisionModels_ = new planning_environment::CollisionModels("robot_description");
+ if (collisionModels_->loadedModels())
+ {
+ stateValidityPublisher_ = nh_.advertise<std_msgs::Byte>("state_validity", 1);
+ collisionSpaceMonitor_ = new planning_environment::CollisionSpaceMonitor(collisionModels_, &tf_);
+ collisionSpaceMonitor_->getEnvironmentModel()->setVerbose(true);
+ collisionSpaceMonitor_->setOnAfterMapUpdateCallback(boost::bind(&ViewStateValidity::afterWorldUpdate, this, _1));
+ collisionSpaceMonitor_->setOnStateUpdateCallback(boost::bind(&ViewStateValidity::stateUpdate, this));
+ }
+ }
+
+ virtual ~ViewStateValidity(void)
+ {
+ if (collisionSpaceMonitor_)
+ delete collisionSpaceMonitor_;
+ if (collisionModels_)
+ delete collisionModels_;
+ }
+
+protected:
+
+ void afterWorldUpdate(const mapping_msgs::CollisionMapConstPtr &collisionMap)
+ {
+ last_ = -1;
+ }
+
+ void stateUpdate(void)
+ {
+ collisionSpaceMonitor_->getEnvironmentModel()->lock();
+ collisionSpaceMonitor_->getKinematicModel()->computeTransforms(collisionSpaceMonitor_->getRobotState()->getParams());
+ collisionSpaceMonitor_->getEnvironmentModel()->updateRobotModel();
+ bool invalid = collisionSpaceMonitor_->getEnvironmentModel()->isCollision();
+ collisionSpaceMonitor_->getEnvironmentModel()->unlock();
+ std_msgs::Byte msg;
+ msg.data = invalid ? 0 : 1;
+ if (last_ != msg.data)
+ {
+ last_ = msg.data;
+ stateValidityPublisher_.publish(msg);
+ if (invalid)
+ ROS_WARN("State is in collision");
+ else
+ ROS_INFO("State is valid");
+ }
+ }
+
+private:
+
+ int last_;
+ ros::NodeHandle nh_;
+ ros::Publisher stateValidityPublisher_;
+ tf::TransformListener tf_;
+ planning_environment::CollisionModels *collisionModels_;
+ planning_environment::CollisionSpaceMonitor *collisionSpaceMonitor_;
+};
+
+int main(int argc, char **argv)
+{
+ ros::init(argc, argv, "view_state_validity");
+
+ ViewStateValidity validator;
+ ros::spin();
+
+ return 0;
+}
Property changes on: pkg/trunk/motion_planning/planning_environment/src/view_state_validity.cpp
___________________________________________________________________
Added: svn:mergeinfo
+ /pkg/branches/gazebo-branch-merge/motion_planning/ompl_planning/src/state_validity_monitor.cpp:15683-15684,15739-15794,15797-15820,15822-15839,15852-15870,15983-16008,16010-16016,16129-16141,16145-16169,16245-16262,16274-16334
Added: pkg/trunk/motion_planning/planning_environment/view_state_validity.launch
===================================================================
--- pkg/trunk/motion_planning/planning_environment/view_state_validity.launch (rev 0)
+++ pkg/trunk/motion_planning/planning_environment/view_state_validity.launch 2009-07-12 03:10:08 UTC (rev 18675)
@@ -0,0 +1,12 @@
+
+<launch>
+ <node pkg="planning_environment" type="view_state_validity" respawn="false" output="screen">
+ <remap from="robot_description" to="robotdesc/pr2" />
+ <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>
Property changes on: pkg/trunk/motion_planning/planning_environment/view_state_validity.launch
___________________________________________________________________
Added: svn:mergeinfo
+
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <is...@us...> - 2009-07-13 21:56:06
|
Revision: 18697
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=18697&view=rev
Author: isucan
Date: 2009-07-13 21:56:03 +0000 (Mon, 13 Jul 2009)
Log Message:
-----------
moved the attached bodies monitor from collision to kinematic model
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/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/monitors/collision_space_monitor.h
===================================================================
--- pkg/trunk/motion_planning/planning_environment/include/planning_environment/monitors/collision_space_monitor.h 2009-07-13 21:52:41 UTC (rev 18696)
+++ pkg/trunk/motion_planning/planning_environment/include/planning_environment/monitors/collision_space_monitor.h 2009-07-13 21:56:03 UTC (rev 18697)
@@ -40,9 +40,7 @@
#include "planning_environment/models/collision_models.h"
#include "planning_environment/monitors/kinematic_model_state_monitor.h"
-#include <tf/message_notifier.h>
#include <mapping_msgs/CollisionMap.h>
-#include <mapping_msgs/AttachedObject.h>
#include <boost/thread/mutex.hpp>
@@ -74,8 +72,6 @@
delete collisionMapNotifier_;
if (collisionMapUpdateNotifier_)
delete collisionMapUpdateNotifier_;
- if (attachedBodyNotifier_)
- delete attachedBodyNotifier_;
}
/** \brief Return the instance of the environment model maintained */
@@ -110,12 +106,6 @@
onAfterMapUpdate_ = callback;
}
- /** \brief Define a callback for after updating a map */
- void setOnAfterAttachBodyCallback(const boost::function<void(planning_models::KinematicModel::Link*)> &callback)
- {
- onAfterAttachBody_ = callback;
- }
-
/** \brief Return true if map has been received */
bool haveMap(void) const
{
@@ -141,8 +131,8 @@
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 mapping_msgs::AttachedObjectConstPtr &attachedObject);
-
+ virtual bool attachObject(const mapping_msgs::AttachedObjectConstPtr &attachedObject);
+
CollisionModels *cm_;
collision_space::EnvironmentModel *collisionSpace_;
double boxScale_;
@@ -152,11 +142,9 @@
ros::Time lastMapUpdate_;
tf::MessageNotifier<mapping_msgs::CollisionMap> *collisionMapNotifier_;
tf::MessageNotifier<mapping_msgs::CollisionMap> *collisionMapUpdateNotifier_;
- tf::MessageNotifier<mapping_msgs::AttachedObject> *attachedBodyNotifier_;
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/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-13 21:52:41 UTC (rev 18696)
+++ pkg/trunk/motion_planning/planning_environment/include/planning_environment/monitors/kinematic_model_state_monitor.h 2009-07-13 21:56:03 UTC (rev 18697)
@@ -40,7 +40,9 @@
#include "planning_environment/models/robot_models.h"
#include <tf/transform_datatypes.h>
#include <tf/transform_listener.h>
+#include <tf/message_notifier.h>
#include <mechanism_msgs/MechanismState.h>
+#include <mapping_msgs/AttachedObject.h>
#include <boost/bind.hpp>
#include <vector>
#include <string>
@@ -77,6 +79,8 @@
{
if (robotState_)
delete robotState_;
+ if (attachedBodyNotifier_)
+ delete attachedBodyNotifier_;
}
/** \brief Define a callback for when the state is changed */
@@ -85,6 +89,12 @@
onStateUpdate_ = callback;
}
+ /** \brief Define a callback for after updating a map */
+ void setOnAfterAttachBodyCallback(const boost::function<void(planning_models::KinematicModel::Link*)> &callback)
+ {
+ onAfterAttachBody_ = callback;
+ }
+
/** \brief Get the kinematic model that is being monitored */
planning_models::KinematicModel* getKinematicModel(void) const
{
@@ -163,8 +173,9 @@
void setupRSM(void);
void mechanismStateCallback(const mechanism_msgs::MechanismStateConstPtr &mechanismState);
+ void attachObjectCallback(const mapping_msgs::AttachedObjectConstPtr &attachedObject);
+ virtual bool attachObject(const mapping_msgs::AttachedObjectConstPtr &attachedObject);
-
RobotModels *rm_;
bool includePose_;
planning_models::KinematicModel *kmodel_;
@@ -175,6 +186,9 @@
ros::Subscriber mechanismStateSubscriber_;
tf::TransformListener *tf_;
+ 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_;
@@ -184,6 +198,8 @@
std::string frame_id_;
boost::function<void(void)> onStateUpdate_;
+ boost::function<void(planning_models::KinematicModel::Link*)>
+ onAfterAttachBody_;
bool havePose_;
bool haveMechanismState_;
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-13 21:52:41 UTC (rev 18696)
+++ pkg/trunk/motion_planning/planning_environment/src/monitors/collision_space_monitor.cpp 2009-07-13 21:56:03 UTC (rev 18697)
@@ -35,7 +35,6 @@
/** \author Ioan Sucan */
#include "planning_environment/monitors/collision_space_monitor.h"
-#include "planning_environment/util/construct_object.h"
#include <robot_msgs/PoseStamped.h>
#include <boost/bind.hpp>
#include <sstream>
@@ -228,59 +227,26 @@
onAfterMapUpdate_(collisionMap);
}
-void planning_environment::CollisionSpaceMonitor::attachObjectCallback(const mapping_msgs::AttachedObjectConstPtr &attachedObject)
+bool planning_environment::CollisionSpaceMonitor::attachObject(const mapping_msgs::AttachedObjectConstPtr &attachedObject)
{
collisionSpace_->lock();
- planning_models::KinematicModel::Link *link = kmodel_->getLink(attachedObject->link_name);
-
- if (attachedObject->objects.size() != attachedObject->poses.size())
- ROS_ERROR("Number of objects to attach does not match number of poses");
- else
- if (link)
- {
- // clear the previously attached bodies
- for (unsigned int i = 0 ; i < link->attachedBodies.size() ; ++i)
- delete link->attachedBodies[i];
- link->attachedBodies.resize(0);
- unsigned int n = attachedObject->objects.size();
-
- // create the new ones
- for (unsigned int i = 0 ; i < n ; ++i)
- {
- robot_msgs::PoseStamped pose;
- robot_msgs::PoseStamped poseP;
- pose.pose = attachedObject->poses[i];
- pose.header = attachedObject->header;
- bool err = false;
- try
- {
- tf_->transformPose(attachedObject->link_name, pose, poseP);
- }
- catch(...)
- {
- err = true;
- ROS_ERROR("Unable to transform object to be attached from frame '%s' to frame '%s'", attachedObject->header.frame_id.c_str(), attachedObject->link_name.c_str());
- }
- if (err)
- continue;
-
- shapes::Shape *shape = construct_object(attachedObject->objects[i]);
- if (!shape)
- continue;
-
- unsigned int j = link->attachedBodies.size();
- link->attachedBodies.push_back(new planning_models::KinematicModel::AttachedBody());
- tf::poseMsgToTF(poseP.pose, link->attachedBodies[j]->attachTrans);
- link->attachedBodies[j]->shape = shape;
- }
-
- // update the collision model
- collisionSpace_->updateAttachedBodies();
- ROS_DEBUG("Link '%s' has %d objects attached", attachedObject->link_name.c_str(), n);
- }
- else
- ROS_WARN("Unable to attach object to link '%s'", attachedObject->link_name.c_str());
+ // call the same code as in the kinematic model state monitor, but disable the callback
+ boost::function<void(planning_models::KinematicModel::Link*)> backup = onAfterAttachBody_;
+ onAfterAttachBody_ = NULL;
+ bool result = KinematicModelStateMonitor::attachObject(attachedObject);
+
+ // restore the callback
+ onAfterAttachBody_ = backup;
+ if (result)
+ {
+ collisionSpace_->updateAttachedBodies();
+ ROS_DEBUG("Attached bodies have been updated");
+ }
collisionSpace_->unlock();
- if (link && (onAfterAttachBody_ != NULL))
- onAfterAttachBody_(link);
+
+ // call the event, if needed
+ if (result && (onAfterAttachBody_ != NULL))
+ onAfterAttachBody_(kmodel_->getLink(attachedObject->link_name));
+
+ return result;
}
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-13 21:52:41 UTC (rev 18696)
+++ pkg/trunk/motion_planning/planning_environment/src/monitors/kinematic_model_state_monitor.cpp 2009-07-13 21:56:03 UTC (rev 18697)
@@ -35,6 +35,7 @@
/** \author Ioan Sucan */
#include "planning_environment/monitors/kinematic_model_state_monitor.h"
+#include "planning_environment/util/construct_object.h"
#include <angles/angles.h>
#include <sstream>
@@ -184,6 +185,69 @@
onStateUpdate_();
}
+bool planning_environment::KinematicModelStateMonitor::attachObject(const mapping_msgs::AttachedObjectConstPtr &attachedObject)
+{
+ bool result = false;
+ planning_models::KinematicModel::Link *link = kmodel_->getLink(attachedObject->link_name);
+
+ if (attachedObject->objects.size() != attachedObject->poses.size())
+ ROS_ERROR("Number of objects to attach does not match number of poses");
+ else
+ if (link)
+ {
+ // clear the previously attached bodies
+ for (unsigned int i = 0 ; i < link->attachedBodies.size() ; ++i)
+ delete link->attachedBodies[i];
+ link->attachedBodies.resize(0);
+ unsigned int n = attachedObject->objects.size();
+
+ // create the new ones
+ for (unsigned int i = 0 ; i < n ; ++i)
+ {
+ robot_msgs::PoseStamped pose;
+ robot_msgs::PoseStamped poseP;
+ pose.pose = attachedObject->poses[i];
+ pose.header = attachedObject->header;
+ bool err = false;
+ try
+ {
+ tf_->transformPose(attachedObject->link_name, pose, poseP);
+ }
+ catch(...)
+ {
+ err = true;
+ ROS_ERROR("Unable to transform object to be attached from frame '%s' to frame '%s'", attachedObject->header.frame_id.c_str(), attachedObject->link_name.c_str());
+ }
+ if (err)
+ continue;
+
+ shapes::Shape *shape = construct_object(attachedObject->objects[i]);
+ if (!shape)
+ continue;
+
+ unsigned int j = link->attachedBodies.size();
+ link->attachedBodies.push_back(new planning_models::KinematicModel::AttachedBody());
+ tf::poseMsgToTF(poseP.pose, link->attachedBodies[j]->attachTrans);
+ link->attachedBodies[j]->shape = shape;
+ }
+
+ result = true;
+ ROS_DEBUG("Link '%s' has %d objects attached", attachedObject->link_name.c_str(), n);
+ }
+ else
+ ROS_WARN("Unable to attach object to link '%s'", attachedObject->link_name.c_str());
+
+ if (result && (onAfterAttachBody_ != NULL))
+ onAfterAttachBody_(link);
+
+ return result;
+}
+
+void planning_environment::KinematicModelStateMonitor::attachObjectCallback(const mapping_msgs::AttachedObjectConstPtr &attachedObject)
+{
+ attachObject(attachedObject);
+}
+
void planning_environment::KinematicModelStateMonitor::waitForState(void) const
{
int s = 0;
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <is...@us...> - 2009-07-13 23:47:40
|
Revision: 18718
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=18718&view=rev
Author: isucan
Date: 2009-07-13 23:47:38 +0000 (Mon, 13 Jul 2009)
Log Message:
-----------
listening to objects_in_map topic
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-13 23:47:11 UTC (rev 18717)
+++ pkg/trunk/motion_planning/planning_environment/include/planning_environment/monitors/collision_space_monitor.h 2009-07-13 23:47:38 UTC (rev 18718)
@@ -41,7 +41,7 @@
#include "planning_environment/monitors/kinematic_model_state_monitor.h"
#include <mapping_msgs/CollisionMap.h>
-
+#include <mapping_msgs/ObjectInMap.h>
#include <boost/thread/mutex.hpp>
namespace planning_environment
@@ -68,6 +68,8 @@
virtual ~CollisionSpaceMonitor(void)
{
+ if (objectInMapNotifier_)
+ delete objectInMapNotifier_;
if (collisionMapNotifier_)
delete collisionMapNotifier_;
if (collisionMapUpdateNotifier_)
@@ -131,6 +133,7 @@
void updateCollisionSpace(const mapping_msgs::CollisionMapConstPtr &collisionMap, bool clear);
void collisionMapCallback(const mapping_msgs::CollisionMapConstPtr &collisionMap);
void collisionMapUpdateCallback(const mapping_msgs::CollisionMapConstPtr &collisionMap);
+ void objectInMapCallback(const mapping_msgs::ObjectInMapConstPtr &objectInMap);
virtual bool attachObject(const mapping_msgs::AttachedObjectConstPtr &attachedObject);
CollisionModels *cm_;
@@ -142,6 +145,7 @@
ros::Time lastMapUpdate_;
tf::MessageNotifier<mapping_msgs::CollisionMap> *collisionMapNotifier_;
tf::MessageNotifier<mapping_msgs::CollisionMap> *collisionMapUpdateNotifier_;
+ tf::MessageNotifier<mapping_msgs::ObjectInMap> *objectInMapNotifier_;
boost::function<void(const mapping_msgs::CollisionMapConstPtr)> onBeforeMapUpdate_;
boost::function<void(const mapping_msgs::CollisionMapConstPtr)> onAfterMapUpdate_;
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-13 23:47:11 UTC (rev 18717)
+++ pkg/trunk/motion_planning/planning_environment/src/monitors/collision_space_monitor.cpp 2009-07-13 23:47:38 UTC (rev 18718)
@@ -35,6 +35,8 @@
/** \author Ioan Sucan */
#include "planning_environment/monitors/collision_space_monitor.h"
+#include "planning_environment/util/construct_object.h"
+#include <robot_msgs/PointStamped.h>
#include <robot_msgs/PoseStamped.h>
#include <boost/bind.hpp>
#include <sstream>
@@ -55,6 +57,8 @@
onAfterMapUpdate_ = NULL;
collisionMapNotifier_ = NULL;
+ collisionMapUpdateNotifier_ = NULL;
+ objectInMapNotifier_ = NULL;
haveMap_ = false;
@@ -89,6 +93,9 @@
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());
+
+ 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());
}
bool planning_environment::CollisionSpaceMonitor::isMapUpdated(double sec) const
@@ -218,6 +225,51 @@
onAfterMapUpdate_(collisionMap);
}
+void planning_environment::CollisionSpaceMonitor::objectInMapCallback(const mapping_msgs::ObjectInMapConstPtr &objectInMap)
+{
+ if (objectInMap->action == mapping_msgs::ObjectInMap::ADD)
+ {
+ // add the object to the map
+ shapes::Shape *shape = construct_object(objectInMap->object);
+ if (shape)
+ {
+ bool err = false;
+ robot_msgs::PoseStamped psi;
+ robot_msgs::PoseStamped pso;
+ psi.pose = objectInMap->pose;
+ psi.header = objectInMap->header;
+ try
+ {
+ tf_->transformPose(getFrameId(), psi, pso);
+ }
+ catch(...)
+ {
+ err = true;
+ }
+
+ if (err)
+ ROS_ERROR("Unable to transform object '%s' in frame '%s' to frame '%s'", objectInMap->id.c_str(), objectInMap->header.frame_id.c_str(), getFrameId().c_str());
+ else
+ {
+ btTransform pose;
+ tf::poseMsgToTF(pso.pose, pose);
+ collisionSpace_->lock();
+ collisionSpace_->addObject(objectInMap->id, shape, pose);
+ collisionSpace_->unlock();
+ ROS_DEBUG("Added object '%s' to collision space", objectInMap->id.c_str());
+ }
+ delete shape;
+ }
+ }
+ else
+ {
+ // remove the object from the map
+ collisionSpace_->lock();
+ collisionSpace_->clearObstacles(objectInMap->id);
+ collisionSpace_->unlock();
+ }
+}
+
bool planning_environment::CollisionSpaceMonitor::attachObject(const mapping_msgs::AttachedObjectConstPtr &attachedObject)
{
collisionSpace_->lock();
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <is...@us...> - 2009-07-14 01:50:53
|
Revision: 18726
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=18726&view=rev
Author: isucan
Date: 2009-07-14 01:50:50 +0000 (Tue, 14 Jul 2009)
Log Message:
-----------
filter for known objects
Modified Paths:
--------------
pkg/trunk/motion_planning/planning_environment/CMakeLists.txt
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/CMakeLists.txt
===================================================================
--- pkg/trunk/motion_planning/planning_environment/CMakeLists.txt 2009-07-14 01:12:45 UTC (rev 18725)
+++ pkg/trunk/motion_planning/planning_environment/CMakeLists.txt 2009-07-14 01:50:50 UTC (rev 18726)
@@ -21,6 +21,8 @@
rospack_add_executable(clear_known_objects src/tools/clear_known_objects.cpp)
target_link_libraries(clear_known_objects planning_environment)
+rospack_link_boost(clear_known_objects thread)
+rospack_add_openmp_flags(clear_known_objects)
# Tests
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-14 01:12:45 UTC (rev 18725)
+++ pkg/trunk/motion_planning/planning_environment/src/monitors/kinematic_model_state_monitor.cpp 2009-07-14 01:50:50 UTC (rev 18726)
@@ -232,7 +232,7 @@
continue;
unsigned int j = link->attachedBodies.size();
- link->attachedBodies.push_back(new planning_models::KinematicModel::AttachedBody());
+ link->attachedBodies.push_back(new planning_models::KinematicModel::AttachedBody(link));
tf::poseMsgToTF(poseP.pose, link->attachedBodies[j]->attachTrans);
link->attachedBodies[j]->shape = shape;
}
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-07-14 01:12:45 UTC (rev 18725)
+++ pkg/trunk/motion_planning/planning_environment/src/tools/clear_known_objects.cpp 2009-07-14 01:50:50 UTC (rev 18726)
@@ -41,13 +41,16 @@
**/
-#include "planning_environment/models/collision_models.h"
+#include <ros/ros.h>
#include "planning_environment/monitors/kinematic_model_state_monitor.h"
#include "planning_environment/util/construct_object.h"
+#include <geometric_shapes/bodies.h>
#include <tf/message_notifier.h>
-#include <mapping_msgs/CollisionMap.h>
+#include <robot_msgs/PointCloud.h>
+#include <robot_msgs/PoseStamped.h>
#include <mapping_msgs/AttachedObject.h>
+#include <mapping_msgs/ObjectInMap.h>
class ClearKnownObjects
{
@@ -55,72 +58,272 @@
ClearKnownObjects(void)
{
- cm_ = new planning_environment::CollisionModels("robot_description");
- if (cm_->loadedModels())
+ rm_ = new planning_environment::RobotModels("robot_description");
+ if (rm_->loadedModels())
{
- em_ = cm_->getODECollisionModel().get();
- kmsm_ = new planning_environment::KinematicModelStateMonitor(static_cast<planning_environment::RobotModels*>(cm_), &tf_);
+ kmsm_ = new planning_environment::KinematicModelStateMonitor(rm_, &tf_);
+ nh_.param<std::string>("~fixed_frame", fixed_frame_, kmsm_->getFrameId());
+ nh_.param<double>("~object_scale", scale_, 1.0);
+ nh_.param<double>("~object_padd", padd_, 0.02);
+
+ cloudPublisher_ = nh_.advertise<robot_msgs::PointCloud>("cloud_out", 1);
kmsm_->setOnAfterAttachBodyCallback(boost::bind(&ClearKnownObjects::attachObjectEvent, this, _1));
-
- collisionMapNotifier_ = new tf::MessageNotifier<mapping_msgs::CollisionMap>(tf_, boost::bind(&ClearKnownObjects::collisionMapCallback, this, _1), "collision_map", kmsm_->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(&ClearKnownObjects::collisionMapUpdateCallback, this, _1), "collision_map_update", kmsm_->getFrameId(), 1);
- ROS_DEBUG("Listening to collision_map_update using message notifier with target frame %s", collisionMapUpdateNotifier_->getTargetFramesString().c_str());
+ cloudNotifier_ = new tf::MessageNotifier<robot_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);
}
else
{
- em_ = NULL;
kmsm_ = NULL;
- collisionMapNotifier_ = NULL;
- collisionMapUpdateNotifier_ = NULL;
+ cloudNotifier_ = NULL;
+ objectInMapNotifier_ = NULL;
}
}
~ClearKnownObjects(void)
{
- if (collisionMapNotifier_)
- delete collisionMapNotifier_;
- if (collisionMapUpdateNotifier_)
- delete collisionMapUpdateNotifier_;
+ if (cloudNotifier_)
+ delete cloudNotifier_;
+ if (objectInMapNotifier_)
+ delete objectInMapNotifier_;
if (kmsm_)
delete kmsm_;
- if (cm_)
- delete cm_;
+ if (rm_)
+ delete rm_;
+ for (unsigned int i = 0 ; i < attachedObjects_.size() ; ++i)
+ delete attachedObjects_[i].body;
+ for (std::map<std::string, KnownObject>::iterator it = objectsInMap_.begin() ; it != objectsInMap_.end() ; ++it)
+ delete it->second.body;
}
void run(void)
{
- ros::spin();
+ if (rm_->loadedModels())
+ {
+ kmsm_->waitForState();
+ ros::spin();
+ }
}
private:
- void collisionMapCallback(const mapping_msgs::CollisionMapConstPtr &collisionMap)
+ struct KnownObject
{
+ KnownObject(void)
+ {
+ body = NULL;
+ }
+
+ void usePose(btTransform &pose)
+ {
+ body->setPose(pose);
+ body->computeBoundingSphere(bsphere);
+ rsquare = bsphere.radius * bsphere.radius;
+ }
+
+ bodies::Body *body;
+ bodies::BoundingSphere bsphere;
+ double rsquare;
+ };
+
+ void cloudCallback(const robot_msgs::PointCloudConstPtr &cloud)
+ {
+ updateObjects_.lock();
+
+ // check if we have attached bodies
+ if (attachedObjects_.size() > 0)
+ {
+ // update the poses for the attached bodies
+ kmsm_->getKinematicModel()->lock();
+ kmsm_->getKinematicModel()->computeTransforms(kmsm_->getRobotState()->getParams());
+ if (fixed_frame_ != kmsm_->getFrameId())
+ {
+ std::string errStr;
+ ros::Time tm;
+ if (!tf_.getLatestCommonTime(kmsm_->getFrameId(), fixed_frame_, tm, &errStr) == tf::NO_ERROR)
+ {
+ ROS_ERROR("Unable to transform attached body from frame '%s' to frame '%s'", kmsm_->getFrameId().c_str(), fixed_frame_.c_str());
+ if (!errStr.empty())
+ ROS_ERROR("TF said: %s", errStr.c_str());
+ }
+ else
+ {
+ bool error = false;
+ for (unsigned int i = 0 ; i < attachedObjects_.size() ; ++i)
+ {
+ tf::Stamped<tf::Pose> pose(attached_[i]->globalTrans, tm, kmsm_->getFrameId());
+ tf::Stamped<tf::Pose> poseOut;
+ try
+ {
+ tf_.transformPose(fixed_frame_, pose, poseOut);
+ attachedObjects_[i].usePose(poseOut);
+ }
+ catch(...)
+ {
+ error = true;
+ }
+ }
+ if (error)
+ ROS_ERROR("Errors encountered when transforming attached bodies from frame '%s' to frame '%s'", kmsm_->getFrameId().c_str(), fixed_frame_.c_str());
+ }
+ }
+ else
+ {
+ for (unsigned int i = 0 ; i < attachedObjects_.size() ; ++i)
+ attachedObjects_[i].usePose(attached_[i]->globalTrans);
+ }
+ kmsm_->getKinematicModel()->unlock();
+ }
+
+ // transform pointcloud into fixed frame
+ robot_msgs::PointCloud cloudTransf;
+ tf_.transformPointCloud(fixed_frame_, *cloud, cloudTransf);
+
+ // compute mask for cloud
+ int n = cloud->pts.size();
+ std::vector<int> mask(n);
+
+#pragma omp parallel for
+ for (int i = 0 ; i < n ; ++i)
+ {
+ btVector3 pt = btVector3(cloudTransf.pts[i].x, cloudTransf.pts[i].y, cloudTransf.pts[i].z);
+ int out = 1;
+
+ for (unsigned int j = 0 ; out && j < attachedObjects_.size() ; ++j)
+ if (attachedObjects_[j].bsphere.center.distance2(pt) < attachedObjects_[j].rsquare)
+ if (attachedObjects_[j].body->containsPoint(pt))
+ out = 0;
+
+ for (std::map<std::string, KnownObject>::iterator it = objectsInMap_.begin() ; out && it != objectsInMap_.end() ; ++it)
+ if (it->second.bsphere.center.distance2(pt) < it->second.rsquare)
+ if (it->second.body->containsPoint(pt))
+ out = 0;
+
+ mask[i] = out;
+ }
+
+ updateObjects_.unlock();
+
+ // publish new cloud
+ const unsigned int np = cloud->pts.size();
+ robot_msgs::PointCloud data_out;
+
+ // fill in output data with points that are NOT in the known objects
+ data_out.header = cloud->header;
+
+ data_out.pts.resize(0);
+ data_out.pts.reserve(np);
+
+ data_out.chan.resize(cloud->chan.size());
+ for (unsigned int i = 0 ; i < data_out.chan.size() ; ++i)
+ {
+ ROS_ASSERT(cloud->chan[i].vals.size() == cloud->pts.size());
+ data_out.chan[i].name = cloud->chan[i].name;
+ data_out.chan[i].vals.reserve(cloud->chan[i].vals.size());
+ }
+
+ for (unsigned int i = 0 ; i < np ; ++i)
+ if (mask[i])
+ {
+ data_out.pts.push_back(cloud->pts[i]);
+ for (unsigned int j = 0 ; j < data_out.chan.size() ; ++j)
+ data_out.chan[j].vals.push_back(cloud->chan[j].vals[i]);
+ }
+
+ cloudPublisher_.publish(data_out);
}
- void collisionMapUpdateCallback(const mapping_msgs::CollisionMapConstPtr &collisionMap)
+ void objectInMapCallback(const mapping_msgs::ObjectInMapConstPtr &objectInMap)
{
+ updateObjects_.lock();
+ if (objectInMap->action == mapping_msgs::ObjectInMap::ADD)
+ {
+ // add the object to the map
+ shapes::Shape *shape = planning_environment::construct_object(objectInMap->object);
+ if (shape)
+ {
+ bool err = false;
+ robot_msgs::PoseStamped psi;
+ robot_msgs::PoseStamped pso;
+ psi.pose = objectInMap->pose;
+ psi.header = objectInMap->header;
+ try
+ {
+ tf_.transformPose(fixed_frame_, psi, pso);
+ }
+ catch(...)
+ {
+ err = true;
+ }
+
+ if (err)
+ ROS_ERROR("Unable to transform object '%s' in frame '%s' to frame '%s'", objectInMap->id.c_str(), objectInMap->header.frame_id.c_str(), fixed_frame_.c_str());
+ else
+ {
+ btTransform pose;
+ tf::poseMsgToTF(pso.pose, pose);
+ KnownObject kb;
+ kb.body = bodies::createBodyFromShape(shape);
+ kb.body->setScale(scale_);
+ kb.body->setPadding(padd_);
+ kb.usePose(pose);
+ objectsInMap_[objectInMap->id] = kb;
+ ROS_DEBUG("Added object '%s' to list of known objects", objectInMap->id.c_str());
+ }
+ delete shape;
+ }
+ }
+ else
+ {
+ if (objectsInMap_.find(objectInMap->id) != objectsInMap_.end())
+ {
+ delete objectsInMap_[objectInMap->id].body;
+ objectsInMap_.erase(objectInMap->id);
+ }
+ else
+ ROS_WARN("Object '%s' is not in list of known objects", objectInMap->id.c_str());
+ }
+ updateObjects_.unlock();
}
void attachObjectEvent(const planning_models::KinematicModel::Link* link)
{
- em_->updateAttachedBodies();
+ updateObjects_.lock();
+ attached_.clear();
+ std::vector<planning_models::KinematicModel::Link*> links;
+ rm_->getKinematicModel()->getLinks(links);
+ for (unsigned int i = 0 ; i < links.size() ; ++i)
+ for (unsigned int j = 0 ; j < links[i]->attachedBodies.size() ; ++j)
+ attached_.push_back(links[i]->attachedBodies[j]);
+ for (unsigned int i = 0 ; i < attachedObjects_.size() ; ++i)
+ delete attachedObjects_[i].body;
+ attachedObjects_.resize(attached_.size());
+ for (unsigned int i = 0 ; i < attached_.size() ; ++i)
+ {
+ attachedObjects_[i].body = bodies::createBodyFromShape(attached_[i]->shape);
+ attachedObjects_[i].body->setScale(scale_);
+ attachedObjects_[i].body->setPadding(padd_);
+ }
+ updateObjects_.unlock();
}
- tf::TransformListener tf_;
- planning_environment::CollisionModels *cm_;
- planning_environment::KinematicModelStateMonitor *kmsm_;
- collision_space::EnvironmentModel *em_;
-
- tf::MessageNotifier<mapping_msgs::CollisionMap> *collisionMapNotifier_;
- tf::MessageNotifier<mapping_msgs::CollisionMap> *collisionMapUpdateNotifier_;
+ ros::NodeHandle nh_;
+ tf::TransformListener tf_;
+ planning_environment::RobotModels *rm_;
+ planning_environment::KinematicModelStateMonitor *kmsm_;
+ tf::MessageNotifier<robot_msgs::PointCloud> *cloudNotifier_;
+ tf::MessageNotifier<mapping_msgs::ObjectInMap> *objectInMapNotifier_;
+ std::string fixed_frame_;
+ boost::mutex updateObjects_;
+ ros::Publisher cloudPublisher_;
+
+ double scale_;
+ double padd_;
+ std::vector<planning_models::KinematicModel::AttachedBody*> attached_;
+ std::vector<KnownObject> attachedObjects_;
+ std::map<std::string, KnownObject> objectsInMap_;
};
-
-
-
+
int main(int argc, char **argv)
{
ros::init(argc, argv, "clear_known_objects", ros::init_options::AnonymousName);
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
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.
|
|
From: <is...@us...> - 2009-07-14 22:21:18
|
Revision: 18796
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=18796&view=rev
Author: isucan
Date: 2009-07-14 22:21:09 +0000 (Tue, 14 Jul 2009)
Log Message:
-----------
adding launch file
Modified Paths:
--------------
pkg/trunk/motion_planning/planning_environment/CMakeLists.txt
Added Paths:
-----------
pkg/trunk/motion_planning/planning_environment/display_planner_collision_model.launch
Modified: pkg/trunk/motion_planning/planning_environment/CMakeLists.txt
===================================================================
--- pkg/trunk/motion_planning/planning_environment/CMakeLists.txt 2009-07-14 22:19:18 UTC (rev 18795)
+++ pkg/trunk/motion_planning/planning_environment/CMakeLists.txt 2009-07-14 22:21:09 UTC (rev 18796)
@@ -5,6 +5,11 @@
set(ROS_BUILD_TYPE Debug)
+#set the default path for built executables to the "bin" directory
+set(EXECUTABLE_OUTPUT_PATH ${PROJECT_SOURCE_DIR}/bin)
+#set the default path for built libraries to the "lib" directory
+set(LIBRARY_OUTPUT_PATH ${PROJECT_SOURCE_DIR}/lib)
+
rospack_add_library(planning_environment src/models/robot_models.cpp
src/models/collision_models.cpp
src/monitors/kinematic_model_state_monitor.cpp
Added: pkg/trunk/motion_planning/planning_environment/display_planner_collision_model.launch
===================================================================
--- pkg/trunk/motion_planning/planning_environment/display_planner_collision_model.launch (rev 0)
+++ pkg/trunk/motion_planning/planning_environment/display_planner_collision_model.launch 2009-07-14 22:21:09 UTC (rev 18796)
@@ -0,0 +1,12 @@
+
+<launch>
+ <node pkg="planning_environment" type="display_planner_collision_model" respawn="false" output="screen">
+ <remap from="robot_description" to="robotdesc/pr2" />
+ <remap from="collision_map" to="collision_map_occ" />
+ <remap from="collision_map_update" to="SKIP_THIS_TOPIC" />
+ <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>
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <is...@us...> - 2009-07-16 00:36:57
|
Revision: 18928
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=18928&view=rev
Author: isucan
Date: 2009-07-16 00:36:56 +0000 (Thu, 16 Jul 2009)
Log Message:
-----------
additional parameter for map update event
Modified Paths:
--------------
pkg/trunk/motion_planning/planning_environment/display_planner_collision_model.launch
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
pkg/trunk/motion_planning/planning_environment/src/tools/display_planner_collision_model.cpp
pkg/trunk/motion_planning/planning_environment/src/tools/view_state_validity.cpp
Modified: pkg/trunk/motion_planning/planning_environment/display_planner_collision_model.launch
===================================================================
--- pkg/trunk/motion_planning/planning_environment/display_planner_collision_model.launch 2009-07-16 00:31:30 UTC (rev 18927)
+++ pkg/trunk/motion_planning/planning_environment/display_planner_collision_model.launch 2009-07-16 00:36:56 UTC (rev 18928)
@@ -3,10 +3,7 @@
<node pkg="planning_environment" type="display_planner_collision_model" respawn="false" output="screen">
<remap from="robot_description" to="robotdesc/pr2" />
<remap from="collision_map" to="collision_map_occ" />
- <remap from="collision_map_update" to="SKIP_THIS_TOPIC" />
- <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" />
+ <remap from="collision_map_update" to="collision_map_occ_update" />
+ <param name="skip_collision_map" type="bool" value="true" />
</node>
</launch>
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-16 00:31:30 UTC (rev 18927)
+++ pkg/trunk/motion_planning/planning_environment/include/planning_environment/monitors/collision_space_monitor.h 2009-07-16 00:36:56 UTC (rev 18928)
@@ -89,13 +89,13 @@
}
/** \brief Define a callback for before updating a map */
- void setOnBeforeMapUpdateCallback(const boost::function<void(const mapping_msgs::CollisionMapConstPtr)> &callback)
+ void setOnBeforeMapUpdateCallback(const boost::function<void(const mapping_msgs::CollisionMapConstPtr, bool)> &callback)
{
onBeforeMapUpdate_ = callback;
}
/** \brief Define a callback for after updating a map */
- void setOnAfterMapUpdateCallback(const boost::function<void(const mapping_msgs::CollisionMapConstPtr)> &callback)
+ void setOnAfterMapUpdateCallback(const boost::function<void(const mapping_msgs::CollisionMapConstPtr, bool)> &callback)
{
onAfterMapUpdate_ = callback;
}
@@ -144,9 +144,9 @@
tf::MessageNotifier<mapping_msgs::CollisionMap> *collisionMapUpdateNotifier_;
tf::MessageNotifier<mapping_msgs::ObjectInMap> *objectInMapNotifier_;
- boost::function<void(const mapping_msgs::CollisionMapConstPtr)> onBeforeMapUpdate_;
- boost::function<void(const mapping_msgs::CollisionMapConstPtr)> onAfterMapUpdate_;
- boost::function<void(const mapping_msgs::ObjectInMapConstPtr)> onObjectInMapUpdate_;
+ 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/src/monitors/collision_space_monitor.cpp
===================================================================
--- pkg/trunk/motion_planning/planning_environment/src/monitors/collision_space_monitor.cpp 2009-07-16 00:31:30 UTC (rev 18927)
+++ pkg/trunk/motion_planning/planning_environment/src/monitors/collision_space_monitor.cpp 2009-07-16 00:36:56 UTC (rev 18928)
@@ -143,7 +143,7 @@
ROS_DEBUG("Received %d points (collision map)", n);
if (onBeforeMapUpdate_ != NULL)
- onBeforeMapUpdate_(collisionMap);
+ onBeforeMapUpdate_(collisionMap, clear);
// we want to make sure the frame the robot model is kept in is the same as the frame of the collisionMap
bool transform = !frame_id_.empty() && collisionMap->header.frame_id != frame_id_;
@@ -220,7 +220,7 @@
haveMap_ = true;
if (onAfterMapUpdate_ != NULL)
- onAfterMapUpdate_(collisionMap);
+ onAfterMapUpdate_(collisionMap, clear);
}
void planning_environment::CollisionSpaceMonitor::objectInMapCallback(const mapping_msgs::ObjectInMapConstPtr &objectInMap)
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-16 00:31:30 UTC (rev 18927)
+++ pkg/trunk/motion_planning/planning_environment/src/tools/display_planner_collision_model.cpp 2009-07-16 00:36:56 UTC (rev 18928)
@@ -57,10 +57,13 @@
{
visualizationMarkerPublisher_ = nh_.advertise<visualization_msgs::Marker>("visualization_marker", 10240);
collisionModels_ = new planning_environment::CollisionModels("robot_description");
+ nh_.param<bool>("~skip_collision_map", skip_collision_map_, false);
+
if (collisionModels_->loadedModels())
{
collisionSpaceMonitor_ = new planning_environment::CollisionSpaceMonitor(collisionModels_, &tf_);
- collisionSpaceMonitor_->setOnAfterMapUpdateCallback(boost::bind(&DisplayPlannerCollisionModel::afterWorldUpdate, this, _1));
+ if (!skip_collision_map_)
+ collisionSpaceMonitor_->setOnAfterMapUpdateCallback(boost::bind(&DisplayPlannerCollisionModel::afterWorldUpdate, this, _1, _2));
collisionSpaceMonitor_->setOnAfterAttachBodyCallback(boost::bind(&DisplayPlannerCollisionModel::afterAttachBody, this, _1, _2));
collisionSpaceMonitor_->setOnObjectInMapUpdateCallback(boost::bind(&DisplayPlannerCollisionModel::objectInMapUpdate, this, _1));
}
@@ -100,8 +103,11 @@
visualizationMarkerPublisher_.publish(mk);
}
- void afterWorldUpdate(const mapping_msgs::CollisionMapConstPtr &collisionMap)
+ void afterWorldUpdate(const mapping_msgs::CollisionMapConstPtr &collisionMap, bool clear)
{
+ if (!clear)
+ return;
+
unsigned int n = collisionMap->get_boxes_size();
for (unsigned int i = 0 ; i < n ; ++i)
{
@@ -203,11 +209,13 @@
visualizationMarkerPublisher_.publish(mk);
}
- ros::Publisher visualizationMarkerPublisher_;
ros::NodeHandle nh_;
tf::TransformListener tf_;
planning_environment::CollisionModels *collisionModels_;
planning_environment::CollisionSpaceMonitor *collisionSpaceMonitor_;
+ ros::Publisher visualizationMarkerPublisher_;
+ bool skip_collision_map_;
+
};
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-16 00:31:30 UTC (rev 18927)
+++ pkg/trunk/motion_planning/planning_environment/src/tools/view_state_validity.cpp 2009-07-16 00:36:56 UTC (rev 18928)
@@ -61,7 +61,7 @@
stateValidityPublisher_ = nh_.advertise<std_msgs::Byte>("state_validity", 1);
planningMonitor_ = new planning_environment::PlanningMonitor(collisionModels_, &tf_);
planningMonitor_->getEnvironmentModel()->setVerbose(true);
- planningMonitor_->setOnAfterMapUpdateCallback(boost::bind(&ViewStateValidity::afterWorldUpdate, this, _1));
+ planningMonitor_->setOnAfterMapUpdateCallback(boost::bind(&ViewStateValidity::afterWorldUpdate, this, _1, _2));
planningMonitor_->setOnStateUpdateCallback(boost::bind(&ViewStateValidity::stateUpdate, this));
}
}
@@ -76,7 +76,7 @@
protected:
- void afterWorldUpdate(const mapping_msgs::CollisionMapConstPtr &collisionMap)
+ void afterWorldUpdate(const mapping_msgs::CollisionMapConstPtr &collisionMap, bool clear)
{
last_ = -1;
}
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|