An instantiation of a particular planner for a specific group. More...
#include <ompl_ros_planning_group.h>
Public Member Functions | |
bool | computePlan (motion_planning_msgs::GetMotionPlan::Request &request, motion_planning_msgs::GetMotionPlan::Response &response) |
std::string | getFrameId () |
std::string | getName () |
bool | initialize (const ros::NodeHandle &node_handle, const std::string &group_name, const std::string &planner_config_name, planning_environment::PlanningMonitor *planning_monitor) |
Initialize the planning group from the param server. | |
OmplRosPlanningGroup () | |
Public Attributes | |
boost::shared_ptr < ompl::geometric::SimpleSetup > | planner_ |
The underlying planner to be used for planning. | |
Protected Member Functions | |
bool | finish (const bool &result) |
virtual motion_planning_msgs::RobotTrajectory | getSolutionPath ()=0 |
Returns the solution path. | |
virtual bool | initializePlanningStateSpace (ompl::base::StateSpacePtr &state_space)=0 |
Initialize the planning state space. This function must allocate and instantiate a state space on which planning will take place. | |
virtual bool | initializeStateValidityChecker (ompl_ros_interface::OmplRosStateValidityCheckerPtr &state_validity_checker)=0 |
Initialize the state validity checker. This function must allocate and instantiate a state validity checker. | |
virtual bool | isRequestValid (motion_planning_msgs::GetMotionPlan::Request &request, motion_planning_msgs::GetMotionPlan::Response &response)=0 |
bool | omplPathGeometricToRobotTrajectory (const ompl::geometric::PathGeometric &path, motion_planning_msgs::RobotTrajectory &robot_trajectory) |
virtual bool | setGoal (motion_planning_msgs::GetMotionPlan::Request &request, motion_planning_msgs::GetMotionPlan::Response &response)=0 |
virtual bool | setStart (motion_planning_msgs::GetMotionPlan::Request &request, motion_planning_msgs::GetMotionPlan::Response &response)=0 |
Protected Attributes | |
std::string | group_name_ |
ros::NodeHandle | node_handle_ |
const planning_models::KinematicModel::JointModelGroup * | physical_joint_group_ |
possibly abstract state | |
planning_models::KinematicState::JointStateGroup * | physical_joint_state_group_ |
A pointer to the state in the kinematic state corresponding to this joint group. | |
planning_environment::PlanningMonitor * | planning_monitor_ |
the name of the group | |
ompl::base::StateSpacePtr | state_space_ |
A pointer to an instance of the planning monitor. | |
ompl_ros_interface::OmplRosStateValidityCheckerPtr | state_validity_checker_ |
A state validity checker. | |
Private Member Functions | |
bool | configurePlanningMonitor (motion_planning_msgs::GetMotionPlan::Request &request, motion_planning_msgs::GetMotionPlan::Response &response, planning_models::KinematicState *kinematic_state) |
bool | initializeESTPlanner () |
bool | initializeKPIECEPlanner () |
bool | initializeLazyRRTPlanner () |
bool | initializeLBKPIECEPlanner () |
bool | initializePhysicalGroup () |
bool | initializePlanner () |
bool | initializeProjectionEvaluator () |
bool | initializepRRTPlanner () |
bool | initializepSBLPlanner () |
bool | initializeRRTConnectPlanner () |
bool | initializeRRTPlanner () |
bool | initializeSBLPlanner () |
bool | setStartAndGoalStates (motion_planning_msgs::GetMotionPlan::Request &request, motion_planning_msgs::GetMotionPlan::Response &response) |
bool | transformConstraints (motion_planning_msgs::GetMotionPlan::Request &request, motion_planning_msgs::GetMotionPlan::Response &response) |
Private Attributes | |
boost::scoped_ptr < planning_models::KinematicState > | kinematic_state_ |
ompl::base::PlannerPtr | ompl_planner_ |
boost::shared_ptr < ompl_ros_interface::PlannerConfig > | planner_config_ |
std::string | planner_config_name_ |
An instantiation of a particular planner for a specific group.
Definition at line 77 of file ompl_ros_planning_group.h.
ompl_ros_interface::OmplRosPlanningGroup::OmplRosPlanningGroup | ( | ) | [inline] |
Definition at line 81 of file ompl_ros_planning_group.h.
bool ompl_ros_interface::OmplRosPlanningGroup::computePlan | ( | motion_planning_msgs::GetMotionPlan::Request & | request, | |
motion_planning_msgs::GetMotionPlan::Response & | response | |||
) |
Definition at line 315 of file ompl_ros_planning_group.cpp.
bool ompl_ros_interface::OmplRosPlanningGroup::configurePlanningMonitor | ( | motion_planning_msgs::GetMotionPlan::Request & | request, | |
motion_planning_msgs::GetMotionPlan::Response & | response, | |||
planning_models::KinematicState * | kinematic_state | |||
) | [private] |
Definition at line 377 of file ompl_ros_planning_group.cpp.
bool ompl_ros_interface::OmplRosPlanningGroup::finish | ( | const bool & | result | ) | [protected] |
Definition at line 371 of file ompl_ros_planning_group.cpp.
std::string ompl_ros_interface::OmplRosPlanningGroup::getFrameId | ( | ) | [inline] |
Definition at line 106 of file ompl_ros_planning_group.h.
std::string ompl_ros_interface::OmplRosPlanningGroup::getName | ( | void | ) | [inline] |
Definition at line 98 of file ompl_ros_planning_group.h.
virtual motion_planning_msgs::RobotTrajectory ompl_ros_interface::OmplRosPlanningGroup::getSolutionPath | ( | ) | [protected, pure virtual] |
Returns the solution path.
Implemented in ompl_ros_interface::OmplRosJointPlanner, ompl_ros_interface::OmplRosRPYIKTaskSpacePlanner, and ompl_ros_interface::OmplRosTaskSpacePlanner.
bool ompl_ros_interface::OmplRosPlanningGroup::initialize | ( | const ros::NodeHandle & | node_handle, | |
const std::string & | group_name, | |||
const std::string & | planner_config_name, | |||
planning_environment::PlanningMonitor * | planning_monitor | |||
) |
Initialize the planning group from the param server.
param_server_prefix | The param server namespace from which all data can be accessed | |
group_name | The name of the group that this class will plan for | |
planner_config_name | The planner configuration that this class will use | |
planning_monitor | A copy of the planning monitor for this planner |
Definition at line 41 of file ompl_ros_planning_group.cpp.
bool ompl_ros_interface::OmplRosPlanningGroup::initializeESTPlanner | ( | ) | [private] |
Definition at line 213 of file ompl_ros_planning_group.cpp.
bool ompl_ros_interface::OmplRosPlanningGroup::initializeKPIECEPlanner | ( | ) | [private] |
Definition at line 259 of file ompl_ros_planning_group.cpp.
bool ompl_ros_interface::OmplRosPlanningGroup::initializeLazyRRTPlanner | ( | ) | [private] |
Definition at line 196 of file ompl_ros_planning_group.cpp.
bool ompl_ros_interface::OmplRosPlanningGroup::initializeLBKPIECEPlanner | ( | ) | [private] |
Definition at line 276 of file ompl_ros_planning_group.cpp.
bool ompl_ros_interface::OmplRosPlanningGroup::initializePhysicalGroup | ( | ) | [private] |
Definition at line 82 of file ompl_ros_planning_group.cpp.
bool ompl_ros_interface::OmplRosPlanningGroup::initializePlanner | ( | ) | [private] |
Definition at line 121 of file ompl_ros_planning_group.cpp.
virtual bool ompl_ros_interface::OmplRosPlanningGroup::initializePlanningStateSpace | ( | ompl::base::StateSpacePtr & | state_space | ) | [protected, pure virtual] |
Initialize the planning state space. This function must allocate and instantiate a state space on which planning will take place.
Implemented in ompl_ros_interface::OmplRosJointPlanner, and ompl_ros_interface::OmplRosTaskSpacePlanner.
bool ompl_ros_interface::OmplRosPlanningGroup::initializeProjectionEvaluator | ( | ) | [private] |
Definition at line 105 of file ompl_ros_planning_group.cpp.
bool ompl_ros_interface::OmplRosPlanningGroup::initializepRRTPlanner | ( | ) | [private] |
Definition at line 174 of file ompl_ros_planning_group.cpp.
bool ompl_ros_interface::OmplRosPlanningGroup::initializepSBLPlanner | ( | ) | [private] |
Definition at line 242 of file ompl_ros_planning_group.cpp.
bool ompl_ros_interface::OmplRosPlanningGroup::initializeRRTConnectPlanner | ( | ) | [private] |
Definition at line 162 of file ompl_ros_planning_group.cpp.
bool ompl_ros_interface::OmplRosPlanningGroup::initializeRRTPlanner | ( | ) | [private] |
Definition at line 150 of file ompl_ros_planning_group.cpp.
bool ompl_ros_interface::OmplRosPlanningGroup::initializeSBLPlanner | ( | ) | [private] |
Definition at line 230 of file ompl_ros_planning_group.cpp.
virtual bool ompl_ros_interface::OmplRosPlanningGroup::initializeStateValidityChecker | ( | ompl_ros_interface::OmplRosStateValidityCheckerPtr & | state_validity_checker | ) | [protected, pure virtual] |
Initialize the state validity checker. This function must allocate and instantiate a state validity checker.
Implemented in ompl_ros_interface::OmplRosJointPlanner, ompl_ros_interface::OmplRosRPYIKTaskSpacePlanner, and ompl_ros_interface::OmplRosTaskSpacePlanner.
virtual bool ompl_ros_interface::OmplRosPlanningGroup::isRequestValid | ( | motion_planning_msgs::GetMotionPlan::Request & | request, | |
motion_planning_msgs::GetMotionPlan::Response & | response | |||
) | [protected, pure virtual] |
Implemented in ompl_ros_interface::OmplRosJointPlanner, and ompl_ros_interface::OmplRosTaskSpacePlanner.
bool ompl_ros_interface::OmplRosPlanningGroup::omplPathGeometricToRobotTrajectory | ( | const ompl::geometric::PathGeometric & | path, | |
motion_planning_msgs::RobotTrajectory & | robot_trajectory | |||
) | [protected] |
Definition at line 305 of file ompl_ros_planning_group.cpp.
virtual bool ompl_ros_interface::OmplRosPlanningGroup::setGoal | ( | motion_planning_msgs::GetMotionPlan::Request & | request, | |
motion_planning_msgs::GetMotionPlan::Response & | response | |||
) | [protected, pure virtual] |
Implemented in ompl_ros_interface::OmplRosJointPlanner, and ompl_ros_interface::OmplRosTaskSpacePlanner.
virtual bool ompl_ros_interface::OmplRosPlanningGroup::setStart | ( | motion_planning_msgs::GetMotionPlan::Request & | request, | |
motion_planning_msgs::GetMotionPlan::Response & | response | |||
) | [protected, pure virtual] |
bool ompl_ros_interface::OmplRosPlanningGroup::setStartAndGoalStates | ( | motion_planning_msgs::GetMotionPlan::Request & | request, | |
motion_planning_msgs::GetMotionPlan::Response & | response | |||
) | [private] |
Definition at line 405 of file ompl_ros_planning_group.cpp.
bool ompl_ros_interface::OmplRosPlanningGroup::transformConstraints | ( | motion_planning_msgs::GetMotionPlan::Request & | request, | |
motion_planning_msgs::GetMotionPlan::Response & | response | |||
) | [private] |
Definition at line 288 of file ompl_ros_planning_group.cpp.
std::string ompl_ros_interface::OmplRosPlanningGroup::group_name_ [protected] |
Definition at line 160 of file ompl_ros_planning_group.h.
boost::scoped_ptr<planning_models::KinematicState> ompl_ros_interface::OmplRosPlanningGroup::kinematic_state_ [private] |
Definition at line 199 of file ompl_ros_planning_group.h.
ros::NodeHandle ompl_ros_interface::OmplRosPlanningGroup::node_handle_ [protected] |
Definition at line 188 of file ompl_ros_planning_group.h.
ompl::base::PlannerPtr ompl_ros_interface::OmplRosPlanningGroup::ompl_planner_ [private] |
Definition at line 201 of file ompl_ros_planning_group.h.
const planning_models::KinematicModel::JointModelGroup* ompl_ros_interface::OmplRosPlanningGroup::physical_joint_group_ [protected] |
possibly abstract state
The actual (physical) joint group that this state maps onto. In most cases, this will be an identity mapping but in some cases it will be through IK
Definition at line 170 of file ompl_ros_planning_group.h.
planning_models::KinematicState::JointStateGroup* ompl_ros_interface::OmplRosPlanningGroup::physical_joint_state_group_ [protected] |
A pointer to the state in the kinematic state corresponding to this joint group.
Definition at line 175 of file ompl_ros_planning_group.h.
boost::shared_ptr<ompl::geometric::SimpleSetup> ompl_ros_interface::OmplRosPlanningGroup::planner_ |
The underlying planner to be used for planning.
Definition at line 122 of file ompl_ros_planning_group.h.
boost::shared_ptr<ompl_ros_interface::PlannerConfig> ompl_ros_interface::OmplRosPlanningGroup::planner_config_ [private] |
Definition at line 196 of file ompl_ros_planning_group.h.
std::string ompl_ros_interface::OmplRosPlanningGroup::planner_config_name_ [private] |
Definition at line 195 of file ompl_ros_planning_group.h.
planning_environment::PlanningMonitor* ompl_ros_interface::OmplRosPlanningGroup::planning_monitor_ [protected] |
the name of the group
Definition at line 162 of file ompl_ros_planning_group.h.
ompl::base::StateSpacePtr ompl_ros_interface::OmplRosPlanningGroup::state_space_ [protected] |
A pointer to an instance of the planning monitor.
Definition at line 164 of file ompl_ros_planning_group.h.
ompl_ros_interface::OmplRosStateValidityCheckerPtr ompl_ros_interface::OmplRosPlanningGroup::state_validity_checker_ [protected] |
A state validity checker.
Definition at line 180 of file ompl_ros_planning_group.h.