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