37 #ifndef MOVEIT_ROBOT_INTERACTION_INTERACTION_ 38 #define MOVEIT_ROBOT_INTERACTION_INTERACTION_ 40 #include <visualization_msgs/InteractiveMarkerFeedback.h> 41 #include <visualization_msgs/InteractiveMarker.h> 44 #include <boost/function.hpp> 45 #include <boost/thread.hpp> 89 typedef boost::function<bool(const robot_state::RobotState& state, visualization_msgs::InteractiveMarker& marker)>
103 typedef boost::function<bool(robot_state::RobotState& state,
104 const visualization_msgs::InteractiveMarkerFeedbackConstPtr& feedback)>
std::string parent_link
The name of the link in the parent group that connects to the end-effector.
InteractionStyle::InteractionStyle interaction
Which degrees of freedom to enable for the end-effector.
double size
The size of the end effector group (diameter of enclosing sphere)
double size
The size of the connecting link (diameter of enclosing sphere)
std::string eef_group
The name of the group that defines the group joints.
std::string parent_group
The name of the group that sustains the end-effector (usually an arm)
boost::function< bool(const robot_state::RobotState &, geometry_msgs::Pose &)> InteractiveMarkerUpdateFn
boost::function< bool(robot_state::RobotState &state, const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)> ProcessFeedbackFn
boost::function< bool(const robot_state::RobotState &state, visualization_msgs::InteractiveMarker &marker)> InteractiveMarkerConstructorFn
std::string marker_name_suffix
std::string connecting_link
The link in the robot model this joint is a parent of.
std::string parent_frame
The name of the frame that is a parent of this joint.
unsigned int dof
The type of joint disguised as the number of DOF it has. 3=PLANAR in X/Y; 6=FLOATING.
InteractiveMarkerConstructorFn construct_marker
std::string joint_name
The name of the joint.
ProcessFeedbackFn process_feedback
InteractiveMarkerUpdateFn update_pose