stomp_example.cpp
Go to the documentation of this file.
1 
27 #include <iostream>
28 #include <Eigen/Dense>
29 #include "stomp_core/stomp.h"
31 
32 using Trajectory = Eigen::MatrixXd;
35 static const std::size_t NUM_DIMENSIONS = 3;
36 static const std::size_t NUM_TIMESTEPS = 20;
37 static const double DELTA_T = 0.1;
38 static const std::vector<double> START_POS = {1.4, 1.4, 0.5};
39 static const std::vector<double> END_POS = {-1.25, 1.0, -0.26};
40 static const std::vector<double> BIAS_THRESHOLD = {0.050,0.050,0.050};
41 static const std::vector<double> STD_DEV = {1.0, 1.0, 1.0};
48 {
50  using namespace stomp_core;
51 
54  c.num_iterations = 40;
56  c.delta_t = DELTA_T;
57  c.control_cost_weight = 0.0;
58  c.initialization_method = TrajectoryInitializations::LINEAR_INTERPOLATION;
60  c.num_rollouts = 20;
61  c.max_rollouts = 20;
63 
64  return c;
65 }
66 
74 bool compareDiff(const Trajectory& optimized, const Trajectory& desired,
75  const std::vector<double>& thresholds)
76 {
77  auto num_dimensions = optimized.rows();
78  Trajectory diff = Trajectory::Zero(num_dimensions,optimized.cols());
79  for(auto d = 0u;d < num_dimensions ; d++)
80  {
81  diff.row(d) = optimized.row(d)- desired.row(d);
82  diff.row(d).cwiseAbs();
83  if((diff.row(d).array() > thresholds[d] ).any() )
84  {
85  return false;
86  }
87  }
88 
89  return true;
90 }
91 
99 void interpolate(const std::vector<double>& start, const std::vector<double>& end,
100  std::size_t num_timesteps, Trajectory& traj)
101 {
102  auto dimensions = start.size();
103  traj = Eigen::MatrixXd::Zero(dimensions,num_timesteps);
104  for(auto d = 0u; d < dimensions; d++)
105  {
106  double delta = (end[d] - start[d])/(num_timesteps - 1);
107  for(auto t = 0u; t < num_timesteps; t++)
108  {
109  traj(d,t) = start[d] + t*delta;
110  }
111  }
112 }
113 
114 int main(int argc,char** argv)
115 {
116  using namespace stomp_core_examples;
117  using namespace stomp_core;
118 
120  Trajectory trajectory_bias;
121  interpolate(START_POS,END_POS,NUM_TIMESTEPS,trajectory_bias);
122 
124  TaskPtr task(new SimpleOptimizationTask(trajectory_bias,BIAS_THRESHOLD,STD_DEV));
126 
128 
130  Stomp stomp(config,task);
132 
134 
135  Trajectory optimized;
136  if(stomp.solve(START_POS,END_POS,optimized))
137  {
138  std::cout<<"STOMP succeeded"<<std::endl;
139  }
140  else
141  {
142  std::cout<<"A valid solution was not found"<<std::endl;
143  return -1;
144  }
146 
148  if(compareDiff(optimized,trajectory_bias,BIAS_THRESHOLD))
149  {
150  std::cout<<"The solution is within the expected thresholds"<<std::endl;
151  }
152  else
153  {
154  std::cout<<"The solution exceeded the required thresholds"<<std::endl;
155  return -1;
156  }
157 
158  return 0;
159 
160 }
161 
162 
163 
164 
std::shared_ptr< Task > TaskPtr
Definition: task.h:37
d
int num_rollouts
Number of noisy trajectories.
Definition: utils.h:95
static const double DELTA_T
static const std::vector< double > START_POS
This contains the stomp core algorithm.
int num_iterations
Maximum number of iteration allowed.
Definition: utils.h:84
double control_cost_weight
Percentage of the trajectory accelerations cost to be applied in the total cost calculation > ...
Definition: utils.h:99
int num_dimensions
Parameter dimensionality.
Definition: utils.h:87
int main(int argc, char **argv)
The Stomp class.
Definition: stomp.h:38
A simple task for showing how to use STOMP.
static const std::vector< double > END_POS
static const std::vector< double > STD_DEV
The data structure used to store STOMP configuration parameters.
Definition: utils.h:81
bool solve(const std::vector< double > &first, const std::vector< double > &last, Eigen::MatrixXd &parameters_optimized)
Find the optimal solution provided a start and end goal.
Definition: stomp.cpp:192
static const std::size_t NUM_TIMESTEPS
int initialization_method
TrajectoryInitializations::TrajectoryInitialization.
Definition: utils.h:89
static const std::size_t NUM_DIMENSIONS
Eigen::MatrixXd Trajectory
int max_rollouts
The combined number of new and old rollouts during each iteration shouldn&#39;t exceed this value...
Definition: utils.h:96
static const std::vector< double > BIAS_THRESHOLD
void interpolate(const std::vector< double > &start, const std::vector< double > &end, std::size_t num_timesteps, Trajectory &traj)
Compute a linear interpolated trajectory given a start and end state.
bool compareDiff(const Trajectory &optimized, const Trajectory &desired, const std::vector< double > &thresholds)
Compares whether two trajectories are close to each other within a threshold.
double delta_t
Time change between consecutive points.
Definition: utils.h:88
stomp_core::StompConfiguration create3DOFConfiguration()
Creates a STOMP configuration object with default parameters.
int num_iterations_after_valid
Stomp will stop optimizing this many iterations after finding a valid solution.
Definition: utils.h:85
int num_timesteps
Number of timesteps.
Definition: utils.h:86


stomp_core
Author(s): Jorge Nicho
autogenerated on Fri May 8 2020 03:35:43