robot_interaction.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2012-2013, Willow Garage, Inc.
5  * Copyright (c) 2013, Ioan A. Sucan
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/or other materials provided
17  * with the distribution.
18  * * Neither the name of Willow Garage nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *********************************************************************/
35 
36 /* Author: Ioan Sucan, Adam Leeper */
37 
47 #include <boost/lexical_cast.hpp>
48 #include <boost/math/constants/constants.hpp>
49 #include <boost/algorithm/string.hpp>
50 
51 #include <algorithm>
52 #include <limits>
53 
54 #include <Eigen/Core>
55 #include <Eigen/Geometry>
56 
57 namespace robot_interaction
58 {
59 static const float END_EFFECTOR_UNREACHABLE_COLOR[4] = { 1.0, 0.3, 0.3, 1.0 };
60 static const float END_EFFECTOR_REACHABLE_COLOR[4] = { 0.2, 1.0, 0.2, 1.0 };
61 
62 const std::string RobotInteraction::INTERACTIVE_MARKER_TOPIC = "robot_interaction_interactive_marker_topic";
63 
64 RobotInteraction::RobotInteraction(const robot_model::RobotModelConstPtr& robot_model, const std::string& ns)
65  : robot_model_(robot_model), kinematic_options_map_(new KinematicOptionsMap)
66 {
67  topic_ = ns.empty() ? INTERACTIVE_MARKER_TOPIC : ns + "/" + INTERACTIVE_MARKER_TOPIC;
69 
70  // spin a thread that will process feedback events
72  processing_thread_.reset(new boost::thread(boost::bind(&RobotInteraction::processingThread, this)));
73 }
74 
76 {
77  run_processing_thread_ = false;
78  new_feedback_condition_.notify_all();
79  processing_thread_->join();
80 
81  clear();
82  delete int_marker_server_;
83 }
84 
85 void RobotInteraction::decideActiveComponents(const std::string& group)
86 {
88 }
89 
91 {
92  decideActiveEndEffectors(group, style);
93  decideActiveJoints(group);
94  if (!group.empty() && active_eef_.empty() && active_vj_.empty() && active_generic_.empty())
95  ROS_INFO_NAMED("robot_interaction", "No active joints or end effectors found for group '%s'. "
96  "Make sure that kinematics.yaml is loaded in this node's namespace.",
97  group.c_str());
98 }
99 
101  const ProcessFeedbackFn& process, const InteractiveMarkerUpdateFn& update,
102  const std::string& name)
103 {
104  boost::unique_lock<boost::mutex> ulock(marker_access_lock_);
106  g.construct_marker = construct;
107  g.update_pose = update;
108  g.process_feedback = process;
109  // compute the suffix that will be added to the generated markers
110  g.marker_name_suffix = "_" + name + "_" + boost::lexical_cast<std::string>(active_generic_.size());
111  active_generic_.push_back(g);
112 }
113 
114 static const double DEFAULT_SCALE = 0.25;
115 double RobotInteraction::computeLinkMarkerSize(const std::string& link)
116 {
117  const robot_model::LinkModel* lm = robot_model_->getLinkModel(link);
118  double size = 0;
119 
120  while (lm)
121  {
122  Eigen::Vector3d ext = lm->getShapeExtentsAtOrigin();
123  // drop largest extension and take norm of two remaining
124  Eigen::MatrixXd::Index maxIndex;
125  ext.maxCoeff(&maxIndex);
126  ext[maxIndex] = 0;
127  size = 1.01 * ext.norm();
128  if (size > 0)
129  break; // break, if a non-empty shape was found
130 
131  // process kinematic chain upwards (but only following fixed joints)
132  // to find a link with some non-empty shape (to ignore virtual links)
133  if (lm->getParentJointModel()->getType() == robot_model::JointModel::FIXED)
134  lm = lm->getParentLinkModel();
135  else
136  lm = 0;
137  }
138  if (!lm)
139  return DEFAULT_SCALE; // no link with non-zero shape extends found
140 
141  // the marker sphere will be half the size, so double the size here
142  return 2. * size;
143 }
144 
145 double RobotInteraction::computeGroupMarkerSize(const std::string& group)
146 {
147  if (group.empty())
148  return DEFAULT_SCALE;
149  const robot_model::JointModelGroup* jmg = robot_model_->getJointModelGroup(group);
150  if (!jmg)
151  return 0.0;
152 
153  const std::vector<std::string>& links = jmg->getLinkModelNames();
154  if (links.empty())
155  return DEFAULT_SCALE;
156 
157  // compute the aabb of the links that make up the group
158  double size = 0;
159  for (std::size_t i = 0; i < links.size(); ++i)
160  {
161  const robot_model::LinkModel* lm = robot_model_->getLinkModel(links[i]);
162  if (!lm)
163  continue;
164  Eigen::Vector3d ext = lm->getShapeExtentsAtOrigin();
165 
166  // drop largest extension and take norm of two remaining
167  Eigen::MatrixXd::Index maxIndex;
168  ext.maxCoeff(&maxIndex);
169  ext[maxIndex] = 0;
170  size = std::max(size, 1.01 * ext.norm());
171  }
172 
173  // if size is zero, all links have empty shapes and are placed at same position
174  // in this case, fall back to link marker size
175  if (size == 0)
176  return computeLinkMarkerSize(links[0]);
177 
178  // the marker sphere will be half the size, so double the size here
179  return 2. * size;
180 }
181 
182 void RobotInteraction::decideActiveJoints(const std::string& group)
183 {
184  boost::unique_lock<boost::mutex> ulock(marker_access_lock_);
185  active_vj_.clear();
186 
187  if (group.empty())
188  return;
189 
190  ROS_DEBUG_NAMED("robot_interaction", "Deciding active joints for group '%s'", group.c_str());
191 
192  const srdf::ModelConstSharedPtr& srdf = robot_model_->getSRDF();
193  const robot_model::JointModelGroup* jmg = robot_model_->getJointModelGroup(group);
194 
195  if (!jmg || !srdf)
196  return;
197 
198  std::set<std::string> used;
199  if (jmg->hasJointModel(robot_model_->getRootJointName()))
200  {
201  robot_state::RobotState default_state(robot_model_);
202  default_state.setToDefaultValues();
203  std::vector<double> aabb;
204  default_state.computeAABB(aabb);
205 
206  const std::vector<srdf::Model::VirtualJoint>& vj = srdf->getVirtualJoints();
207  for (std::size_t i = 0; i < vj.size(); ++i)
208  if (vj[i].name_ == robot_model_->getRootJointName())
209  {
210  if (vj[i].type_ == "planar" || vj[i].type_ == "floating")
211  {
213  v.connecting_link = vj[i].child_link_;
214  v.parent_frame = vj[i].parent_frame_;
215  if (!v.parent_frame.empty() && v.parent_frame[0] == '/')
216  v.parent_frame = v.parent_frame.substr(1);
217  v.joint_name = vj[i].name_;
218  if (vj[i].type_ == "planar")
219  v.dof = 3;
220  else
221  v.dof = 6;
222  // take the max of the X, Y, Z extent
223  v.size = std::max(std::max(aabb[1] - aabb[0], aabb[3] - aabb[2]), aabb[5] - aabb[4]);
224  active_vj_.push_back(v);
225  used.insert(v.joint_name);
226  }
227  }
228  }
229 
230  const std::vector<const robot_model::JointModel*>& joints = jmg->getJointModels();
231  for (std::size_t i = 0; i < joints.size(); ++i)
232  {
233  if ((joints[i]->getType() == robot_model::JointModel::PLANAR ||
234  joints[i]->getType() == robot_model::JointModel::FLOATING) &&
235  used.find(joints[i]->getName()) == used.end())
236  {
238  v.connecting_link = joints[i]->getChildLinkModel()->getName();
239  if (joints[i]->getParentLinkModel())
240  v.parent_frame = joints[i]->getParentLinkModel()->getName();
241  v.joint_name = joints[i]->getName();
242  if (joints[i]->getType() == robot_model::JointModel::PLANAR)
243  v.dof = 3;
244  else
245  v.dof = 6;
246  // take the max of the X, Y, Z extent
247  v.size = computeGroupMarkerSize(group);
248  active_vj_.push_back(v);
249  }
250  }
251 }
252 
253 void RobotInteraction::decideActiveEndEffectors(const std::string& group)
254 {
256 }
257 
259 {
260  boost::unique_lock<boost::mutex> ulock(marker_access_lock_);
261  active_eef_.clear();
262 
263  if (group.empty())
264  return;
265 
266  ROS_DEBUG_NAMED("robot_interaction", "Deciding active end-effectors for group '%s'", group.c_str());
267 
268  const srdf::ModelConstSharedPtr& srdf = robot_model_->getSRDF();
269  const robot_model::JointModelGroup* jmg = robot_model_->getJointModelGroup(group);
270 
271  if (!jmg || !srdf)
272  {
273  ROS_WARN_NAMED("robot_interaction", "Unable to decide active end effector: no joint model group or no srdf model");
274  return;
275  }
276 
277  const std::vector<srdf::Model::EndEffector>& eef = srdf->getEndEffectors();
278  const std::pair<robot_model::JointModelGroup::KinematicsSolver, robot_model::JointModelGroup::KinematicsSolverMap>&
279  smap = jmg->getGroupKinematics();
280 
281  // if we have an IK solver for the selected group, we check if there are any end effectors attached to this group
282  if (smap.first)
283  {
284  for (std::size_t i = 0; i < eef.size(); ++i)
285  if ((jmg->hasLinkModel(eef[i].parent_link_) || jmg->getName() == eef[i].parent_group_) &&
286  jmg->canSetStateFromIK(eef[i].parent_link_))
287  {
288  // We found an end-effector whose parent is the group.
290  ee.parent_group = group;
291  ee.parent_link = eef[i].parent_link_;
292  ee.eef_group = eef[i].component_group_;
293  ee.interaction = style;
294  active_eef_.push_back(ee);
295  }
296 
297  // No end effectors found. Use last link in group as the "end effector".
298  if (active_eef_.empty() && !jmg->getLinkModelNames().empty())
299  {
301  ee.parent_group = group;
302  ee.parent_link = jmg->getLinkModelNames().back();
303  ee.eef_group = group;
304  ee.interaction = style;
305  active_eef_.push_back(ee);
306  }
307  }
308  else if (!smap.second.empty())
309  {
310  for (robot_model::JointModelGroup::KinematicsSolverMap::const_iterator it = smap.second.begin();
311  it != smap.second.end(); ++it)
312  {
313  for (std::size_t i = 0; i < eef.size(); ++i)
314  {
315  if ((it->first->hasLinkModel(eef[i].parent_link_) || jmg->getName() == eef[i].parent_group_) &&
316  it->first->canSetStateFromIK(eef[i].parent_link_))
317  {
318  // We found an end-effector whose parent is a subgroup of the group. (May be more than one)
320  ee.parent_group = it->first->getName();
321  ee.parent_link = eef[i].parent_link_;
322  ee.eef_group = eef[i].component_group_;
323  ee.interaction = style;
324  active_eef_.push_back(ee);
325  break;
326  }
327  }
328  }
329  }
330 
331  for (std::size_t i = 0; i < active_eef_.size(); ++i)
332  {
333  // if we have a separate group for the eef, we compute the scale based on it;
334  // otherwise, we use the size of the parent_link
335  active_eef_[i].size = active_eef_[i].eef_group == active_eef_[i].parent_group ?
336  computeLinkMarkerSize(active_eef_[i].parent_link) :
337  computeGroupMarkerSize(active_eef_[i].eef_group);
338  ROS_DEBUG_NAMED("robot_interaction", "Found active end-effector '%s', of scale %lf",
339  active_eef_[i].eef_group.c_str(), active_eef_[i].size);
340  }
341  // if there is only a single end effector marker, we can safely use a larger marker
342  if (active_eef_.size() == 1)
343  active_eef_[0].size *= 1.5;
344 }
345 
347 {
348  boost::unique_lock<boost::mutex> ulock(marker_access_lock_);
349  active_eef_.clear();
350  active_vj_.clear();
351  active_generic_.clear();
354 }
355 
357 {
358  boost::unique_lock<boost::mutex> ulock(marker_access_lock_);
360 }
361 
363 {
364  handlers_.clear();
365  shown_markers_.clear();
367  int_marker_move_topics_.clear();
368  int_marker_names_.clear();
370 }
371 
372 void RobotInteraction::addEndEffectorMarkers(const ::robot_interaction::InteractionHandlerPtr& handler,
373  const EndEffectorInteraction& eef,
374  visualization_msgs::InteractiveMarker& im, bool position, bool orientation)
375 {
376  geometry_msgs::Pose pose;
377  pose.orientation.w = 1;
378  addEndEffectorMarkers(handler, eef, pose, im, position, orientation);
379 }
380 
381 void RobotInteraction::addEndEffectorMarkers(const ::robot_interaction::InteractionHandlerPtr& handler,
382  const EndEffectorInteraction& eef, const geometry_msgs::Pose& im_to_eef,
383  visualization_msgs::InteractiveMarker& im, bool position, bool orientation)
384 {
385  if (eef.parent_group == eef.eef_group || !robot_model_->hasLinkModel(eef.parent_link))
386  return;
387 
388  visualization_msgs::InteractiveMarkerControl m_control;
389  m_control.always_visible = false;
390  if (position && orientation)
391  m_control.interaction_mode = m_control.MOVE_ROTATE_3D;
392  else if (orientation)
393  m_control.interaction_mode = m_control.ROTATE_3D;
394  else
395  m_control.interaction_mode = m_control.MOVE_3D;
396 
397  std_msgs::ColorRGBA marker_color;
398  const float* color = handler->inError(eef) ? END_EFFECTOR_UNREACHABLE_COLOR : END_EFFECTOR_REACHABLE_COLOR;
399  marker_color.r = color[0];
400  marker_color.g = color[1];
401  marker_color.b = color[2];
402  marker_color.a = color[3];
403 
404  robot_state::RobotStateConstPtr rstate = handler->getState();
405  const std::vector<std::string>& link_names = rstate->getJointModelGroup(eef.eef_group)->getLinkModelNames();
406  visualization_msgs::MarkerArray marker_array;
407  rstate->getRobotMarkers(marker_array, link_names, marker_color, eef.eef_group, ros::Duration());
408  tf::Pose tf_root_to_link;
409  tf::poseEigenToTF(rstate->getGlobalLinkTransform(eef.parent_link), tf_root_to_link);
410  // Release the ptr count on the kinematic state
411  rstate.reset();
412 
413  for (std::size_t i = 0; i < marker_array.markers.size(); ++i)
414  {
415  marker_array.markers[i].header = im.header;
416  marker_array.markers[i].mesh_use_embedded_materials = true;
417  // - - - - - - Do some math for the offset - - - - - -
418  tf::Pose tf_root_to_im, tf_root_to_mesh, tf_im_to_eef;
419  tf::poseMsgToTF(im.pose, tf_root_to_im);
420  tf::poseMsgToTF(marker_array.markers[i].pose, tf_root_to_mesh);
421  tf::poseMsgToTF(im_to_eef, tf_im_to_eef);
422  tf::Pose tf_eef_to_mesh = tf_root_to_link.inverse() * tf_root_to_mesh;
423  tf::Pose tf_im_to_mesh = tf_im_to_eef * tf_eef_to_mesh;
424  tf::Pose tf_root_to_mesh_new = tf_root_to_im * tf_im_to_mesh;
425  tf::poseTFToMsg(tf_root_to_mesh_new, marker_array.markers[i].pose);
426  // - - - - - - - - - - - - - - - - - - - - - - - - - -
427  m_control.markers.push_back(marker_array.markers[i]);
428  }
429 
430  im.controls.push_back(m_control);
431 }
432 
433 static inline std::string getMarkerName(const ::robot_interaction::InteractionHandlerPtr& handler,
434  const EndEffectorInteraction& eef)
435 {
436  return "EE:" + handler->getName() + "_" + eef.parent_link;
437 }
438 
439 static inline std::string getMarkerName(const ::robot_interaction::InteractionHandlerPtr& handler,
440  const JointInteraction& vj)
441 {
442  return "JJ:" + handler->getName() + "_" + vj.connecting_link;
443 }
444 
445 static inline std::string getMarkerName(const ::robot_interaction::InteractionHandlerPtr& handler,
446  const GenericInteraction& g)
447 {
448  return "GG:" + handler->getName() + "_" + g.marker_name_suffix;
449 }
450 
451 void RobotInteraction::addInteractiveMarkers(const ::robot_interaction::InteractionHandlerPtr& handler,
452  const double marker_scale)
453 {
454  handler->setRobotInteraction(this);
455  // If scale is left at default size of 0, scale will be based on end effector link size. a good value is between 0-1
456  std::vector<visualization_msgs::InteractiveMarker> ims;
457  ros::NodeHandle nh;
458  {
459  boost::unique_lock<boost::mutex> ulock(marker_access_lock_);
460  robot_state::RobotStateConstPtr s = handler->getState();
461 
462  for (std::size_t i = 0; i < active_generic_.size(); ++i)
463  {
464  visualization_msgs::InteractiveMarker im;
465  if (active_generic_[i].construct_marker(*s, im))
466  {
467  im.name = getMarkerName(handler, active_generic_[i]);
468  shown_markers_[im.name] = i;
469  ims.push_back(im);
470  ROS_DEBUG_NAMED("robot_interaction", "Publishing interactive marker %s (size = %lf)", im.name.c_str(),
471  im.scale);
472  }
473  }
474  ros::NodeHandle nh;
475 
476  for (std::size_t i = 0; i < active_eef_.size(); ++i)
477  {
478  geometry_msgs::PoseStamped pose;
479  geometry_msgs::Pose control_to_eef_tf;
480  pose.header.frame_id = robot_model_->getModelFrame();
481  pose.header.stamp = ros::Time::now();
482  computeMarkerPose(handler, active_eef_[i], *s, pose.pose, control_to_eef_tf);
483 
484  std::string marker_name = getMarkerName(handler, active_eef_[i]);
485  shown_markers_[marker_name] = i;
486 
487  // Determine interactive maker size
488  double mscale = marker_scale < std::numeric_limits<double>::epsilon() ? active_eef_[i].size : marker_scale;
489 
490  visualization_msgs::InteractiveMarker im = makeEmptyInteractiveMarker(marker_name, pose, mscale);
491  if (handler && handler->getControlsVisible())
492  {
493  if (active_eef_[i].interaction & EEF_POSITION_ARROWS)
494  addPositionControl(im, active_eef_[i].interaction & EEF_FIXED);
495  if (active_eef_[i].interaction & EEF_ORIENTATION_CIRCLES)
496  addOrientationControl(im, active_eef_[i].interaction & EEF_FIXED);
497  if (active_eef_[i].interaction & (EEF_POSITION_SPHERE | EEF_ORIENTATION_SPHERE))
498  {
499  std_msgs::ColorRGBA color;
500  color.r = 0;
501  color.g = 1;
502  color.b = 1;
503  color.a = 0.5;
504  addViewPlaneControl(im, mscale * 0.25, color, active_eef_[i].interaction & EEF_POSITION_SPHERE,
505  active_eef_[i].interaction & EEF_ORIENTATION_SPHERE);
506  }
507  }
508  if (handler && handler->getMeshesVisible() &&
509  (active_eef_[i].interaction & (EEF_POSITION_EEF | EEF_ORIENTATION_EEF)))
510  addEndEffectorMarkers(handler, active_eef_[i], control_to_eef_tf, im,
511  active_eef_[i].interaction & EEF_POSITION_EEF,
512  active_eef_[i].interaction & EEF_ORIENTATION_EEF);
513  ims.push_back(im);
514  registerMoveInteractiveMarkerTopic(marker_name, handler->getName() + "_" + active_eef_[i].parent_link);
515  ROS_DEBUG_NAMED("robot_interaction", "Publishing interactive marker %s (size = %lf)", marker_name.c_str(),
516  mscale);
517  }
518  for (std::size_t i = 0; i < active_vj_.size(); ++i)
519  {
520  geometry_msgs::PoseStamped pose;
521  pose.header.frame_id = robot_model_->getModelFrame();
522  pose.header.stamp = ros::Time::now();
523  tf::poseEigenToMsg(s->getGlobalLinkTransform(active_vj_[i].connecting_link), pose.pose);
524  std::string marker_name = getMarkerName(handler, active_vj_[i]);
525  shown_markers_[marker_name] = i;
526 
527  // Determine interactive maker size
528  double mscale = marker_scale < std::numeric_limits<double>::epsilon() ? active_vj_[i].size : marker_scale;
529 
530  visualization_msgs::InteractiveMarker im = makeEmptyInteractiveMarker(marker_name, pose, mscale);
531  if (handler && handler->getControlsVisible())
532  {
533  if (active_vj_[i].dof == 3) // planar joint
534  addPlanarXYControl(im, false);
535  else
536  add6DOFControl(im, false);
537  }
538  ims.push_back(im);
539  registerMoveInteractiveMarkerTopic(marker_name, handler->getName() + "_" + active_vj_[i].connecting_link);
540  ROS_DEBUG_NAMED("robot_interaction", "Publishing interactive marker %s (size = %lf)", marker_name.c_str(),
541  mscale);
542  }
543  handlers_[handler->getName()] = handler;
544  }
545 
546  // we do this while marker_access_lock_ is unlocked because the interactive marker server locks
547  // for most function calls, and maintains that lock while the feedback callback is running
548  // that can cause a deadlock if we were to run the loop below while marker_access_lock_ is locked
549  for (std::size_t i = 0; i < ims.size(); ++i)
550  {
551  int_marker_server_->insert(ims[i]);
552  int_marker_server_->setCallback(ims[i].name,
554 
555  // Add menu handler to all markers that this interaction handler creates.
556  if (std::shared_ptr<interactive_markers::MenuHandler> mh = handler->getMenuHandler())
557  mh->apply(*int_marker_server_, ims[i].name);
558  }
559 }
560 
561 void RobotInteraction::registerMoveInteractiveMarkerTopic(const std::string marker_name, const std::string& name)
562 {
563  ros::NodeHandle nh;
564  std::stringstream ss;
565  ss << "/rviz/moveit/move_marker/";
566  ss << name;
567  int_marker_move_topics_.push_back(ss.str());
568  int_marker_names_.push_back(marker_name);
569 }
570 
572 {
573  if (enable)
574  {
575  boost::unique_lock<boost::mutex> ulock(marker_access_lock_);
576  if (int_marker_move_subscribers_.size() == 0)
577  {
578  ros::NodeHandle nh;
579  for (size_t i = 0; i < int_marker_move_topics_.size(); i++)
580  {
581  std::string topic_name = int_marker_move_topics_[i];
582  std::string marker_name = int_marker_names_[i];
583  int_marker_move_subscribers_.push_back(nh.subscribe<geometry_msgs::PoseStamped>(
584  topic_name, 1, boost::bind(&RobotInteraction::moveInteractiveMarker, this, marker_name, _1)));
585  }
586  }
587  }
588  else
589  {
590  boost::unique_lock<boost::mutex> ulock(marker_access_lock_);
592  }
593 }
594 
595 void RobotInteraction::computeMarkerPose(const ::robot_interaction::InteractionHandlerPtr& handler,
596  const EndEffectorInteraction& eef, const robot_state::RobotState& robot_state,
597  geometry_msgs::Pose& pose, geometry_msgs::Pose& control_to_eef_tf) const
598 {
599  // Need to allow for control pose offsets
600  tf::Transform tf_root_to_link, tf_root_to_control;
601  tf::poseEigenToTF(robot_state.getGlobalLinkTransform(eef.parent_link), tf_root_to_link);
602 
603  geometry_msgs::Pose msg_link_to_control;
604  if (handler->getPoseOffset(eef, msg_link_to_control))
605  {
606  tf::Transform tf_link_to_control;
607  tf::poseMsgToTF(msg_link_to_control, tf_link_to_control);
608 
609  tf_root_to_control = tf_root_to_link * tf_link_to_control;
610  tf::poseTFToMsg(tf_link_to_control.inverse(), control_to_eef_tf);
611  }
612  else
613  {
614  tf_root_to_control = tf_root_to_link;
615  control_to_eef_tf.orientation.x = 0.0;
616  control_to_eef_tf.orientation.y = 0.0;
617  control_to_eef_tf.orientation.z = 0.0;
618  control_to_eef_tf.orientation.w = 1.0;
619  }
620 
621  tf::poseTFToMsg(tf_root_to_control, pose);
622 }
623 
624 void RobotInteraction::updateInteractiveMarkers(const ::robot_interaction::InteractionHandlerPtr& handler)
625 {
626  handler->setRobotInteraction(this);
627  std::string root_link;
628  std::map<std::string, geometry_msgs::Pose> pose_updates;
629  {
630  boost::unique_lock<boost::mutex> ulock(marker_access_lock_);
631 
632  robot_state::RobotStateConstPtr s = handler->getState();
633  root_link = s->getRobotModel()->getModelFrame();
634 
635  for (std::size_t i = 0; i < active_eef_.size(); ++i)
636  {
637  std::string marker_name = getMarkerName(handler, active_eef_[i]);
638  geometry_msgs::Pose control_to_eef_tf;
639  computeMarkerPose(handler, active_eef_[i], *s, pose_updates[marker_name], control_to_eef_tf);
640  }
641 
642  for (std::size_t i = 0; i < active_vj_.size(); ++i)
643  {
644  std::string marker_name = getMarkerName(handler, active_vj_[i]);
645  tf::poseEigenToMsg(s->getGlobalLinkTransform(active_vj_[i].connecting_link), pose_updates[marker_name]);
646  }
647 
648  for (std::size_t i = 0; i < active_generic_.size(); ++i)
649  {
650  std::string marker_name = getMarkerName(handler, active_generic_[i]);
651  geometry_msgs::Pose pose;
652  if (active_generic_[i].update_pose && active_generic_[i].update_pose(*s, pose))
653  pose_updates[marker_name] = pose;
654  }
655  }
656 
657  std_msgs::Header header;
658  header.frame_id = root_link; // marker poses are give w.r.t. root frame
659  for (std::map<std::string, geometry_msgs::Pose>::const_iterator it = pose_updates.begin(); it != pose_updates.end();
660  ++it)
661  int_marker_server_->setPose(it->first, it->second, header);
663 }
664 
666 {
667  // the server locks internally, so we need not worry about locking
669 }
670 
671 bool RobotInteraction::showingMarkers(const ::robot_interaction::InteractionHandlerPtr& handler)
672 {
673  boost::unique_lock<boost::mutex> ulock(marker_access_lock_);
674 
675  for (std::size_t i = 0; i < active_eef_.size(); ++i)
676  if (shown_markers_.find(getMarkerName(handler, active_eef_[i])) == shown_markers_.end())
677  return false;
678  for (std::size_t i = 0; i < active_vj_.size(); ++i)
679  if (shown_markers_.find(getMarkerName(handler, active_vj_[i])) == shown_markers_.end())
680  return false;
681  for (std::size_t i = 0; i < active_generic_.size(); ++i)
682  if (shown_markers_.find(getMarkerName(handler, active_generic_[i])) == shown_markers_.end())
683  return false;
684  return true;
685 }
686 
687 // TODO: can we get rid of this? Only used in moveit_ros/benchmarks_gui/src/tab_states_and_goals.cpp right now.
688 bool RobotInteraction::updateState(robot_state::RobotState& state, const EndEffectorInteraction& eef,
689  const geometry_msgs::Pose& pose, unsigned int attempts, double ik_timeout,
690  const robot_state::GroupStateValidityCallbackFn& validity_callback,
691  const kinematics::KinematicsQueryOptions& kinematics_query_options)
692 {
693  if (state.setFromIK(state.getJointModelGroup(eef.parent_group), pose, eef.parent_link,
694  kinematics_query_options.lock_redundant_joints ? 1 : attempts, ik_timeout, validity_callback,
695  kinematics_query_options))
696  {
697  state.update();
698  return true;
699  }
700  return false;
701 }
702 
703 void RobotInteraction::moveInteractiveMarker(const std::string name, const geometry_msgs::PoseStampedConstPtr& msg)
704 {
705  std::map<std::string, std::size_t>::const_iterator it = shown_markers_.find(name);
706  if (it != shown_markers_.end())
707  {
708  visualization_msgs::InteractiveMarkerFeedback::Ptr feedback(new visualization_msgs::InteractiveMarkerFeedback);
709  feedback->header = msg->header;
710  feedback->marker_name = name;
711  feedback->pose = msg->pose;
712  feedback->event_type = visualization_msgs::InteractiveMarkerFeedback::POSE_UPDATE;
714  {
715  boost::unique_lock<boost::mutex> ulock(marker_access_lock_);
716  int_marker_server_->setPose(name, msg->pose, msg->header); // move the interactive marker
718  }
719  }
720 }
721 
723  const visualization_msgs::InteractiveMarkerFeedbackConstPtr& feedback)
724 {
725  // perform some validity checks
726  boost::unique_lock<boost::mutex> ulock(marker_access_lock_);
727  std::map<std::string, std::size_t>::const_iterator it = shown_markers_.find(feedback->marker_name);
728  if (it == shown_markers_.end())
729  {
730  ROS_ERROR("Unknown marker name: '%s' (not published by RobotInteraction class)", feedback->marker_name.c_str());
731  return;
732  }
733 
734  std::size_t u = feedback->marker_name.find_first_of("_");
735  if (u == std::string::npos || u < 4)
736  {
737  ROS_ERROR("Invalid marker name: '%s'", feedback->marker_name.c_str());
738  return;
739  }
740 
741  feedback_map_[feedback->marker_name] = feedback;
742  new_feedback_condition_.notify_all();
743 }
744 
746 {
747  boost::unique_lock<boost::mutex> ulock(marker_access_lock_);
748 
749  while (run_processing_thread_ && ros::ok())
750  {
751  while (feedback_map_.empty() && run_processing_thread_ && ros::ok())
752  new_feedback_condition_.wait(ulock);
753 
754  while (!feedback_map_.empty() && ros::ok())
755  {
756  visualization_msgs::InteractiveMarkerFeedbackConstPtr feedback = feedback_map_.begin()->second;
757  feedback_map_.erase(feedback_map_.begin());
758  ROS_DEBUG_NAMED("robot_interaction", "Processing feedback from map for marker [%s]",
759  feedback->marker_name.c_str());
760 
761  std::map<std::string, std::size_t>::const_iterator it = shown_markers_.find(feedback->marker_name);
762  if (it == shown_markers_.end())
763  {
764  ROS_ERROR("Unknown marker name: '%s' (not published by RobotInteraction class) "
765  "(should never have ended up in the feedback_map!)",
766  feedback->marker_name.c_str());
767  continue;
768  }
769  std::size_t u = feedback->marker_name.find_first_of("_");
770  if (u == std::string::npos || u < 4)
771  {
772  ROS_ERROR("Invalid marker name: '%s' (should never have ended up in the feedback_map!)",
773  feedback->marker_name.c_str());
774  continue;
775  }
776  std::string marker_class = feedback->marker_name.substr(0, 2);
777  std::string handler_name = feedback->marker_name.substr(3, u - 3); // skip the ":"
778  std::map<std::string, ::robot_interaction::InteractionHandlerPtr>::const_iterator jt =
779  handlers_.find(handler_name);
780  if (jt == handlers_.end())
781  {
782  ROS_ERROR("Interactive Marker Handler '%s' is not known.", handler_name.c_str());
783  continue;
784  }
785 
786  // we put this in a try-catch because user specified callbacks may be triggered
787  try
788  {
789  if (marker_class == "EE")
790  {
791  // make a copy of the data, so we do not lose it while we are unlocked
792  EndEffectorInteraction eef = active_eef_[it->second];
793  ::robot_interaction::InteractionHandlerPtr ih = jt->second;
794  marker_access_lock_.unlock();
795  try
796  {
797  ih->handleEndEffector(eef, feedback);
798  }
799  catch (std::exception& ex)
800  {
801  ROS_ERROR("Exception caught while handling end-effector update: %s", ex.what());
802  }
803  marker_access_lock_.lock();
804  }
805  else if (marker_class == "JJ")
806  {
807  // make a copy of the data, so we do not lose it while we are unlocked
808  JointInteraction vj = active_vj_[it->second];
809  ::robot_interaction::InteractionHandlerPtr ih = jt->second;
810  marker_access_lock_.unlock();
811  try
812  {
813  ih->handleJoint(vj, feedback);
814  }
815  catch (std::exception& ex)
816  {
817  ROS_ERROR("Exception caught while handling joint update: %s", ex.what());
818  }
819  marker_access_lock_.lock();
820  }
821  else if (marker_class == "GG")
822  {
823  ::robot_interaction::InteractionHandlerPtr ih = jt->second;
824  GenericInteraction g = active_generic_[it->second];
825  marker_access_lock_.unlock();
826  try
827  {
828  ih->handleGeneric(g, feedback);
829  }
830  catch (std::exception& ex)
831  {
832  ROS_ERROR("Exception caught while handling joint update: %s", ex.what());
833  }
834  marker_access_lock_.lock();
835  }
836  else
837  ROS_ERROR("Unknown marker class ('%s') for marker '%s'", marker_class.c_str(), feedback->marker_name.c_str());
838  }
839  catch (std::exception& ex)
840  {
841  ROS_ERROR("Exception caught while processing event: %s", ex.what());
842  }
843  }
844  }
845 }
846 
847 // DEPRECATED FUNCTIONALITY for backwards compatibility
849 {
851 }
852 
853 // DEPRECATED FUNCTIONALITY for backwards compatibility
855 {
857 }
858 }
boost::condition_variable new_feedback_condition_
std::vector< JointInteraction > active_vj_
void moveInteractiveMarker(const std::string name, const geometry_msgs::PoseStampedConstPtr &msg)
visualization_msgs::InteractiveMarker makeEmptyInteractiveMarker(const std::string &name, const geometry_msgs::PoseStamped &stamped, double scale)
static void poseMsgToTF(const geometry_msgs::Pose &msg, Pose &bt)
void poseEigenToTF(const Eigen::Affine3d &e, tf::Pose &t)
#define ROS_INFO_NAMED(name,...)
std::string parent_link
The name of the link in the parent group that connects to the end-effector.
Definition: interaction.h:147
InteractionStyle::InteractionStyle interaction
Which degrees of freedom to enable for the end-effector.
Definition: interaction.h:153
std::map< std::string,::robot_interaction::InteractionHandlerPtr > handlers_
#define ROS_WARN_NAMED(name,...)
void registerMoveInteractiveMarkerTopic(const std::string marker_name, const std::string &name)
double computeGroupMarkerSize(const std::string &group)
void poseEigenToMsg(const Eigen::Affine3d &e, geometry_msgs::Pose &m)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
void addPlanarXYControl(visualization_msgs::InteractiveMarker &int_marker, bool orientation_fixed=false)
void decideActiveJoints(const std::string &group)
XmlRpcServer s
static bool updateState(robot_state::RobotState &state, const EndEffectorInteraction &eef, const geometry_msgs::Pose &pose, unsigned int attempts, double ik_timeout, const robot_state::GroupStateValidityCallbackFn &validity_callback=robot_state::GroupStateValidityCallbackFn(), const kinematics::KinematicsQueryOptions &kinematics_query_options=kinematics::KinematicsQueryOptions())
void addPositionControl(visualization_msgs::InteractiveMarker &int_marker, bool orientation_fixed=false)
std::string getName(void *handle)
std::vector< ros::Subscriber > int_marker_move_subscribers_
static const float END_EFFECTOR_UNREACHABLE_COLOR[4]
void addViewPlaneControl(visualization_msgs::InteractiveMarker &int_marker, double radius, const std_msgs::ColorRGBA &color, bool position=true, bool orientation=true)
double size
The size of the connecting link (diameter of enclosing sphere)
Definition: interaction.h:176
static const double DEFAULT_SCALE
double computeLinkMarkerSize(const std::string &link)
#define ROS_DEBUG_NAMED(name,...)
std::vector< std::string > int_marker_names_
robot_model::RobotModelConstPtr robot_model_
interactive_markers::InteractiveMarkerServer * int_marker_server_
void addEndEffectorMarkers(const ::robot_interaction::InteractionHandlerPtr &handler, const EndEffectorInteraction &eef, visualization_msgs::InteractiveMarker &im, bool position=true, bool orientation=true)
std::string eef_group
The name of the group that defines the group joints.
Definition: interaction.h:150
void addOrientationControl(visualization_msgs::InteractiveMarker &int_marker, bool orientation_fixed=false)
void decideActiveEndEffectors(const std::string &group)
std::vector< std::string > int_marker_move_topics_
static const float END_EFFECTOR_REACHABLE_COLOR[4]
ROSCPP_DECL bool ok()
std::map< std::string, visualization_msgs::InteractiveMarkerFeedbackConstPtr > feedback_map_
std::string parent_group
The name of the group that sustains the end-effector (usually an arm)
Definition: interaction.h:144
boost::function< bool(const robot_state::RobotState &, geometry_msgs::Pose &)> InteractiveMarkerUpdateFn
Definition: interaction.h:116
Transform inverse() const
boost::function< bool(robot_state::RobotState &state, const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)> ProcessFeedbackFn
Definition: interaction.h:105
RobotInteraction(const robot_model::RobotModelConstPtr &kmodel, const std::string &ns="")
void processInteractiveMarkerFeedback(const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
static std::string getMarkerName(const ::robot_interaction::InteractionHandlerPtr &handler, const EndEffectorInteraction &eef)
boost::function< bool(const robot_state::RobotState &state, visualization_msgs::InteractiveMarker &marker)> InteractiveMarkerConstructorFn
Definition: interaction.h:90
void add6DOFControl(visualization_msgs::InteractiveMarker &int_marker, bool orientation_fixed=false)
void computeMarkerPose(const ::robot_interaction::InteractionHandlerPtr &handler, const EndEffectorInteraction &eef, const robot_state::RobotState &robot_state, geometry_msgs::Pose &pose, geometry_msgs::Pose &control_to_eef_tf) const
std::string connecting_link
The link in the robot model this joint is a parent of.
Definition: interaction.h:164
std::string parent_frame
The name of the frame that is a parent of this joint.
Definition: interaction.h:167
unsigned int dof
The type of joint disguised as the number of DOF it has. 3=PLANAR in X/Y; 6=FLOATING.
Definition: interaction.h:173
INTERACTIVE_MARKERS_PUBLIC void insert(const visualization_msgs::InteractiveMarker &int_marker)
static void poseTFToMsg(const Pose &bt, geometry_msgs::Pose &msg)
INTERACTIVE_MARKERS_PUBLIC void applyChanges()
INTERACTIVE_MARKERS_PUBLIC bool setCallback(const std::string &name, FeedbackCallback feedback_cb, uint8_t feedback_type=DEFAULT_FEEDBACK_CB)
void addInteractiveMarkers(const ::robot_interaction::InteractionHandlerPtr &handler, const double marker_scale=0.0)
static Time now()
InteractiveMarkerConstructorFn construct_marker
Definition: interaction.h:124
std::vector< EndEffectorInteraction > active_eef_
INTERACTIVE_MARKERS_PUBLIC void clear()
bool showingMarkers(const ::robot_interaction::InteractionHandlerPtr &handler)
INTERACTIVE_MARKERS_PUBLIC bool setPose(const std::string &name, const geometry_msgs::Pose &pose, const std_msgs::Header &header=std_msgs::Header())
std::unique_ptr< boost::thread > processing_thread_
std::string joint_name
The name of the joint.
Definition: interaction.h:170
std::map< std::string, std::size_t > shown_markers_
std::vector< GenericInteraction > active_generic_
void updateInteractiveMarkers(const ::robot_interaction::InteractionHandlerPtr &handler)
#define ROS_ERROR(...)
InteractiveMarkerUpdateFn update_pose
Definition: interaction.h:132
void addActiveComponent(const InteractiveMarkerConstructorFn &construct, const ProcessFeedbackFn &process, const InteractiveMarkerUpdateFn &update=InteractiveMarkerUpdateFn(), const std::string &name="")
static const std::string INTERACTIVE_MARKER_TOPIC
The topic name on which the internal Interactive Marker Server operates.
void decideActiveComponents(const std::string &group)


robot_interaction
Author(s): Ioan Sucan
autogenerated on Sun Oct 18 2020 13:18:32