Go to the documentation of this file.
43 #include <moveit_msgs/MotionPlanRequest.h>
44 #include <moveit_msgs/MotionPlanResponse.h>
64 OMPLInterface(
const moveit::core::RobotModelConstPtr& robot_model,
85 moveit_msgs::MoveItErrorCodes& error_code)
const;
132 const std::map<std::string, std::string>& group_params,
146 moveit_msgs::MoveItErrorCodes* error_code,
unsigned int* attempts,
147 double* timeout)
const;
constraint_samplers::ConstraintSamplerManager & getConstraintSamplerManager()
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.
constraint_samplers::ConstraintSamplerManagerPtr constraint_sampler_manager_
bool use_constraints_approximations_
void loadPlannerConfigurations()
Configure the planners.
void loadConstraintSamplers()
Load the additional plugins for sampling constraints.
void setPlannerConfigurations(const planning_interface::PlannerConfigurationMap &pconfig)
Specify configurations for the planners.
void printStatus()
Print the status of this node.
constraint_sampler_manager_loader::ConstraintSamplerManagerLoaderPtr constraint_sampler_manager_loader_
bool simplifySolutions() const
The MoveIt interface to OMPL.
OMPLInterface(const moveit::core::RobotModelConstPtr &robot_model, const ros::NodeHandle &nh=ros::NodeHandle("~"))
Initialize OMPL-based planning for a particular robot model. ROS configuration is read from the speci...
std::map< std::string, PlannerConfigurationSettings > PlannerConfigurationMap
const planning_interface::PlannerConfigurationMap & getPlannerConfigurations() const
Return the previously set planner configurations.
const PlanningContextManager & getPlanningContextManager() const
void configureContext(const ModelBasedPlanningContextPtr &context) const
void useConstraintsApproximations(bool flag)
moveit_msgs::MotionPlanRequest MotionPlanRequest
PlanningContextManager context_manager_
const planning_interface::PlannerConfigurationMap & getPlannerConfigurations() const
Get the configurations for the planners that are already loaded.
ModelBasedPlanningContextPtr getPlanningContext(const planning_scene::PlanningSceneConstPtr &planning_scene, const planning_interface::MotionPlanRequest &req) const
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.
moveit::core::RobotModelConstPtr robot_model_
The ROS node handle.
bool isUsingConstraintsApproximations() const
ompl
Author(s): Ioan Sucan
autogenerated on Tue Dec 24 2024 03:28:10