task.h
Go to the documentation of this file.
1 
26 #ifndef STOMP_TASK_H_
27 #define STOMP_TASK_H_
28 
29 #include <XmlRpcValue.h>
30 #include <boost/shared_ptr.hpp>
31 #include <Eigen/Core>
32 #include "stomp_core/utils.h"
33 
34 namespace stomp_core
35 {
36 
37 class Task;
38 typedef std::shared_ptr<Task> TaskPtr;
41 class Task
42 {
43 
44 public:
45 
46  Task(){}
47 
59  virtual bool generateNoisyParameters(const Eigen::MatrixXd& parameters,
60  std::size_t start_timestep,
61  std::size_t num_timesteps,
62  int iteration_number,
63  int rollout_number,
64  Eigen::MatrixXd& parameters_noise,
65  Eigen::MatrixXd& noise) = 0;
66 
78  virtual bool computeNoisyCosts(const Eigen::MatrixXd& parameters,
79  std::size_t start_timestep,
80  std::size_t num_timesteps,
81  int iteration_number,
82  int rollout_number,
83  Eigen::VectorXd& costs,
84  bool& validity) = 0 ;
85 
96  virtual bool computeCosts(const Eigen::MatrixXd& parameters,
97  std::size_t start_timestep,
98  std::size_t num_timesteps,
99  int iteration_number,
100  Eigen::VectorXd& costs,
101  bool& validity) = 0 ;
102 
115  virtual bool filterNoisyParameters(std::size_t start_timestep,
116  std::size_t num_timesteps,
117  int iteration_number,
118  int rollout_number,
119  Eigen::MatrixXd& parameters,
120  bool& filtered)
121  {
122  filtered = false;
123  return true;
124  }
125 
137  virtual bool filterParameterUpdates(std::size_t start_timestep,
138  std::size_t num_timesteps,
139  int iteration_number,
140  const Eigen::MatrixXd& parameters,
141  Eigen::MatrixXd& updates)
142  {
143  return true;
144  }
145 
154  virtual void postIteration(std::size_t start_timestep,
155  std::size_t num_timesteps,int iteration_number,double cost,const Eigen::MatrixXd& parameters){}
156 
157 
166  virtual void done(bool success,int total_iterations,double final_cost,const Eigen::MatrixXd& parameters){}
167 
168 };
169 
170 }
171 #endif /* TASK_H_ */
std::shared_ptr< Task > TaskPtr
Definition: task.h:37
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.
Definition: task.h:166
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 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.
Definition: task.h:115
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 join...
Definition: task.h:137
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.
Definition: task.h:154
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 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.
Defines the STOMP improvement policy.
Definition: task.h:41


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