obstacle_distance_moveit.cpp
Go to the documentation of this file.
1 /*
2  * Copyright 2017 Fraunhofer Institute for Manufacturing Engineering and Automation (IPA)
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9 
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  */
16 
17 #include <ros/ros.h>
18 
19 #if ROS_VERSION_MINIMUM(1,14,0) // melodic
21 #else
22 #include <tf/transform_listener.h>
23 #endif
24 
26 
28 {
29 public:
30  CreateCollisionWorld(const collision_detection::WorldPtr &world) :
31  CollisionWorldFCL(world)
32  {}
33 
34  void getCollisionObject(std::vector<std::shared_ptr<fcl::CollisionObject> > &obj)
35  {
36  std::map<std::string, collision_detection::FCLObject>::iterator it = fcl_objs_.begin();
37  obj.reserve(fcl_objs_.size());
38 
39  for (it; it != fcl_objs_.end(); ++it)
40  {
41  obj.push_back(it->second.collision_objects_[0]);
42  }
43  }
44 };
45 
47 {
48 public:
49  CreateCollisionRobot(const robot_model::RobotModelConstPtr &model) :
50  CollisionRobotFCL(model)
51  {}
52 
53  void getCollisionObject(const robot_state::RobotState &state,
54  std::vector<std::shared_ptr<fcl::CollisionObject> > &obj)
55  {
57  constructFCLObject(state, fcl_obj);
58  obj = fcl_obj.collision_objects_;
59  }
60 };
61 
63 {
64  planning_scene_monitor::LockedPlanningSceneRO ps(planning_scene_monitor_);
65  planning_scene::PlanningScenePtr planning_scene_ptr = ps->diff();
66 
67  std::vector<std::shared_ptr<fcl::CollisionObject> > robot_obj, world_obj;
68  robot_state::RobotState robot_state(planning_scene_ptr->getCurrentState());
69 
70  CreateCollisionWorld collision_world(planning_scene_ptr->getWorldNonConst());
71  collision_world.getCollisionObject(world_obj);
72 
73  CreateCollisionRobot collision_robot(robot_state.getRobotModel());
74  collision_robot.getCollisionObject(robot_state, robot_obj);
75 
76  this->robot_links_.clear();
77  this->collision_objects_.clear();
78 
79  for (unsigned int i = 0; i < robot_obj.size(); i++)
80  {
82  static_cast<const collision_detection::CollisionGeometryData *>(robot_obj[i]->collisionGeometry()->getUserData());
83  this->robot_links_[robot_link->getID()] = robot_obj[i];
84  }
85  for (unsigned int i = 0; i < world_obj.size(); i++)
86  {
87  const collision_detection::CollisionGeometryData *collision_object =
88  static_cast<const collision_detection::CollisionGeometryData *>(world_obj[i]->collisionGeometry()->getUserData());
89  this->collision_objects_[collision_object->getID()] = world_obj[i];
90  }
91 }
92 
93 bool ObstacleDistanceMoveit::planningSceneCallback(moveit_msgs::GetPlanningScene::Request &req, moveit_msgs::GetPlanningScene::Response &res)
94 {
95  planning_scene_monitor::LockedPlanningSceneRO ps(planning_scene_monitor_);
96  planning_scene::PlanningScenePtr planning_scene_ptr = ps->diff();
97 
98  planning_scene_ptr->getPlanningSceneMsg(res.scene, req.components);
99 
100  return true;
101 }
102 
103 bool ObstacleDistanceMoveit::registerCallback(cob_srvs::SetString::Request &req,
104  cob_srvs::SetString::Response &res)
105 {
106  boost::mutex::scoped_lock lock(registered_links_mutex_);
107  std::pair<std::set<std::string>::iterator, bool> ret = registered_links_.insert(req.data);
108 
109  res.success = true;
110  res.message = (ret.second) ? (req.data + " successfully registered") : (req.data + " already registered");
111  return true;
112 }
113 
114 bool ObstacleDistanceMoveit::unregisterCallback(cob_srvs::SetString::Request &req,
115  cob_srvs::SetString::Response &res)
116 {
117  boost::mutex::scoped_lock lock(registered_links_mutex_);
118  std::set<std::string>::iterator it = registered_links_.find(req.data);
119 
120  if (it != registered_links_.end())
121  {
122  registered_links_.erase(it);
123 
124  res.success = true;
125  res.message = req.data + " successfully unregistered";
126  }
127  else
128  {
129  res.success = true;
130  res.message = req.data + " has not been registered before";
131  }
132 
133  return true;
134 }
135 
137 {
138  std::map<std::string, std::shared_ptr<fcl::CollisionObject> > robot_links = this->robot_links_;
139  std::map<std::string, std::shared_ptr<fcl::CollisionObject> > collision_objects = this->collision_objects_;
140 
141  boost::mutex::scoped_lock lock(registered_links_mutex_);
142  cob_control_msgs::ObstacleDistances distance_infos;
143 
144  planning_scene_monitor::LockedPlanningSceneRO ps(planning_scene_monitor_);
145  planning_scene::PlanningScenePtr planning_scene_ptr = ps->diff();
146 
147  std::string planning_frame = planning_scene_ptr->getPlanningFrame();
148 
149  std::set<std::string>::iterator link_it;
150  for (link_it = registered_links_.begin(); link_it!=registered_links_.end(); ++link_it)
151  {
152  std::string robot_link_name = *link_it;
153  const std::shared_ptr<fcl::CollisionObject> robot_object = robot_links[robot_link_name];
154  ROS_DEBUG_STREAM("RobotLink: " << robot_link_name << ", Type: " << robot_object->getObjectType());
155 
156  std::map<std::string, std::shared_ptr<fcl::CollisionObject> >::iterator obj_it;
157  for (obj_it = collision_objects.begin(); obj_it != collision_objects.end(); ++obj_it)
158  {
159  std::string collision_object_name = obj_it->first;
160  const std::shared_ptr<fcl::CollisionObject> collision_object = collision_objects[collision_object_name];
161  ROS_DEBUG_STREAM("CollisionLink: " << collision_object_name << ", Type: " << collision_object->getObjectType());
162 
163  if(collision_object->getObjectType() == fcl::OT_OCTREE)
164  {
165  ROS_WARN_THROTTLE(1, "Consideration of <octomap> not yet implemented");
166  continue;
167  }
168 
169  cob_control_msgs::ObstacleDistance info;
170  info = getDistanceInfo(robot_object, collision_object);
171 
172  info.header.frame_id = planning_frame;
173  info.header.stamp = event.current_real;
174  info.link_of_interest = robot_link_name;
175  info.obstacle_id = collision_object_name;
176 
177  distance_infos.distances.push_back(info);
178  }
179 
180  std::map<std::string, std::shared_ptr<fcl::CollisionObject> >::iterator selfcollision_it;
181  for (selfcollision_it = robot_links.begin(); selfcollision_it != robot_links.end(); ++selfcollision_it)
182  {
183  std::string robot_self_name = selfcollision_it->first;
185 
186  if(acm_.getEntry(robot_link_name, robot_self_name, type))
187  {
189  {
190  const std::shared_ptr<fcl::CollisionObject> robot_self_object = robot_links[robot_self_name];
191  ROS_DEBUG_STREAM("CollisionLink: " << robot_self_name << ", Type: " << robot_self_object->getObjectType());
192 
193  cob_control_msgs::ObstacleDistance info;
194  info = getDistanceInfo(robot_object, robot_self_object);
195 
196  info.header.frame_id = planning_frame;
197  info.header.stamp = event.current_real;
198  info.link_of_interest = robot_link_name;
199  info.obstacle_id = robot_self_name;
200 
201  distance_infos.distances.push_back(info);
202  }
203  else
204  {
205  // This is diagonal of allowed collision matrix
206  }
207  }
208  }
209  }
210  distance_pub_.publish(distance_infos);
211 }
212 
214 {
215  planning_scene_monitor::LockedPlanningSceneRO ps(planning_scene_monitor_);
216  planning_scene::PlanningScenePtr planning_scene_ptr = ps->diff();
217 
218  moveit_msgs::PlanningScene scene;
219  planning_scene_ptr->getPlanningSceneMsg(scene);
220  monitored_scene_pub_.publish(scene);
221 }
222 
223 
224 bool ObstacleDistanceMoveit::calculateDistanceServiceCallback(cob_control_msgs::GetObstacleDistance::Request &req,
225  cob_control_msgs::GetObstacleDistance::Response &resp)
226 {
227  std::map<std::string, std::shared_ptr<fcl::CollisionObject> > robot_links = this->robot_links_;
228  std::map<std::string, std::shared_ptr<fcl::CollisionObject> > collision_objects = this->collision_objects_;
229 
230  // Links
231  for (unsigned int i=0; i< req.links.size(); ++i)
232  {
233  if (req.objects.size() == 0)
234  {
235  // All objects
236  std::map<std::string, std::shared_ptr<fcl::CollisionObject> >::iterator it;
237  for (it = collision_objects.begin(); it != collision_objects.end(); ++it)
238  {
239  const std::shared_ptr<fcl::CollisionObject> collision_object = collision_objects[it->first];
240  if(collision_object->getObjectType() == fcl::OT_OCTREE)
241  {
242  ROS_WARN_THROTTLE(1, "Consideration of <octomap> not yet implemented");
243  continue;
244  }
245  resp.link_to_object.push_back(req.links[i] + "_to_" + it->first);
246  resp.distances.push_back(getDistanceInfo(robot_links[req.links[i]], collision_object).distance);
247  }
248  }
249  else
250  {
251  // Specific objects
252  for (int y = 0; y < req.objects.size(); y++)
253  {
254  const std::shared_ptr<fcl::CollisionObject> collision_object = collision_objects[req.objects[y]];
255  if(collision_object->getObjectType() == fcl::OT_OCTREE)
256  {
257  ROS_WARN_THROTTLE(1, "Consideration of <octomap> not yet implemented");
258  continue;
259  }
260  resp.link_to_object.push_back(req.links[i] + " to " + req.objects[y]);
261  resp.distances.push_back(getDistanceInfo(robot_links[req.links[i]], collision_object).distance);
262  }
263  }
264  }
265  return true;
266 }
267 
268 cob_control_msgs::ObstacleDistance ObstacleDistanceMoveit::getDistanceInfo(const std::shared_ptr<fcl::CollisionObject> object_a,
269  const std::shared_ptr<fcl::CollisionObject> object_b)
270 {
271  fcl::DistanceRequest req(true); // enable_nearest_points
272  fcl::DistanceResult res;
273  res.update(MAXIMAL_MINIMAL_DISTANCE, NULL, NULL, fcl::DistanceResult::NONE, fcl::DistanceResult::NONE);
274 
275  Eigen::Vector3d np_object_a;
276  Eigen::Vector3d np_object_b;
277 
278  double dist = fcl::distance(object_a.get(), object_b.get(), req, res);
279 
280  // this is to prevent what seems to be a nasty bug in fcl
281  if(object_a->getObjectType() == fcl::OT_GEOM && object_b->getObjectType() == fcl::OT_BVH)
282  {
283  // res.nearest_points is swapped in this case
284  np_object_a(0) = res.nearest_points[1][0];
285  np_object_a(1) = res.nearest_points[1][1];
286  np_object_a(2) = res.nearest_points[1][2];
287 
288  np_object_b(0) = res.nearest_points[0][0];
289  np_object_b(1) = res.nearest_points[0][1];
290  np_object_b(2) = res.nearest_points[0][2];
291  }
292  else
293  {
294  np_object_a(0) = res.nearest_points[0][0];
295  np_object_a(1) = res.nearest_points[0][1];
296  np_object_a(2) = res.nearest_points[0][2];
297 
298  np_object_b(0) = res.nearest_points[1][0];
299  np_object_b(1) = res.nearest_points[1][1];
300  np_object_b(2) = res.nearest_points[1][2];
301  }
302  // ToDo: are there other cases? OT_OCTREE? see fcl::OBJECT_TYPE
303 
304  geometry_msgs::Vector3 np_object_a_msg;
305  tf::vectorEigenToMsg(np_object_a, np_object_a_msg);
306  ROS_DEBUG_STREAM("NearestPoint OBJ_A: \n" << np_object_a_msg);
307 
308  geometry_msgs::Vector3 np_object_b_msg;
309  tf::vectorEigenToMsg(np_object_b, np_object_b_msg);
310  ROS_DEBUG_STREAM("NearestPoint OBJ_B: \n" << np_object_b_msg);
311 
312  // Transformation for object_a
313  fcl::Transform3f fcl_trans_object_a = object_a->getTransform();
314  fcl::Vec3f fcl_vec_object_a = fcl_trans_object_a.getTranslation();
315  fcl::Quaternion3f fcl_quat_object_a = fcl_trans_object_a.getQuatRotation();
316 
317  Eigen::Affine3d eigen_trans_object_a;
318  tf::Transform tf_trans_object_a(tf::Quaternion(fcl_quat_object_a.getX(),fcl_quat_object_a.getY(),fcl_quat_object_a.getZ(),fcl_quat_object_a.getW()),
319  tf::Vector3(fcl_vec_object_a[0],fcl_vec_object_a[1],fcl_vec_object_a[2]));
320  tf::transformTFToEigen(tf_trans_object_a, eigen_trans_object_a);
321 
322  geometry_msgs::Transform trans_object_a_msg;
323  tf::transformTFToMsg(tf_trans_object_a, trans_object_a_msg);
324  ROS_DEBUG_STREAM("Transform OBJ_A: \n" << trans_object_a_msg);
325 
326  // Transformation for object_b
327  fcl::Transform3f fcl_trans_object_b = object_b->getTransform();
328  fcl::Vec3f fcl_vec_object_b = fcl_trans_object_b.getTranslation();
329  fcl::Quaternion3f fcl_quat_object_b = fcl_trans_object_b.getQuatRotation();
330 
331  Eigen::Affine3d eigen_trans_object_b;
332  tf::Transform tf_trans_object_b(tf::Quaternion(fcl_quat_object_b.getX(),fcl_quat_object_b.getY(),fcl_quat_object_b.getZ(),fcl_quat_object_b.getW()),
333  tf::Vector3(fcl_vec_object_b[0],fcl_vec_object_b[1],fcl_vec_object_b[2]));
334  tf::transformTFToEigen(tf_trans_object_b, eigen_trans_object_b);
335 
336  geometry_msgs::Transform trans_object_b_msg;
337  tf::transformTFToMsg(tf_trans_object_b, trans_object_b_msg);
338  ROS_DEBUG_STREAM("Transform OBJ_B: \n" << trans_object_b_msg);
339 
340  // in case both objects are of OBJECT_TYPE OT_BVH the nearest points are already given in PlanningFrame coordinates
341  if(!(object_a->getObjectType() == fcl::OT_BVH && object_b->getObjectType() == fcl::OT_BVH))
342  {
343  np_object_a = eigen_trans_object_a * np_object_a;
344  np_object_b = eigen_trans_object_b * np_object_b;
345  }
346  // ToDo: are there other cases? OT_OCTREE? see fcl::OBJECT_TYPE
347 
348  if (dist < 0) dist = 0;
349 
350  cob_control_msgs::ObstacleDistance info;
351  info.distance = dist;
352 
353  tf::vectorEigenToMsg(np_object_a, info.nearest_point_frame_vector);
354  tf::vectorEigenToMsg(np_object_b, info.nearest_point_obstacle_vector);
355  ROS_DEBUG_STREAM("NearestPointTransformed OBJ_A: \n" << info.nearest_point_frame_vector);
356  ROS_DEBUG_STREAM("NearestPointTransformed OBJ_B: \n" << info.nearest_point_obstacle_vector);
357 
358  return info;
359 }
360 
362 {
363  MAXIMAL_MINIMAL_DISTANCE = 5.0; //m
364  double update_frequency = 50.0; //Hz
365 
366  std::string robot_description = "/robot_description";
367  std::string robot_description_semantic = "/robot_description_semantic";
368  std::string distance_service = "/calculate_distance";
369  std::string register_service = "/register_links";
370  std::string unregister_service = "/unregister_links";
371  std::string distance_topic = "/obstacle_distances";
372 
373 
374  // Get AllowedCollisionMatrix
375  robot_model_loader::RobotModelLoader robot_model_loader("robot_description", "robot_description_semantic");
376  planning_scene::PlanningScene pss(robot_model_loader.getURDF(), robot_model_loader.getSRDF());
377  acm_ = pss.getAllowedCollisionMatrix();
378 
379  //Initialize planning scene monitor
380 #if ROS_VERSION_MINIMUM(1,14,0) // melodic
381  std::shared_ptr<tf2_ros::Buffer> tf(new tf2_ros::Buffer(ros::Duration(2.0)));
382  //planning_scene_monitor::PlanningSceneMonitorPtr psm(new planning_scene_monitor::PlanningSceneMonitor(robot_description, tf, ""));
383  planning_scene_monitor_.reset(new planning_scene_monitor::PlanningSceneMonitor(robot_description, tf, ""));
384 #else
386  planning_scene_monitor_ = std::make_shared<planning_scene_monitor::PlanningSceneMonitor>(robot_description, tf_listener_);
387 #endif
388 
389  planning_scene_monitor_->setStateUpdateFrequency(update_frequency);
390  planning_scene_monitor_->startSceneMonitor(planning_scene_monitor::PlanningSceneMonitor::DEFAULT_PLANNING_SCENE_TOPIC);
391  planning_scene_monitor_->startWorldGeometryMonitor(planning_scene_monitor::PlanningSceneMonitor::DEFAULT_COLLISION_OBJECT_TOPIC,
393  true); // load_octomap_monitor
394  planning_scene_monitor_->startStateMonitor(planning_scene_monitor::PlanningSceneMonitor::DEFAULT_JOINT_STATES_TOPIC,
396  planning_scene_monitor_->addUpdateCallback(boost::bind(&ObstacleDistanceMoveit::updatedScene, this, _1));
397 
398  registered_links_.clear();
399 
400  calculate_obstacle_distance_ = nh_.advertiseService(distance_service, &ObstacleDistanceMoveit::calculateDistanceServiceCallback, this);
401  register_server_ = nh_.advertiseService(register_service, &ObstacleDistanceMoveit::registerCallback, this);
402  unregister_server_ = nh_.advertiseService(unregister_service, &ObstacleDistanceMoveit::unregisterCallback, this);
403  distance_timer_ = nh_.createTimer(ros::Duration(1.0/update_frequency), &ObstacleDistanceMoveit::calculateDistanceTimerCallback, this);
404  distance_pub_ = nh_.advertise<cob_control_msgs::ObstacleDistances>(distance_topic, 1);
405 
406  monitored_scene_pub_ = nh_.advertise<moveit_msgs::PlanningScene>("/monitored_planning_scene", 1);
407  monitored_scene_server_ = nh_.advertiseService("/get_planning_scene", &ObstacleDistanceMoveit::planningSceneCallback, this);
408  planning_scene_timer_ = nh_.createTimer(ros::Duration(1.0/update_frequency), &ObstacleDistanceMoveit::planningSceneTimerCallback, this);
409 }
#define NULL
void getCollisionObject(std::vector< std::shared_ptr< fcl::CollisionObject > > &obj)
const srdf::ModelSharedPtr & getSRDF() const
bool registerCallback(cob_srvs::SetString::Request &req, cob_srvs::SetString::Response &res)
#define ROS_WARN_THROTTLE(rate,...)
bool planningSceneCallback(moveit_msgs::GetPlanningScene::Request &req, moveit_msgs::GetPlanningScene::Response &res)
CreateCollisionRobot(const robot_model::RobotModelConstPtr &model)
bool calculateDistanceServiceCallback(cob_control_msgs::GetObstacleDistance::Request &req, cob_control_msgs::GetObstacleDistance::Response &res)
static const std::string DEFAULT_PLANNING_SCENE_WORLD_TOPIC
void updatedScene(planning_scene_monitor::PlanningSceneMonitor::SceneUpdateType type)
const urdf::ModelInterfaceSharedPtr & getURDF() const
bool unregisterCallback(cob_srvs::SetString::Request &req, cob_srvs::SetString::Response &res)
void vectorEigenToMsg(const Eigen::Vector3d &e, geometry_msgs::Vector3 &m)
static const std::string DEFAULT_PLANNING_SCENE_TOPIC
CreateCollisionWorld(const collision_detection::WorldPtr &world)
void calculateDistanceTimerCallback(const ros::TimerEvent &event)
std::vector< FCLCollisionObjectPtr > collision_objects_
#define ROS_DEBUG_STREAM(args)
static const std::string DEFAULT_COLLISION_OBJECT_TOPIC
const std::string & getID() const
res
cob_control_msgs::ObstacleDistance getDistanceInfo(const std::shared_ptr< fcl::CollisionObject > object_a, const std::shared_ptr< fcl::CollisionObject > object_b)
void planningSceneTimerCallback(const ros::TimerEvent &event)
void transformTFToEigen(const tf::Transform &t, Eigen::Isometry3d &e)
static const std::string DEFAULT_ATTACHED_COLLISION_OBJECT_TOPIC
std::map< std::string, FCLObject > fcl_objs_
void constructFCLObject(const World::Object *obj, FCLObject &fcl_obj) const
static void transformTFToMsg(const Transform &bt, geometry_msgs::Transform &msg)
static const std::string DEFAULT_JOINT_STATES_TOPIC
void getCollisionObject(const robot_state::RobotState &state, std::vector< std::shared_ptr< fcl::CollisionObject > > &obj)


cob_obstacle_distance_moveit
Author(s): Florian Koehler , Felix Messmer
autogenerated on Sun Dec 6 2020 03:26:02