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