28 #include <Eigen/Dense> 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};
41 static const std::vector<double>
STD_DEV = {1.0, 1.0, 1.0};
75 const std::vector<double>& thresholds)
77 auto num_dimensions = optimized.rows();
78 Trajectory diff = Trajectory::Zero(num_dimensions,optimized.cols());
79 for(
auto d = 0u;
d < num_dimensions ;
d++)
81 diff.row(
d) = optimized.row(
d)- desired.row(
d);
82 diff.row(
d).cwiseAbs();
83 if((diff.row(
d).array() > thresholds[
d] ).any() )
99 void interpolate(
const std::vector<double>& start,
const std::vector<double>& end,
102 auto dimensions = start.size();
103 traj = Eigen::MatrixXd::Zero(dimensions,num_timesteps);
104 for(
auto d = 0u;
d < dimensions;
d++)
106 double delta = (end[
d] - start[
d])/(num_timesteps - 1);
107 for(
auto t = 0u; t < num_timesteps; t++)
109 traj(
d,t) = start[
d] + t*delta;
130 Stomp stomp(config,task);
138 std::cout<<
"STOMP succeeded"<<std::endl;
142 std::cout<<
"A valid solution was not found"<<std::endl;
150 std::cout<<
"The solution is within the expected thresholds"<<std::endl;
154 std::cout<<
"The solution exceeded the required thresholds"<<std::endl;
std::shared_ptr< Task > TaskPtr
int num_rollouts
Number of noisy trajectories.
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.
double control_cost_weight
Percentage of the trajectory accelerations cost to be applied in the total cost calculation > ...
int num_dimensions
Parameter dimensionality.
int main(int argc, char **argv)
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.
bool solve(const std::vector< double > &first, const std::vector< double > &last, Eigen::MatrixXd ¶meters_optimized)
Find the optimal solution provided a start and end goal.
static const std::size_t NUM_TIMESTEPS
int initialization_method
TrajectoryInitializations::TrajectoryInitialization.
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't exceed this value...
[SimpleOptimizationTask Inherit]
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.
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.
int num_timesteps
Number of timesteps.