$search
An instantiation of a particular planner for a specific group. More...
#include <ompl_ros_planning_group.h>
An instantiation of a particular planner for a specific group.
Definition at line 79 of file ompl_ros_planning_group.h.
ompl_ros_interface::OmplRosPlanningGroup::OmplRosPlanningGroup | ( | ) | [inline] |
Definition at line 83 of file ompl_ros_planning_group.h.
bool ompl_ros_interface::OmplRosPlanningGroup::computePlan | ( | arm_navigation_msgs::GetMotionPlan::Request & | request, | |
arm_navigation_msgs::GetMotionPlan::Response & | response | |||
) |
Definition at line 409 of file ompl_ros_planning_group.cpp.
bool ompl_ros_interface::OmplRosPlanningGroup::configureStateValidityChecker | ( | arm_navigation_msgs::GetMotionPlan::Request & | request, | |
arm_navigation_msgs::GetMotionPlan::Response & | response, | |||
planning_models::KinematicState * | kinematic_state | |||
) | [private] |
Definition at line 485 of file ompl_ros_planning_group.cpp.
bool ompl_ros_interface::OmplRosPlanningGroup::finish | ( | const bool & | result | ) | [protected] |
Definition at line 477 of file ompl_ros_planning_group.cpp.
std::string ompl_ros_interface::OmplRosPlanningGroup::getFrameId | ( | ) | [inline] |
Definition at line 108 of file ompl_ros_planning_group.h.
std::string ompl_ros_interface::OmplRosPlanningGroup::getName | ( | void | ) | [inline] |
Definition at line 100 of file ompl_ros_planning_group.h.
virtual arm_navigation_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::CollisionModelsInterface * | cmi | |||
) |
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 42 of file ompl_ros_planning_group.cpp.
bool ompl_ros_interface::OmplRosPlanningGroup::initializeBKPIECEPlanner | ( | ) | [private] |
Definition at line 330 of file ompl_ros_planning_group.cpp.
bool ompl_ros_interface::OmplRosPlanningGroup::initializeESTPlanner | ( | ) | [private] |
Definition at line 256 of file ompl_ros_planning_group.cpp.
bool ompl_ros_interface::OmplRosPlanningGroup::initializeKPIECEPlanner | ( | ) | [private] |
Definition at line 302 of file ompl_ros_planning_group.cpp.
bool ompl_ros_interface::OmplRosPlanningGroup::initializeLazyRRTPlanner | ( | ) | [private] |
Definition at line 239 of file ompl_ros_planning_group.cpp.
bool ompl_ros_interface::OmplRosPlanningGroup::initializeLBKPIECEPlanner | ( | ) | [private] |
Definition at line 358 of file ompl_ros_planning_group.cpp.
bool ompl_ros_interface::OmplRosPlanningGroup::initializePhysicalGroup | ( | ) | [private] |
Definition at line 83 of file ompl_ros_planning_group.cpp.
bool ompl_ros_interface::OmplRosPlanningGroup::initializePlanner | ( | ) | [private] |
Definition at line 128 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 217 of file ompl_ros_planning_group.cpp.
bool ompl_ros_interface::OmplRosPlanningGroup::initializepSBLPlanner | ( | ) | [private] |
Definition at line 285 of file ompl_ros_planning_group.cpp.
bool ompl_ros_interface::OmplRosPlanningGroup::initializeRRTConnectPlanner | ( | ) | [private] |
Definition at line 205 of file ompl_ros_planning_group.cpp.
bool ompl_ros_interface::OmplRosPlanningGroup::initializeRRTPlanner | ( | ) | [private] |
Definition at line 161 of file ompl_ros_planning_group.cpp.
bool ompl_ros_interface::OmplRosPlanningGroup::initializeRRTStarPlanner | ( | ) | [private] |
Definition at line 178 of file ompl_ros_planning_group.cpp.
bool ompl_ros_interface::OmplRosPlanningGroup::initializeSBLPlanner | ( | ) | [private] |
Definition at line 273 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 | ( | arm_navigation_msgs::GetMotionPlan::Request & | request, | |
arm_navigation_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, | |
arm_navigation_msgs::RobotTrajectory & | robot_trajectory | |||
) | [protected] |
Definition at line 399 of file ompl_ros_planning_group.cpp.
virtual bool ompl_ros_interface::OmplRosPlanningGroup::setGoal | ( | arm_navigation_msgs::GetMotionPlan::Request & | request, | |
arm_navigation_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 | ( | arm_navigation_msgs::GetMotionPlan::Request & | request, | |
arm_navigation_msgs::GetMotionPlan::Response & | response | |||
) | [protected, pure virtual] |
bool ompl_ros_interface::OmplRosPlanningGroup::setStartAndGoalStates | ( | arm_navigation_msgs::GetMotionPlan::Request & | request, | |
arm_navigation_msgs::GetMotionPlan::Response & | response | |||
) | [private] |
Definition at line 498 of file ompl_ros_planning_group.cpp.
bool ompl_ros_interface::OmplRosPlanningGroup::transformConstraints | ( | arm_navigation_msgs::GetMotionPlan::Request & | request, | |
arm_navigation_msgs::GetMotionPlan::Response & | response | |||
) | [private] |
Definition at line 380 of file ompl_ros_planning_group.cpp.
planning_environment::CollisionModelsInterface* ompl_ros_interface::OmplRosPlanningGroup::collision_models_interface_ [protected] |
the name of the group
Definition at line 164 of file ompl_ros_planning_group.h.
std::string ompl_ros_interface::OmplRosPlanningGroup::group_name_ [protected] |
Definition at line 162 of file ompl_ros_planning_group.h.
boost::scoped_ptr<planning_models::KinematicState> ompl_ros_interface::OmplRosPlanningGroup::kinematic_state_ [private] |
Definition at line 201 of file ompl_ros_planning_group.h.
Definition at line 190 of file ompl_ros_planning_group.h.
ompl::base::PlannerPtr ompl_ros_interface::OmplRosPlanningGroup::ompl_planner_ [private] |
Definition at line 203 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 172 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 177 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 124 of file ompl_ros_planning_group.h.
boost::shared_ptr<ompl_ros_interface::PlannerConfig> ompl_ros_interface::OmplRosPlanningGroup::planner_config_ [private] |
Definition at line 198 of file ompl_ros_planning_group.h.
std::string ompl_ros_interface::OmplRosPlanningGroup::planner_config_name_ [private] |
Definition at line 197 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 166 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 182 of file ompl_ros_planning_group.h.