$search
00001 /********************************************************************* 00002 * Software License Agreement (BSD License) 00003 * 00004 * Copyright (c) 2009, Willow Garage, Inc. 00005 * All rights reserved. 00006 * 00007 * Redistribution and use in source and binary forms, with or without 00008 * modification, are permitted provided that the following conditions 00009 * are met: 00010 * 00011 * * Redistributions of source code must retain the above copyright 00012 * notice, this list of conditions and the following disclaimer. 00013 * * Redistributions in binary form must reproduce the above 00014 * copyright notice, this list of conditions and the following 00015 * disclaimer in the documentation and/or other materials provided 00016 * with the distribution. 00017 * * Neither the name of the Willow Garage nor the names of its 00018 * contributors may be used to endorse or promote products derived 00019 * from this software without specific prior written permission. 00020 * 00021 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00022 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00023 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00024 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00025 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00026 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00027 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00028 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00029 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00030 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00031 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00032 * POSSIBILITY OF SUCH DAMAGE. 00033 *********************************************************************/ 00034 00037 #include <chomp_motion_planner/chomp_trajectory.h> 00038 #include <iostream> 00039 using namespace std; 00040 00041 namespace chomp 00042 { 00043 00044 ChompTrajectory::ChompTrajectory(const planning_models::KinematicModel* robot_model, double duration, double discretization, std::string groupName): 00045 planning_group_name_(groupName), 00046 num_points_((duration/discretization)+1), 00047 discretization_(discretization), 00048 duration_(duration), 00049 start_index_(1), 00050 end_index_(num_points_-2) 00051 { 00052 std::map<std::string, planning_models::KinematicModel::JointModelGroup*> groupMap = robot_model->getJointModelGroupMap(); 00053 const planning_models::KinematicModel::JointModelGroup* modelGroup = groupMap[planning_group_name_]; 00054 num_joints_ = modelGroup->getJointModels().size(); 00055 init(); 00056 } 00057 00058 ChompTrajectory::ChompTrajectory(const planning_models::KinematicModel* robot_model, int num_points, double discretization, std::string groupName): 00059 planning_group_name_(groupName), 00060 num_points_(num_points), 00061 discretization_(discretization), 00062 duration_((num_points-1)*discretization), 00063 start_index_(1), 00064 end_index_(num_points_-2) 00065 { 00066 std::map<std::string, planning_models::KinematicModel::JointModelGroup*> groupMap = robot_model->getJointModelGroupMap(); 00067 const planning_models::KinematicModel::JointModelGroup* modelGroup = groupMap[planning_group_name_]; 00068 num_joints_ = modelGroup->getJointModels().size(); 00069 init(); 00070 } 00071 00072 ChompTrajectory::ChompTrajectory(const ChompTrajectory& source_traj, const std::string& planning_group, int diff_rule_length): 00073 planning_group_name_(planning_group), 00074 discretization_(source_traj.discretization_) 00075 { 00076 num_joints_ = source_traj.getNumJoints(); 00077 00078 // figure out the num_points_: 00079 // we need diff_rule_length-1 extra points on either side: 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 // allocate the memory: 00089 init(); 00090 00091 full_trajectory_index_.resize(num_points_); 00092 00093 // now copy the trajectories over: 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 (*this)(i,j) = source_traj(source_traj_point, j); 00105 } 00106 } 00107 } 00108 00109 ChompTrajectory::ChompTrajectory(const planning_models::KinematicModel* robot_model, 00110 const std::string& planning_group, 00111 const trajectory_msgs::JointTrajectory& traj) : 00112 planning_group_name_(planning_group) 00113 { 00114 std::map<std::string, planning_models::KinematicModel::JointModelGroup*> groupMap = robot_model->getJointModelGroupMap(); 00115 const planning_models::KinematicModel::JointModelGroup* modelGroup = groupMap[planning_group_name_]; 00116 num_joints_ = modelGroup->getJointModels().size(); 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 for(unsigned int i = 1; i <= traj.points.size(); i++) { 00148 for(unsigned int j = 0; j < traj.joint_names.size(); j++) { 00149 trajectory_(i,j) = traj.points[i-1].positions[j]; 00150 } 00151 } 00152 } 00153 00154 void ChompTrajectory::init() 00155 { 00156 trajectory_.resize(num_points_, num_joints_); 00157 trajectory_ = Eigen::MatrixXd(num_points_, num_joints_); 00158 } 00159 00160 void ChompTrajectory::updateFromGroupTrajectory(const ChompTrajectory& group_trajectory) 00161 { 00162 int num_vars_free = end_index_ - start_index_ + 1; 00163 for (int i=0; i < num_joints_; i++) 00164 { 00165 trajectory_.block(start_index_, i, num_vars_free, 1) = group_trajectory.trajectory_.block(group_trajectory.start_index_, i, num_vars_free, 1); 00166 } 00167 } 00168 00169 void ChompTrajectory::fillInMinJerk() 00170 { 00171 double start_index = start_index_-1; 00172 double end_index = end_index_+1; 00173 double T[6]; // powers of the time duration 00174 T[0] = 1.0; 00175 T[1] = (end_index - start_index)*discretization_; 00176 00177 for (int i=2; i<=5; i++) 00178 T[i] = T[i-1]*T[1]; 00179 00180 // calculate the spline coefficients for each joint: 00181 // (these are for the special case of zero start and end vel and acc) 00182 double coeff[num_joints_][6]; 00183 for (int i=0; i<num_joints_; i++) 00184 { 00185 double x0 = (*this)(start_index,i); 00186 double x1 = (*this)(end_index,i); 00187 coeff[i][0] = x0; 00188 coeff[i][1] = 0; 00189 coeff[i][2] = 0; 00190 coeff[i][3] = (-20*x0 + 20*x1) / (2*T[3]); 00191 coeff[i][4] = (30*x0 - 30*x1) / (2*T[4]); 00192 coeff[i][5] = (-12*x0 + 12*x1) / (2*T[5]); 00193 } 00194 00195 // now fill in the joint positions at each time step 00196 for (int i=start_index+1; i<end_index; i++) 00197 { 00198 double t[6]; // powers of the time index point 00199 t[0] = 1.0; 00200 t[1] = (i - start_index)*discretization_; 00201 for (int k=2; k<=5; k++) 00202 t[k] = t[k-1]*t[1]; 00203 00204 for (int j=0; j<num_joints_; j++) 00205 { 00206 (*this)(i,j) = 0.0; 00207 for (int k=0; k<=5; k++) 00208 { 00209 (*this)(i,j) += t[k]*coeff[j][k]; 00210 } 00211 } 00212 } 00213 } 00214 00215 } // namespace chomp