Public Member Functions | Protected Member Functions | Protected Attributes
stomp_core::Stomp Class Reference

The Stomp class. More...

#include <stomp.h>

List of all members.

Public Member Functions

bool cancel ()
 Cancel optimization in progress. (Thread-Safe) This method is thead-safe.
bool clear ()
 Resets all internal variables.
void setConfig (const StompConfiguration &config)
 Sets the configuration and resets all internal variables.
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.
bool solve (const Eigen::VectorXd &first, const Eigen::VectorXd &last, Eigen::MatrixXd &parameters_optimized)
 Find the optimal solution provided a start and end goal.
bool solve (const Eigen::MatrixXd &initial_parameters, Eigen::MatrixXd &parameters_optimized)
 Find the optimal solution provided an intial guess.
 Stomp (const StompConfiguration &config, TaskPtr task)
 Stomp Constructor.

Protected Member Functions

bool computeInitialTrajectory (const std::vector< double > &first, const std::vector< double > &last)
 Computes an inital guess at a solution given a start and end state.
bool computeNoisyRolloutsCosts ()
 Computes the total cost for each of the noisy rollouts.
bool computeOptimizedCost ()
 Computes the optimized trajectory cost [Control Cost + State Cost] If the current cost is not less than the previous cost the parameters are reset to the previous iteration's parameters.
bool computeProbabilities ()
 Computes the probability from the state cost at every timestep for each noisy rollout.
bool computeRolloutsControlCosts ()
 Compute the control cost for each noisy rollout. This is the sum of the acceleration squared, then each noisy rollouts control cost is divided by the maximum control cost found amoung the noisy rollouts.
bool computeRolloutsStateCosts ()
 Computes the cost at every timestep for each noisy rollout.
bool filterNoisyRollouts ()
 Applies the optimization task's filter methods to the noisy trajectories.
bool generateNoisyRollouts ()
 Generate a set of noisy rollouts.
bool resetVariables ()
 Reset all internal variables.
bool runSingleIteration ()
 Run a single iteration of the stomp algorithm.
bool updateParameters ()
 Computes update from probabilities using convex combination.

Protected Attributes

StompConfiguration config_
 Configuration parameters.
Eigen::MatrixXd control_cost_matrix_R_
 A matrix [timesteps][timesteps], Referred to as 'R = A x A_transpose' in the literature.
Eigen::MatrixXd control_cost_matrix_R_padded_
 The control cost matrix including padding.
unsigned int current_iteration_
 Current iteration for the optimization.
double current_lowest_cost_
 Hold the lowest cost of the optimized parameters.
Eigen::MatrixXd finite_diff_matrix_A_padded_
 The finite difference matrix including padding.
Eigen::MatrixXd inv_control_cost_matrix_R_
 A matrix [timesteps][timesteps], R^-1 ' matrix.
std::vector< Rolloutnoisy_rollouts_
 Holds the noisy rollouts.
int num_active_rollouts_
 Number of active rollouts.
int num_timesteps_padded_
 The number of timesteps to pad the optimization with: timesteps + 2*(FINITE_DIFF_RULE_LENGTH - 1)
Eigen::MatrixXd parameters_control_costs_
 A matrix [dimensions][timesteps] of the parameters control costs.
Eigen::MatrixXd parameters_optimized_
 A matrix [dimensions][timesteps] of the optimized parameters.
Eigen::VectorXd parameters_state_costs_
 A vector [timesteps] of the parameters state costs.
double parameters_total_cost_
 Total cost of the optimized parameters.
Eigen::MatrixXd parameters_updates_
 A matrix [dimensions][timesteps] of the parameter updates.
bool parameters_valid_
 whether or not the optimized parameters are valid
std::atomic< bool > proceed_
 Used to determine if the optimization has been cancelled.
std::vector< Rolloutreused_rollouts_
 Used for reordering arrays based on cost.
int start_index_padded_
 The index corresponding to the start of the non-paded section in the padded arrays.
TaskPtr task_
 The task to be optimized.

Detailed Description

The Stomp class.

Definition at line 38 of file stomp.h.


Constructor & Destructor Documentation

stomp_core::Stomp::Stomp ( const StompConfiguration config,
TaskPtr  task 
)

Stomp Constructor.

Parameters:
configStomp configuration parameters
taskThe item to be optimized.

Definition at line 172 of file stomp.cpp.


Member Function Documentation

Cancel optimization in progress. (Thread-Safe) This method is thead-safe.

Returns:
True if sucessful, otherwise false.

Definition at line 415 of file stomp.cpp.

Resets all internal variables.

Returns:
True if sucessful, otherwise false.

Definition at line 181 of file stomp.cpp.

bool stomp_core::Stomp::computeInitialTrajectory ( const std::vector< double > &  first,
const std::vector< double > &  last 
) [protected]

Computes an inital guess at a solution given a start and end state.

Parameters:
firstStart state for the task
lastFinal state for the task
Returns:
True if sucessful, otherwise false.

Definition at line 392 of file stomp.cpp.

Computes the total cost for each of the noisy rollouts.

Returns:
True if sucessful, otherwise false.

Definition at line 553 of file stomp.cpp.

Computes the optimized trajectory cost [Control Cost + State Cost] If the current cost is not less than the previous cost the parameters are reset to the previous iteration's parameters.

Returns:

Definition at line 760 of file stomp.cpp.

Computes the probability from the state cost at every timestep for each noisy rollout.

Returns:
True if sucessful, otherwise false.

Definition at line 643 of file stomp.cpp.

Compute the control cost for each noisy rollout. This is the sum of the acceleration squared, then each noisy rollouts control cost is divided by the maximum control cost found amoung the noisy rollouts.

Returns:
True if sucessful, otherwise false.

Definition at line 618 of file stomp.cpp.

Computes the cost at every timestep for each noisy rollout.

Returns:
True if sucessful, otherwise false.

Definition at line 591 of file stomp.cpp.

Applies the optimization task's filter methods to the noisy trajectories.

Returns:
True if sucessful, otherwise false.

Definition at line 532 of file stomp.cpp.

Generate a set of noisy rollouts.

Returns:
True if sucessful, otherwise false.

Definition at line 442 of file stomp.cpp.

bool stomp_core::Stomp::resetVariables ( ) [protected]

Reset all internal variables.

Returns:
True if sucessful, otherwise false.

Definition at line 298 of file stomp.cpp.

Run a single iteration of the stomp algorithm.

Returns:
True if it was able to succesfully perform a single iteration. False is returned when an error is encounter at one of the many optimization steps.

Definition at line 422 of file stomp.cpp.

Sets the configuration and resets all internal variables.

Parameters:
configStomp Configuration struct

Definition at line 186 of file stomp.cpp.

bool stomp_core::Stomp::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.

Parameters:
firstStart state for the task
lastFinal state for the task
parameters_optimizedOptimized solution [parameters][timesteps]
Returns:
True if solution was found, otherwise false.

Definition at line 192 of file stomp.cpp.

bool stomp_core::Stomp::solve ( const Eigen::VectorXd &  first,
const Eigen::VectorXd &  last,
Eigen::MatrixXd &  parameters_optimized 
)

Find the optimal solution provided a start and end goal.

Parameters:
firstStart state for the task
lastFinal state for the task
parameters_optimizedOptimized solution [Parameters][timesteps]
Returns:
True if solution was found, otherwise false.

Definition at line 204 of file stomp.cpp.

bool stomp_core::Stomp::solve ( const Eigen::MatrixXd &  initial_parameters,
Eigen::MatrixXd &  parameters_optimized 
)

Find the optimal solution provided an intial guess.

Parameters:
initial_parametersA matrix [Parameters][timesteps]
parameters_optimizedThe optimized solution [Parameters][timesteps]
Returns:
True if solution was found, otherwise false.

Definition at line 217 of file stomp.cpp.

Computes update from probabilities using convex combination.

Returns:
True if sucessful, otherwise false.

Definition at line 732 of file stomp.cpp.


The documentation for this class was generated from the following files:


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