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