00001 00028 #ifndef CONSTRAINED_IK_PLANNING_CONTEXT_H 00029 #define CONSTRAINED_IK_PLANNING_CONTEXT_H 00030 00031 #include <moveit/planning_interface/planning_interface.h> 00032 #include <constrained_ik/CLIKPlannerDynamicConfig.h> 00033 00034 namespace constrained_ik 00035 { 00040 class CLIKPlanningContext : public planning_interface::PlanningContext 00041 { 00042 public: 00043 EIGEN_MAKE_ALIGNED_OPERATOR_NEW 00044 00050 CLIKPlanningContext(const std::string &name, const std::string &group) : planning_interface::PlanningContext(name, group) {} 00051 00053 void clear() override = 0; 00054 00059 bool terminate() override = 0; 00060 00066 bool solve(planning_interface::MotionPlanResponse &res) override = 0; 00067 00073 bool solve(planning_interface::MotionPlanDetailedResponse &res) override = 0; 00074 00079 virtual void setPlannerConfiguration(const CLIKPlannerDynamicConfig &config) { config_ = config; } 00080 00082 virtual void resetPlannerConfiguration() { config_.__getDefault__(); } 00083 00084 protected: 00085 CLIKPlannerDynamicConfig config_; 00088 }; 00089 typedef boost::shared_ptr<CLIKPlanningContext> CLIKPlanningContextPtr; 00090 } //namespace constrained_ik 00091 00092 #endif // CONSTRAINED_IK_PLANNING_CONTEXT_H