A dummy task for testing STOMP. More...

Public Member Functions | |
| bool | computeCosts (const Trajectory ¶meters, std::size_t start_timestep, std::size_t num_timesteps, int iteration_number, Eigen::VectorXd &costs, bool &validity) override |
| bool | computeNoisyCosts (const Trajectory ¶meters, 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 ¶meters_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 ¶meters, 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 ¶meters, std::size_t start_timestep, std::size_t num_timesteps, int iteration_number, int rollout_number, Eigen::MatrixXd ¶meters_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_ |
A dummy task for testing STOMP.
Definition at line 46 of file stomp_3dof.cpp.
| 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_bias | default parameter bias used for computing cost for the test |
| bias_thresholds | threshold to determine whether two trajectories are equal |
| std_dev | standard deviation used for generating noisy parameters |
Definition at line 55 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 | ||
| ) | [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.
| start_timestep | The start index into the 'parameters' array, usually 0. |
| num_timesteps | The number of elements to use from 'parameters' starting from 'start_timestep' |
| iteration_number | The current iteration count in the optimization loop |
| parameters | The optimized parameters |
| updates | The updates to the parameters |
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.
| start_timestep | starting timestep |
| num_timesteps | number of timesteps |
| iteration_number | number of interations allowed |
| updates | returned smooth update |
Definition at line 159 of file stomp_3dof.cpp.
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.