Go to the documentation of this file.00001
00026 #ifndef STOMP_TASK_H_
00027 #define STOMP_TASK_H_
00028
00029 #include <XmlRpcValue.h>
00030 #include <boost/shared_ptr.hpp>
00031 #include <Eigen/Core>
00032 #include "stomp_core/utils.h"
00033
00034 namespace stomp_core
00035 {
00036
00037 class Task;
00038 typedef boost::shared_ptr<Task> TaskPtr;
00041 class Task
00042 {
00043
00044 public:
00045
00046 Task(){}
00047
00059 virtual bool generateNoisyParameters(const Eigen::MatrixXd& parameters,
00060 std::size_t start_timestep,
00061 std::size_t num_timesteps,
00062 int iteration_number,
00063 int rollout_number,
00064 Eigen::MatrixXd& parameters_noise,
00065 Eigen::MatrixXd& noise) = 0;
00066
00078 virtual bool computeNoisyCosts(const Eigen::MatrixXd& parameters,
00079 std::size_t start_timestep,
00080 std::size_t num_timesteps,
00081 int iteration_number,
00082 int rollout_number,
00083 Eigen::VectorXd& costs,
00084 bool& validity) = 0 ;
00085
00096 virtual bool computeCosts(const Eigen::MatrixXd& parameters,
00097 std::size_t start_timestep,
00098 std::size_t num_timesteps,
00099 int iteration_number,
00100 Eigen::VectorXd& costs,
00101 bool& validity) = 0 ;
00102
00115 virtual bool filterNoisyParameters(std::size_t start_timestep,
00116 std::size_t num_timesteps,
00117 int iteration_number,
00118 int rollout_number,
00119 Eigen::MatrixXd& parameters,
00120 bool& filtered)
00121 {
00122 filtered = false;
00123 return true;
00124 }
00125
00137 virtual bool filterParameterUpdates(std::size_t start_timestep,
00138 std::size_t num_timesteps,
00139 int iteration_number,
00140 const Eigen::MatrixXd& parameters,
00141 Eigen::MatrixXd& updates)
00142 {
00143 return true;
00144 }
00145
00154 virtual void postIteration(std::size_t start_timestep,
00155 std::size_t num_timesteps,int iteration_number,double cost,const Eigen::MatrixXd& parameters){}
00156
00157
00166 virtual void done(bool success,int total_iterations,double final_cost,const Eigen::MatrixXd& parameters){}
00167
00168 };
00169
00170 }
00171 #endif