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
00081 ModelBasedPlanningContextPtr getPlanningContext(const planning_scene::PlanningSceneConstPtr& planning_scene,
00082 const planning_interface::MotionPlanRequest &req) const;
00083 ModelBasedPlanningContextPtr getPlanningContext(const planning_scene::PlanningSceneConstPtr& planning_scene,
00084 const planning_interface::MotionPlanRequest &req,
00085 moveit_msgs::MoveItErrorCodes &error_code) const;
00086
00087 ModelBasedPlanningContextPtr getPlanningContext(const std::string &config, const std::string &factory_type = "") const;
00088
00089 ModelBasedPlanningContextPtr getLastPlanningContext() const
00090 {
00091 return context_manager_.getLastPlanningContext();
00092 }
00093
00094 const PlanningContextManager& getPlanningContextManager() const
00095 {
00096 return context_manager_;
00097 }
00098
00099 PlanningContextManager& getPlanningContextManager()
00100 {
00101 return context_manager_;
00102 }
00103
00104 ConstraintsLibrary& getConstraintsLibrary()
00105 {
00106 return *constraints_library_;
00107 }
00108
00109 const ConstraintsLibrary& getConstraintsLibrary() const
00110 {
00111 return *constraints_library_;
00112 }
00113
00114 constraint_samplers::ConstraintSamplerManager& getConstraintSamplerManager()
00115 {
00116 return *constraint_sampler_manager_;
00117 }
00118
00119 const constraint_samplers::ConstraintSamplerManager& getConstraintSamplerManager() const
00120 {
00121 return *constraint_sampler_manager_;
00122 }
00123
00124 void useConstraintsApproximations(bool flag)
00125 {
00126 use_constraints_approximations_ = flag;
00127 }
00128
00129 bool isUsingConstraintsApproximations() const
00130 {
00131 return use_constraints_approximations_;
00132 }
00133
00134 void loadConstraintApproximations(const std::string &path);
00135
00136 void saveConstraintApproximations(const std::string &path);
00137
00138 bool simplifySolutions() const
00139 {
00140 return simplify_solutions_;
00141 }
00142
00143 void simplifySolutions(bool flag)
00144 {
00145 simplify_solutions_ = true;
00146 }
00147
00149 bool saveConstraintApproximations();
00150
00152 bool loadConstraintApproximations();
00153
00155 void printStatus();
00156
00157 protected:
00158
00160 void loadPlannerConfigurations();
00161
00163 void loadConstraintSamplers();
00164
00165 void configureContext(const ModelBasedPlanningContextPtr &context) const;
00166
00168 ModelBasedPlanningContextPtr prepareForSolve(const planning_interface::MotionPlanRequest &req,
00169 const planning_scene::PlanningSceneConstPtr& planning_scene,
00170 moveit_msgs::MoveItErrorCodes *error_code,
00171 unsigned int *attempts, double *timeout) const;
00172
00173
00174 ros::NodeHandle nh_;
00175
00177 robot_model::RobotModelConstPtr kmodel_;
00178
00179 constraint_samplers::ConstraintSamplerManagerPtr constraint_sampler_manager_;
00180
00181 PlanningContextManager context_manager_;
00182
00183 ConstraintsLibraryPtr constraints_library_;
00184 bool use_constraints_approximations_;
00185
00186 bool simplify_solutions_;
00187
00188 private:
00189
00190 constraint_sampler_manager_loader::ConstraintSamplerManagerLoaderPtr constraint_sampler_manager_loader_;
00191
00192 };
00193
00194 }
00195
00196
00197 #endif