moveit2
The MoveIt Motion Planning Framework for ROS 2.
|
#include <ompl_interface.h>
Public Member Functions | |
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 specified Node. More... | |
OMPLInterface (const moveit::core::RobotModelConstPtr &robot_model, const planning_interface::PlannerConfigurationMap &pconfig, 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 specified Node. However, planner configurations are used as specified in pconfig instead of reading them from ROS parameters. More... | |
virtual | ~OMPLInterface () |
void | setPlannerConfigurations (const planning_interface::PlannerConfigurationMap &pconfig) |
Specify configurations for the planners. More... | |
const planning_interface::PlannerConfigurationMap & | getPlannerConfigurations () const |
Get the configurations for the planners that are already loaded. More... | |
ModelBasedPlanningContextPtr | getPlanningContext (const planning_scene::PlanningSceneConstPtr &planning_scene, const planning_interface::MotionPlanRequest &req) const |
ModelBasedPlanningContextPtr | getPlanningContext (const planning_scene::PlanningSceneConstPtr &planning_scene, const planning_interface::MotionPlanRequest &req, moveit_msgs::msg::MoveItErrorCodes &error_code) const |
const PlanningContextManager & | getPlanningContextManager () const |
PlanningContextManager & | getPlanningContextManager () |
constraint_samplers::ConstraintSamplerManager & | getConstraintSamplerManager () |
const constraint_samplers::ConstraintSamplerManager & | getConstraintSamplerManager () const |
void | useConstraintsApproximations (bool flag) |
bool | isUsingConstraintsApproximations () const |
void | printStatus () |
Print the status of this node. More... | |
Protected Member Functions | |
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. More... | |
void | loadPlannerConfigurations () |
Configure the planners. More... | |
void | loadConstraintSamplers () |
Load the additional plugins for sampling constraints. More... | |
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. More... | |
Protected Attributes | |
rclcpp::Node::SharedPtr | node_ |
const std::string | parameter_namespace_ |
The ROS node. More... | |
moveit::core::RobotModelConstPtr | robot_model_ |
The kinematic model for which motion plans are computed. More... | |
constraint_samplers::ConstraintSamplerManagerPtr | constraint_sampler_manager_ |
PlanningContextManager | context_manager_ |
bool | use_constraints_approximations_ |
This class defines the interface to the motion planners in OMPL
Definition at line 54 of file ompl_interface.h.
ompl_interface::OMPLInterface::OMPLInterface | ( | const moveit::core::RobotModelConstPtr & | robot_model, |
const rclcpp::Node::SharedPtr & | node, | ||
const std::string & | parameter_namespace | ||
) |
Initialize OMPL-based planning for a particular robot model. ROS configuration is read from the specified Node.
Definition at line 49 of file ompl_interface.cpp.
ompl_interface::OMPLInterface::OMPLInterface | ( | const moveit::core::RobotModelConstPtr & | robot_model, |
const planning_interface::PlannerConfigurationMap & | pconfig, | ||
const rclcpp::Node::SharedPtr & | node, | ||
const std::string & | parameter_namespace | ||
) |
Initialize OMPL-based planning for a particular robot model. ROS configuration is read from the specified Node. However, planner configurations are used as specified in pconfig instead of reading them from ROS parameters.
Definition at line 63 of file ompl_interface.cpp.
|
virtualdefault |
|
inline |
Definition at line 99 of file ompl_interface.h.
|
inline |
Definition at line 104 of file ompl_interface.h.
|
inline |
Get the configurations for the planners that are already loaded.
pconfig | Configurations for the different planners |
Definition at line 78 of file ompl_interface.h.
ModelBasedPlanningContextPtr ompl_interface::OMPLInterface::getPlanningContext | ( | const planning_scene::PlanningSceneConstPtr & | planning_scene, |
const planning_interface::MotionPlanRequest & | req | ||
) | const |
Definition at line 99 of file ompl_interface.cpp.
ModelBasedPlanningContextPtr ompl_interface::OMPLInterface::getPlanningContext | ( | const planning_scene::PlanningSceneConstPtr & | planning_scene, |
const planning_interface::MotionPlanRequest & | req, | ||
moveit_msgs::msg::MoveItErrorCodes & | error_code | ||
) | const |
|
inline |
Definition at line 94 of file ompl_interface.h.
|
inline |
Definition at line 89 of file ompl_interface.h.
|
inline |
Definition at line 114 of file ompl_interface.h.
|
protected |
Load the additional plugins for sampling constraints.
Definition at line 116 of file ompl_interface.cpp.
|
protected |
Load planner configurations for specified group into planner_config.
Definition at line 123 of file ompl_interface.cpp.
|
protected |
Configure the planners.
Definition at line 153 of file ompl_interface.cpp.
|
protected |
Configure the OMPL planning context for a new planning request.
void ompl_interface::OMPLInterface::printStatus | ( | ) |
Print the status of this node.
Definition at line 249 of file ompl_interface.cpp.
void ompl_interface::OMPLInterface::setPlannerConfigurations | ( | const planning_interface::PlannerConfigurationMap & | pconfig | ) |
Specify configurations for the planners.
pconfig | Configurations for the different planners |
Definition at line 80 of file ompl_interface.cpp.
|
inline |
Definition at line 109 of file ompl_interface.h.
|
protected |
Definition at line 146 of file ompl_interface.h.
|
protected |
Definition at line 148 of file ompl_interface.h.
|
protected |
Definition at line 140 of file ompl_interface.h.
|
protected |
The ROS node.
Definition at line 141 of file ompl_interface.h.
|
protected |
The kinematic model for which motion plans are computed.
Definition at line 144 of file ompl_interface.h.
|
protected |
Definition at line 150 of file ompl_interface.h.