A generic task space planner. More...
#include <ompl_ros_task_space_planner.h>

Public Member Functions | |
| OmplRosTaskSpacePlanner () | |
| ~OmplRosTaskSpacePlanner () | |
Protected Member Functions | |
| virtual bool | constraintsToOmplState (const motion_planning_msgs::Constraints &constraints, ompl::base::ScopedState< ompl::base::CompoundStateSpace > &goal) |
| virtual motion_planning_msgs::RobotTrajectory | getSolutionPath ()=0 |
| Returns the solution path. | |
| bool | getSpaceFromParamServer (const ros::NodeHandle &node_handle, const std::string &space_name, ompl::base::StateSpacePtr &state_space, int &real_vector_index) |
| Load a state space from the parameter server. | |
| virtual bool | initializePlanningStateSpace (ompl::base::StateSpacePtr &state_space) |
| Initialize the planning state space. | |
| virtual bool | initializeStateValidityChecker (ompl_ros_interface::OmplRosStateValidityCheckerPtr &state_validity_checker) |
| Initialize the state validity checker. | |
| virtual bool | isRequestValid (motion_planning_msgs::GetMotionPlan::Request &request, motion_planning_msgs::GetMotionPlan::Response &response) |
| Returns whether the motion planning request is valid. | |
| virtual bool | setGoal (motion_planning_msgs::GetMotionPlan::Request &request, motion_planning_msgs::GetMotionPlan::Response &response) |
| Set the goal state(s). | |
| virtual bool | setStart (motion_planning_msgs::GetMotionPlan::Request &request, motion_planning_msgs::GetMotionPlan::Response &response) |
| Set the start state(s). | |
Protected Attributes | |
| std::string | end_effector_name_ |
| std::string | planning_frame_id_ |
| boost::shared_ptr < ompl_ros_interface::OmplRosStateTransformer > | state_transformer_ |
A generic task space planner.
Definition at line 53 of file ompl_ros_task_space_planner.h.
| ompl_ros_interface::OmplRosTaskSpacePlanner::OmplRosTaskSpacePlanner | ( | ) | [inline] |
Definition at line 57 of file ompl_ros_task_space_planner.h.
| ompl_ros_interface::OmplRosTaskSpacePlanner::~OmplRosTaskSpacePlanner | ( | ) | [inline] |
Definition at line 58 of file ompl_ros_task_space_planner.h.
| bool ompl_ros_interface::OmplRosTaskSpacePlanner::constraintsToOmplState | ( | const motion_planning_msgs::Constraints & | constraints, | |
| ompl::base::ScopedState< ompl::base::CompoundStateSpace > & | goal | |||
| ) | [protected, virtual] |
Reimplemented in ompl_ros_interface::OmplRosRPYIKTaskSpacePlanner.
Definition at line 245 of file ompl_ros_task_space_planner.cpp.
| virtual motion_planning_msgs::RobotTrajectory ompl_ros_interface::OmplRosTaskSpacePlanner::getSolutionPath | ( | ) | [protected, pure virtual] |
Returns the solution path.
Implements ompl_ros_interface::OmplRosPlanningGroup.
Implemented in ompl_ros_interface::OmplRosRPYIKTaskSpacePlanner.
| bool ompl_ros_interface::OmplRosTaskSpacePlanner::getSpaceFromParamServer | ( | const ros::NodeHandle & | node_handle, | |
| const std::string & | space_name, | |||
| ompl::base::StateSpacePtr & | state_space, | |||
| int & | real_vector_index | |||
| ) | [protected] |
Load a state space from the parameter server.
| node_handle | - The node handle to load the state space information from | |
| space_name | - The name of the state space to initialize | |
| state_space | - The state space to use | |
| real_vector_index | - The index of the real vector state space in the state space (treated as a compound state space) |
Definition at line 102 of file ompl_ros_task_space_planner.cpp.
| bool ompl_ros_interface::OmplRosTaskSpacePlanner::initializePlanningStateSpace | ( | ompl::base::StateSpacePtr & | state_space | ) | [protected, virtual] |
Initialize the planning state space.
Implements ompl_ros_interface::OmplRosPlanningGroup.
Definition at line 41 of file ompl_ros_task_space_planner.cpp.
| bool ompl_ros_interface::OmplRosTaskSpacePlanner::initializeStateValidityChecker | ( | ompl_ros_interface::OmplRosStateValidityCheckerPtr & | state_validity_checker | ) | [protected, virtual] |
Initialize the state validity checker.
Implements ompl_ros_interface::OmplRosPlanningGroup.
Reimplemented in ompl_ros_interface::OmplRosRPYIKTaskSpacePlanner.
Definition at line 271 of file ompl_ros_task_space_planner.cpp.
| bool ompl_ros_interface::OmplRosTaskSpacePlanner::isRequestValid | ( | motion_planning_msgs::GetMotionPlan::Request & | request, | |
| motion_planning_msgs::GetMotionPlan::Response & | response | |||
| ) | [protected, virtual] |
Returns whether the motion planning request is valid.
Implements ompl_ros_interface::OmplRosPlanningGroup.
Definition at line 184 of file ompl_ros_task_space_planner.cpp.
| bool ompl_ros_interface::OmplRosTaskSpacePlanner::setGoal | ( | motion_planning_msgs::GetMotionPlan::Request & | request, | |
| motion_planning_msgs::GetMotionPlan::Response & | response | |||
| ) | [protected, virtual] |
Set the goal state(s).
Implements ompl_ros_interface::OmplRosPlanningGroup.
Definition at line 217 of file ompl_ros_task_space_planner.cpp.
| bool ompl_ros_interface::OmplRosTaskSpacePlanner::setStart | ( | motion_planning_msgs::GetMotionPlan::Request & | request, | |
| motion_planning_msgs::GetMotionPlan::Response & | response | |||
| ) | [protected, virtual] |
Set the start state(s).
Implements ompl_ros_interface::OmplRosPlanningGroup.
Reimplemented in ompl_ros_interface::OmplRosRPYIKTaskSpacePlanner.
Definition at line 251 of file ompl_ros_task_space_planner.cpp.
std::string ompl_ros_interface::OmplRosTaskSpacePlanner::end_effector_name_ [protected] |
Reimplemented in ompl_ros_interface::OmplRosRPYIKTaskSpacePlanner.
Definition at line 106 of file ompl_ros_task_space_planner.h.
std::string ompl_ros_interface::OmplRosTaskSpacePlanner::planning_frame_id_ [protected] |
Definition at line 104 of file ompl_ros_task_space_planner.h.
boost::shared_ptr<ompl_ros_interface::OmplRosStateTransformer> ompl_ros_interface::OmplRosTaskSpacePlanner::state_transformer_ [protected] |
Definition at line 112 of file ompl_ros_task_space_planner.h.