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 
45 #include <tf2_eigen/tf2_eigen.h>
48 #include <boost/lexical_cast.hpp>
49 #include <boost/math/constants/constants.hpp>
50 #include <boost/algorithm/string.hpp>
51 
52 #include <algorithm>
53 #include <limits>
54 
55 #include <Eigen/Core>
56 #include <Eigen/Geometry>
57 
58 namespace robot_interaction
59 {
60 static const float END_EFFECTOR_UNREACHABLE_COLOR[4] = { 1.0, 0.3, 0.3, 1.0 };
61 static const float END_EFFECTOR_REACHABLE_COLOR[4] = { 0.2, 1.0, 0.2, 1.0 };
62 
63 const std::string RobotInteraction::INTERACTIVE_MARKER_TOPIC = "robot_interaction_interactive_marker_topic";
64 
65 RobotInteraction::RobotInteraction(const moveit::core::RobotModelConstPtr& robot_model, const std::string& ns)
66  : robot_model_(robot_model), kinematic_options_map_(new KinematicOptionsMap)
67 {
68  topic_ = ns.empty() ? INTERACTIVE_MARKER_TOPIC : ns + "/" + INTERACTIVE_MARKER_TOPIC;
69  int_marker_server_ = new interactive_markers::InteractiveMarkerServer(topic_);
70 
71  // spin a thread that will process feedback events
72  run_processing_thread_ = true;
73  processing_thread_ = std::make_unique<boost::thread>([this] { processingThread(); });
74 }
75 
76 RobotInteraction::~RobotInteraction()
77 {
78  run_processing_thread_ = false;
79  new_feedback_condition_.notify_all();
80  processing_thread_->join();
81 
82  clear();
83  delete int_marker_server_;
84 }
85 
86 void RobotInteraction::decideActiveComponents(const std::string& group)
87 {
88  decideActiveComponents(group, InteractionStyle::SIX_DOF);
89 }
90 
91 void RobotInteraction::decideActiveComponents(const std::string& group, InteractionStyle::InteractionStyle style)
92 {
93  decideActiveEndEffectors(group, style);
94  decideActiveJoints(group);
95  if (!group.empty() && active_eef_.empty() && active_vj_.empty() && active_generic_.empty())
96  ROS_INFO_NAMED("robot_interaction",
97  "No active joints or end effectors found for group '%s'. "
98  "Make sure that kinematics.yaml is loaded in this node's namespace.",
99  group.c_str());
100 }
101 
102 void RobotInteraction::addActiveComponent(const InteractiveMarkerConstructorFn& construct,
103  const ProcessFeedbackFn& process, const InteractiveMarkerUpdateFn& update,
104  const std::string& name)
105 {
106  boost::unique_lock<boost::mutex> ulock(marker_access_lock_);
108  g.construct_marker = construct;
110  g.process_feedback = process;
111  // compute the suffix that will be added to the generated markers
112  g.marker_name_suffix = "_" + name + "_" + boost::lexical_cast<std::string>(active_generic_.size());
113  active_generic_.push_back(g);
114 }
115 
116 static const double DEFAULT_SCALE = 0.25;
117 double RobotInteraction::computeLinkMarkerSize(const std::string& link)
118 {
119  const moveit::core::LinkModel* lm = robot_model_->getLinkModel(link);
120  double size = 0;
121 
122  while (lm)
123  {
124  Eigen::Vector3d ext = lm->getShapeExtentsAtOrigin();
125  // drop largest extension and take norm of two remaining
126  Eigen::MatrixXd::Index max_index;
127  ext.maxCoeff(&max_index);
128  ext[max_index] = 0;
129  size = 1.01 * ext.norm();
130  if (size > 0)
131  break; // break, if a non-empty shape was found
132 
133  // process kinematic chain upwards (but only following fixed joints)
134  // to find a link with some non-empty shape (to ignore virtual links)
136  lm = lm->getParentLinkModel();
137  else
138  lm = nullptr;
139  }
140  if (!lm)
141  return DEFAULT_SCALE; // no link with non-zero shape extends found
142 
143  // the marker sphere will be half the size, so double the size here
144  return 2. * size;
145 }
146 
147 double RobotInteraction::computeGroupMarkerSize(const std::string& group)
148 {
149  if (group.empty())
151  const moveit::core::JointModelGroup* jmg = robot_model_->getJointModelGroup(group);
152  if (!jmg)
153  return 0.0;
154 
155  const std::vector<std::string>& links = jmg->getLinkModelNames();
156  if (links.empty())
157  return DEFAULT_SCALE;
158 
159  // compute the aabb of the links that make up the group
160  double size = 0;
161  for (const std::string& link : links)
162  {
163  const moveit::core::LinkModel* lm = robot_model_->getLinkModel(link);
164  if (!lm)
165  continue;
166  Eigen::Vector3d ext = lm->getShapeExtentsAtOrigin();
167 
168  // drop largest extension and take norm of two remaining
169  Eigen::MatrixXd::Index max_index;
170  ext.maxCoeff(&max_index);
171  ext[max_index] = 0;
172  size = std::max(size, 1.01 * ext.norm());
173  }
174 
175  // if size is zero, all links have empty shapes and are placed at same position
176  // in this case, fall back to link marker size
177  if (size == 0)
178  return computeLinkMarkerSize(links[0]);
179 
180  // the marker sphere will be half the size, so double the size here
181  return 2. * size;
182 }
183 
184 void RobotInteraction::decideActiveJoints(const std::string& group)
185 {
186  boost::unique_lock<boost::mutex> ulock(marker_access_lock_);
187  active_vj_.clear();
188 
189  if (group.empty())
190  return;
191 
192  ROS_DEBUG_NAMED("robot_interaction", "Deciding active joints for group '%s'", group.c_str());
193 
194  const srdf::ModelConstSharedPtr& srdf = robot_model_->getSRDF();
195  const moveit::core::JointModelGroup* jmg = robot_model_->getJointModelGroup(group);
196 
197  if (!jmg || !srdf)
198  return;
199 
200  std::set<std::string> used;
201  if (jmg->hasJointModel(robot_model_->getRootJointName()))
202  {
203  moveit::core::RobotState default_state(robot_model_);
204  default_state.setToDefaultValues();
205  std::vector<double> aabb;
206  default_state.computeAABB(aabb);
207 
208  const std::vector<srdf::Model::VirtualJoint>& vj = srdf->getVirtualJoints();
209  for (const srdf::Model::VirtualJoint& joint : vj)
210  if (joint.name_ == robot_model_->getRootJointName())
211  {
212  if (joint.type_ == "planar" || joint.type_ == "floating")
213  {
215  v.connecting_link = joint.child_link_;
216  v.parent_frame = joint.parent_frame_;
217  if (!v.parent_frame.empty() && v.parent_frame[0] == '/')
218  v.parent_frame = v.parent_frame.substr(1);
219  v.joint_name = joint.name_;
220  if (joint.type_ == "planar")
221  v.dof = 3;
222  else
223  v.dof = 6;
224  // take the max of the X, Y, Z extent
225  v.size = std::max(std::max(aabb[1] - aabb[0], aabb[3] - aabb[2]), aabb[5] - aabb[4]);
226  active_vj_.push_back(v);
227  used.insert(v.joint_name);
228  }
229  }
230  }
231 
232  const std::vector<const moveit::core::JointModel*>& joints = jmg->getJointModels();
233  for (const moveit::core::JointModel* joint : joints)
234  {
235  if ((joint->getType() == moveit::core::JointModel::PLANAR ||
236  joint->getType() == moveit::core::JointModel::FLOATING) &&
237  used.find(joint->getName()) == used.end())
238  {
239  JointInteraction v;
240  v.connecting_link = joint->getChildLinkModel()->getName();
241  if (joint->getParentLinkModel())
242  v.parent_frame = joint->getParentLinkModel()->getName();
243  v.joint_name = joint->getName();
244  if (joint->getType() == moveit::core::JointModel::PLANAR)
245  v.dof = 3;
246  else
247  v.dof = 6;
248  // take the max of the X, Y, Z extent
249  v.size = computeGroupMarkerSize(group);
250  active_vj_.push_back(v);
251  }
252  }
253 }
254 
255 void RobotInteraction::decideActiveEndEffectors(const std::string& group)
256 {
257  decideActiveEndEffectors(group, InteractionStyle::SIX_DOF);
258 }
259 
260 void RobotInteraction::decideActiveEndEffectors(const std::string& group, InteractionStyle::InteractionStyle style)
261 {
262  boost::unique_lock<boost::mutex> ulock(marker_access_lock_);
263  active_eef_.clear();
264 
265  if (group.empty())
266  return;
267 
268  ROS_DEBUG_NAMED("robot_interaction", "Deciding active end-effectors for group '%s'", group.c_str());
269 
270  const srdf::ModelConstSharedPtr& srdf = robot_model_->getSRDF();
271  const moveit::core::JointModelGroup* jmg = robot_model_->getJointModelGroup(group);
272 
273  if (!jmg || !srdf)
274  {
275  ROS_WARN_NAMED("robot_interaction", "Unable to decide active end effector: no joint model group or no srdf model");
276  return;
277  }
278 
279  const std::vector<srdf::Model::EndEffector>& eefs = srdf->getEndEffectors();
280  const std::pair<moveit::core::JointModelGroup::KinematicsSolver, moveit::core::JointModelGroup::KinematicsSolverMap>&
281  smap = jmg->getGroupKinematics();
282 
283  auto add_active_end_effectors_for_single_group = [&](const moveit::core::JointModelGroup* single_group) {
284  bool found_eef{ false };
285  for (const srdf::Model::EndEffector& eef : eefs)
286  {
287  if (single_group->hasLinkModel(eef.parent_link_) &&
288  (eef.parent_group_.empty() || single_group->getName() == eef.parent_group_) &&
289  single_group->canSetStateFromIK(eef.parent_link_))
290  {
291  // We found an end-effector whose parent is the group.
293  ee.parent_group = single_group->getName();
294  ee.parent_link = eef.parent_link_;
295  ee.eef_group = eef.component_group_;
296  ee.interaction = style;
297  active_eef_.push_back(ee);
298  found_eef = true;
299  }
300  }
301 
302  // No end effectors found. Use last link in group as the "end effector".
303  if (!found_eef && !single_group->getLinkModelNames().empty())
304  {
305  std::string last_link{ single_group->getLinkModelNames().back() };
306 
307  if (single_group->canSetStateFromIK(last_link))
308  {
309  EndEffectorInteraction ee;
310  ee.parent_group = single_group->getName();
311  ee.parent_link = last_link;
312  ee.eef_group = single_group->getName();
313  ee.interaction = style;
314  active_eef_.push_back(ee);
315  }
316  }
317  };
318 
319  // if we have an IK solver for the selected group, we check if there are any end effectors attached to this group
320  if (smap.first)
321  {
322  add_active_end_effectors_for_single_group(jmg);
323  }
324  // if the group contains subgroups with IK, add markers for them individually
325  else if (!smap.second.empty())
326  {
327  for (const std::pair<const moveit::core::JointModelGroup* const, moveit::core::JointModelGroup::KinematicsSolver>&
328  it : smap.second)
329  add_active_end_effectors_for_single_group(it.first);
330  }
331 
332  // lastly determine automatic marker sizes
333  for (EndEffectorInteraction& eef : active_eef_)
334  {
335  // if we have a separate group for the eef, we compute the scale based on it;
336  // otherwise, we use the size of the parent_link
337  eef.size = (eef.eef_group == eef.parent_group) ? computeLinkMarkerSize(eef.parent_link) :
338  computeGroupMarkerSize(eef.eef_group);
339  ROS_DEBUG_NAMED("robot_interaction", "Found active end-effector '%s', of scale %lf", eef.eef_group.c_str(),
340  eef.size);
341  }
342  // if there is only a single end effector marker, we can safely use a larger marker
343  if (active_eef_.size() == 1)
344  active_eef_[0].size *= 1.5;
345 }
346 
347 void RobotInteraction::clear()
348 {
349  boost::unique_lock<boost::mutex> ulock(marker_access_lock_);
350  active_eef_.clear();
351  active_vj_.clear();
352  active_generic_.clear();
353  clearInteractiveMarkersUnsafe();
354  publishInteractiveMarkers();
355 }
356 
357 void RobotInteraction::clearInteractiveMarkers()
358 {
359  boost::unique_lock<boost::mutex> ulock(marker_access_lock_);
360  clearInteractiveMarkersUnsafe();
361 }
362 
363 void RobotInteraction::clearInteractiveMarkersUnsafe()
364 {
365  handlers_.clear();
366  shown_markers_.clear();
367  int_marker_move_subscribers_.clear();
368  int_marker_move_topics_.clear();
369  int_marker_names_.clear();
370  int_marker_server_->clear();
371 }
372 
373 void RobotInteraction::addEndEffectorMarkers(const InteractionHandlerPtr& handler, 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 InteractionHandlerPtr& handler, const EndEffectorInteraction& eef,
382  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  moveit::core::RobotStateConstPtr rstate = handler->getState();
405  visualization_msgs::MarkerArray marker_array;
406  auto jmg = rstate->getJointModelGroup(eef.eef_group);
407  if (jmg)
408  rstate->getRobotMarkers(marker_array, jmg->getLinkModelNames(), marker_color, eef.eef_group, ros::Duration());
409  tf2::Transform tf_root_to_link;
410  tf2::fromMsg(tf2::toMsg(rstate->getGlobalLinkTransform(eef.parent_link)), tf_root_to_link);
411  // Release the ptr count on the kinematic state
412  rstate.reset();
413 
414  for (visualization_msgs::Marker& marker : marker_array.markers)
415  {
416  marker.header = im.header;
417  marker.mesh_use_embedded_materials = !marker.mesh_resource.empty();
418  // - - - - - - Do some math for the offset - - - - - -
419  tf2::Transform tf_root_to_im, tf_root_to_mesh, tf_im_to_eef;
420  tf2::fromMsg(im.pose, tf_root_to_im);
421  tf2::fromMsg(marker.pose, tf_root_to_mesh);
422  tf2::fromMsg(im_to_eef, tf_im_to_eef);
423  tf2::Transform tf_eef_to_mesh = tf_root_to_link.inverse() * tf_root_to_mesh;
424  tf2::Transform tf_im_to_mesh = tf_im_to_eef * tf_eef_to_mesh;
425  tf2::Transform tf_root_to_mesh_new = tf_root_to_im * tf_im_to_mesh;
426  tf2::toMsg(tf_root_to_mesh_new, marker.pose);
427  // - - - - - - - - - - - - - - - - - - - - - - - - - -
428  m_control.markers.push_back(marker);
429  }
430 
431  im.controls.push_back(m_control);
432 }
433 
434 static inline std::string getMarkerName(const InteractionHandlerPtr& handler, const EndEffectorInteraction& eef)
435 {
436  return "EE:" + handler->getName() + "_" + eef.parent_link;
437 }
438 
439 static inline std::string getMarkerName(const InteractionHandlerPtr& handler, const JointInteraction& vj)
440 {
441  return "JJ:" + handler->getName() + "_" + vj.connecting_link;
442 }
443 
444 static inline std::string getMarkerName(const InteractionHandlerPtr& handler, const GenericInteraction& g)
445 {
446  return "GG:" + handler->getName() + "_" + g.marker_name_suffix;
447 }
448 
449 void RobotInteraction::addInteractiveMarkers(const InteractionHandlerPtr& handler, const double marker_scale)
450 {
451  // 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
452  std::vector<visualization_msgs::InteractiveMarker> ims;
453  {
454  boost::unique_lock<boost::mutex> ulock(marker_access_lock_);
455  moveit::core::RobotStateConstPtr s = handler->getState();
456 
457  for (std::size_t i = 0; i < active_generic_.size(); ++i)
458  {
459  visualization_msgs::InteractiveMarker im;
460  if (active_generic_[i].construct_marker(*s, im))
461  {
462  im.name = getMarkerName(handler, active_generic_[i]);
463  shown_markers_[im.name] = i;
464  ims.push_back(im);
465  ROS_DEBUG_NAMED("robot_interaction", "Publishing interactive marker %s (size = %lf)", im.name.c_str(), im.scale);
466  }
467  }
468 
469  for (std::size_t i = 0; i < active_eef_.size(); ++i)
470  {
471  geometry_msgs::PoseStamped pose;
472  geometry_msgs::Pose control_to_eef_tf;
473  pose.header.frame_id = robot_model_->getModelFrame();
474  pose.header.stamp = ros::Time::now();
475  computeMarkerPose(handler, active_eef_[i], *s, pose.pose, control_to_eef_tf);
476 
477  std::string marker_name = getMarkerName(handler, active_eef_[i]);
478  shown_markers_[marker_name] = i;
479 
480  // Determine interactive maker size
481  double mscale = marker_scale < std::numeric_limits<double>::epsilon() ? active_eef_[i].size : marker_scale;
482 
483  visualization_msgs::InteractiveMarker im = makeEmptyInteractiveMarker(marker_name, pose, mscale);
484  if (handler && handler->getControlsVisible())
485  {
486  if (active_eef_[i].interaction & InteractionStyle::POSITION_ARROWS)
487  addPositionControl(im, active_eef_[i].interaction & InteractionStyle::FIXED);
488  if (active_eef_[i].interaction & InteractionStyle::ORIENTATION_CIRCLES)
489  addOrientationControl(im, active_eef_[i].interaction & InteractionStyle::FIXED);
490  if (active_eef_[i].interaction & (InteractionStyle::POSITION_SPHERE | InteractionStyle::ORIENTATION_SPHERE))
491  {
492  std_msgs::ColorRGBA color;
493  color.r = 0;
494  color.g = 1;
495  color.b = 1;
496  color.a = 0.5;
497  addViewPlaneControl(im, mscale * 0.25, color, active_eef_[i].interaction & InteractionStyle::POSITION_SPHERE,
498  active_eef_[i].interaction & InteractionStyle::ORIENTATION_SPHERE);
499  }
500  }
501  if (handler && handler->getMeshesVisible() &&
502  (active_eef_[i].interaction & (InteractionStyle::POSITION_EEF | InteractionStyle::ORIENTATION_EEF)))
503  addEndEffectorMarkers(handler, active_eef_[i], control_to_eef_tf, im,
504  active_eef_[i].interaction & InteractionStyle::POSITION_EEF,
505  active_eef_[i].interaction & InteractionStyle::ORIENTATION_EEF);
506  ims.push_back(im);
507  registerMoveInteractiveMarkerTopic(marker_name, handler->getName() + "_" + active_eef_[i].parent_link);
508  ROS_DEBUG_NAMED("robot_interaction", "Publishing interactive marker %s (size = %lf)", marker_name.c_str(), mscale);
509  }
510  for (std::size_t i = 0; i < active_vj_.size(); ++i)
511  {
512  geometry_msgs::PoseStamped pose;
513  pose.header.frame_id = robot_model_->getModelFrame();
514  pose.header.stamp = ros::Time::now();
515  pose.pose = tf2::toMsg(s->getGlobalLinkTransform(active_vj_[i].connecting_link));
516  std::string marker_name = getMarkerName(handler, active_vj_[i]);
517  shown_markers_[marker_name] = i;
518 
519  // Determine interactive maker size
520  double mscale = marker_scale < std::numeric_limits<double>::epsilon() ? active_vj_[i].size : marker_scale;
521 
522  visualization_msgs::InteractiveMarker im = makeEmptyInteractiveMarker(marker_name, pose, mscale);
523  if (handler && handler->getControlsVisible())
524  {
525  if (active_vj_[i].dof == 3) // planar joint
526  addPlanarXYControl(im, false);
527  else
528  add6DOFControl(im, false);
529  }
530  ims.push_back(im);
531  registerMoveInteractiveMarkerTopic(marker_name, handler->getName() + "_" + active_vj_[i].connecting_link);
532  ROS_DEBUG_NAMED("robot_interaction", "Publishing interactive marker %s (size = %lf)", marker_name.c_str(), mscale);
533  }
534  handlers_[handler->getName()] = handler;
535  }
536 
537  // we do this while marker_access_lock_ is unlocked because the interactive marker server locks
538  // for most function calls, and maintains that lock while the feedback callback is running
539  // that can cause a deadlock if we were to run the loop below while marker_access_lock_ is locked
540  for (const visualization_msgs::InteractiveMarker& im : ims)
541  {
542  int_marker_server_->insert(im);
543  int_marker_server_->setCallback(im.name,
544  [this](const auto& feedback) { processInteractiveMarkerFeedback(feedback); });
545 
546  // Add menu handler to all markers that this interaction handler creates.
547  if (std::shared_ptr<interactive_markers::MenuHandler> mh = handler->getMenuHandler())
548  mh->apply(*int_marker_server_, im.name);
549  }
550 }
551 
552 void RobotInteraction::registerMoveInteractiveMarkerTopic(const std::string& marker_name, const std::string& name)
553 {
554  std::stringstream ss;
555  ss << "/rviz/moveit/move_marker/";
556  ss << name;
557  int_marker_move_topics_.push_back(ss.str());
558  int_marker_names_.push_back(marker_name);
559 }
560 
561 void RobotInteraction::toggleMoveInteractiveMarkerTopic(bool enable)
562 {
563  if (enable)
564  {
565  boost::unique_lock<boost::mutex> ulock(marker_access_lock_);
566  if (int_marker_move_subscribers_.empty())
567  {
568  ros::NodeHandle nh;
569  for (size_t i = 0; i < int_marker_move_topics_.size(); i++)
570  {
571  std::string topic_name = int_marker_move_topics_[i];
572  std::string marker_name = int_marker_names_[i];
573  int_marker_move_subscribers_.push_back(nh.subscribe<geometry_msgs::PoseStamped>(
574  topic_name, 1, [this, marker_name](const geometry_msgs::PoseStampedConstPtr& pose) {
575  moveInteractiveMarker(marker_name, *pose);
576  }));
577  }
578  }
579  }
580  else
581  {
582  boost::unique_lock<boost::mutex> ulock(marker_access_lock_);
583  int_marker_move_subscribers_.clear();
584  }
585 }
586 
587 void RobotInteraction::computeMarkerPose(const InteractionHandlerPtr& handler, const EndEffectorInteraction& eef,
588  const moveit::core::RobotState& robot_state, geometry_msgs::Pose& pose,
589  geometry_msgs::Pose& control_to_eef_tf) const
590 {
591  // Need to allow for control pose offsets
592  tf2::Transform tf_root_to_link, tf_root_to_control;
593  tf2::fromMsg(tf2::toMsg(robot_state.getGlobalLinkTransform(eef.parent_link)), tf_root_to_link);
594 
595  geometry_msgs::Pose msg_link_to_control;
596  if (handler->getPoseOffset(eef, msg_link_to_control))
597  {
598  tf2::Transform tf_link_to_control;
599  tf2::fromMsg(msg_link_to_control, tf_link_to_control);
600 
601  tf_root_to_control = tf_root_to_link * tf_link_to_control;
602  tf2::toMsg(tf_link_to_control.inverse(), control_to_eef_tf);
603  }
604  else
605  {
606  tf_root_to_control = tf_root_to_link;
607  control_to_eef_tf.orientation.x = 0.0;
608  control_to_eef_tf.orientation.y = 0.0;
609  control_to_eef_tf.orientation.z = 0.0;
610  control_to_eef_tf.orientation.w = 1.0;
611  }
612 
613  tf2::toMsg(tf_root_to_control, pose);
614 }
615 
616 void RobotInteraction::updateInteractiveMarkers(const InteractionHandlerPtr& handler)
617 {
618  std::string root_link;
619  std::map<std::string, geometry_msgs::Pose> pose_updates;
620  {
621  boost::unique_lock<boost::mutex> ulock(marker_access_lock_);
622 
623  moveit::core::RobotStateConstPtr s = handler->getState();
624  root_link = s->getRobotModel()->getModelFrame();
625 
626  for (const EndEffectorInteraction& eef : active_eef_)
627  {
628  std::string marker_name = getMarkerName(handler, eef);
629  geometry_msgs::Pose control_to_eef_tf;
630  computeMarkerPose(handler, eef, *s, pose_updates[marker_name], control_to_eef_tf);
631  }
632 
633  for (JointInteraction& vj : active_vj_)
634  {
635  std::string marker_name = getMarkerName(handler, vj);
636  pose_updates[marker_name] = tf2::toMsg(s->getGlobalLinkTransform(vj.connecting_link));
637  }
638 
639  for (GenericInteraction& gi : active_generic_)
640  {
641  std::string marker_name = getMarkerName(handler, gi);
642  geometry_msgs::Pose pose;
643  if (gi.update_pose && gi.update_pose(*s, pose))
644  pose_updates[marker_name] = pose;
645  }
646  }
647 
648  std_msgs::Header header;
649  header.frame_id = root_link; // marker poses are give w.r.t. root frame
650  for (std::map<std::string, geometry_msgs::Pose>::const_iterator it = pose_updates.begin(); it != pose_updates.end();
651  ++it)
652  int_marker_server_->setPose(it->first, it->second, header);
653  int_marker_server_->applyChanges();
654 }
655 
656 void RobotInteraction::publishInteractiveMarkers()
657 {
658  // the server locks internally, so we need not worry about locking
659  int_marker_server_->applyChanges();
660 }
661 
662 bool RobotInteraction::showingMarkers(const InteractionHandlerPtr& handler)
663 {
664  boost::unique_lock<boost::mutex> ulock(marker_access_lock_);
665 
666  for (const EndEffectorInteraction& eef : active_eef_)
667  if (shown_markers_.find(getMarkerName(handler, eef)) == shown_markers_.end())
668  return false;
669  for (const JointInteraction& vj : active_vj_)
670  if (shown_markers_.find(getMarkerName(handler, vj)) == shown_markers_.end())
671  return false;
672  for (const GenericInteraction& gi : active_generic_)
673  if (shown_markers_.find(getMarkerName(handler, gi)) == shown_markers_.end())
674  return false;
675  return true;
676 }
677 
678 void RobotInteraction::moveInteractiveMarker(const std::string& name, const geometry_msgs::PoseStamped& msg)
679 {
680  std::map<std::string, std::size_t>::const_iterator it = shown_markers_.find(name);
681  if (it != shown_markers_.end())
682  {
683  auto feedback = boost::make_shared<visualization_msgs::InteractiveMarkerFeedback>();
684  feedback->header = msg.header;
685  feedback->marker_name = name;
686  feedback->pose = msg.pose;
687  feedback->event_type = visualization_msgs::InteractiveMarkerFeedback::POSE_UPDATE;
688  processInteractiveMarkerFeedback(feedback);
689  {
690  boost::unique_lock<boost::mutex> ulock(marker_access_lock_);
691  int_marker_server_->setPose(name, msg.pose, msg.header); // move the interactive marker
692  int_marker_server_->applyChanges();
693  }
694  }
695 }
696 
697 void RobotInteraction::processInteractiveMarkerFeedback(
698  const visualization_msgs::InteractiveMarkerFeedbackConstPtr& feedback)
699 {
700  // perform some validity checks
701  boost::unique_lock<boost::mutex> ulock(marker_access_lock_);
702  std::map<std::string, std::size_t>::const_iterator it = shown_markers_.find(feedback->marker_name);
703  if (it == shown_markers_.end())
704  {
705  ROS_ERROR("Unknown marker name: '%s' (not published by RobotInteraction class)", feedback->marker_name.c_str());
706  return;
707  }
708 
709  std::size_t u = feedback->marker_name.find_first_of('_');
710  if (u == std::string::npos || u < 4)
711  {
712  ROS_ERROR("Invalid marker name: '%s'", feedback->marker_name.c_str());
713  return;
714  }
715 
716  feedback_map_[feedback->marker_name] = feedback;
717  new_feedback_condition_.notify_all();
718 }
719 
720 void RobotInteraction::processingThread()
721 {
722  boost::unique_lock<boost::mutex> ulock(marker_access_lock_);
723 
724  while (run_processing_thread_ && ros::ok())
725  {
726  while (feedback_map_.empty() && run_processing_thread_ && ros::ok())
727  new_feedback_condition_.wait(ulock);
728 
729  while (!feedback_map_.empty() && ros::ok())
730  {
731  visualization_msgs::InteractiveMarkerFeedbackConstPtr feedback = feedback_map_.begin()->second;
732  feedback_map_.erase(feedback_map_.begin());
733  ROS_DEBUG_NAMED("robot_interaction", "Processing feedback from map for marker [%s]",
734  feedback->marker_name.c_str());
735 
736  std::map<std::string, std::size_t>::const_iterator it = shown_markers_.find(feedback->marker_name);
737  if (it == shown_markers_.end())
738  {
739  ROS_ERROR("Unknown marker name: '%s' (not published by RobotInteraction class) "
740  "(should never have ended up in the feedback_map!)",
741  feedback->marker_name.c_str());
742  continue;
743  }
744  std::size_t u = feedback->marker_name.find_first_of('_');
745  if (u == std::string::npos || u < 4)
746  {
747  ROS_ERROR("Invalid marker name: '%s' (should never have ended up in the feedback_map!)",
748  feedback->marker_name.c_str());
749  continue;
750  }
751  std::string marker_class = feedback->marker_name.substr(0, 2);
752  std::string handler_name = feedback->marker_name.substr(3, u - 3); // skip the ":"
753  std::map<std::string, InteractionHandlerPtr>::const_iterator jt = handlers_.find(handler_name);
754  if (jt == handlers_.end())
755  {
756  ROS_ERROR("Interactive Marker Handler '%s' is not known.", handler_name.c_str());
757  continue;
758  }
759 
760  // we put this in a try-catch because user specified callbacks may be triggered
761  try
762  {
763  if (marker_class == "EE")
764  {
765  // make a copy of the data, so we do not lose it while we are unlocked
766  EndEffectorInteraction eef = active_eef_[it->second];
767  InteractionHandlerPtr ih = jt->second;
768  marker_access_lock_.unlock();
769  try
770  {
771  ih->handleEndEffector(eef, feedback);
772  }
773  catch (std::exception& ex)
774  {
775  ROS_ERROR("Exception caught while handling end-effector update: %s", ex.what());
776  }
777  marker_access_lock_.lock();
778  }
779  else if (marker_class == "JJ")
780  {
781  // make a copy of the data, so we do not lose it while we are unlocked
782  JointInteraction vj = active_vj_[it->second];
783  InteractionHandlerPtr ih = jt->second;
784  marker_access_lock_.unlock();
785  try
786  {
787  ih->handleJoint(vj, feedback);
788  }
789  catch (std::exception& ex)
790  {
791  ROS_ERROR("Exception caught while handling joint update: %s", ex.what());
792  }
793  marker_access_lock_.lock();
794  }
795  else if (marker_class == "GG")
796  {
797  InteractionHandlerPtr ih = jt->second;
798  GenericInteraction g = active_generic_[it->second];
799  marker_access_lock_.unlock();
800  try
801  {
802  ih->handleGeneric(g, feedback);
803  }
804  catch (std::exception& ex)
805  {
806  ROS_ERROR("Exception caught while handling joint update: %s", ex.what());
807  }
808  marker_access_lock_.lock();
809  }
810  else
811  ROS_ERROR("Unknown marker class ('%s') for marker '%s'", marker_class.c_str(), feedback->marker_name.c_str());
812  }
813  catch (std::exception& ex)
814  {
815  ROS_ERROR("Exception caught while processing event: %s", ex.what());
816  }
817  }
818  }
819 }
820 } // namespace robot_interaction
moveit::core::LinkModel
robot_interaction::InteractionStyle::FIXED
@ FIXED
Definition: interaction.h:68
robot_interaction::addViewPlaneControl
void addViewPlaneControl(visualization_msgs::InteractiveMarker &int_marker, double radius, const std_msgs::ColorRGBA &color, bool position=true, bool orientation=true)
Definition: interactive_marker_helpers.cpp:266
robot_interaction::add6DOFControl
void add6DOFControl(visualization_msgs::InteractiveMarker &int_marker, bool orientation_fixed=false)
Definition: interactive_marker_helpers.cpp:204
robot_interaction::EndEffectorInteraction::eef_group
std::string eef_group
The name of the group that defines the group joints.
Definition: interaction.h:148
robot_interaction::RobotInteraction::INTERACTIVE_MARKER_TOPIC
static const std::string INTERACTIVE_MARKER_TOPIC
The topic name on which the internal Interactive Marker Server operates.
Definition: robot_interaction.h:76
robot_interaction::RobotInteraction::RobotInteraction
RobotInteraction(const moveit::core::RobotModelConstPtr &robot_model, const std::string &ns="")
Definition: robot_interaction.cpp:98
moveit::core::JointModel::PLANAR
PLANAR
tf2::Transform::inverse
Transform inverse() const
moveit::core::JointModelGroup::getGroupKinematics
const std::pair< KinematicsSolver, KinematicsSolverMap > & getGroupKinematics() const
tf2_eigen.h
tf2::fromMsg
void fromMsg(const A &, B &b)
robot_interaction::GenericInteraction
Definition: interaction.h:118
s
XmlRpcServer s
robot_interaction::InteractionStyle::ORIENTATION_EEF
@ ORIENTATION_EEF
Definition: interaction.h:67
robot_interaction::InteractionStyle::POSITION_EEF
@ POSITION_EEF
Definition: interaction.h:66
robot_interaction::GenericInteraction::marker_name_suffix
std::string marker_name_suffix
Definition: interaction.h:134
moveit::core::LinkModel::getShapeExtentsAtOrigin
const Eigen::Vector3d & getShapeExtentsAtOrigin() const
moveit::core::LinkModel::getParentJointModel
const JointModel * getParentJointModel() const
menu_handler.h
robot_interaction::JointInteraction
Definition: interaction.h:159
moveit::core::RobotState
moveit::core::RobotState::getGlobalLinkTransform
const Eigen::Isometry3d & getGlobalLinkTransform(const std::string &link_name)
robot_interaction::EndEffectorInteraction::parent_group
std::string parent_group
The name of the group that sustains the end-effector (usually an arm)
Definition: interaction.h:142
robot_interaction::InteractionStyle::POSITION_SPHERE
@ POSITION_SPHERE
Definition: interaction.h:64
robot_interaction::InteractionStyle::ORIENTATION_SPHERE
@ ORIENTATION_SPHERE
Definition: interaction.h:65
ros::ok
ROSCPP_DECL bool ok()
transforms.h
robot_interaction.h
moveit::core::JointModel::getType
JointType getType() const
robot_interaction::InteractionStyle::SIX_DOF
@ SIX_DOF
Definition: interaction.h:72
robot_interaction::InteractiveMarkerUpdateFn
boost::function< bool(const moveit::core::RobotState &, geometry_msgs::Pose &)> InteractiveMarkerUpdateFn
Definition: interaction.h:114
interaction_handler.h
robot_interaction::InteractionStyle::InteractionStyle
InteractionStyle
Definition: interaction.h:60
robot_interaction::InteractiveMarkerConstructorFn
boost::function< bool(const moveit::core::RobotState &state, visualization_msgs::InteractiveMarker &marker)> InteractiveMarkerConstructorFn
Definition: interaction.h:88
kinematic_options_map.h
robot_interaction::makeEmptyInteractiveMarker
visualization_msgs::InteractiveMarker makeEmptyInteractiveMarker(const std::string &name, const geometry_msgs::PoseStamped &stamped, double scale)
Definition: interactive_marker_helpers.cpp:78
name
std::string name
ROS_INFO_NAMED
#define ROS_INFO_NAMED(name,...)
update
void update(const std::string &key, const XmlRpc::XmlRpcValue &v)
moveit::core::RobotState::computeAABB
void computeAABB(std::vector< double > &aabb)
ROS_DEBUG_NAMED
#define ROS_DEBUG_NAMED(name,...)
robot_interaction::EndEffectorInteraction::parent_link
std::string parent_link
The name of the link in the parent group that connects to the end-effector.
Definition: interaction.h:145
robot_interaction::InteractionStyle::POSITION_ARROWS
@ POSITION_ARROWS
Definition: interaction.h:62
moveit::core::RobotState::setToDefaultValues
void setToDefaultValues()
srdf::ModelConstSharedPtr
std::shared_ptr< const Model > ModelConstSharedPtr
ROS_ERROR
#define ROS_ERROR(...)
tf2::Transform
robot_interaction::JointInteraction::joint_name
std::string joint_name
The name of the joint.
Definition: interaction.h:168
robot_interaction::EndEffectorInteraction::interaction
InteractionStyle::InteractionStyle interaction
Which degrees of freedom to enable for the end-effector.
Definition: interaction.h:151
ros::NodeHandle::subscribe
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
robot_interaction::addPositionControl
void addPositionControl(visualization_msgs::InteractiveMarker &int_marker, bool orientation_fixed=false)
Definition: interactive_marker_helpers.cpp:238
moveit::core::JointModelGroup::getJointModels
const std::vector< const JointModel * > & getJointModels() const
interactive_markers::InteractiveMarkerServer
moveit::core::JointModelGroup::hasJointModel
bool hasJointModel(const std::string &joint) const
robot_interaction::EndEffectorInteraction
Definition: interaction.h:139
robot_interaction::ProcessFeedbackFn
boost::function< bool(moveit::core::RobotState &state, const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)> ProcessFeedbackFn
Definition: interaction.h:103
moveit::core::JointModelGroup::getLinkModelNames
const std::vector< std::string > & getLinkModelNames() const
srdf::Model::VirtualJoint
robot_interaction::addPlanarXYControl
void addPlanarXYControl(visualization_msgs::InteractiveMarker &int_marker, bool orientation_fixed=false)
Definition: interactive_marker_helpers.cpp:176
interactive_marker_server.h
interactive_marker_helpers.h
robot_interaction::JointInteraction::size
double size
The size of the connecting link (diameter of enclosing sphere)
Definition: interaction.h:174
robot_interaction::getMarkerName
static std::string getMarkerName(const InteractionHandlerPtr &handler, const GenericInteraction &g)
Definition: robot_interaction.cpp:477
srdf
ROS_WARN_NAMED
#define ROS_WARN_NAMED(name,...)
moveit::core::JointModelGroup
tf2_geometry_msgs.h
robot_interaction
Definition: interaction.h:54
tf2::toMsg
B toMsg(const A &a)
robot_interaction::END_EFFECTOR_UNREACHABLE_COLOR
static const float END_EFFECTOR_UNREACHABLE_COLOR[4]
Definition: robot_interaction.cpp:93
robot_interaction::addOrientationControl
void addOrientationControl(visualization_msgs::InteractiveMarker &int_marker, bool orientation_fixed=false)
Definition: interactive_marker_helpers.cpp:210
robot_interaction::JointInteraction::connecting_link
std::string connecting_link
The link in the robot model this joint is a parent of.
Definition: interaction.h:162
robot_interaction::GenericInteraction::process_feedback
ProcessFeedbackFn process_feedback
Definition: interaction.h:126
robot_interaction::GenericInteraction::update_pose
InteractiveMarkerUpdateFn update_pose
Definition: interaction.h:130
robot_interaction::JointInteraction::dof
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:171
moveit::core::JointModel::FLOATING
FLOATING
aabb
SaPCollisionManager< S >::SaPAABB * aabb
header
const std::string header
robot_interaction::GenericInteraction::construct_marker
InteractiveMarkerConstructorFn construct_marker
Definition: interaction.h:122
robot_interaction::JointInteraction::parent_frame
std::string parent_frame
The name of the frame that is a parent of this joint.
Definition: interaction.h:165
robot_interaction::END_EFFECTOR_REACHABLE_COLOR
static const float END_EFFECTOR_REACHABLE_COLOR[4]
Definition: robot_interaction.cpp:94
moveit::core::JointModel::FIXED
FIXED
ros::Duration
robot_interaction::DEFAULT_SCALE
static const double DEFAULT_SCALE
Definition: robot_interaction.cpp:149
Transform.h
moveit::core::JointModel
ros::NodeHandle
srdf::Model::EndEffector
moveit::core::LinkModel::getParentLinkModel
const LinkModel * getParentLinkModel() const
robot_interaction::InteractionStyle::ORIENTATION_CIRCLES
@ ORIENTATION_CIRCLES
Definition: interaction.h:63
ros::Time::now
static Time now()


robot_interaction
Author(s): Ioan Sucan
autogenerated on Sat Mar 15 2025 02:26:54