#include <ompl_interface.h>
This class defines the interface to the motion planners in OMPL
Definition at line 54 of file ompl_interface.h.
◆ OMPLInterface() [1/2]
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 54 of file ompl_interface.cpp.
◆ OMPLInterface() [2/2]
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 68 of file ompl_interface.cpp.
◆ ~OMPLInterface()
ompl_interface::OMPLInterface::~OMPLInterface |
( |
| ) |
|
|
virtualdefault |
◆ getConstraintSamplerManager() [1/2]
◆ getConstraintSamplerManager() [2/2]
◆ getPlannerConfigurations()
Get the configurations for the planners that are already loaded.
- Parameters
-
pconfig | Configurations for the different planners |
Definition at line 78 of file ompl_interface.h.
◆ getPlanningContext() [1/2]
ModelBasedPlanningContextPtr ompl_interface::OMPLInterface::getPlanningContext |
( |
const planning_scene::PlanningSceneConstPtr & |
planning_scene, |
|
|
const planning_interface::MotionPlanRequest & |
req |
|
) |
| const |
◆ getPlanningContext() [2/2]
ModelBasedPlanningContextPtr ompl_interface::OMPLInterface::getPlanningContext |
( |
const planning_scene::PlanningSceneConstPtr & |
planning_scene, |
|
|
const planning_interface::MotionPlanRequest & |
req, |
|
|
moveit_msgs::msg::MoveItErrorCodes & |
error_code |
|
) |
| const |
◆ getPlanningContextManager() [1/2]
◆ getPlanningContextManager() [2/2]
◆ isUsingConstraintsApproximations()
bool ompl_interface::OMPLInterface::isUsingConstraintsApproximations |
( |
| ) |
const |
|
inline |
◆ loadConstraintSamplers()
void ompl_interface::OMPLInterface::loadConstraintSamplers |
( |
| ) |
|
|
protected |
◆ loadPlannerConfiguration()
bool ompl_interface::OMPLInterface::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 |
|
) |
| |
|
protected |
Load planner configurations for specified group into planner_config.
Definition at line 128 of file ompl_interface.cpp.
◆ loadPlannerConfigurations()
void ompl_interface::OMPLInterface::loadPlannerConfigurations |
( |
| ) |
|
|
protected |
◆ prepareForSolve()
ModelBasedPlanningContextPtr ompl_interface::OMPLInterface::prepareForSolve |
( |
const planning_interface::MotionPlanRequest & |
req, |
|
|
const planning_scene::PlanningSceneConstPtr & |
planning_scene, |
|
|
moveit_msgs::msg::MoveItErrorCodes * |
error_code, |
|
|
unsigned int * |
attempts, |
|
|
double * |
timeout |
|
) |
| const |
|
protected |
Configure the OMPL planning context for a new planning request.
◆ printStatus()
void ompl_interface::OMPLInterface::printStatus |
( |
| ) |
|
◆ setPlannerConfigurations()
Specify configurations for the planners.
- Parameters
-
pconfig | Configurations for the different planners |
Definition at line 85 of file ompl_interface.cpp.
◆ useConstraintsApproximations()
void ompl_interface::OMPLInterface::useConstraintsApproximations |
( |
bool |
flag | ) |
|
|
inline |
◆ constraint_sampler_manager_
constraint_samplers::ConstraintSamplerManagerPtr ompl_interface::OMPLInterface::constraint_sampler_manager_ |
|
protected |
◆ context_manager_
◆ node_
rclcpp::Node::SharedPtr ompl_interface::OMPLInterface::node_ |
|
protected |
◆ parameter_namespace_
const std::string ompl_interface::OMPLInterface::parameter_namespace_ |
|
protected |
◆ robot_model_
moveit::core::RobotModelConstPtr ompl_interface::OMPLInterface::robot_model_ |
|
protected |
The kinematic model for which motion plans are computed.
Definition at line 144 of file ompl_interface.h.
◆ use_constraints_approximations_
bool ompl_interface::OMPLInterface::use_constraints_approximations_ |
|
protected |
The documentation for this class was generated from the following files: