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>
55#include <Eigen/Geometry>
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 };
65 const rclcpp::Node::SharedPtr& node,
const std::string& ns)
66 : robot_model_(robot_model)
68 , logger_(
moveit::getLogger(
"moveit.ros.robot_interaction"))
72 int_marker_server_ =
new interactive_markers::InteractiveMarkerServer(topic_, node_);
75 run_processing_thread_ =
true;
76 processing_thread_ = std::make_unique<std::thread>([
this] { processingThread(); });
81 run_processing_thread_ =
false;
82 new_feedback_condition_.notify_all();
83 processing_thread_->join();
86 delete int_marker_server_;
96 decideActiveEndEffectors(group, style);
97 decideActiveJoints(group);
98 if (!group.empty() && active_eef_.empty() && active_vj_.empty() && active_generic_.empty())
101 "No active joints or end effectors found for group '%s'. "
102 "Make sure that kinematics.yaml is loaded in this node's namespace.",
109 const std::string& name)
111 std::unique_lock<std::mutex> ulock(marker_access_lock_);
118 active_generic_.push_back(g);
121static const double DEFAULT_SCALE = 0.25;
122double RobotInteraction::computeLinkMarkerSize(
const std::string& link)
131 Eigen::MatrixXd::Index max_index;
132 ext.maxCoeff(&max_index);
134 size = 1.01 * ext.norm();
150 return DEFAULT_SCALE;
156double RobotInteraction::computeGroupMarkerSize(
const std::string& group)
159 return DEFAULT_SCALE;
166 return DEFAULT_SCALE;
170 for (
const std::string& link : links)
178 Eigen::MatrixXd::Index max_index;
179 ext.maxCoeff(&max_index);
181 size = std::max(size, 1.01 * ext.norm());
187 return computeLinkMarkerSize(links[0]);
193void RobotInteraction::decideActiveJoints(
const std::string& group)
195 std::unique_lock<std::mutex> ulock(marker_access_lock_);
201 RCLCPP_DEBUG(logger_,
"Deciding active joints for group '%s'", group.c_str());
203 const srdf::ModelConstSharedPtr& srdf = robot_model_->getSRDF();
209 std::set<std::string> used;
213 default_state.setToDefaultValues();
214 std::vector<double> aabb;
215 default_state.computeAABB(aabb);
217 const std::vector<srdf::Model::VirtualJoint>& vj = srdf->getVirtualJoints();
218 for (
const srdf::Model::VirtualJoint& joint : vj)
220 if (joint.name_ == robot_model_->getRootJointName())
222 if (joint.type_ ==
"planar" || joint.type_ ==
"floating")
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")
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);
247 const std::vector<const moveit::core::JointModel*>& joints = jmg->
getJointModels();
252 used.find(joint->getName()) == used.end())
255 v.connecting_link = joint->getChildLinkModel()->getName();
256 if (joint->getParentLinkModel())
257 v.parent_frame = joint->getParentLinkModel()->getName();
258 v.joint_name = joint->getName();
268 v.size = computeGroupMarkerSize(group);
269 active_vj_.push_back(v);
274void RobotInteraction::decideActiveEndEffectors(
const std::string& group)
281 std::unique_lock<std::mutex> ulock(marker_access_lock_);
287 RCLCPP_DEBUG(logger_,
"Deciding active end-effectors for group '%s'", group.c_str());
289 const srdf::ModelConstSharedPtr& srdf = robot_model_->getSRDF();
294 RCLCPP_WARN(logger_,
"Unable to decide active end effector: no joint model group or no srdf model");
298 const std::vector<srdf::Model::EndEffector>& eefs = srdf->getEndEffectors();
299 const std::pair<moveit::core::JointModelGroup::KinematicsSolver, moveit::core::JointModelGroup::KinematicsSolverMap>&
303 bool found_eef{
false };
304 for (
const srdf::Model::EndEffector& eef : eefs)
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_))
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);
322 if (!found_eef && !single_group->getLinkModelNames().empty())
324 std::string last_link{ single_group->getLinkModelNames().back() };
326 if (single_group->canSetStateFromIK(last_link))
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);
341 add_active_end_effectors_for_single_group(jmg);
344 else if (!smap.second.empty())
346 for (
const std::pair<const moveit::core::JointModelGroup* const, moveit::core::JointModelGroup::KinematicsSolver>&
348 add_active_end_effectors_for_single_group(it.first);
352 for (EndEffectorInteraction& eef : active_eef_)
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);
361 if (active_eef_.size() == 1)
362 active_eef_[0].size *= 1.5;
367 std::unique_lock<std::mutex> ulock(marker_access_lock_);
370 active_generic_.clear();
371 clearInteractiveMarkersUnsafe();
377 std::unique_lock<std::mutex> ulock(marker_access_lock_);
378 clearInteractiveMarkersUnsafe();
381void RobotInteraction::clearInteractiveMarkersUnsafe()
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();
391void RobotInteraction::addEndEffectorMarkers(
const InteractionHandlerPtr& handler,
const EndEffectorInteraction& eef,
392 visualization_msgs::msg::InteractiveMarker& im,
bool position,
395 geometry_msgs::msg::Pose pose;
396 pose.orientation.w = 1;
397 addEndEffectorMarkers(handler, eef, pose, im, position, orientation);
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,
405 if (eef.parent_group == eef.eef_group || !robot_model_->hasLinkModel(eef.parent_link))
408 visualization_msgs::msg::InteractiveMarkerControl m_control;
409 m_control.always_visible =
false;
410 if (position && orientation)
412 m_control.interaction_mode = m_control.MOVE_ROTATE_3D;
414 else if (orientation)
416 m_control.interaction_mode = m_control.ROTATE_3D;
420 m_control.interaction_mode = m_control.MOVE_3D;
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];
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);
439 for (visualization_msgs::msg::Marker& marker : marker_array.markers)
441 marker.header = im.header;
442 marker.mesh_use_embedded_materials = !marker.mesh_resource.empty();
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);
453 m_control.markers.push_back(marker);
456 im.controls.push_back(m_control);
459static inline std::string getMarkerName(
const InteractionHandlerPtr& handler,
const EndEffectorInteraction& eef)
461 return "EE:" + handler->getName() +
"_" + eef.parent_link;
464static inline std::string getMarkerName(
const InteractionHandlerPtr& handler,
const JointInteraction& vj)
466 return "JJ:" + handler->getName() +
"_" + vj.connecting_link;
469static inline std::string getMarkerName(
const InteractionHandlerPtr& handler,
const GenericInteraction& g)
471 return "GG:" + handler->getName() +
"_" + g.marker_name_suffix;
477 std::vector<visualization_msgs::msg::InteractiveMarker> ims;
479 std::unique_lock<std::mutex> ulock(marker_access_lock_);
480 moveit::core::RobotStateConstPtr s = handler->getState();
482 for (std::size_t i = 0; i < active_generic_.size(); ++i)
484 visualization_msgs::msg::InteractiveMarker im;
485 if (active_generic_[i].construct_marker(*s, im))
487 im.name = getMarkerName(handler, active_generic_[i]);
488 shown_markers_[im.name] = i;
490 RCLCPP_DEBUG(logger_,
"Publishing interactive marker %s (size = %lf)", im.name.c_str(), im.scale);
494 for (std::size_t i = 0; i < active_eef_.size(); ++i)
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);
502 std::string marker_name = getMarkerName(handler, active_eef_[i]);
503 shown_markers_[marker_name] = i;
506 double mscale = marker_scale < std::numeric_limits<double>::epsilon() ? active_eef_[i].size : marker_scale;
509 if (handler && handler->getControlsVisible())
517 std_msgs::msg::ColorRGBA color;
526 if (handler && handler->getMeshesVisible() &&
529 addEndEffectorMarkers(handler, active_eef_[i], control_to_eef_tf, 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);
537 for (std::size_t i = 0; i < active_vj_.size(); ++i)
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;
547 double mscale = marker_scale < std::numeric_limits<double>::epsilon() ? active_vj_[i].size : marker_scale;
550 if (handler && handler->getControlsVisible())
552 if (active_vj_[i].dof == 3)
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);
565 handlers_[handler->getName()] = handler;
571 for (
const visualization_msgs::msg::InteractiveMarker& im : ims)
573 int_marker_server_->insert(im);
574 int_marker_server_->setCallback(im.name,
575 [
this](
const auto& feedback) { processInteractiveMarkerFeedback(feedback); });
578 if (std::shared_ptr<interactive_markers::MenuHandler> mh = handler->getMenuHandler())
579 mh->apply(*int_marker_server_, im.name);
583void RobotInteraction::registerMoveInteractiveMarkerTopic(
const std::string& marker_name,
const std::string& name)
585 std::stringstream ss;
586 ss <<
"/rviz/moveit/move_marker/";
588 int_marker_move_topics_.push_back(ss.str());
589 int_marker_names_.push_back(marker_name);
596 std::unique_lock<std::mutex> ulock(marker_access_lock_);
597 if (int_marker_move_subscribers_.empty())
599 for (
size_t i = 0; i < int_marker_move_topics_.size(); ++i)
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);
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);
615 std::unique_lock<std::mutex> ulock(marker_access_lock_);
616 int_marker_move_subscribers_.clear();
620void RobotInteraction::computeMarkerPose(
const InteractionHandlerPtr& handler,
const EndEffectorInteraction& eef,
622 geometry_msgs::msg::Pose& control_to_eef_tf)
const
625 tf2::Transform tf_root_to_link, tf_root_to_control;
628 geometry_msgs::msg::Pose msg_link_to_control;
629 if (handler->getPoseOffset(eef, msg_link_to_control))
631 tf2::Transform tf_link_to_control;
632 tf2::fromMsg(msg_link_to_control, tf_link_to_control);
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);
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;
646 tf2::toMsg(tf_root_to_control, pose);
651 std::string root_link;
652 std::map<std::string, geometry_msgs::msg::Pose> pose_updates;
654 std::unique_lock<std::mutex> ulock(marker_access_lock_);
656 moveit::core::RobotStateConstPtr s = handler->getState();
657 root_link = s->getRobotModel()->getModelFrame();
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);
668 std::string marker_name = getMarkerName(handler, vj);
669 pose_updates[marker_name] = tf2::toMsg(s->getGlobalLinkTransform(vj.connecting_link));
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;
681 std_msgs::msg::Header header;
682 header.frame_id = root_link;
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();
692 int_marker_server_->applyChanges();
697 std::unique_lock<std::mutex> ulock(marker_access_lock_);
701 if (shown_markers_.find(getMarkerName(handler, eef)) == shown_markers_.end())
706 if (shown_markers_.find(getMarkerName(handler, vj)) == shown_markers_.end())
711 if (shown_markers_.find(getMarkerName(handler, gi)) == shown_markers_.end())
717void RobotInteraction::moveInteractiveMarker(
const std::string& name,
const geometry_msgs::msg::PoseStamped& msg)
719 std::map<std::string, std::size_t>::const_iterator it = shown_markers_.find(name);
720 if (it != shown_markers_.end())
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);
729 std::unique_lock<std::mutex> ulock(marker_access_lock_);
730 int_marker_server_->setPose(name, msg.pose, msg.header);
731 int_marker_server_->applyChanges();
736void RobotInteraction::processInteractiveMarkerFeedback(
737 const visualization_msgs::msg::InteractiveMarkerFeedback::ConstSharedPtr& feedback)
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())
744 RCLCPP_ERROR(logger_,
"Unknown marker name: '%s' (not published by RobotInteraction class)",
745 feedback->marker_name.c_str());
749 std::size_t u = feedback->marker_name.find_first_of(
'_');
750 if (u == std::string::npos || u < 4)
752 RCLCPP_ERROR(logger_,
"Invalid marker name: '%s'", feedback->marker_name.c_str());
756 feedback_map_[feedback->marker_name] = feedback;
757 new_feedback_condition_.notify_all();
760void RobotInteraction::processingThread()
762 std::unique_lock<std::mutex> ulock(marker_access_lock_);
764 while (run_processing_thread_ && rclcpp::ok())
766 while (feedback_map_.empty() && run_processing_thread_ && rclcpp::ok())
767 new_feedback_condition_.wait(ulock);
769 while (!feedback_map_.empty() && rclcpp::ok())
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());
775 std::map<std::string, std::size_t>::const_iterator it = shown_markers_.find(feedback->marker_name);
776 if (it == shown_markers_.end())
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());
784 std::size_t u = feedback->marker_name.find_first_of(
'_');
785 if (u == std::string::npos || u < 4)
787 RCLCPP_ERROR(logger_,
"Invalid marker name: '%s' (should never have ended up in the feedback_map!)",
788 feedback->marker_name.c_str());
791 std::string marker_class = feedback->marker_name.substr(0, 2);
792 std::string handler_name = feedback->marker_name.substr(3, u - 3);
793 std::map<std::string, InteractionHandlerPtr>::const_iterator jt = handlers_.find(handler_name);
794 if (jt == handlers_.end())
796 RCLCPP_ERROR(logger_,
"Interactive Marker Handler '%s' is not known.", handler_name.c_str());
803 if (marker_class ==
"EE")
806 EndEffectorInteraction eef = active_eef_[it->second];
807 InteractionHandlerPtr ih = jt->second;
808 marker_access_lock_.unlock();
811 ih->handleEndEffector(eef, feedback);
813 catch (std::exception& ex)
815 RCLCPP_ERROR(logger_,
"Exception caught while handling end-effector update: %s", ex.what());
817 marker_access_lock_.lock();
819 else if (marker_class ==
"JJ")
822 JointInteraction vj = active_vj_[it->second];
823 InteractionHandlerPtr ih = jt->second;
824 marker_access_lock_.unlock();
827 ih->handleJoint(vj, feedback);
829 catch (std::exception& ex)
831 RCLCPP_ERROR(logger_,
"Exception caught while handling joint update: %s", ex.what());
833 marker_access_lock_.lock();
835 else if (marker_class ==
"GG")
837 InteractionHandlerPtr ih = jt->second;
838 GenericInteraction g = active_generic_[it->second];
839 marker_access_lock_.unlock();
842 ih->handleGeneric(g, feedback);
844 catch (std::exception& ex)
846 RCLCPP_ERROR(logger_,
"Exception caught while handling joint update: %s", ex.what());
848 marker_access_lock_.lock();
852 RCLCPP_ERROR(logger_,
"Unknown marker class ('%s') for marker '%s'", marker_class.c_str(),
853 feedback->marker_name.c_str());
856 catch (std::exception& ex)
858 RCLCPP_ERROR(logger_,
"Exception caught while processing event: %s", ex.what());
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.
const JointModel * getParentJointModel() const
Get the joint model whose child this link is. There will always be a parent joint.
const LinkModel * getParentLinkModel() const
Get the link model whose child this link is (through some joint). There may not always be a parent li...
const Eigen::Vector3d & getShapeExtentsAtOrigin() const
Get the extents of the link's geometry (dimensions of axis-aligned bounding box around all shapes tha...
Representation of a robot's state. This includes position, velocity, acceleration and effort.
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 publishInteractiveMarkers()
void clearInteractiveMarkers()
void updateInteractiveMarkers(const InteractionHandlerPtr &handler)
void decideActiveComponents(const std::string &group)
void toggleMoveInteractiveMarkerTopic(bool enable)
virtual ~RobotInteraction()
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.
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
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.
std::string marker_name_suffix
ProcessFeedbackFn process_feedback
InteractiveMarkerConstructorFn construct_marker
InteractiveMarkerUpdateFn update_pose