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 #include <chomp_motion_planner/chomp_trajectory.h>
00038 #include <iostream>
00039
00040 using namespace std;
00041
00042 namespace chomp
00043 {
00044
00045 ChompTrajectory::ChompTrajectory(const ChompRobotModel* robot_model, double duration, double discretization):
00046 robot_model_(robot_model),
00047 planning_group_(NULL),
00048 num_points_((duration/discretization)+1),
00049 num_joints_(robot_model_->getNumKDLJoints()),
00050 discretization_(discretization),
00051 duration_(duration),
00052 start_index_(1),
00053 end_index_(num_points_-2)
00054 {
00055 init();
00056 }
00057
00058 ChompTrajectory::ChompTrajectory(const ChompRobotModel* robot_model, int num_points, double discretization):
00059 robot_model_(robot_model),
00060 planning_group_(NULL),
00061 num_points_(num_points),
00062 num_joints_(robot_model_->getNumKDLJoints()),
00063 discretization_(discretization),
00064 duration_((num_points-1)*discretization),
00065 start_index_(1),
00066 end_index_(num_points_-2)
00067 {
00068 init();
00069 }
00070
00071 ChompTrajectory::ChompTrajectory(const ChompTrajectory& source_traj, const ChompRobotModel::ChompPlanningGroup* planning_group, int diff_rule_length):
00072 robot_model_(source_traj.robot_model_),
00073 planning_group_(planning_group),
00074 discretization_(source_traj.discretization_)
00075 {
00076 num_joints_ = planning_group_->num_joints_;
00077
00078
00079
00080 int start_extra = (diff_rule_length - 1) - source_traj.start_index_;
00081 int end_extra = (diff_rule_length - 1) - ((source_traj.num_points_-1) - source_traj.end_index_);
00082
00083 num_points_ = source_traj.num_points_ + start_extra + end_extra;
00084 start_index_ = diff_rule_length - 1;
00085 end_index_ = (num_points_ - 1) - (diff_rule_length - 1);
00086 duration_ = (num_points_ - 1)*discretization_;
00087
00088
00089 init();
00090
00091 full_trajectory_index_.resize(num_points_);
00092
00093
00094 for (int i=0; i<num_points_; i++)
00095 {
00096 int source_traj_point = i - start_extra;
00097 if (source_traj_point < 0)
00098 source_traj_point = 0;
00099 if (source_traj_point >= source_traj.num_points_)
00100 source_traj_point = source_traj.num_points_-1;
00101 full_trajectory_index_[i] = source_traj_point;
00102 for (int j=0; j<num_joints_; j++)
00103 {
00104 int source_joint = planning_group_->chomp_joints_[j].kdl_joint_index_;
00105 (*this)(i,j) = source_traj(source_traj_point, source_joint);
00106 }
00107 }
00108 }
00109
00110 ChompTrajectory::ChompTrajectory(const ChompRobotModel* robot_model,
00111 const ChompRobotModel::ChompPlanningGroup* planning_group,
00112 const trajectory_msgs::JointTrajectory& traj) :
00113 robot_model_(robot_model),
00114 planning_group_(planning_group),
00115 num_joints_(robot_model_->getNumKDLJoints())
00116 {
00117 double discretization = (traj.points[1].time_from_start-traj.points[0].time_from_start).toSec();
00118
00119 double discretization2 = (traj.points[2].time_from_start-traj.points[1].time_from_start).toSec();
00120
00121 if(fabs(discretization2-discretization) > .001) {
00122 ROS_WARN_STREAM("Trajectory Discretization not constant " << discretization << " " << discretization2);
00123 }
00124 discretization_ = discretization;
00125
00126 num_points_ = traj.points.size()+1;
00127 duration_ = (traj.points.back().time_from_start-traj.points[0].time_from_start).toSec();
00128
00129 start_index_ = 1;
00130 end_index_ = num_points_-2;
00131
00132 init();
00133
00134 for(int i = 0; i < num_points_; i++) {
00135 for(int j = 0; j < num_joints_; j++) {
00136 trajectory_(i,j) = 0.0;
00137 }
00138 }
00139 overwriteTrajectory(traj);
00140 }
00141
00142 ChompTrajectory::~ChompTrajectory()
00143 {
00144 }
00145
00146 void ChompTrajectory::overwriteTrajectory(const trajectory_msgs::JointTrajectory& traj) {
00147 std::vector<int> ind;
00148 for(unsigned int j = 0; j < traj.joint_names.size(); j++) {
00149 int kdl_number = robot_model_->urdfNameToKdlNumber(traj.joint_names[j]);
00150 if(kdl_number == 0) {
00151 ROS_WARN_STREAM("Can't find kdl index for joint " << traj.joint_names[j]);
00152 }
00153 ind.push_back(kdl_number);
00154 }
00155
00156 for(unsigned int i = 1; i <= traj.points.size(); i++) {
00157 for(unsigned int j = 0; j < traj.joint_names.size(); j++) {
00158 trajectory_(i,ind[j]) = traj.points[i-1].positions[j];
00159 }
00160 }
00161 }
00162
00163 void ChompTrajectory::init()
00164 {
00165
00166 trajectory_ = Eigen::MatrixXd(num_points_, num_joints_);
00167 }
00168
00169 void ChompTrajectory::updateFromGroupTrajectory(const ChompTrajectory& group_trajectory)
00170 {
00171 int num_vars_free = end_index_ - start_index_ + 1;
00172 for (int i=0; i<group_trajectory.planning_group_->num_joints_; i++)
00173 {
00174 int target_joint = group_trajectory.planning_group_->chomp_joints_[i].kdl_joint_index_;
00175 trajectory_.block(start_index_, target_joint, num_vars_free, 1)
00176 = group_trajectory.trajectory_.block(group_trajectory.start_index_, i, num_vars_free, 1);
00177 }
00178 }
00179
00180 void ChompTrajectory::fillInMinJerk()
00181 {
00182 double start_index = start_index_-1;
00183 double end_index = end_index_+1;
00184 double T[6];
00185 T[0] = 1.0;
00186 T[1] = (end_index - start_index)*discretization_;
00187
00188 for (int i=2; i<=5; i++)
00189 T[i] = T[i-1]*T[1];
00190
00191
00192
00193 double coeff[num_joints_][6];
00194 for (int i=0; i<num_joints_; i++)
00195 {
00196 double x0 = (*this)(start_index,i);
00197 double x1 = (*this)(end_index,i);
00198 coeff[i][0] = x0;
00199 coeff[i][1] = 0;
00200 coeff[i][2] = 0;
00201 coeff[i][3] = (-20*x0 + 20*x1) / (2*T[3]);
00202 coeff[i][4] = (30*x0 - 30*x1) / (2*T[4]);
00203 coeff[i][5] = (-12*x0 + 12*x1) / (2*T[5]);
00204 }
00205
00206
00207 for (int i=start_index+1; i<end_index; i++)
00208 {
00209 double t[6];
00210 t[0] = 1.0;
00211 t[1] = (i - start_index)*discretization_;
00212 for (int k=2; k<=5; k++)
00213 t[k] = t[k-1]*t[1];
00214
00215 for (int j=0; j<num_joints_; j++)
00216 {
00217 (*this)(i,j) = 0.0;
00218 for (int k=0; k<=5; k++)
00219 {
00220 (*this)(i,j) += t[k]*coeff[j][k];
00221 }
00222 }
00223 }
00224 }
00225
00226 }