Public Member Functions
stomp_core::Task Class Reference

Defines the STOMP improvement policy. More...

#include <task.h>

Inheritance diagram for stomp_core::Task:
Inheritance graph
[legend]

List of all members.

Public Member Functions

virtual bool computeCosts (const Eigen::MatrixXd &parameters, std::size_t start_timestep, std::size_t num_timesteps, int iteration_number, Eigen::VectorXd &costs, bool &validity)=0
 computes the state costs as a function of the optimized parameters for each time step.
virtual 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)=0
 computes the state costs as a function of the noisy parameters for each time step.
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.
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.
virtual bool filterParameterUpdates (std::size_t start_timestep, std::size_t num_timesteps, int iteration_number, const Eigen::MatrixXd &parameters, Eigen::MatrixXd &updates)
 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.
virtual 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)=0
 Generates a noisy trajectory from the parameters.
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.

Detailed Description

Defines the STOMP improvement policy.

Definition at line 41 of file task.h.


Member Function Documentation

virtual bool stomp_core::Task::computeCosts ( const Eigen::MatrixXd &  parameters,
std::size_t  start_timestep,
std::size_t  num_timesteps,
int  iteration_number,
Eigen::VectorXd &  costs,
bool &  validity 
) [pure virtual]

computes the state costs as a function of the optimized parameters for each time step.

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

Implemented in stomp_core_examples::SimpleOptimizationTask.

virtual bool stomp_core::Task::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 
) [pure virtual]

computes the state costs as a function of the noisy parameters for each time step.

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 whose cost is being evaluated.
costsvector A vector containing the state costs per timestep.
validityWhether or not the trajectory is valid
Returns:
True if cost were properly computed, otherwise false

Implemented in stomp_core_examples::SimpleOptimizationTask.

virtual void stomp_core::Task::done ( bool  success,
int  total_iterations,
double  final_cost,
const Eigen::MatrixXd &  parameters 
) [inline, virtual]

Called by Stomp at the end of the optimization process.

Parameters:
successWhether the optimization succeeded
total_iterationsNumber of iterations used
final_costThe cost value after optimizing.
parametersThe parameters generated at the end of the optimization [num_dimensions x num_timesteps]

Definition at line 166 of file task.h.

virtual bool stomp_core::Task::filterNoisyParameters ( std::size_t  start_timestep,
std::size_t  num_timesteps,
int  iteration_number,
int  rollout_number,
Eigen::MatrixXd &  parameters,
bool &  filtered 
) [inline, virtual]

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.

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 rollout index for this noisy parameter set
parametersThe noisy parameters *
filteredFalse if no filtering was done
Returns:
False if no filtering was done, otherwise true

Definition at line 115 of file task.h.

virtual bool stomp_core::Task::filterParameterUpdates ( std::size_t  start_timestep,
std::size_t  num_timesteps,
int  iteration_number,
const Eigen::MatrixXd &  parameters,
Eigen::MatrixXd &  updates 
) [inline, virtual]

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 in stomp_core_examples::SimpleOptimizationTask, and DummyTask.

Definition at line 137 of file task.h.

virtual bool stomp_core::Task::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 
) [pure virtual]

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

Implemented in stomp_core_examples::SimpleOptimizationTask, and DummyTask.

virtual void stomp_core::Task::postIteration ( std::size_t  start_timestep,
std::size_t  num_timesteps,
int  iteration_number,
double  cost,
const Eigen::MatrixXd &  parameters 
) [inline, virtual]

Called by STOMP at the end of each iteration.

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
costThe cost value for the current parameters.
parametersThe value of the parameters at the end of the current iteration [num_dimensions x num_timesteps].

Definition at line 154 of file task.h.


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


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