37 #ifndef MOVEIT_OMPL_INTERFACE_OMPL_INTERFACE_ 38 #define MOVEIT_OMPL_INTERFACE_OMPL_INTERFACE_ 45 #include <moveit_msgs/MotionPlanRequest.h> 46 #include <moveit_msgs/MotionPlanResponse.h> 86 ModelBasedPlanningContextPtr
getPlanningContext(
const planning_scene::PlanningSceneConstPtr& planning_scene,
88 moveit_msgs::MoveItErrorCodes& error_code)
const;
91 const std::string& factory_type =
"")
const;
166 const std::map<std::string, std::string>& group_params,
179 const planning_scene::PlanningSceneConstPtr& planning_scene,
180 moveit_msgs::MoveItErrorCodes* error_code,
unsigned int* attempts,
181 double* timeout)
const;
PlanningContextManager & getPlanningContextManager()
bool loadPlannerConfiguration(const std::string &group_name, const std::string &planner_id, const std::map< std::string, std::string > &group_params, planning_interface::PlannerConfigurationSettings &planner_config)
Load planner configurations for specified group into planner_config.
const planning_interface::PlannerConfigurationMap & getPlannerConfigurations() const
Get the configurations for the planners that are already loaded.
std::map< std::string, PlannerConfigurationSettings > PlannerConfigurationMap
constraint_sampler_manager_loader::ConstraintSamplerManagerLoaderPtr constraint_sampler_manager_loader_
ModelBasedPlanningContextPtr getPlanningContext(const planning_scene::PlanningSceneConstPtr &planning_scene, const planning_interface::MotionPlanRequest &req) const
void configureContext(const ModelBasedPlanningContextPtr &context) const
constraint_samplers::ConstraintSamplerManager & getConstraintSamplerManager()
bool loadConstraintApproximations()
Look up param server 'constraint_approximations' and use its value as the path to load constraint app...
The MoveIt! interface to OMPL.
void loadPlannerConfigurations()
Configure the planners.
robot_model::RobotModelConstPtr kmodel_
The ROS node handle.
bool use_constraints_approximations_
void setPlannerConfigurations(const planning_interface::PlannerConfigurationMap &pconfig)
Specify configurations for the planners.
bool isUsingConstraintsApproximations() const
bool simplifySolutions() const
void useConstraintsApproximations(bool flag)
const PlanningContextManager & getPlanningContextManager() const
constraint_samplers::ConstraintSamplerManagerPtr constraint_sampler_manager_
ConstraintsLibraryPtr constraints_library_
PlanningContextManager context_manager_
void printStatus()
Print the status of this node.
const planning_interface::PlannerConfigurationMap & getPlannerConfigurations() const
Return the previously set planner configurations.
const ConstraintsLibrary & getConstraintsLibrary() const
void loadConstraintSamplers()
Load the additional plugins for sampling constraints.
OMPLInterface(const robot_model::RobotModelConstPtr &kmodel, const ros::NodeHandle &nh=ros::NodeHandle("~"))
Initialize OMPL-based planning for a particular robot model. ROS configuration is read from the speci...
const constraint_samplers::ConstraintSamplerManager & getConstraintSamplerManager() const
moveit_msgs::MotionPlanRequest MotionPlanRequest
ModelBasedPlanningContextPtr prepareForSolve(const planning_interface::MotionPlanRequest &req, const planning_scene::PlanningSceneConstPtr &planning_scene, moveit_msgs::MoveItErrorCodes *error_code, unsigned int *attempts, double *timeout) const
Configure the OMPL planning context for a new planning request.
ModelBasedPlanningContextPtr getLastPlanningContext() const
bool saveConstraintApproximations()
Look up param server 'constraint_approximations' and use its value as the path to save constraint app...
ConstraintsLibrary & getConstraintsLibrary()
ModelBasedPlanningContextPtr getLastPlanningContext() const
void simplifySolutions(bool flag)