dmp.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002  *
00003  * Software License Agreement (BSD License)
00004  *
00005  *  Copyright (c) 2012, Scott Niekum
00006  *  All rights reserved.
00007  *
00008  *  Redistribution and use in source and binary forms, with or without
00009  *  modification, are permitted provided that the following conditions
00010  *  are met:
00011  *
00012  *   * Redistributions of source code must retain the above copyright
00013  *     notice, this list of conditions and the following disclaimer.
00014  *   * Redistributions in binary form must reproduce the above
00015  *     copyright notice, this list of conditions and the following
00016  *     disclaimer in the documentation and/or other materials provided
00017  *     with the distribution.
00018  *   * Neither the name of the Willow Garage nor the names of its
00019  *     contributors may be used to endorse or promote products derived
00020  *     from this software without specific prior written permission.
00021  *
00022  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00023  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00024  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00025  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00026  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00027  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00028  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00030  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00031  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00032  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00033  *  POSSIBILITY OF SUCH DAMAGE.
00034  *
00035  *********************************************************************/
00036 
00042 #include "dmp/dmp.h"
00043 using namespace std;
00044 
00045 namespace dmp{
00046 
00047 #define MAX_PLAN_LENGTH 1000
00048 
00049 double alpha = -log(0.01); //Ensures 99% phase convergence at t=tau
00050 
00057 double calcPhase(double curr_time, double tau)
00058 {
00059         return exp(-(alpha/tau)*curr_time);
00060 }
00061 
00062 
00071 void learnFromDemo(const DMPTraj &demo,
00072                                    const vector<double> &k_gains,
00073                                    const vector<double> &d_gains,
00074                                    const int &num_bases,
00075                                    vector<DMPData> &dmp_list)
00076 {
00077         //Determine traj length and dim
00078         int n_pts = demo.points.size();
00079         if(n_pts < 1){
00080                 ROS_ERROR("Empty trajectory passed to learn_dmp_from_demo service!");
00081                 return;
00082         }
00083         int dims = demo.points[0].positions.size();
00084         double tau = demo.times[n_pts-1];
00085 
00086         double *x_demo = new double[n_pts];
00087         double *v_demo = new double[n_pts];
00088         double *v_dot_demo = new double[n_pts];
00089         double *f_domain = new double[n_pts];
00090         double *f_targets = new double[n_pts];
00091         FunctionApprox *f_approx = new LinearApprox();
00092 
00093         //Compute the DMP weights for each DOF separately
00094         for(int d=0; d<dims; d++){
00095                 double curr_k = k_gains[d];
00096                 double curr_d = d_gains[d];
00097                 double x_0 = demo.points[0].positions[d];
00098                 double goal = demo.points[n_pts-1].positions[d];
00099                 x_demo[0] = demo.points[0].positions[d];
00100                 v_demo[0] = 0;
00101                 v_dot_demo[0] = 0;
00102 
00103                 //Calculate the demonstration v and v dot by assuming constant acceleration over a time period
00104                 for(int i=1; i<n_pts; i++){
00105                         x_demo[i] = demo.points[i].positions[d];
00106                         double dx = x_demo[i] - x_demo[i-1];
00107                         double dt = demo.times[i] - demo.times[i-1];
00108                         v_demo[i] = dx/dt;
00109                         v_dot_demo[i] = (v_demo[i] - v_demo[i-1]) / dt;
00110                 }
00111 
00112                 //Calculate the target pairs so we can solve for the weights
00113                 for(int i=0; i<n_pts; i++){
00114                         double phase = calcPhase(demo.times[i],tau);
00115                         f_domain[i] = demo.times[i]/tau;  //Scaled time is cleaner than phase for spacing reasons
00116                         f_targets[i] = ((tau*tau*v_dot_demo[i] + curr_d*tau*v_demo[i]) / curr_k) - (goal-x_demo[i]) + ((goal-x_0)*phase);
00117                         f_targets[i] /= phase; // Do this instead of having fxn approx scale its output based on phase
00118                 }
00119 
00120                 //Solve for weights
00121                 f_approx->leastSquaresWeights(f_domain, f_targets, n_pts);
00122 
00123                 //Create the DMP structures
00124                 DMPData *curr_dmp = new DMPData();
00125                 curr_dmp->weights = f_approx->getWeights();
00126                 curr_dmp->k_gain = curr_k;
00127                 curr_dmp->d_gain = curr_d;
00128                 for(int i=0; i<n_pts; i++){
00129                     curr_dmp->f_domain.push_back(f_domain[i]); 
00130                     curr_dmp->f_targets.push_back(f_targets[i]);
00131                 }
00132                 dmp_list.push_back(*curr_dmp);
00133         }
00134 
00135         delete[] x_demo;
00136         delete[] v_demo;
00137         delete[] v_dot_demo;
00138         delete[] f_domain;
00139         delete[] f_targets;
00140         delete f_approx;
00141 }
00142 
00143 
00144 
00160 void generatePlan(const vector<DMPData> &dmp_list,
00161                                   const vector<double> &x_0,
00162                                   const vector<double> &x_dot_0,
00163                                   const double &t_0,
00164                                   const vector<double> &goal,
00165                                   const vector<double> &goal_thresh,
00166                                   const double &seg_length,
00167                                   const double &tau,
00168                                   const double &total_dt,
00169                                   const int &integrate_iter,
00170                                   DMPTraj &plan,
00171                                   uint8_t &at_goal)
00172 {
00173         plan.points.clear();
00174         plan.times.clear();
00175         at_goal = false;
00176 
00177         int dims = dmp_list.size();
00178         int n_pts = 0;
00179         double dt = total_dt / integrate_iter;
00180 
00181         vector<double> *x_vecs, *x_dot_vecs;
00182         vector<double> t_vec;
00183         x_vecs = new vector<double>[dims];
00184         x_dot_vecs = new vector<double>[dims];
00185         FunctionApprox **f = new FunctionApprox*[dims];
00186 
00187         for(int i=0; i<dims; i++)
00188                 f[i] = new LinearApprox(dmp_list[i].f_domain, dmp_list[i].f_targets);
00189         
00190         double t = 0;
00191         double f_eval;
00192 
00193         //Plan for at least tau seconds.  After that, plan until goal_thresh is satisfied.
00194         //Cut off if plan exceeds MAX_PLAN_LENGTH seconds, in case of overshoot / oscillation
00195         //Only plan for seg_length seconds if specified
00196         bool seg_end = false;
00197         while(((t+t_0) < tau || (!at_goal && t<MAX_PLAN_LENGTH)) && !seg_end){
00198                 //Check if we've planned to the segment end yet
00199                 if(seg_length > 0){
00200                         if (t > seg_length) seg_end = true;
00201                 }
00202 
00203                 //Plan in each dimension
00204                 for(int i=0; i<dims; i++){
00205             double x,v;
00206             if(n_pts==0){
00207                 x = x_0[i];
00208                 v = x_dot_0[i];
00209             }
00210             else{                       
00211                 x = x_vecs[i][n_pts-1];
00212                             v = x_dot_vecs[i][n_pts-1] * tau;
00213             }
00214 
00215                         //Numerically integrate to get new x and v
00216                         for(int iter=0; iter<integrate_iter; iter++)
00217                         {
00218                                 //Compute the phase and the log of the phase to assist with some numerical issues
00219                                 //Then, evaluate the function approximator at the log of the phase
00220                                 double s = calcPhase((t+t_0) + (dt*iter), tau);
00221                                 double log_s = (t+t_0)/tau;
00222                                 if(log_s >= 1.0){
00223                                         f_eval = 0;
00224                                 }
00225                                 else{
00226                                         f_eval = f[i]->evalAt(log_s) * s;
00227                                 }
00228                                 
00229                                 //Update v dot and x dot based on DMP differential equations
00230                                 double v_dot = (dmp_list[i].k_gain*((goal[i]-x) - (goal[i]-x_0[i])*s + f_eval) - dmp_list[i].d_gain*v) / tau;
00231                                 double x_dot = v/tau;
00232 
00233                                 //Update state variables
00234                                 v += v_dot * dt;
00235                                 x += x_dot * dt;
00236                         }
00237 
00238                         //Add current state to the plan
00239                         x_vecs[i].push_back(x);
00240                         x_dot_vecs[i].push_back(v/tau);
00241                 }
00242                 t += total_dt;
00243                 t_vec.push_back(t);
00244                 n_pts++;
00245 
00246                 //If plan is at least minimum length, check to see if we are close enough to goal
00247                 if((t+t_0) >= tau){
00248                         at_goal = true;
00249                         for(int i=0; i<dims; i++){
00250                                 if(goal_thresh[i] > 0){
00251                                         if(fabs(x_vecs[i][n_pts-1] - goal[i]) > goal_thresh[i])
00252                                                 at_goal = false;
00253                                 }
00254                         }
00255                 }
00256         }
00257 
00258         //Create a plan from the generated trajectories
00259         plan.points.resize(n_pts);
00260         for(int j=0; j<n_pts; j++){
00261                 plan.points[j].positions.resize(dims);
00262                 plan.points[j].velocities.resize(dims);
00263         }
00264         for(int i=0; i<dims; i++){
00265                 for(int j=0; j<n_pts; j++){
00266                         plan.points[j].positions[i] = x_vecs[i][j];
00267                         plan.points[j].velocities[i] = x_dot_vecs[i][j];
00268                 }
00269         }
00270         plan.times = t_vec;
00271 
00272         //Clean up
00273         for(int i=0; i<dims; i++){
00274                 delete f[i];
00275         }
00276         delete[] f;
00277         delete[] x_vecs;
00278         delete[] x_dot_vecs;
00279 }
00280 
00281 }
00282 


dmp
Author(s): Scott Niekum
autogenerated on Sun Oct 5 2014 23:29:12