39#include <visualization_msgs/msg/interactive_marker_feedback.hpp>
40#include <visualization_msgs/msg/interactive_marker.hpp>
41#include <interactive_markers/menu_handler.hpp>
87typedef std::function<bool(
const moveit::core::RobotState& state, visualization_msgs::msg::InteractiveMarker& marker)>
102 const visualization_msgs::msg::InteractiveMarkerFeedback::ConstSharedPtr& feedback)>
Representation of a robot's state. This includes position, velocity, acceleration and effort.
Main namespace for MoveIt.
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
double size
The size of the end effector group (diameter of enclosing sphere)
std::string parent_group
The name of the group that sustains the end-effector (usually an arm)
InteractionStyle::InteractionStyle interaction
Which degrees of freedom to enable for the end-effector.
std::string eef_group
The name of the group that defines the group joints.
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
double size
The size of the connecting link (diameter of enclosing sphere)
unsigned int dof
The type of joint disguised as the number of DOF it has. 3=PLANAR in X/Y; 6=FLOATING.
std::string parent_frame
The name of the frame that is a parent of this joint.
std::string connecting_link
The link in the robot model this joint is a parent of.
std::string joint_name
The name of the joint.