Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
stomp_core_examples::SimpleOptimizationTask Class Reference

[SimpleOptimizationTask Inherit] More...

#include <simple_optimization_task.h>

Inheritance diagram for stomp_core_examples::SimpleOptimizationTask:
Inheritance graph
[legend]

Public Member Functions

bool computeCosts (const Eigen::MatrixXd &parameters, std::size_t start_timestep, std::size_t num_timesteps, int iteration_number, Eigen::VectorXd &costs, bool &validity) override
 computes the state costs as a function of the distance from the bias parameters More...
 
bool computeNoisyCosts (const Eigen::MatrixXd &parameters, std::size_t start_timestep, std::size_t num_timesteps, int iteration_number, int rollout_number, Eigen::VectorXd &costs, bool &validity) override
 computes the state costs as a function of the distance from the bias parameters More...
 
bool filterParameterUpdates (std::size_t start_timestep, std::size_t num_timesteps, int iteration_number, const Eigen::MatrixXd &parameters, Eigen::MatrixXd &updates) override
 Filters the given parameters which is applied after the update. It could be used for clipping of joint limits or projecting into the null space of the Jacobian. More...
 
bool generateNoisyParameters (const Eigen::MatrixXd &parameters, std::size_t start_timestep, std::size_t num_timesteps, int iteration_number, int rollout_number, Eigen::MatrixXd &parameters_noise, Eigen::MatrixXd &noise) override
 [SimpleOptimizationTask Inherit] More...
 
 SimpleOptimizationTask (const Eigen::MatrixXd &parameters_bias, const std::vector< double > &bias_thresholds, const std::vector< double > &std_dev)
 A simple task for demonstrating how to use Stomp. More...
 
- Public Member Functions inherited from stomp_core::Task
virtual void done (bool success, int total_iterations, double final_cost, const Eigen::MatrixXd &parameters)
 Called by Stomp at the end of the optimization process. More...
 
virtual bool filterNoisyParameters (std::size_t start_timestep, std::size_t num_timesteps, int iteration_number, int rollout_number, Eigen::MatrixXd &parameters, bool &filtered)
 Filters the given noisy parameters which is applied after noisy trajectory generation. It could be used for clipping of joint limits or projecting into the null space of the Jacobian. More...
 
virtual void postIteration (std::size_t start_timestep, std::size_t num_timesteps, int iteration_number, double cost, const Eigen::MatrixXd &parameters)
 Called by STOMP at the end of each iteration. More...
 

Protected Member Functions

bool smoothParameterUpdates (std::size_t start_timestep, std::size_t num_timesteps, int iteration_number, Eigen::MatrixXd &updates)
 Perform a smooth update given a noisy update. More...
 

Protected Attributes

std::vector< double > bias_thresholds_
 
Eigen::MatrixXd parameters_bias_
 
Eigen::MatrixXd smoothing_M_
 
std::vector< double > std_dev_
 

Detailed Description

[SimpleOptimizationTask Inherit]

A dummy task for testing STOMP

Definition at line 37 of file simple_optimization_task.h.

Constructor & Destructor Documentation

stomp_core_examples::SimpleOptimizationTask::SimpleOptimizationTask ( const Eigen::MatrixXd &  parameters_bias,
const std::vector< double > &  bias_thresholds,
const std::vector< double > &  std_dev 
)
inline

A simple task for demonstrating how to use Stomp.

Parameters
parameters_biasdefault parameter bias used for computing cost.
bias_thresholdsthreshold to determine whether two trajectories are equal
std_devstandard deviation used for generating noisy parameters

Definition at line 46 of file simple_optimization_task.h.

Member Function Documentation

bool stomp_core_examples::SimpleOptimizationTask::computeCosts ( const Eigen::MatrixXd &  parameters,
std::size_t  start_timestep,
std::size_t  num_timesteps,
int  iteration_number,
Eigen::VectorXd &  costs,
bool &  validity 
)
inlineoverridevirtual

computes the state costs as a function of the distance from the bias parameters

Parameters
parametersA matrix [num_dimensions][num_parameters] of the policy parameters to execute
start_timestepThe start index into the 'parameters' array, usually 0.
num_timestepsThe number of elements to use from 'parameters' starting from 'start_timestep'
iteration_numberThe current iteration count in the optimization loop
costsA vector containing the state costs per timestep.
validityWhether or not the trajectory is valid
Returns
True if cost were properly computed, otherwise false

Implements stomp_core::Task.

Definition at line 107 of file simple_optimization_task.h.

bool stomp_core_examples::SimpleOptimizationTask::computeNoisyCosts ( const Eigen::MatrixXd &  parameters,
std::size_t  start_timestep,
std::size_t  num_timesteps,
int  iteration_number,
int  rollout_number,
Eigen::VectorXd &  costs,
bool &  validity 
)
inlineoverridevirtual

computes the state costs as a function of the distance from the bias parameters

Parameters
parametersA matrix [num_dimensions][num_parameters] of the policy parameters to execute
start_timestepThe start index into the 'parameters' array, usually 0.
num_timestepsThe number of elements to use from 'parameters' starting from 'start_timestep'
iteration_numberThe current iteration count in the optimization loop
rollout_numberThe index of the noisy trajectory.
costsA vector containing the state costs per timestep.
validityWhether or not the trajectory is valid
Returns
True if cost were properly computed, otherwise false

Implements stomp_core::Task.

Definition at line 128 of file simple_optimization_task.h.

bool stomp_core_examples::SimpleOptimizationTask::filterParameterUpdates ( std::size_t  start_timestep,
std::size_t  num_timesteps,
int  iteration_number,
const Eigen::MatrixXd &  parameters,
Eigen::MatrixXd &  updates 
)
inlineoverridevirtual

Filters the given parameters which is applied after the update. It could be used for clipping of joint limits or projecting into the null space of the Jacobian.

Parameters
start_timestepThe start index into the 'parameters' array, usually 0.
num_timestepsThe number of elements to use from 'parameters' starting from 'start_timestep'
iteration_numberThe current iteration count in the optimization loop
parametersThe optimized parameters
updatesThe updates to the parameters
Returns
True if successful, otherwise false

Reimplemented from stomp_core::Task.

Definition at line 172 of file simple_optimization_task.h.

bool stomp_core_examples::SimpleOptimizationTask::generateNoisyParameters ( const Eigen::MatrixXd &  parameters,
std::size_t  start_timestep,
std::size_t  num_timesteps,
int  iteration_number,
int  rollout_number,
Eigen::MatrixXd &  parameters_noise,
Eigen::MatrixXd &  noise 
)
inlineoverridevirtual

[SimpleOptimizationTask Inherit]

Generates a noisy trajectory from the parameters.

Parameters
parametersA matrix [num_dimensions][num_parameters] of the current optimized parameters
start_timestepThe start index into the 'parameters' array, usually 0.
num_timestepsThe number of elements to use from 'parameters' starting from 'start_timestep'
iteration_numberThe current iteration count in the optimization loop
rollout_numberThe index of the noisy trajectory.
parameters_noiseThe parameters + noise
noiseThe noise applied to the parameters
Returns
True if cost were properly computed, otherwise false

Implements stomp_core::Task.

Definition at line 73 of file simple_optimization_task.h.

bool stomp_core_examples::SimpleOptimizationTask::smoothParameterUpdates ( std::size_t  start_timestep,
std::size_t  num_timesteps,
int  iteration_number,
Eigen::MatrixXd &  updates 
)
inlineprotected

Perform a smooth update given a noisy update.

Parameters
start_timestepstarting timestep
num_timestepsnumber of timesteps
iteration_numbernumber of interations allowed
updatesreturned smooth update
Returns
True if successful, otherwise false

Definition at line 192 of file simple_optimization_task.h.

Member Data Documentation

std::vector<double> stomp_core_examples::SimpleOptimizationTask::bias_thresholds_
protected

Threshold to determine whether two trajectories are equal

Definition at line 209 of file simple_optimization_task.h.

Eigen::MatrixXd stomp_core_examples::SimpleOptimizationTask::parameters_bias_
protected

Parameter bias used for computing cost for the test

Definition at line 208 of file simple_optimization_task.h.

Eigen::MatrixXd stomp_core_examples::SimpleOptimizationTask::smoothing_M_
protected

Matrix used for smoothing the trajectory

Definition at line 211 of file simple_optimization_task.h.

std::vector<double> stomp_core_examples::SimpleOptimizationTask::std_dev_
protected

Standard deviation used for generating noisy parameters

Definition at line 210 of file simple_optimization_task.h.


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


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