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>
48#if __has_include(<tf2/LinearMath/Transform.hpp>)
49#include <tf2/LinearMath/Transform.hpp>
51#include <tf2/LinearMath/Transform.h>
60#include <Eigen/Geometry>
64static const double END_EFFECTOR_UNREACHABLE_COLOR[4] = { 1.0, 0.3, 0.3, 1.0 };
65static const double END_EFFECTOR_REACHABLE_COLOR[4] = { 0.2, 1.0, 0.2, 1.0 };
70 const rclcpp::Node::SharedPtr& node,
const std::string& ns)
71 : robot_model_(robot_model)
73 , logger_(
moveit::getLogger(
"moveit.ros.robot_interaction"))
77 int_marker_server_ =
new interactive_markers::InteractiveMarkerServer(topic_, node_);
80 run_processing_thread_ =
true;
81 processing_thread_ = std::make_unique<std::thread>([
this] { processingThread(); });
86 run_processing_thread_ =
false;
87 new_feedback_condition_.notify_all();
88 processing_thread_->join();
91 delete int_marker_server_;
101 decideActiveEndEffectors(group, style);
102 decideActiveJoints(group);
103 if (!group.empty() && active_eef_.empty() && active_vj_.empty() && active_generic_.empty())
106 "No active joints or end effectors found for group '%s'. "
107 "Make sure that kinematics.yaml is loaded in this node's namespace.",
114 const std::string& name)
116 std::unique_lock<std::mutex> ulock(marker_access_lock_);
123 active_generic_.push_back(g);
126static const double DEFAULT_SCALE = 0.25;
127double RobotInteraction::computeLinkMarkerSize(
const std::string& link)
136 Eigen::MatrixXd::Index max_index;
137 ext.maxCoeff(&max_index);
139 size = 1.01 * ext.norm();
155 return DEFAULT_SCALE;
161double RobotInteraction::computeGroupMarkerSize(
const std::string& group)
164 return DEFAULT_SCALE;
171 return DEFAULT_SCALE;
175 for (
const std::string& link : links)
183 Eigen::MatrixXd::Index max_index;
184 ext.maxCoeff(&max_index);
186 size = std::max(size, 1.01 * ext.norm());
192 return computeLinkMarkerSize(links[0]);
198void RobotInteraction::decideActiveJoints(
const std::string& group)
200 std::unique_lock<std::mutex> ulock(marker_access_lock_);
206 RCLCPP_DEBUG(logger_,
"Deciding active joints for group '%s'", group.c_str());
208 const srdf::ModelConstSharedPtr& srdf = robot_model_->getSRDF();
214 std::set<std::string> used;
218 default_state.setToDefaultValues();
219 std::vector<double> aabb;
220 default_state.computeAABB(aabb);
222 const std::vector<srdf::Model::VirtualJoint>& vj = srdf->getVirtualJoints();
223 for (
const srdf::Model::VirtualJoint& joint : vj)
225 if (joint.name_ == robot_model_->getRootJointName())
227 if (joint.type_ ==
"planar" || joint.type_ ==
"floating")
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")
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);
252 const std::vector<const moveit::core::JointModel*>& joints = jmg->
getJointModels();
257 used.find(joint->getName()) == used.end())
260 v.connecting_link = joint->getChildLinkModel()->getName();
261 if (joint->getParentLinkModel())
262 v.parent_frame = joint->getParentLinkModel()->getName();
263 v.joint_name = joint->getName();
273 v.size = computeGroupMarkerSize(group);
274 active_vj_.push_back(v);
279void RobotInteraction::decideActiveEndEffectors(
const std::string& group)
286 std::unique_lock<std::mutex> ulock(marker_access_lock_);
292 RCLCPP_DEBUG(logger_,
"Deciding active end-effectors for group '%s'", group.c_str());
294 const srdf::ModelConstSharedPtr& srdf = robot_model_->getSRDF();
299 RCLCPP_WARN(logger_,
"Unable to decide active end effector: no joint model group or no srdf model");
303 const std::vector<srdf::Model::EndEffector>& eefs = srdf->getEndEffectors();
304 const std::pair<moveit::core::JointModelGroup::KinematicsSolver, moveit::core::JointModelGroup::KinematicsSolverMap>&
308 bool found_eef{
false };
309 for (
const srdf::Model::EndEffector& eef : eefs)
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_))
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);
327 if (!found_eef && !single_group->getLinkModelNames().empty())
329 std::string last_link{ single_group->getLinkModelNames().back() };
331 if (single_group->canSetStateFromIK(last_link))
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);
346 add_active_end_effectors_for_single_group(jmg);
349 else if (!smap.second.empty())
351 for (
const std::pair<const moveit::core::JointModelGroup* const, moveit::core::JointModelGroup::KinematicsSolver>&
353 add_active_end_effectors_for_single_group(it.first);
357 for (EndEffectorInteraction& eef : active_eef_)
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);
366 if (active_eef_.size() == 1)
367 active_eef_[0].size *= 1.5;
372 std::unique_lock<std::mutex> ulock(marker_access_lock_);
375 active_generic_.clear();
376 clearInteractiveMarkersUnsafe();
382 std::unique_lock<std::mutex> ulock(marker_access_lock_);
383 clearInteractiveMarkersUnsafe();
386void RobotInteraction::clearInteractiveMarkersUnsafe()
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();
396void RobotInteraction::addEndEffectorMarkers(
const InteractionHandlerPtr& handler,
const EndEffectorInteraction& eef,
397 visualization_msgs::msg::InteractiveMarker& im,
bool position,
400 geometry_msgs::msg::Pose pose;
401 pose.orientation.w = 1;
402 addEndEffectorMarkers(handler, eef, pose, im, position, orientation);
405void 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,
410 if (eef.parent_group == eef.eef_group || !robot_model_->hasLinkModel(eef.parent_link))
413 visualization_msgs::msg::InteractiveMarkerControl m_control;
414 m_control.always_visible =
false;
415 if (position && orientation)
417 m_control.interaction_mode = m_control.MOVE_ROTATE_3D;
419 else if (orientation)
421 m_control.interaction_mode = m_control.ROTATE_3D;
425 m_control.interaction_mode = m_control.MOVE_3D;
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];
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);
444 for (visualization_msgs::msg::Marker& marker : marker_array.markers)
446 marker.header = im.header;
447 marker.mesh_use_embedded_materials = !marker.mesh_resource.empty();
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);
458 m_control.markers.push_back(marker);
461 im.controls.push_back(m_control);
464static inline std::string getMarkerName(
const InteractionHandlerPtr& handler,
const EndEffectorInteraction& eef)
466 return "EE:" + handler->getName() +
"_" + eef.parent_link;
469static inline std::string getMarkerName(
const InteractionHandlerPtr& handler,
const JointInteraction& vj)
471 return "JJ:" + handler->getName() +
"_" + vj.connecting_link;
474static inline std::string getMarkerName(
const InteractionHandlerPtr& handler,
const GenericInteraction& g)
476 return "GG:" + handler->getName() +
"_" + g.marker_name_suffix;
482 std::vector<visualization_msgs::msg::InteractiveMarker> ims;
484 std::unique_lock<std::mutex> ulock(marker_access_lock_);
485 moveit::core::RobotStateConstPtr s = handler->getState();
487 for (std::size_t i = 0; i < active_generic_.size(); ++i)
489 visualization_msgs::msg::InteractiveMarker im;
490 if (active_generic_[i].construct_marker(*s, im))
492 im.name = getMarkerName(handler, active_generic_[i]);
493 shown_markers_[im.name] = i;
495 RCLCPP_DEBUG(logger_,
"Publishing interactive marker %s (size = %lf)", im.name.c_str(), im.scale);
499 for (std::size_t i = 0; i < active_eef_.size(); ++i)
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);
507 std::string marker_name = getMarkerName(handler, active_eef_[i]);
508 shown_markers_[marker_name] = i;
511 double mscale = marker_scale < std::numeric_limits<double>::epsilon() ? active_eef_[i].size : marker_scale;
514 if (handler && handler->getControlsVisible())
522 std_msgs::msg::ColorRGBA color;
531 if (handler && handler->getMeshesVisible() &&
534 addEndEffectorMarkers(handler, active_eef_[i], control_to_eef_tf, 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);
542 for (std::size_t i = 0; i < active_vj_.size(); ++i)
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;
552 double mscale = marker_scale < std::numeric_limits<double>::epsilon() ? active_vj_[i].size : marker_scale;
555 if (handler && handler->getControlsVisible())
557 if (active_vj_[i].dof == 3)
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);
570 handlers_[handler->getName()] = handler;
576 for (
const visualization_msgs::msg::InteractiveMarker& im : ims)
578 int_marker_server_->insert(im);
579 int_marker_server_->setCallback(im.name,
580 [
this](
const auto& feedback) { processInteractiveMarkerFeedback(feedback); });
583 if (std::shared_ptr<interactive_markers::MenuHandler> mh = handler->getMenuHandler())
584 mh->apply(*int_marker_server_, im.name);
588void RobotInteraction::registerMoveInteractiveMarkerTopic(
const std::string& marker_name,
const std::string& name)
590 std::stringstream ss;
591 ss <<
"/rviz/moveit/move_marker/";
593 int_marker_move_topics_.push_back(ss.str());
594 int_marker_names_.push_back(marker_name);
601 std::unique_lock<std::mutex> ulock(marker_access_lock_);
602 if (int_marker_move_subscribers_.empty())
604 for (
size_t i = 0; i < int_marker_move_topics_.size(); ++i)
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);
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);
620 std::unique_lock<std::mutex> ulock(marker_access_lock_);
621 int_marker_move_subscribers_.clear();
625void RobotInteraction::computeMarkerPose(
const InteractionHandlerPtr& handler,
const EndEffectorInteraction& eef,
627 geometry_msgs::msg::Pose& control_to_eef_tf)
const
630 tf2::Transform tf_root_to_link, tf_root_to_control;
633 geometry_msgs::msg::Pose msg_link_to_control;
634 if (handler->getPoseOffset(eef, msg_link_to_control))
636 tf2::Transform tf_link_to_control;
637 tf2::fromMsg(msg_link_to_control, tf_link_to_control);
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);
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;
651 tf2::toMsg(tf_root_to_control, pose);
656 std::string root_link;
657 std::map<std::string, geometry_msgs::msg::Pose> pose_updates;
659 std::unique_lock<std::mutex> ulock(marker_access_lock_);
661 moveit::core::RobotStateConstPtr s = handler->getState();
662 root_link = s->getRobotModel()->getModelFrame();
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);
673 std::string marker_name = getMarkerName(handler, vj);
674 pose_updates[marker_name] = tf2::toMsg(s->getGlobalLinkTransform(vj.connecting_link));
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;
686 std_msgs::msg::Header header;
687 header.frame_id = root_link;
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();
697 int_marker_server_->applyChanges();
702 std::unique_lock<std::mutex> ulock(marker_access_lock_);
706 if (shown_markers_.find(getMarkerName(handler, eef)) == shown_markers_.end())
711 if (shown_markers_.find(getMarkerName(handler, vj)) == shown_markers_.end())
716 if (shown_markers_.find(getMarkerName(handler, gi)) == shown_markers_.end())
722void RobotInteraction::moveInteractiveMarker(
const std::string& name,
const geometry_msgs::msg::PoseStamped& msg)
724 std::map<std::string, std::size_t>::const_iterator it = shown_markers_.find(name);
725 if (it != shown_markers_.end())
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);
734 std::unique_lock<std::mutex> ulock(marker_access_lock_);
735 int_marker_server_->setPose(name, msg.pose, msg.header);
736 int_marker_server_->applyChanges();
741void RobotInteraction::processInteractiveMarkerFeedback(
742 const visualization_msgs::msg::InteractiveMarkerFeedback::ConstSharedPtr& feedback)
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())
749 RCLCPP_ERROR(logger_,
"Unknown marker name: '%s' (not published by RobotInteraction class)",
750 feedback->marker_name.c_str());
754 std::size_t u = feedback->marker_name.find_first_of(
'_');
755 if (u == std::string::npos || u < 4)
757 RCLCPP_ERROR(logger_,
"Invalid marker name: '%s'", feedback->marker_name.c_str());
761 feedback_map_[feedback->marker_name] = feedback;
762 new_feedback_condition_.notify_all();
765void RobotInteraction::processingThread()
767 std::unique_lock<std::mutex> ulock(marker_access_lock_);
769 while (run_processing_thread_ && rclcpp::ok())
771 while (feedback_map_.empty() && run_processing_thread_ && rclcpp::ok())
772 new_feedback_condition_.wait(ulock);
774 while (!feedback_map_.empty() && rclcpp::ok())
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());
780 std::map<std::string, std::size_t>::const_iterator it = shown_markers_.find(feedback->marker_name);
781 if (it == shown_markers_.end())
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());
789 std::size_t u = feedback->marker_name.find_first_of(
'_');
790 if (u == std::string::npos || u < 4)
792 RCLCPP_ERROR(logger_,
"Invalid marker name: '%s' (should never have ended up in the feedback_map!)",
793 feedback->marker_name.c_str());
796 std::string marker_class = feedback->marker_name.substr(0, 2);
797 std::string handler_name = feedback->marker_name.substr(3, u - 3);
798 std::map<std::string, InteractionHandlerPtr>::const_iterator jt = handlers_.find(handler_name);
799 if (jt == handlers_.end())
801 RCLCPP_ERROR(logger_,
"Interactive Marker Handler '%s' is not known.", handler_name.c_str());
808 if (marker_class ==
"EE")
811 EndEffectorInteraction eef = active_eef_[it->second];
812 InteractionHandlerPtr ih = jt->second;
813 marker_access_lock_.unlock();
816 ih->handleEndEffector(eef, feedback);
818 catch (std::exception& ex)
820 RCLCPP_ERROR(logger_,
"Exception caught while handling end-effector update: %s", ex.what());
822 marker_access_lock_.lock();
824 else if (marker_class ==
"JJ")
827 JointInteraction vj = active_vj_[it->second];
828 InteractionHandlerPtr ih = jt->second;
829 marker_access_lock_.unlock();
832 ih->handleJoint(vj, feedback);
834 catch (std::exception& ex)
836 RCLCPP_ERROR(logger_,
"Exception caught while handling joint update: %s", ex.what());
838 marker_access_lock_.lock();
840 else if (marker_class ==
"GG")
842 InteractionHandlerPtr ih = jt->second;
843 GenericInteraction g = active_generic_[it->second];
844 marker_access_lock_.unlock();
847 ih->handleGeneric(g, feedback);
849 catch (std::exception& ex)
851 RCLCPP_ERROR(logger_,
"Exception caught while handling joint update: %s", ex.what());
853 marker_access_lock_.lock();
857 RCLCPP_ERROR(logger_,
"Unknown marker class ('%s') for marker '%s'", marker_class.c_str(),
858 feedback->marker_name.c_str());
861 catch (std::exception& ex)
863 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