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