43 #include <moveit_msgs/msg/motion_plan_request.hpp>
44 #include <moveit_msgs/msg/motion_plan_response.hpp>
45 #include <rclcpp/node.hpp>
59 OMPLInterface(
const moveit::core::RobotModelConstPtr& robot_model,
const rclcpp::Node::SharedPtr& node,
60 const std::string& parameter_namespace);
66 OMPLInterface(
const moveit::core::RobotModelConstPtr& robot_model,
68 const std::string& parameter_namespace);
87 moveit_msgs::msg::MoveItErrorCodes& error_code)
const;
125 const std::map<std::string, std::string>& group_params,
137 moveit_msgs::msg::MoveItErrorCodes* error_code,
unsigned int* attempts,
138 double* timeout)
const;
153 constraint_sampler_manager_loader::ConstraintSamplerManagerLoaderPtr constraint_sampler_manager_loader_;
This class assists in the generation of a ConstraintSampler for a particular group from a moveit_msgs...
rclcpp::Node::SharedPtr node_
bool use_constraints_approximations_
void printStatus()
Print the status of this node.
constraint_samplers::ConstraintSamplerManagerPtr constraint_sampler_manager_
const PlanningContextManager & getPlanningContextManager() const
constraint_samplers::ConstraintSamplerManager & getConstraintSamplerManager()
const constraint_samplers::ConstraintSamplerManager & getConstraintSamplerManager() const
void loadConstraintSamplers()
Load the additional plugins for sampling constraints.
void useConstraintsApproximations(bool flag)
PlanningContextManager & getPlanningContextManager()
void setPlannerConfigurations(const planning_interface::PlannerConfigurationMap &pconfig)
Specify configurations for the planners.
PlanningContextManager context_manager_
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.
bool isUsingConstraintsApproximations() const
moveit::core::RobotModelConstPtr robot_model_
The kinematic model for which motion plans are computed.
const std::string parameter_namespace_
The ROS node.
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
void loadPlannerConfigurations()
Configure the planners.
ModelBasedPlanningContextPtr prepareForSolve(const planning_interface::MotionPlanRequest &req, const planning_scene::PlanningSceneConstPtr &planning_scene, moveit_msgs::msg::MoveItErrorCodes *error_code, unsigned int *attempts, double *timeout) const
Configure the OMPL planning context for a new planning request.
OMPLInterface(const moveit::core::RobotModelConstPtr &robot_model, const rclcpp::Node::SharedPtr &node, const std::string ¶meter_namespace)
Initialize OMPL-based planning for a particular robot model. ROS configuration is read from the speci...
const planning_interface::PlannerConfigurationMap & getPlannerConfigurations() const
Return the previously set planner configurations.
The MoveIt interface to OMPL.
std::map< std::string, PlannerConfigurationSettings > PlannerConfigurationMap
Map from PlannerConfigurationSettings.name to PlannerConfigurationSettings.
moveit_msgs::msg::MotionPlanRequest MotionPlanRequest
This namespace includes the central class for representing planning contexts.
Specify the settings for a particular planning algorithm, for a particular group. The Planner plugin ...