stomp_example.cpp
Go to the documentation of this file.
00001 
00027 #include <iostream>
00028 #include <Eigen/Dense>
00029 #include "stomp_core/stomp.h"
00030 #include "simple_optimization_task.h"
00031 
00032 using Trajectory = Eigen::MatrixXd;                              
00035 static const std::size_t NUM_DIMENSIONS = 3;                            
00036 static const std::size_t NUM_TIMESTEPS = 20;                            
00037 static const double DELTA_T = 0.1;                                      
00038 static const std::vector<double> START_POS = {1.4, 1.4, 0.5};           
00039 static const std::vector<double> END_POS = {-1.25, 1.0, -0.26};         
00040 static const std::vector<double> BIAS_THRESHOLD = {0.050,0.050,0.050};  
00041 static const std::vector<double> STD_DEV = {1.0, 1.0, 1.0};             
00047 stomp_core::StompConfiguration create3DOFConfiguration()
00048 {
00050   using namespace stomp_core;
00051 
00052   StompConfiguration c;
00053   c.num_timesteps = NUM_TIMESTEPS;
00054   c.num_iterations = 40;
00055   c.num_dimensions = NUM_DIMENSIONS;
00056   c.delta_t = DELTA_T;
00057   c.control_cost_weight = 0.0;
00058   c.initialization_method = TrajectoryInitializations::LINEAR_INTERPOLATION;
00059   c.num_iterations_after_valid = 0;
00060   c.num_rollouts = 20;
00061   c.max_rollouts = 20;
00063 
00064   return c;
00065 }
00066 
00074 bool compareDiff(const Trajectory& optimized, const Trajectory& desired,
00075                  const std::vector<double>& thresholds)
00076 {
00077   auto num_dimensions = optimized.rows();
00078   Trajectory diff = Trajectory::Zero(num_dimensions,optimized.cols());
00079   for(auto d = 0u;d < num_dimensions ; d++)
00080   {
00081     diff.row(d) = optimized.row(d)- desired.row(d);
00082     diff.row(d).cwiseAbs();
00083     if((diff.row(d).array() > thresholds[d] ).any() )
00084     {
00085       return false;
00086     }
00087   }
00088 
00089   return true;
00090 }
00091 
00099 void interpolate(const std::vector<double>& start, const std::vector<double>& end,
00100                  std::size_t num_timesteps, Trajectory& traj)
00101 {
00102   auto dimensions = start.size();
00103   traj = Eigen::MatrixXd::Zero(dimensions,num_timesteps);
00104   for(auto d = 0u; d < dimensions; d++)
00105   {
00106     double delta = (end[d] - start[d])/(num_timesteps - 1);
00107     for(auto t = 0u; t < num_timesteps; t++)
00108     {
00109       traj(d,t) = start[d] + t*delta;
00110     }
00111   }
00112 }
00113 
00114 int main(int argc,char** argv)
00115 {
00116   using namespace stomp_core_examples;
00117   using namespace stomp_core;
00118 
00120   Trajectory trajectory_bias;
00121   interpolate(START_POS,END_POS,NUM_TIMESTEPS,trajectory_bias);
00122 
00124   TaskPtr task(new SimpleOptimizationTask(trajectory_bias,BIAS_THRESHOLD,STD_DEV));
00126 
00128 
00129   StompConfiguration config = create3DOFConfiguration();
00130   Stomp stomp(config,task);
00132 
00134 
00135   Trajectory optimized;
00136   if(stomp.solve(START_POS,END_POS,optimized))
00137   {
00138     std::cout<<"STOMP succeeded"<<std::endl;
00139   }
00140   else
00141   {
00142     std::cout<<"A valid solution was not found"<<std::endl;
00143     return -1;
00144   }
00146 
00148   if(compareDiff(optimized,trajectory_bias,BIAS_THRESHOLD))
00149   {
00150     std::cout<<"The solution is within the expected thresholds"<<std::endl;
00151   }
00152   else
00153   {
00154     std::cout<<"The solution exceeded the required thresholds"<<std::endl;
00155     return -1;
00156   }
00157 
00158   return 0;
00159 
00160 }
00161 
00162 
00163 
00164 


stomp_core
Author(s): Jorge Nicho
autogenerated on Sat Jun 8 2019 19:23:57