Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037 #ifndef MOVEIT_OMPL_INTERFACE_OMPL_INTERFACE_
00038 #define MOVEIT_OMPL_INTERFACE_OMPL_INTERFACE_
00039
00040 #include <moveit/ompl_interface/planning_context_manager.h>
00041 #include <moveit/ompl_interface/constraints_library.h>
00042 #include <moveit/constraint_samplers/constraint_sampler_manager.h>
00043 #include <moveit/constraint_sampler_manager_loader/constraint_sampler_manager_loader.h>
00044 #include <moveit/planning_interface/planning_interface.h>
00045 #include <moveit_msgs/MotionPlanRequest.h>
00046 #include <moveit_msgs/MotionPlanResponse.h>
00047 #include <string>
00048 #include <map>
00049 #include <ros/ros.h>
00050
00052 namespace ompl_interface
00053 {
00054
00057 class OMPLInterface
00058 {
00059 public:
00060
00062 OMPLInterface(const robot_model::RobotModelConstPtr &kmodel, const ros::NodeHandle &nh = ros::NodeHandle("~"));
00063
00066 OMPLInterface(const robot_model::RobotModelConstPtr &kmodel, const planning_interface::PlannerConfigurationMap &pconfig, const ros::NodeHandle &nh = ros::NodeHandle("~"));
00067
00068 virtual ~OMPLInterface();
00069
00072 void setPlannerConfigurations(const planning_interface::PlannerConfigurationMap &pconfig);
00073
00076 const planning_interface::PlannerConfigurationMap& getPlannerConfigurations() const
00077 {
00078 return context_manager_.getPlannerConfigurations();
00079 }
00080
00082 bool solve(const planning_scene::PlanningSceneConstPtr& planning_scene,
00083 const planning_interface::MotionPlanRequest &req, planning_interface::MotionPlanResponse &res) const;
00084
00086 bool solve(const planning_scene::PlanningSceneConstPtr& planning_scene,
00087 const planning_interface::MotionPlanRequest &req, planning_interface::MotionPlanDetailedResponse &res) const;
00088
00089 ModelBasedPlanningContextPtr getPlanningContext(const planning_scene::PlanningSceneConstPtr& planning_scene,
00090 const planning_interface::MotionPlanRequest &req) const;
00091 ModelBasedPlanningContextPtr getPlanningContext(const planning_scene::PlanningSceneConstPtr& planning_scene,
00092 const planning_interface::MotionPlanRequest &req,
00093 moveit_msgs::MoveItErrorCodes &error_code) const;
00094
00095 ModelBasedPlanningContextPtr getPlanningContext(const std::string &config, const std::string &factory_type = "") const;
00096
00097 ModelBasedPlanningContextPtr getLastPlanningContext() const
00098 {
00099 return context_manager_.getLastPlanningContext();
00100 }
00101
00102 const PlanningContextManager& getPlanningContextManager() const
00103 {
00104 return context_manager_;
00105 }
00106
00107 PlanningContextManager& getPlanningContextManager()
00108 {
00109 return context_manager_;
00110 }
00111
00112 ConstraintsLibrary& getConstraintsLibrary()
00113 {
00114 return *constraints_library_;
00115 }
00116
00117 const ConstraintsLibrary& getConstraintsLibrary() const
00118 {
00119 return *constraints_library_;
00120 }
00121
00122 constraint_samplers::ConstraintSamplerManager& getConstraintSamplerManager()
00123 {
00124 return *constraint_sampler_manager_;
00125 }
00126
00127 const constraint_samplers::ConstraintSamplerManager& getConstraintSamplerManager() const
00128 {
00129 return *constraint_sampler_manager_;
00130 }
00131
00132 void useConstraintsApproximations(bool flag)
00133 {
00134 use_constraints_approximations_ = flag;
00135 }
00136
00137 bool isUsingConstraintsApproximations() const
00138 {
00139 return use_constraints_approximations_;
00140 }
00141
00142 void loadConstraintApproximations(const std::string &path);
00143
00144 void saveConstraintApproximations(const std::string &path);
00145
00146 bool simplifySolutions() const
00147 {
00148 return simplify_solutions_;
00149 }
00150
00151 void simplifySolutions(bool flag)
00152 {
00153 simplify_solutions_ = true;
00154 }
00155
00157 bool saveConstraintApproximations();
00158
00160 bool loadConstraintApproximations();
00161
00163 void printStatus();
00164
00165 protected:
00166
00168 void loadPlannerConfigurations();
00169
00171 void loadConstraintSamplers();
00172
00173 void configureContext(const ModelBasedPlanningContextPtr &context) const;
00174
00176 ModelBasedPlanningContextPtr prepareForSolve(const planning_interface::MotionPlanRequest &req,
00177 const planning_scene::PlanningSceneConstPtr& planning_scene,
00178 moveit_msgs::MoveItErrorCodes *error_code,
00179 unsigned int *attempts, double *timeout) const;
00180
00181
00182 ros::NodeHandle nh_;
00183
00185 robot_model::RobotModelConstPtr kmodel_;
00186
00187 constraint_samplers::ConstraintSamplerManagerPtr constraint_sampler_manager_;
00188
00189 PlanningContextManager context_manager_;
00190
00191 ConstraintsLibraryPtr constraints_library_;
00192 bool use_constraints_approximations_;
00193
00194 bool simplify_solutions_;
00195
00196 private:
00197
00198 constraint_sampler_manager_loader::ConstraintSamplerManagerLoaderPtr constraint_sampler_manager_loader_;
00199
00200 };
00201
00202 }
00203
00204
00205 #endif