48 #include <boost/lexical_cast.hpp>
49 #include <boost/math/constants/constants.hpp>
50 #include <boost/algorithm/string.hpp>
56 #include <Eigen/Geometry>
66 : robot_model_(robot_model), kinematic_options_map_(new KinematicOptionsMap)
68 topic_ = ns.empty() ? INTERACTIVE_MARKER_TOPIC : ns +
"/" + INTERACTIVE_MARKER_TOPIC;
72 run_processing_thread_ =
true;
73 processing_thread_ = std::make_unique<boost::thread>([
this] { processingThread(); });
76 RobotInteraction::~RobotInteraction()
78 run_processing_thread_ =
false;
79 new_feedback_condition_.notify_all();
80 processing_thread_->join();
83 delete int_marker_server_;
86 void RobotInteraction::decideActiveComponents(
const std::string& group)
93 decideActiveEndEffectors(group, style);
94 decideActiveJoints(group);
95 if (!group.empty() && active_eef_.empty() && active_vj_.empty() && active_generic_.empty())
97 "No active joints or end effectors found for group '%s'. "
98 "Make sure that kinematics.yaml is loaded in this node's namespace.",
104 const std::string& name)
106 boost::unique_lock<boost::mutex> ulock(marker_access_lock_);
113 active_generic_.push_back(g);
117 double RobotInteraction::computeLinkMarkerSize(
const std::string& link)
126 Eigen::MatrixXd::Index max_index;
127 ext.maxCoeff(&max_index);
129 size = 1.01 * ext.norm();
147 double RobotInteraction::computeGroupMarkerSize(
const std::string& group)
161 for (
const std::string& link : links)
169 Eigen::MatrixXd::Index max_index;
170 ext.maxCoeff(&max_index);
172 size = std::max(size, 1.01 * ext.norm());
178 return computeLinkMarkerSize(links[0]);
184 void RobotInteraction::decideActiveJoints(
const std::string& group)
186 boost::unique_lock<boost::mutex> ulock(marker_access_lock_);
192 ROS_DEBUG_NAMED(
"robot_interaction",
"Deciding active joints for group '%s'", group.c_str());
200 std::set<std::string> used;
205 std::vector<double>
aabb;
208 const std::vector<srdf::Model::VirtualJoint>& vj =
srdf->getVirtualJoints();
210 if (joint.name_ == robot_model_->getRootJointName())
212 if (joint.type_ ==
"planar" || joint.type_ ==
"floating")
220 if (joint.type_ ==
"planar")
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);
232 const std::vector<const moveit::core::JointModel*>& joints = jmg->
getJointModels();
237 used.find(joint->getName()) == used.end())
241 if (joint->getParentLinkModel())
242 v.parent_frame = joint->getParentLinkModel()->getName();
243 v.joint_name = joint->getName();
249 v.size = computeGroupMarkerSize(group);
250 active_vj_.push_back(v);
255 void RobotInteraction::decideActiveEndEffectors(
const std::string& group)
262 boost::unique_lock<boost::mutex> ulock(marker_access_lock_);
268 ROS_DEBUG_NAMED(
"robot_interaction",
"Deciding active end-effectors for group '%s'", group.c_str());
275 ROS_WARN_NAMED(
"robot_interaction",
"Unable to decide active end effector: no joint model group or no srdf model");
279 const std::vector<srdf::Model::EndEffector>& eefs =
srdf->getEndEffectors();
280 const std::pair<moveit::core::JointModelGroup::KinematicsSolver, moveit::core::JointModelGroup::KinematicsSolverMap>&
284 bool found_eef{
false };
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_))
297 active_eef_.push_back(ee);
303 if (!found_eef && !single_group->getLinkModelNames().empty())
305 std::string last_link{ single_group->getLinkModelNames().back() };
307 if (single_group->canSetStateFromIK(last_link))
309 EndEffectorInteraction ee;
311 ee.parent_link = last_link;
312 ee.eef_group = single_group->getName();
313 ee.interaction = style;
314 active_eef_.push_back(ee);
322 add_active_end_effectors_for_single_group(jmg);
325 else if (!smap.second.empty())
327 for (
const std::pair<const moveit::core::JointModelGroup* const, moveit::core::JointModelGroup::KinematicsSolver>&
329 add_active_end_effectors_for_single_group(it.first);
333 for (EndEffectorInteraction& eef : active_eef_)
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(),
343 if (active_eef_.size() == 1)
344 active_eef_[0].size *= 1.5;
347 void RobotInteraction::clear()
349 boost::unique_lock<boost::mutex> ulock(marker_access_lock_);
352 active_generic_.clear();
353 clearInteractiveMarkersUnsafe();
354 publishInteractiveMarkers();
357 void RobotInteraction::clearInteractiveMarkers()
359 boost::unique_lock<boost::mutex> ulock(marker_access_lock_);
360 clearInteractiveMarkersUnsafe();
363 void RobotInteraction::clearInteractiveMarkersUnsafe()
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();
373 void RobotInteraction::addEndEffectorMarkers(
const InteractionHandlerPtr& handler,
const EndEffectorInteraction& eef,
374 visualization_msgs::InteractiveMarker& im,
bool position,
bool orientation)
376 geometry_msgs::Pose pose;
377 pose.orientation.w = 1;
378 addEndEffectorMarkers(handler, eef, pose, im, position, orientation);
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)
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;
395 m_control.interaction_mode = m_control.MOVE_3D;
397 std_msgs::ColorRGBA marker_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];
404 moveit::core::RobotStateConstPtr rstate = handler->getState();
405 visualization_msgs::MarkerArray marker_array;
414 for (visualization_msgs::Marker& marker : marker_array.markers)
416 marker.header = im.header;
417 marker.mesh_use_embedded_materials = !marker.mesh_resource.empty();
425 tf2::Transform tf_root_to_mesh_new = tf_root_to_im * tf_im_to_mesh;
428 m_control.markers.push_back(marker);
431 im.controls.push_back(m_control);
434 static inline std::string
getMarkerName(
const InteractionHandlerPtr& handler,
const EndEffectorInteraction& eef)
436 return "EE:" + handler->getName() +
"_" + eef.parent_link;
439 static inline std::string
getMarkerName(
const InteractionHandlerPtr& handler,
const JointInteraction& vj)
441 return "JJ:" + handler->getName() +
"_" + vj.connecting_link;
444 static inline std::string
getMarkerName(
const InteractionHandlerPtr& handler,
const GenericInteraction& g)
446 return "GG:" + handler->getName() +
"_" + g.marker_name_suffix;
449 void RobotInteraction::addInteractiveMarkers(
const InteractionHandlerPtr& handler,
const double marker_scale)
452 std::vector<visualization_msgs::InteractiveMarker> ims;
454 boost::unique_lock<boost::mutex> ulock(marker_access_lock_);
455 moveit::core::RobotStateConstPtr
s = handler->getState();
457 for (std::size_t i = 0; i < active_generic_.size(); ++i)
459 visualization_msgs::InteractiveMarker im;
460 if (active_generic_[i].construct_marker(*s, im))
463 shown_markers_[im.name] = i;
465 ROS_DEBUG_NAMED(
"robot_interaction",
"Publishing interactive marker %s (size = %lf)", im.name.c_str(), im.scale);
469 for (std::size_t i = 0; i < active_eef_.size(); ++i)
471 geometry_msgs::PoseStamped pose;
472 geometry_msgs::Pose control_to_eef_tf;
473 pose.header.frame_id = robot_model_->getModelFrame();
475 computeMarkerPose(handler, active_eef_[i], *s, pose.pose, control_to_eef_tf);
478 shown_markers_[marker_name] = i;
481 double mscale = marker_scale < std::numeric_limits<double>::epsilon() ? active_eef_[i].size : marker_scale;
484 if (handler && handler->getControlsVisible())
492 std_msgs::ColorRGBA color;
501 if (handler && handler->getMeshesVisible() &&
503 addEndEffectorMarkers(handler, active_eef_[i], control_to_eef_tf, 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);
510 for (std::size_t i = 0; i < active_vj_.size(); ++i)
512 geometry_msgs::PoseStamped pose;
513 pose.header.frame_id = robot_model_->getModelFrame();
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;
520 double mscale = marker_scale < std::numeric_limits<double>::epsilon() ? active_vj_[i].size : marker_scale;
523 if (handler && handler->getControlsVisible())
525 if (active_vj_[i].dof == 3)
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);
534 handlers_[handler->getName()] = handler;
540 for (
const visualization_msgs::InteractiveMarker& im : ims)
542 int_marker_server_->insert(im);
543 int_marker_server_->setCallback(im.name,
544 [
this](
const auto& feedback) { processInteractiveMarkerFeedback(feedback); });
547 if (std::shared_ptr<interactive_markers::MenuHandler> mh = handler->getMenuHandler())
548 mh->apply(*int_marker_server_, im.name);
552 void RobotInteraction::registerMoveInteractiveMarkerTopic(
const std::string& marker_name,
const std::string& name)
554 std::stringstream ss;
555 ss <<
"/rviz/moveit/move_marker/";
557 int_marker_move_topics_.push_back(ss.str());
558 int_marker_names_.push_back(marker_name);
561 void RobotInteraction::toggleMoveInteractiveMarkerTopic(
bool enable)
565 boost::unique_lock<boost::mutex> ulock(marker_access_lock_);
566 if (int_marker_move_subscribers_.empty())
569 for (
size_t i = 0; i < int_marker_move_topics_.size(); i++)
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);
582 boost::unique_lock<boost::mutex> ulock(marker_access_lock_);
583 int_marker_move_subscribers_.clear();
587 void RobotInteraction::computeMarkerPose(
const InteractionHandlerPtr& handler,
const EndEffectorInteraction& eef,
589 geometry_msgs::Pose& control_to_eef_tf)
const
595 geometry_msgs::Pose msg_link_to_control;
596 if (handler->getPoseOffset(eef, msg_link_to_control))
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);
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;
616 void RobotInteraction::updateInteractiveMarkers(
const InteractionHandlerPtr& handler)
618 std::string root_link;
619 std::map<std::string, geometry_msgs::Pose> pose_updates;
621 boost::unique_lock<boost::mutex> ulock(marker_access_lock_);
623 moveit::core::RobotStateConstPtr
s = handler->getState();
624 root_link =
s->getRobotModel()->getModelFrame();
629 geometry_msgs::Pose control_to_eef_tf;
630 computeMarkerPose(handler, eef, *
s, pose_updates[marker_name], control_to_eef_tf);
636 pose_updates[marker_name] =
tf2::toMsg(
s->getGlobalLinkTransform(vj.connecting_link));
642 geometry_msgs::Pose pose;
643 if (gi.update_pose && gi.update_pose(*
s, pose))
644 pose_updates[marker_name] = pose;
650 for (std::map<std::string, geometry_msgs::Pose>::const_iterator it = pose_updates.begin(); it != pose_updates.end();
652 int_marker_server_->setPose(it->first, it->second, header);
653 int_marker_server_->applyChanges();
656 void RobotInteraction::publishInteractiveMarkers()
659 int_marker_server_->applyChanges();
662 bool RobotInteraction::showingMarkers(
const InteractionHandlerPtr& handler)
664 boost::unique_lock<boost::mutex> ulock(marker_access_lock_);
666 for (
const EndEffectorInteraction& eef : active_eef_)
667 if (shown_markers_.find(
getMarkerName(handler, eef)) == shown_markers_.end())
669 for (
const JointInteraction& vj : active_vj_)
670 if (shown_markers_.find(
getMarkerName(handler, vj)) == shown_markers_.end())
672 for (
const GenericInteraction& gi : active_generic_)
673 if (shown_markers_.find(
getMarkerName(handler, gi)) == shown_markers_.end())
678 void RobotInteraction::moveInteractiveMarker(
const std::string& name,
const geometry_msgs::PoseStamped& msg)
680 std::map<std::string, std::size_t>::const_iterator it = shown_markers_.find(name);
681 if (it != shown_markers_.end())
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);
690 boost::unique_lock<boost::mutex> ulock(marker_access_lock_);
691 int_marker_server_->setPose(
name, msg.pose, msg.header);
692 int_marker_server_->applyChanges();
697 void RobotInteraction::processInteractiveMarkerFeedback(
698 const visualization_msgs::InteractiveMarkerFeedbackConstPtr& feedback)
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())
705 ROS_ERROR(
"Unknown marker name: '%s' (not published by RobotInteraction class)", feedback->marker_name.c_str());
709 std::size_t u = feedback->marker_name.find_first_of(
'_');
710 if (u == std::string::npos || u < 4)
712 ROS_ERROR(
"Invalid marker name: '%s'", feedback->marker_name.c_str());
716 feedback_map_[feedback->marker_name] = feedback;
717 new_feedback_condition_.notify_all();
720 void RobotInteraction::processingThread()
722 boost::unique_lock<boost::mutex> ulock(marker_access_lock_);
724 while (run_processing_thread_ &&
ros::ok())
726 while (feedback_map_.empty() && run_processing_thread_ &&
ros::ok())
727 new_feedback_condition_.wait(ulock);
729 while (!feedback_map_.empty() &&
ros::ok())
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());
736 std::map<std::string, std::size_t>::const_iterator it = shown_markers_.find(feedback->marker_name);
737 if (it == shown_markers_.end())
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());
744 std::size_t u = feedback->marker_name.find_first_of(
'_');
745 if (u == std::string::npos || u < 4)
747 ROS_ERROR(
"Invalid marker name: '%s' (should never have ended up in the feedback_map!)",
748 feedback->marker_name.c_str());
751 std::string marker_class = feedback->marker_name.substr(0, 2);
752 std::string handler_name = feedback->marker_name.substr(3, u - 3);
753 std::map<std::string, InteractionHandlerPtr>::const_iterator jt = handlers_.find(handler_name);
754 if (jt == handlers_.end())
756 ROS_ERROR(
"Interactive Marker Handler '%s' is not known.", handler_name.c_str());
763 if (marker_class ==
"EE")
767 InteractionHandlerPtr ih = jt->second;
768 marker_access_lock_.unlock();
771 ih->handleEndEffector(eef, feedback);
773 catch (std::exception& ex)
775 ROS_ERROR(
"Exception caught while handling end-effector update: %s", ex.what());
777 marker_access_lock_.lock();
779 else if (marker_class ==
"JJ")
782 JointInteraction vj = active_vj_[it->second];
783 InteractionHandlerPtr ih = jt->second;
784 marker_access_lock_.unlock();
787 ih->handleJoint(vj, feedback);
789 catch (std::exception& ex)
791 ROS_ERROR(
"Exception caught while handling joint update: %s", ex.what());
793 marker_access_lock_.lock();
795 else if (marker_class ==
"GG")
797 InteractionHandlerPtr ih = jt->second;
798 GenericInteraction g = active_generic_[it->second];
799 marker_access_lock_.unlock();
802 ih->handleGeneric(g, feedback);
804 catch (std::exception& ex)
806 ROS_ERROR(
"Exception caught while handling joint update: %s", ex.what());
808 marker_access_lock_.lock();
811 ROS_ERROR(
"Unknown marker class ('%s') for marker '%s'", marker_class.c_str(), feedback->marker_name.c_str());
813 catch (std::exception& ex)
815 ROS_ERROR(
"Exception caught while processing event: %s", ex.what());