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 ¶meters_optimized) |
| Find the optimal solution provided a start and end goal.
|
bool | solve (const Eigen::VectorXd &first, const Eigen::VectorXd &last, Eigen::MatrixXd ¶meters_optimized) |
| Find the optimal solution provided a start and end goal.
|
bool | solve (const Eigen::MatrixXd &initial_parameters, Eigen::MatrixXd ¶meters_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< Rollout > | noisy_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< Rollout > | reused_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.
|
The Stomp class.
Definition at line 38 of file stomp.h.