stomp_cost_function.h
Go to the documentation of this file.
00001 
00026 #ifndef INDUSTRIAL_MOVEIT_STOMP_CORE_INCLUDE_STOMP_CORE_STOMP_COST_FUNCTION_H_
00027 #define INDUSTRIAL_MOVEIT_STOMP_CORE_INCLUDE_STOMP_CORE_STOMP_COST_FUNCTION_H_
00028 
00029 #include <string>
00030 #include <XmlRpc.h>
00031 #include <stomp_core/utils.h>
00032 #include <moveit_msgs/GetMotionPlan.h>
00033 #include <moveit/robot_model/robot_model.h>
00034 #include <moveit/robot_trajectory/robot_trajectory.h>
00035 #include <moveit/planning_scene/planning_scene.h>
00036 
00037 namespace stomp_moveit
00038 {
00039 
00040 namespace cost_functions
00041 {
00042 
00043 class StompCostFunction;
00044 typedef boost::shared_ptr<StompCostFunction> StompCostFunctionPtr;
00045 
00053 class StompCostFunction
00054 {
00055 public:
00056   StompCostFunction():
00057     cost_weight_(1.0)
00058   {
00059 
00060   }
00061 
00062   virtual ~StompCostFunction(){}
00063 
00071   virtual bool initialize(moveit::core::RobotModelConstPtr robot_model_ptr,
00072                           const std::string& group_name,XmlRpc::XmlRpcValue& config) = 0;
00073 
00079   virtual bool configure(const XmlRpc::XmlRpcValue& config) = 0;
00080 
00089   virtual bool setMotionPlanRequest(const planning_scene::PlanningSceneConstPtr& planning_scene,
00090                    const moveit_msgs::MotionPlanRequest &req,
00091                    const stomp_core::StompConfiguration &config,
00092                    moveit_msgs::MoveItErrorCodes& error_code) = 0;
00093 
00094 
00106   virtual bool computeCosts(const Eigen::MatrixXd& parameters,
00107                             std::size_t start_timestep,
00108                             std::size_t num_timesteps,
00109                             int iteration_number,
00110                             int rollout_number,
00111                             Eigen::VectorXd& costs,
00112                             bool& validity) = 0 ;
00113 
00122   virtual void postIteration(std::size_t start_timestep,
00123                                 std::size_t num_timesteps,int iteration_number,double cost,const Eigen::MatrixXd& parameters){}
00124 
00133   virtual void done(bool success,int total_iterations,double final_cost,const Eigen::MatrixXd& parameters){}
00134 
00135 
00136   virtual std::string getGroupName() const
00137   {
00138     return "Not Implemented";
00139   }
00140 
00141   virtual double getWeight() const
00142   {
00143     return cost_weight_;
00144   }
00145 
00146   virtual std::string getName() const
00147   {
00148     return "Not Implemented";
00149   }
00150 
00156   virtual int getOptimizedIndex() const
00157   {
00158     return -1;
00159   }
00160 
00161 
00162 protected:
00163 
00164   double cost_weight_;
00165 
00166 };
00167 
00168 
00169 } /* namespace cost_functions */
00170 } /* namespace stomp */
00171 
00172 #endif /* INDUSTRIAL_MOVEIT_STOMP_CORE_INCLUDE_STOMP_CORE_STOMP_COST_FUNCTION_H_ */


stomp_moveit
Author(s): Jorge Nicho
autogenerated on Sat Jun 8 2019 19:24:01