#include <ompl_interface.h>
Public Member Functions | |
constraint_samplers::ConstraintSamplerManager & | getConstraintSamplerManager () |
const constraint_samplers::ConstraintSamplerManager & | getConstraintSamplerManager () const |
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::MoveItErrorCodes &error_code) const |
PlanningContextManager & | getPlanningContextManager () |
const PlanningContextManager & | getPlanningContextManager () const |
bool | isUsingConstraintsApproximations () const |
OMPLInterface (const moveit::core::RobotModelConstPtr &robot_model, const planning_interface::PlannerConfigurationMap &pconfig, const ros::NodeHandle &nh=ros::NodeHandle("~")) | |
Initialize OMPL-based planning for a particular robot model. ROS configuration is read from the specified NodeHandle. However, planner configurations are used as specified in pconfig instead of reading them from the ROS parameter server. More... | |
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 specified NodeHandle. More... | |
void | printStatus () |
Print the status of this node. More... | |
void | setPlannerConfigurations (const planning_interface::PlannerConfigurationMap &pconfig) |
Specify configurations for the planners. More... | |
bool | simplifySolutions () const |
void | simplifySolutions (bool flag) |
void | useConstraintsApproximations (bool flag) |
virtual | ~OMPLInterface () |
Protected Member Functions | |
void | configureContext (const ModelBasedPlanningContextPtr &context) const |
void | loadConstraintSamplers () |
Load the additional plugins for sampling constraints. More... | |
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... | |
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. More... | |
Protected Attributes | |
constraint_samplers::ConstraintSamplerManagerPtr | constraint_sampler_manager_ |
PlanningContextManager | context_manager_ |
ros::NodeHandle | nh_ |
moveit::core::RobotModelConstPtr | robot_model_ |
The ROS node handle. More... | |
bool | simplify_solutions_ |
bool | use_constraints_approximations_ |
Private Attributes | |
constraint_sampler_manager_loader::ConstraintSamplerManagerLoaderPtr | constraint_sampler_manager_loader_ |
This class defines the interface to the motion planners in OMPL
Definition at line 85 of file ompl_interface.h.
ompl_interface::OMPLInterface::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 specified NodeHandle.
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 ros::NodeHandle & | nh = ros::NodeHandle("~") |
||
) |
Initialize OMPL-based planning for a particular robot model. ROS configuration is read from the specified NodeHandle. However, planner configurations are used as specified in pconfig instead of reading them from the ROS parameter server.
Definition at line 63 of file ompl_interface.cpp.
|
virtualdefault |
|
protected |
Definition at line 118 of file ompl_interface.cpp.
|
inline |
Definition at line 161 of file ompl_interface.h.
|
inline |
Definition at line 166 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 140 of file ompl_interface.h.
ompl_interface::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.
ompl_interface::ModelBasedPlanningContextPtr ompl_interface::OMPLInterface::getPlanningContext | ( | const planning_scene::PlanningSceneConstPtr & | planning_scene, |
const planning_interface::MotionPlanRequest & | req, | ||
moveit_msgs::MoveItErrorCodes & | error_code | ||
) | const |
Definition at line 107 of file ompl_interface.cpp.
|
inline |
Definition at line 156 of file ompl_interface.h.
|
inline |
Definition at line 151 of file ompl_interface.h.
|
inline |
Definition at line 176 of file ompl_interface.h.
|
protected |
Load the additional plugins for sampling constraints.
Definition at line 123 of file ompl_interface.cpp.
|
protected |
Load planner configurations for specified group into planner_config.
Definition at line 129 of file ompl_interface.cpp.
|
protected |
Configure the planners.
Definition at line 170 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 285 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 180 of file ompl_interface.h.
|
inline |
Definition at line 185 of file ompl_interface.h.
|
inline |
Definition at line 171 of file ompl_interface.h.
|
protected |
Definition at line 218 of file ompl_interface.h.
|
private |
Definition at line 227 of file ompl_interface.h.
|
protected |
Definition at line 220 of file ompl_interface.h.
|
protected |
Definition at line 213 of file ompl_interface.h.
|
protected |
The ROS node handle.
The kinematic model for which motion plans are computed
Definition at line 216 of file ompl_interface.h.
|
protected |
Definition at line 224 of file ompl_interface.h.
|
protected |
Definition at line 222 of file ompl_interface.h.