$search
Initializes a bunch of planners for different groups (collections of joints and links, e.g. a robot arm). This class gets all its parameters from the ROS parameter server. After initializing, just call run on the class to start it running. More...
#include <ompl_ros.h>
Public Member Functions | |
boost::shared_ptr < ompl_ros_interface::OmplRosPlanningGroup > & | getPlanner (const std::string &group_name, const std::string &planner_config_name) |
Get a particular planner for a given group. | |
OmplRos () | |
void | run (void) |
Start running the planner. | |
~OmplRos () | |
Private Member Functions | |
bool | computePlan (arm_navigation_msgs::GetMotionPlan::Request &request, arm_navigation_msgs::GetMotionPlan::Response &response) |
Planning - choose the correct planner and then call it with the request. | |
bool | getGroupNamesFromParamServer (const std::string ¶m_server_prefix, std::vector< std::string > &group_names) |
Get the names of all groups we will be planning for. | |
bool | initialize (const std::string ¶m_server_prefix) |
bool | initializePlanningInstance (const std::string ¶m_server_prefix, const std::string &group_name, const std::string &planner_config_name) |
bool | initializePlanningMap (const std::string ¶m_server_prefix, const std::vector< std::string > &group_names) |
Private Attributes | |
planning_environment::CollisionModelsInterface * | collision_models_interface_ |
std::string | default_planner_config_ |
ros::Publisher | diagnostic_publisher_ |
boost::shared_ptr < ompl_ros_interface::OmplRosPlanningGroup > | empty_ptr |
ros::NodeHandle | node_handle_ |
ros::ServiceServer | plan_path_service_ |
std::map< std::string, boost::shared_ptr < ompl_ros_interface::OmplRosPlanningGroup > > | planner_map_ |
Map from planner name[group name] to an instance of ompl_ros_interface::OmplPlanningGroup. | |
bool | publish_diagnostics_ |
Initializes a bunch of planners for different groups (collections of joints and links, e.g. a robot arm). This class gets all its parameters from the ROS parameter server. After initializing, just call run on the class to start it running.
Definition at line 61 of file ompl_ros.h.
ompl_ros_interface::OmplRos::OmplRos | ( | void | ) |
Definition at line 42 of file ompl_ros.cpp.
ompl_ros_interface::OmplRos::~OmplRos | ( | void | ) |
Free the memory
Definition at line 48 of file ompl_ros.cpp.
bool ompl_ros_interface::OmplRos::computePlan | ( | arm_navigation_msgs::GetMotionPlan::Request & | request, | |
arm_navigation_msgs::GetMotionPlan::Response & | response | |||
) | [private] |
Planning - choose the correct planner and then call it with the request.
Definition at line 218 of file ompl_ros.cpp.
bool ompl_ros_interface::OmplRos::getGroupNamesFromParamServer | ( | const std::string & | param_server_prefix, | |
std::vector< std::string > & | group_names | |||
) | [private] |
Get the names of all groups we will be planning for.
Definition at line 102 of file ompl_ros.cpp.
boost::shared_ptr< ompl_ros_interface::OmplRosPlanningGroup > & ompl_ros_interface::OmplRos::getPlanner | ( | const std::string & | group_name, | |
const std::string & | planner_config_name | |||
) |
Get a particular planner for a given group.
Definition at line 271 of file ompl_ros.cpp.
bool ompl_ros_interface::OmplRos::initialize | ( | const std::string & | param_server_prefix | ) | [private] |
Definition at line 68 of file ompl_ros.cpp.
bool ompl_ros_interface::OmplRos::initializePlanningInstance | ( | const std::string & | param_server_prefix, | |
const std::string & | group_name, | |||
const std::string & | planner_config_name | |||
) | [private] |
Definition at line 163 of file ompl_ros.cpp.
bool ompl_ros_interface::OmplRos::initializePlanningMap | ( | const std::string & | param_server_prefix, | |
const std::vector< std::string > & | group_names | |||
) | [private] |
Definition at line 129 of file ompl_ros.cpp.
void ompl_ros_interface::OmplRos::run | ( | void | ) |
Start running the planner.
Definition at line 53 of file ompl_ros.cpp.
planning_environment::CollisionModelsInterface* ompl_ros_interface::OmplRos::collision_models_interface_ [private] |
Definition at line 110 of file ompl_ros.h.
std::string ompl_ros_interface::OmplRos::default_planner_config_ [private] |
Definition at line 112 of file ompl_ros.h.
Definition at line 114 of file ompl_ros.h.
boost::shared_ptr<ompl_ros_interface::OmplRosPlanningGroup> ompl_ros_interface::OmplRos::empty_ptr [private] |
Definition at line 108 of file ompl_ros.h.
Definition at line 111 of file ompl_ros.h.
Definition at line 109 of file ompl_ros.h.
std::map<std::string,boost::shared_ptr<ompl_ros_interface::OmplRosPlanningGroup> > ompl_ros_interface::OmplRos::planner_map_ [private] |
Map from planner name[group name] to an instance of ompl_ros_interface::OmplPlanningGroup.
Definition at line 105 of file ompl_ros.h.
bool ompl_ros_interface::OmplRos::publish_diagnostics_ [private] |
Definition at line 113 of file ompl_ros.h.