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_TRAJECTORY_KINEMATIC_TRAJECTORY_
00038 #define MOVEIT_ROBOT_TRAJECTORY_KINEMATIC_TRAJECTORY_
00039
00040 #include <moveit/macros/class_forward.h>
00041 #include <moveit/robot_state/robot_state.h>
00042 #include <moveit_msgs/RobotTrajectory.h>
00043 #include <moveit_msgs/RobotState.h>
00044 #include <deque>
00045
00046 namespace robot_trajectory
00047 {
00048 MOVEIT_CLASS_FORWARD(RobotTrajectory);
00049
00052 class RobotTrajectory
00053 {
00054 public:
00055 RobotTrajectory(const robot_model::RobotModelConstPtr& robot_model, const std::string& group);
00056
00057 RobotTrajectory(const robot_model::RobotModelConstPtr& robot_model, const robot_model::JointModelGroup* group);
00058
00059 const robot_model::RobotModelConstPtr& getRobotModel() const
00060 {
00061 return robot_model_;
00062 }
00063
00064 const robot_model::JointModelGroup* getGroup() const
00065 {
00066 return group_;
00067 }
00068
00069 const std::string& getGroupName() const;
00070
00071 void setGroupName(const std::string& group_name);
00072
00073 std::size_t getWayPointCount() const
00074 {
00075 return waypoints_.size();
00076 }
00077
00078 const robot_state::RobotState& getWayPoint(std::size_t index) const
00079 {
00080 return *waypoints_[index];
00081 }
00082
00083 const robot_state::RobotState& getLastWayPoint() const
00084 {
00085 return *waypoints_.back();
00086 }
00087
00088 const robot_state::RobotState& getFirstWayPoint() const
00089 {
00090 return *waypoints_.front();
00091 }
00092
00093 robot_state::RobotStatePtr& getWayPointPtr(std::size_t index)
00094 {
00095 return waypoints_[index];
00096 }
00097
00098 robot_state::RobotStatePtr& getLastWayPointPtr()
00099 {
00100 return waypoints_.back();
00101 }
00102
00103 robot_state::RobotStatePtr& getFirstWayPointPtr()
00104 {
00105 return waypoints_.front();
00106 }
00107
00108 const std::deque<double>& getWayPointDurations() const
00109 {
00110 return duration_from_previous_;
00111 }
00112
00117 double getWaypointDurationFromStart(std::size_t index) const;
00118
00119 double getWayPointDurationFromPrevious(std::size_t index) const
00120 {
00121 if (duration_from_previous_.size() > index)
00122 return duration_from_previous_[index];
00123 else
00124 return 0.0;
00125 }
00126
00127 void setWayPointDurationFromPrevious(std::size_t index, double value)
00128 {
00129 if (duration_from_previous_.size() <= index)
00130 duration_from_previous_.resize(index + 1, 0.0);
00131 duration_from_previous_[index] = value;
00132 }
00133
00134 bool empty() const
00135 {
00136 return waypoints_.empty();
00137 }
00138
00144 void addSuffixWayPoint(const robot_state::RobotState& state, double dt)
00145 {
00146 addSuffixWayPoint(robot_state::RobotStatePtr(new robot_state::RobotState(state)), dt);
00147 }
00148
00154 void addSuffixWayPoint(const robot_state::RobotStatePtr& state, double dt)
00155 {
00156 state->update();
00157 waypoints_.push_back(state);
00158 duration_from_previous_.push_back(dt);
00159 }
00160
00161 void addPrefixWayPoint(const robot_state::RobotState& state, double dt)
00162 {
00163 addPrefixWayPoint(robot_state::RobotStatePtr(new robot_state::RobotState(state)), dt);
00164 }
00165
00166 void addPrefixWayPoint(const robot_state::RobotStatePtr& state, double dt)
00167 {
00168 state->update();
00169 waypoints_.push_front(state);
00170 duration_from_previous_.push_front(dt);
00171 }
00172
00173 void insertWayPoint(std::size_t index, const robot_state::RobotState& state, double dt)
00174 {
00175 insertWayPoint(index, robot_state::RobotStatePtr(new robot_state::RobotState(state)), dt);
00176 }
00177
00178 void insertWayPoint(std::size_t index, const robot_state::RobotStatePtr& state, double dt)
00179 {
00180 state->update();
00181 waypoints_.insert(waypoints_.begin() + index, state);
00182 duration_from_previous_.insert(duration_from_previous_.begin() + index, dt);
00183 }
00184
00190 void append(const RobotTrajectory& source, double dt);
00191
00192 void swap(robot_trajectory::RobotTrajectory& other);
00193
00194 void clear();
00195
00196 double getAverageSegmentDuration() const;
00197
00198 void getRobotTrajectoryMsg(moveit_msgs::RobotTrajectory& trajectory) const;
00199
00206 void setRobotTrajectoryMsg(const robot_state::RobotState& reference_state,
00207 const trajectory_msgs::JointTrajectory& trajectory);
00208
00215 void setRobotTrajectoryMsg(const robot_state::RobotState& reference_state,
00216 const moveit_msgs::RobotTrajectory& trajectory);
00217
00225 void setRobotTrajectoryMsg(const robot_state::RobotState& reference_state, const moveit_msgs::RobotState& state,
00226 const moveit_msgs::RobotTrajectory& trajectory);
00227
00228 void reverse();
00229
00230 void unwind();
00231 void unwind(const robot_state::RobotState& state);
00232
00239 void findWayPointIndicesForDurationAfterStart(const double& duration, int& before, int& after, double& blend) const;
00240
00241
00248 bool getStateAtDurationFromStart(const double request_duration, robot_state::RobotStatePtr& output_state) const;
00249
00250 private:
00251 robot_model::RobotModelConstPtr robot_model_;
00252 const robot_model::JointModelGroup* group_;
00253 std::deque<robot_state::RobotStatePtr> waypoints_;
00254 std::deque<double> duration_from_previous_;
00255 };
00256 }
00257
00258 #endif