Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037 #ifndef MOVEIT_ROBOT_INTERACTION_INTERACTION_
00038 #define MOVEIT_ROBOT_INTERACTION_INTERACTION_
00039
00040 #include <visualization_msgs/InteractiveMarkerFeedback.h>
00041 #include <visualization_msgs/InteractiveMarker.h>
00042 #include <interactive_markers/menu_handler.h>
00043 #include <moveit/robot_state/robot_state.h>
00044 #include <boost/function.hpp>
00045 #include <boost/thread.hpp>
00046 #include <tf/tf.h>
00047
00048 namespace moveit
00049 {
00050 namespace core
00051 {
00052 class RobotState;
00053 }
00054 }
00055
00056 namespace robot_interaction
00057 {
00058 namespace InteractionStyle
00059 {
00062 enum InteractionStyle
00063 {
00064 POSITION_ARROWS = 1,
00065 ORIENTATION_CIRCLES = 2,
00066 POSITION_SPHERE = 4,
00067 ORIENTATION_SPHERE = 8,
00068 POSITION_EEF = 16,
00069 ORIENTATION_EEF = 32,
00070 FIXED = 64,
00071
00072 POSITION = POSITION_ARROWS | POSITION_SPHERE | POSITION_EEF,
00073 ORIENTATION = ORIENTATION_CIRCLES | ORIENTATION_SPHERE | ORIENTATION_EEF,
00074 SIX_DOF = POSITION | ORIENTATION,
00075 SIX_DOF_SPHERE = POSITION_SPHERE | ORIENTATION_SPHERE,
00076 POSITION_NOSPHERE = POSITION_ARROWS | POSITION_EEF,
00077 ORIENTATION_NOSPHERE = ORIENTATION_CIRCLES | ORIENTATION_EEF,
00078 SIX_DOF_NOSPHERE = POSITION_NOSPHERE | ORIENTATION_NOSPHERE
00079 };
00080 }
00081
00089 typedef boost::function<bool(const robot_state::RobotState& state, visualization_msgs::InteractiveMarker& marker)>
00090 InteractiveMarkerConstructorFn;
00091
00103 typedef boost::function<bool(robot_state::RobotState& state,
00104 const visualization_msgs::InteractiveMarkerFeedbackConstPtr& feedback)>
00105 ProcessFeedbackFn;
00106
00116 typedef boost::function<bool(const robot_state::RobotState&, geometry_msgs::Pose&)> InteractiveMarkerUpdateFn;
00117
00120 struct GenericInteraction
00121 {
00122
00123
00124 InteractiveMarkerConstructorFn construct_marker;
00125
00126
00127
00128 ProcessFeedbackFn process_feedback;
00129
00130
00131
00132 InteractiveMarkerUpdateFn update_pose;
00133
00134
00135
00136 std::string marker_name_suffix;
00137 };
00138
00141 struct EndEffectorInteraction
00142 {
00144 std::string parent_group;
00145
00147 std::string parent_link;
00148
00150 std::string eef_group;
00151
00153 InteractionStyle::InteractionStyle interaction;
00154
00156 double size;
00157 };
00158
00161 struct JointInteraction
00162 {
00164 std::string connecting_link;
00165
00167 std::string parent_frame;
00168
00170 std::string joint_name;
00171
00173 unsigned int dof;
00174
00176 double size;
00177 };
00178 }
00179
00180 #endif