trajectory.h
Go to the documentation of this file.
00001 /*********************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2013, Willow Garage, Inc.
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of Willow Garage nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  *********************************************************************/
00034 
00035 /* Author: Mario Prats */
00036 
00037 #ifndef BT_TRAJECTORY
00038 #define BT_TRAJECTORY
00039 
00040 #ifndef Q_MOC_RUN
00041 #include <frame_marker.h>
00042 #endif
00043 
00044 namespace benchmark_tool
00045 {
00046 
00047 /* Implements functionality to create and manage straight and arc trajectories with interactive markers
00048  */
00049 class Trajectory: public QObject
00050 {
00051   Q_OBJECT
00052 
00053 public Q_SLOTS:
00054   void trajectoryMarkerFeedback(visualization_msgs::InteractiveMarkerFeedback &feedback);
00055   void handMarkerFeedback(visualization_msgs::InteractiveMarkerFeedback &feedback);
00056   void startMarkerFeedback(visualization_msgs::InteractiveMarkerFeedback &feedback);
00057   void endMarkerFeedback(visualization_msgs::InteractiveMarkerFeedback &feedback);
00058 
00059 public:
00060   static const int TRAJECTORY_SET_START_POSE = 1;
00061   static const int TRAJECTORY_SET_END_POSE = 2;
00062   static const int TRAJECTORY_EDIT_CONTROL_FRAME = 3;
00063   static const int TRAJECTORY_FIX_CONTROL_FRAME = 4;
00064 
00065   static const std::string TRAJECTORY_SET_START_POSE_STRING;
00066   static const std::string TRAJECTORY_SET_END_POSE_STRING;
00067   static const std::string TRAJECTORY_EDIT_CONTROL_FRAME_STRING;
00068   static const std::string TRAJECTORY_FIX_CONTROL_FRAME_STRING;
00069 
00070   GripperMarkerPtr control_marker;
00071   GripperMarkerPtr hand_marker;
00072   GripperMarkerPtr start_marker, end_marker;
00073   std::vector<GripperMarkerPtr> waypoint_markers;
00074 
00075   Eigen::Affine3d control_marker_start_pose; // The control marker pose corresponding to the start marker
00076   Eigen::Affine3d control_marker_end_pose;   // The control marker pose corresponding to the end marker
00077 
00078   Trajectory(const robot_state::RobotState& robot_state, Ogre::SceneNode *parent_node, rviz::DisplayContext *context, const std::string &name,
00079              const std::string &frame_id, const robot_interaction::RobotInteraction::EndEffector &eef, const geometry_msgs::Pose &pose, double scale,
00080              const GripperMarker::GripperMarkerState &state, unsigned int nwaypoints, bool is_selected = true,
00081              bool visible_x = true, bool visible_y = true, bool visible_z = true);
00082 
00083   void setControlMarker(const GripperMarkerPtr control_marker);
00084 
00085   void setNumberOfWaypoints(unsigned int n)
00086   {
00087     nwaypoints_ = n;
00088     if (waypoint_markers.size())
00089     {
00090       rebuildWayPointMarkers();
00091     }
00092   }
00093 
00094   void hide()
00095   {
00096     if (control_marker)
00097       control_marker->hide();
00098     if (hand_marker)
00099       hand_marker->hide();
00100     if (start_marker)
00101       start_marker->hide();
00102     if (end_marker)
00103       end_marker->hide();
00104     for (std::vector<GripperMarkerPtr>::iterator it = waypoint_markers.begin(); it != waypoint_markers.end(); ++it)
00105     {
00106       (*it)->hide();
00107     }
00108   }
00109 
00110   void show(Ogre::SceneNode *scene_node, rviz::DisplayContext *context)
00111   {
00112     if (control_marker)
00113       control_marker->show(scene_node, context);
00114     if (hand_marker)
00115       hand_marker->show(scene_node, context);
00116     if (start_marker)
00117       start_marker->show(scene_node, context);
00118     if (end_marker)
00119       end_marker->show(scene_node, context);
00120     for (std::vector<GripperMarkerPtr>::iterator it = waypoint_markers.begin(); it != waypoint_markers.end(); ++it)
00121     {
00122       (*it)->show(scene_node, context);
00123     }
00124   }
00125 
00126   ~Trajectory() {}
00127 
00128 protected:
00129   void createControlMarker(const robot_state::RobotState& robot_state, Ogre::SceneNode *parent_node, rviz::DisplayContext *context, const std::string &name,
00130                          const std::string &frame_id, const robot_interaction::RobotInteraction::EndEffector &eef, const geometry_msgs::Pose &pose, double scale,
00131                          const GripperMarker::GripperMarkerState &state, bool is_selected = true,
00132                          bool visible_x = true, bool visible_y = true, bool visible_z = true);
00133 
00134   void createHandMarker();
00135   void createStartMarker();
00136   void createEndMarker();
00137 
00138   void connectControlMarker();
00139   void connectHandMarker();
00140   void connectStartMarker();
00141   void connectEndMarker();
00142 
00143   void rebuildWayPointMarkers();
00144 
00145 private:
00146   void editControlFrame();
00147   void fixControlFrame();
00148 
00149   Eigen::Affine3d hand_marker_start_pose;
00150   Eigen::Affine3d control_marker_drag_start_pose;
00151 
00152   bool dragging_;
00153 
00154   unsigned int nwaypoints_;
00155 
00156   typedef enum {CONTROL_MARKER_FLOATING, CONTROL_MARKER_FIXED} ControlMarkerModeType;
00157   ControlMarkerModeType control_marker_mode_;
00158 };
00159 
00160 typedef boost::shared_ptr<Trajectory> TrajectoryPtr;
00161 
00162 }
00163 
00164 #endif


benchmarks_gui
Author(s): Mario Prats
autogenerated on Wed Aug 26 2015 12:44:27