$search

ompl_ros_interface::OmplRosJointPlanner Class Reference

A joint planner - this is the planner that most applications will use. More...

#include <ompl_ros_joint_planner.h>

Inheritance diagram for ompl_ros_interface::OmplRosJointPlanner:
Inheritance graph
[legend]

List of all members.

Public Member Functions

 OmplRosJointPlanner ()
 ~OmplRosJointPlanner ()

Protected Member Functions

virtual
arm_navigation_msgs::RobotTrajectory 
getSolutionPath ()
 Returns the solution path.
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 (arm_navigation_msgs::GetMotionPlan::Request &request, arm_navigation_msgs::GetMotionPlan::Response &response)
 Returns whether the motion planning request is valid.
virtual bool setGoal (arm_navigation_msgs::GetMotionPlan::Request &request, arm_navigation_msgs::GetMotionPlan::Response &response)
 Set the goal state(s).
virtual bool setStart (arm_navigation_msgs::GetMotionPlan::Request &request, arm_navigation_msgs::GetMotionPlan::Response &response)
 Set the start state(s).

Private Member Functions

bool setJointGoal (arm_navigation_msgs::GetMotionPlan::Request &request, arm_navigation_msgs::GetMotionPlan::Response &response)
bool setPoseGoal (arm_navigation_msgs::GetMotionPlan::Request &request, arm_navigation_msgs::GetMotionPlan::Response &response)

Private Attributes

std::string end_effector_name_
ompl_ros_interface::OmplRosIKSampler ik_sampler_
bool ik_sampler_available_
ompl_ros_interface::KinematicStateToOmplStateMapping kinematic_state_to_ompl_state_mapping_
std::string kinematics_solver_name_
ompl_ros_interface::OmplStateToKinematicStateMapping ompl_state_to_kinematic_state_mapping_
ompl_ros_interface::OmplStateToRobotStateMapping ompl_state_to_robot_state_mapping_
arm_navigation_msgs::RobotState robot_state_
ompl_ros_interface::RobotStateToOmplStateMapping robot_state_to_ompl_state_mapping_

Detailed Description

A joint planner - this is the planner that most applications will use.

Definition at line 54 of file ompl_ros_joint_planner.h.


Constructor & Destructor Documentation

ompl_ros_interface::OmplRosJointPlanner::OmplRosJointPlanner (  )  [inline]

Definition at line 58 of file ompl_ros_joint_planner.h.

ompl_ros_interface::OmplRosJointPlanner::~OmplRosJointPlanner (  )  [inline]

Definition at line 59 of file ompl_ros_joint_planner.h.


Member Function Documentation

arm_navigation_msgs::RobotTrajectory ompl_ros_interface::OmplRosJointPlanner::getSolutionPath (  )  [protected, virtual]

Returns the solution path.

Implements ompl_ros_interface::OmplRosPlanningGroup.

Definition at line 245 of file ompl_ros_joint_planner.cpp.

bool ompl_ros_interface::OmplRosJointPlanner::initializePlanningStateSpace ( ompl::base::StateSpacePtr &  state_space  )  [protected, virtual]

Initialize the planning state space.

Implements ompl_ros_interface::OmplRosPlanningGroup.

Definition at line 42 of file ompl_ros_joint_planner.cpp.

bool ompl_ros_interface::OmplRosJointPlanner::initializeStateValidityChecker ( ompl_ros_interface::OmplRosStateValidityCheckerPtr state_validity_checker  )  [protected, virtual]

Initialize the state validity checker.

Implements ompl_ros_interface::OmplRosPlanningGroup.

Definition at line 237 of file ompl_ros_joint_planner.cpp.

bool ompl_ros_interface::OmplRosJointPlanner::isRequestValid ( arm_navigation_msgs::GetMotionPlan::Request request,
arm_navigation_msgs::GetMotionPlan::Response response 
) [protected, virtual]

Returns whether the motion planning request is valid.

Implements ompl_ros_interface::OmplRosPlanningGroup.

Definition at line 75 of file ompl_ros_joint_planner.cpp.

bool ompl_ros_interface::OmplRosJointPlanner::setGoal ( arm_navigation_msgs::GetMotionPlan::Request request,
arm_navigation_msgs::GetMotionPlan::Response response 
) [protected, virtual]

Set the goal state(s).

Implements ompl_ros_interface::OmplRosPlanningGroup.

Definition at line 121 of file ompl_ros_joint_planner.cpp.

bool ompl_ros_interface::OmplRosJointPlanner::setJointGoal ( arm_navigation_msgs::GetMotionPlan::Request request,
arm_navigation_msgs::GetMotionPlan::Response response 
) [private]

Definition at line 174 of file ompl_ros_joint_planner.cpp.

bool ompl_ros_interface::OmplRosJointPlanner::setPoseGoal ( arm_navigation_msgs::GetMotionPlan::Request request,
arm_navigation_msgs::GetMotionPlan::Response response 
) [private]

Definition at line 221 of file ompl_ros_joint_planner.cpp.

bool ompl_ros_interface::OmplRosJointPlanner::setStart ( arm_navigation_msgs::GetMotionPlan::Request request,
arm_navigation_msgs::GetMotionPlan::Response response 
) [protected, virtual]

Set the start state(s).

Implements ompl_ros_interface::OmplRosPlanningGroup.

Definition at line 145 of file ompl_ros_joint_planner.cpp.


Member Data Documentation

Definition at line 115 of file ompl_ros_joint_planner.h.

Definition at line 117 of file ompl_ros_joint_planner.h.

Definition at line 119 of file ompl_ros_joint_planner.h.

Definition at line 105 of file ompl_ros_joint_planner.h.

Definition at line 113 of file ompl_ros_joint_planner.h.

Definition at line 104 of file ompl_ros_joint_planner.h.

Definition at line 100 of file ompl_ros_joint_planner.h.

Definition at line 99 of file ompl_ros_joint_planner.h.

Definition at line 101 of file ompl_ros_joint_planner.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Properties Friends


ompl_ros_interface
Author(s): Sachin Chitta
autogenerated on Fri Mar 1 14:20:53 2013