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
00037 #ifndef CHOMP_TRAJECTORY_H_
00038 #define CHOMP_TRAJECTORY_H_
00039
00040 #include <trajectory_msgs/JointTrajectory.h>
00041
00042 #include <chomp_motion_planner/chomp_robot_model.h>
00043 #include <chomp_motion_planner/chomp_utils.h>
00044
00045 #include <vector>
00046 #include <kdl/jntarray.hpp>
00047 #include <Eigen/Core>
00048
00049 namespace chomp
00050 {
00051
00055 class ChompTrajectory
00056 {
00057 public:
00061 ChompTrajectory(const ChompRobotModel* robot_model, double duration, double discretization);
00062
00066 ChompTrajectory(const ChompRobotModel* robot_model, int num_points, double discretization);
00067
00072 ChompTrajectory(const ChompTrajectory& source_traj, const ChompRobotModel::ChompPlanningGroup* planning_group, int diff_rule_length);
00073
00074 ChompTrajectory(const ChompRobotModel* robot_model,
00075 const ChompRobotModel::ChompPlanningGroup* planning_group,
00076 const trajectory_msgs::JointTrajectory& traj);
00077
00081 virtual ~ChompTrajectory();
00082
00083 double& operator() (int traj_point, int joint);
00084
00085 double operator() (int traj_point, int joint) const;
00086
00087 Eigen::MatrixXd::RowXpr getTrajectoryPoint(int traj_point);
00088
00089 void getTrajectoryPointKDL(int traj_point, KDL::JntArray& kdl_jnt_array) const;
00090
00091 Eigen::MatrixXd::ColXpr getJointTrajectory(int joint);
00092
00093 void overwriteTrajectory(const trajectory_msgs::JointTrajectory& traj);
00094
00098 int getNumPoints() const;
00099
00103 int getNumFreePoints() const;
00104
00108 int getNumJoints() const;
00109
00113 double getDiscretization() const;
00114
00120 void fillInMinJerk();
00121
00128 void setStartEndIndex(int start_index, int end_index);
00129
00133 int getStartIndex() const;
00134
00138 int getEndIndex() const;
00139
00143 Eigen::MatrixXd& getTrajectory();
00144
00148 Eigen::Block<Eigen::MatrixXd, Eigen::Dynamic, Eigen::Dynamic> getFreeTrajectoryBlock();
00149
00153 Eigen::Block<Eigen::MatrixXd, Eigen::Dynamic, Eigen::Dynamic> getFreeJointTrajectoryBlock(int joint);
00154
00158 void updateFromGroupTrajectory(const ChompTrajectory& group_trajectory);
00159
00163 int getFullTrajectoryIndex(int i) const;
00164
00168 template <typename Derived>
00169 void getJointVelocities(int traj_point, Eigen::MatrixBase<Derived>& velocities);
00170
00171 double getDuration() const;
00172
00173 private:
00174
00175 void init();
00177 const ChompRobotModel* robot_model_;
00178 const ChompRobotModel::ChompPlanningGroup* planning_group_;
00179 int num_points_;
00180 int num_joints_;
00181 double discretization_;
00182 double duration_;
00183 Eigen::MatrixXd trajectory_;
00184 int start_index_;
00185 int end_index_;
00186 std::vector<int> full_trajectory_index_;
00187 };
00188
00190
00191 inline double& ChompTrajectory::operator() (int traj_point, int joint)
00192 {
00193 return trajectory_(traj_point, joint);
00194 }
00195
00196 inline double ChompTrajectory::operator() (int traj_point, int joint) const
00197 {
00198 return trajectory_(traj_point, joint);
00199 }
00200
00201 inline Eigen::MatrixXd::RowXpr ChompTrajectory::getTrajectoryPoint(int traj_point)
00202 {
00203 return trajectory_.row(traj_point);
00204 }
00205
00206 inline Eigen::MatrixXd::ColXpr ChompTrajectory::getJointTrajectory(int joint)
00207 {
00208 return trajectory_.col(joint);
00209 }
00210
00211 inline int ChompTrajectory::getNumPoints() const
00212 {
00213 return num_points_;
00214 }
00215
00216 inline int ChompTrajectory::getNumFreePoints() const
00217 {
00218 return (end_index_ - start_index_)+1;
00219 }
00220
00221 inline int ChompTrajectory::getNumJoints() const
00222 {
00223 return num_joints_;
00224 }
00225
00226 inline double ChompTrajectory::getDiscretization() const
00227 {
00228 return discretization_;
00229 }
00230
00231 inline void ChompTrajectory::setStartEndIndex(int start_index, int end_index)
00232 {
00233 start_index_ = start_index;
00234 end_index_ = end_index;
00235 }
00236
00237 inline int ChompTrajectory::getStartIndex() const
00238 {
00239 return start_index_;
00240 }
00241
00242 inline int ChompTrajectory::getEndIndex() const
00243 {
00244 return end_index_;
00245 }
00246
00247 inline Eigen::MatrixXd& ChompTrajectory::getTrajectory()
00248 {
00249 return trajectory_;
00250 }
00251
00252 inline Eigen::Block<Eigen::MatrixXd, Eigen::Dynamic, Eigen::Dynamic> ChompTrajectory::getFreeTrajectoryBlock()
00253 {
00254 return trajectory_.block(start_index_, 0, getNumFreePoints(), getNumJoints());
00255 }
00256
00257 inline Eigen::Block<Eigen::MatrixXd, Eigen::Dynamic, Eigen::Dynamic> ChompTrajectory::getFreeJointTrajectoryBlock(int joint)
00258 {
00259 return trajectory_.block(start_index_, joint, getNumFreePoints(), 1);
00260 }
00261
00262 inline void ChompTrajectory::getTrajectoryPointKDL(int traj_point, KDL::JntArray& kdl_jnt_array) const
00263 {
00264 for (int i=0; i<num_joints_; i++)
00265 kdl_jnt_array(i) = trajectory_(traj_point,i);
00266 }
00267
00268 inline int ChompTrajectory::getFullTrajectoryIndex(int i) const
00269 {
00270 return full_trajectory_index_[i];
00271 }
00272
00273 template <typename Derived>
00274 void ChompTrajectory::getJointVelocities(int traj_point, Eigen::MatrixBase<Derived>& velocities)
00275 {
00276 velocities.setZero();
00277 double invTime = 1.0 / discretization_;
00278
00279 for (int k=-DIFF_RULE_LENGTH/2; k<=DIFF_RULE_LENGTH/2; k++)
00280 {
00281 velocities += (invTime * DIFF_RULES[0][k+DIFF_RULE_LENGTH/2]) * trajectory_.row(traj_point+k).transpose();
00282 }
00283 }
00284
00285 inline double ChompTrajectory::getDuration() const {
00286 return duration_;
00287 }
00288
00289 }
00290
00291 #endif