Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
DummyTask Class Reference

A dummy task for testing STOMP. More...

Inheritance diagram for DummyTask:
Inheritance graph
[legend]

Public Member Functions

bool computeCosts (const Trajectory &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 optimized parameters for each time step. More...
 
bool computeNoisyCosts (const Trajectory &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 noisy parameters for each time step. More...
 
 DummyTask (const Trajectory &parameters_bias, const std::vector< double > &bias_thresholds, const std::vector< double > &std_dev)
 A dummy task for testing Stomp. 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
 See base clase for documentation.
 
- 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_
 
Trajectory parameters_bias_
 
Eigen::MatrixXd smoothing_M_
 
std::vector< double > std_dev_
 

Detailed Description

A dummy task for testing STOMP.

Definition at line 46 of file stomp_3dof.cpp.

Constructor & Destructor Documentation

DummyTask::DummyTask ( const Trajectory parameters_bias,
const std::vector< double > &  bias_thresholds,
const std::vector< double > &  std_dev 
)
inline

A dummy task for testing Stomp.

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

Definition at line 55 of file stomp_3dof.cpp.

Member Function Documentation

bool DummyTask::computeCosts ( const Trajectory 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 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

Implements stomp_core::Task.

Definition at line 95 of file stomp_3dof.cpp.

bool DummyTask::computeNoisyCosts ( const Trajectory 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 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

Implements stomp_core::Task.

Definition at line 105 of file stomp_3dof.cpp.

bool DummyTask::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 139 of file stomp_3dof.cpp.

bool DummyTask::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 159 of file stomp_3dof.cpp.

Member Data Documentation

std::vector<double> DummyTask::bias_thresholds_
protected

Threshold to determine whether two trajectories are equal

Definition at line 176 of file stomp_3dof.cpp.

Trajectory DummyTask::parameters_bias_
protected

Parameter bias used for computing cost for the test

Definition at line 175 of file stomp_3dof.cpp.

Eigen::MatrixXd DummyTask::smoothing_M_
protected

Matrix used for smoothing the trajectory

Definition at line 178 of file stomp_3dof.cpp.

std::vector<double> DummyTask::std_dev_
protected

Standard deviation used for generating noisy parameters

Definition at line 177 of file stomp_3dof.cpp.


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