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 BT_TRAJECTORY
00038 #define BT_TRAJECTORY
00039
00040 #ifndef Q_MOC_RUN
00041 #include <frame_marker.h>
00042 #include <moveit/macros/class_forward.h>
00043 #endif
00044
00045 namespace benchmark_tool
00046 {
00047 MOVEIT_CLASS_FORWARD(Trajectory);
00048
00049
00050
00051 class Trajectory : public QObject
00052 {
00053 Q_OBJECT
00054
00055 public Q_SLOTS:
00056 void trajectoryMarkerFeedback(visualization_msgs::InteractiveMarkerFeedback& feedback);
00057 void handMarkerFeedback(visualization_msgs::InteractiveMarkerFeedback& feedback);
00058 void startMarkerFeedback(visualization_msgs::InteractiveMarkerFeedback& feedback);
00059 void endMarkerFeedback(visualization_msgs::InteractiveMarkerFeedback& feedback);
00060
00061 public:
00062 static const int TRAJECTORY_SET_START_POSE = 1;
00063 static const int TRAJECTORY_SET_END_POSE = 2;
00064 static const int TRAJECTORY_EDIT_CONTROL_FRAME = 3;
00065 static const int TRAJECTORY_FIX_CONTROL_FRAME = 4;
00066
00067 static const std::string TRAJECTORY_SET_START_POSE_STRING;
00068 static const std::string TRAJECTORY_SET_END_POSE_STRING;
00069 static const std::string TRAJECTORY_EDIT_CONTROL_FRAME_STRING;
00070 static const std::string TRAJECTORY_FIX_CONTROL_FRAME_STRING;
00071
00072 GripperMarkerPtr control_marker;
00073 GripperMarkerPtr hand_marker;
00074 GripperMarkerPtr start_marker, end_marker;
00075 std::vector<GripperMarkerPtr> waypoint_markers;
00076
00077 Eigen::Affine3d control_marker_start_pose;
00078 Eigen::Affine3d control_marker_end_pose;
00079
00080 Trajectory(const robot_state::RobotState& robot_state, Ogre::SceneNode* parent_node, rviz::DisplayContext* context,
00081 const std::string& name, const std::string& frame_id,
00082 const robot_interaction::RobotInteraction::EndEffector& eef, const geometry_msgs::Pose& pose, double scale,
00083 const GripperMarker::GripperMarkerState& state, unsigned int nwaypoints, bool is_selected = true,
00084 bool visible_x = true, bool visible_y = true, bool visible_z = true);
00085
00086 void setControlMarker(const GripperMarkerPtr control_marker);
00087
00088 void setNumberOfWaypoints(unsigned int n)
00089 {
00090 nwaypoints_ = n;
00091 if (waypoint_markers.size())
00092 {
00093 rebuildWayPointMarkers();
00094 }
00095 }
00096
00097 void hide()
00098 {
00099 if (control_marker)
00100 control_marker->hide();
00101 if (hand_marker)
00102 hand_marker->hide();
00103 if (start_marker)
00104 start_marker->hide();
00105 if (end_marker)
00106 end_marker->hide();
00107 for (std::vector<GripperMarkerPtr>::iterator it = waypoint_markers.begin(); it != waypoint_markers.end(); ++it)
00108 {
00109 (*it)->hide();
00110 }
00111 }
00112
00113 void show(Ogre::SceneNode* scene_node, rviz::DisplayContext* context)
00114 {
00115 if (control_marker)
00116 control_marker->show(scene_node, context);
00117 if (hand_marker)
00118 hand_marker->show(scene_node, context);
00119 if (start_marker)
00120 start_marker->show(scene_node, context);
00121 if (end_marker)
00122 end_marker->show(scene_node, context);
00123 for (std::vector<GripperMarkerPtr>::iterator it = waypoint_markers.begin(); it != waypoint_markers.end(); ++it)
00124 {
00125 (*it)->show(scene_node, context);
00126 }
00127 }
00128
00129 ~Trajectory()
00130 {
00131 }
00132
00133 protected:
00134 void createControlMarker(const robot_state::RobotState& robot_state, Ogre::SceneNode* parent_node,
00135 rviz::DisplayContext* context, const std::string& name, const std::string& frame_id,
00136 const robot_interaction::RobotInteraction::EndEffector& eef, const geometry_msgs::Pose& pose,
00137 double scale, const GripperMarker::GripperMarkerState& state, bool is_selected = true,
00138 bool visible_x = true, bool visible_y = true, bool visible_z = true);
00139
00140 void createHandMarker();
00141 void createStartMarker();
00142 void createEndMarker();
00143
00144 void connectControlMarker();
00145 void connectHandMarker();
00146 void connectStartMarker();
00147 void connectEndMarker();
00148
00149 void rebuildWayPointMarkers();
00150
00151 private:
00152 void editControlFrame();
00153 void fixControlFrame();
00154
00155 Eigen::Affine3d hand_marker_start_pose;
00156 Eigen::Affine3d control_marker_drag_start_pose;
00157
00158 bool dragging_;
00159
00160 unsigned int nwaypoints_;
00161
00162 typedef enum { CONTROL_MARKER_FLOATING, CONTROL_MARKER_FIXED } ControlMarkerModeType;
00163 ControlMarkerModeType control_marker_mode_;
00164 };
00165 }
00166
00167 #endif