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
00032 #ifndef TRAJECTORY_H
00033 #define TRAJECTORY_H
00034
00035 #include <iostream>
00036 #include <iomanip>
00037 #include <cmath>
00038 #include <vector>
00039 #include <sstream>
00040 #include <map>
00041
00042 #include "ros/console.h"
00043
00044 namespace trajectory
00045 {
00048 class Trajectory
00049 {
00050 public:
00051
00055 struct TPoint
00056 {
00057
00058 TPoint() {}
00060 TPoint(int dimension){setDimension(dimension);};
00062 TPoint(const std::vector<double>& q, double time);
00064 std::vector<double> q_;
00066 std::vector<double> qdot_;
00068 double time_;
00070 int dimension_;
00072 friend class Trajectory;
00073
00078 void setDimension(int dimension){
00079 dimension_ = dimension;
00080 q_.resize(dimension_);
00081 qdot_.resize(dimension_);
00082 }
00083 };
00084
00088 struct TCoeff
00089 {
00090 TCoeff() {}
00091
00092
00093
00094 inline double get_coefficient(int degree, int dim_index);
00095
00096 private:
00097
00098 int degree_;
00100 int dimension_;
00102 double duration_;
00104 std::vector<std::vector<double> > coeff_;
00106 friend class Trajectory;
00107 };
00108
00112 Trajectory(int dimension);
00113
00117 virtual ~Trajectory() {}
00118
00122 void clear();
00123
00127 void addPoint(const TPoint);
00128
00133 int setTrajectory(const std::vector<TPoint>& tp);
00134
00141 int setTrajectory(const std::vector<double> &p, const std::vector<double> &time, int numPoints);
00142
00149 int setTrajectory(const std::vector<double> &p, int numPoints);
00150
00151 int setTrajectory(const std::vector<double> &p, const std::vector<double> &pdot, const std::vector<double> &time, int numPoints);
00152
00153 int setMaxAcc(std::vector<double> max_acc);
00154
00155
00160
00161 double getTotalTime();
00162
00169 int sample(TPoint &tp, double time);
00170
00171
00172
00173
00174
00175
00176
00181 void setInterpolationMethod(std::string interp_method);
00182
00187 int setMaxRates(std::vector<double> max_rate);
00188
00189 bool autocalc_timing_;
00195 int getNumberPoints();
00196
00202 int minimizeSegmentTimes();
00203
00204 int getDuration(std::vector<double> &duration);
00205
00206 int getDuration(int index, double &duration);
00207
00208 int getTimeStamps(std::vector<double> ×tamps);
00209
00210 int write(std::string filename, double dT);
00211
00212 void setJointWraps(int index);
00213
00219 int findTrajectorySegment(double time);
00220
00221 void getTrajectory(std::vector<trajectory::Trajectory::TPoint> &traj, double dT);
00222
00223 protected:
00224
00225 std::string interp_method_;
00227 private:
00228
00229 bool max_acc_set_;
00230
00231 bool max_rate_set_;
00232
00233 const TPoint& lastPoint();
00234
00235 void init(int num_points, int dimension);
00236
00237 int num_points_;
00239 int dimension_;
00241 std::vector<TPoint> tp_;
00243 std::vector<TCoeff> tc_;
00245 std::vector<double> max_limit_;
00247 std::vector<double> min_limit_;
00249 std::vector<double> max_rate_;
00251 std::vector<double> max_acc_;
00253 std::vector<bool> joint_wraps_;
00261 int parameterize();
00262
00269 int parameterizeLinear();
00270
00277 int parameterizeBlendedLinear();
00278
00285 int parameterizeCubic();
00286
00291 int minimizeSegmentTimesWithLinearInterpolation();
00292
00297 int minimizeSegmentTimesWithCubicInterpolation();
00298
00303 int minimizeSegmentTimesWithBlendedLinearInterpolation();
00304
00312 void sampleLinear(TPoint &tp, double time, const TCoeff &tc, double segment_start_time);
00313
00321 void sampleCubic(TPoint &tp, double time, const TCoeff &tc, double segment_start_time);
00322
00330 void sampleBlendedLinear(TPoint &tp, double time, const TCoeff &tc, double segment_start_time);
00331
00332 double calculateMinTimeCubic(double q0, double q1, double v0, double v1, double vmax, int index);
00333
00339 double calculateMinimumTimeLinear(const TPoint &start, const TPoint &end);
00340
00346 double calculateMinimumTimeLSPB(const TPoint &start, const TPoint &end);
00347
00348 double calculateMinTimeLSPB(double q0, double q1, double vmax, double amax, int index);
00349
00350 double calculateMinimumTimeCubic(const TPoint &start, const TPoint &end);
00351
00352 double blendTime(double aa,double bb,double cc);
00353
00354 double jointDiff(double from, double to, int index);
00355
00356 };
00357 }
00358
00359 #endif