Public Member Functions | Protected Member Functions | Protected Attributes
DummyTask Class Reference

A dummy task for testing STOMP. More...

Inheritance diagram for DummyTask:
Inheritance graph
[legend]

List of all members.

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
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
 DummyTask (const Trajectory &parameters_bias, const std::vector< double > &bias_thresholds, const std::vector< double > &std_dev)
 A dummy task for testing Stomp.
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.
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.

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.

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::filterParameterUpdates ( std::size_t  start_timestep,
std::size_t  num_timesteps,
int  iteration_number,
const Eigen::MatrixXd &  parameters,
Eigen::MatrixXd &  updates 
) [inline, override, 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 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 
) [inline, protected]

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 Sat Jun 8 2019 19:23:57