Public Member Functions | Public Attributes | Protected Member Functions | Protected Attributes | Private Member Functions | Private Attributes
ompl_ros_interface::OmplRosPlanningGroup Class Reference

An instantiation of a particular planner for a specific group. More...

#include <ompl_ros_planning_group.h>

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

List of all members.

Public Member Functions

bool computePlan (arm_navigation_msgs::GetMotionPlan::Request &request, arm_navigation_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::CollisionModelsInterface *cmi)
 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
arm_navigation_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 (arm_navigation_msgs::GetMotionPlan::Request &request, arm_navigation_msgs::GetMotionPlan::Response &response)=0
bool omplPathGeometricToRobotTrajectory (const ompl::geometric::PathGeometric &path, arm_navigation_msgs::RobotTrajectory &robot_trajectory)
virtual bool setGoal (arm_navigation_msgs::GetMotionPlan::Request &request, arm_navigation_msgs::GetMotionPlan::Response &response)=0
virtual bool setStart (arm_navigation_msgs::GetMotionPlan::Request &request, arm_navigation_msgs::GetMotionPlan::Response &response)=0

Protected Attributes

planning_environment::CollisionModelsInterfacecollision_models_interface_
 the name of the group
std::string group_name_
ros::NodeHandle node_handle_
const
planning_models::KinematicModel::JointModelGroup
physical_joint_group_
 possibly abstract state
planning_models::KinematicState::JointStateGroupphysical_joint_state_group_
 A pointer to the state in the kinematic state corresponding to this joint 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 configureStateValidityChecker (arm_navigation_msgs::GetMotionPlan::Request &request, arm_navigation_msgs::GetMotionPlan::Response &response, planning_models::KinematicState *kinematic_state)
bool initializeBKPIECEPlanner ()
bool initializeESTPlanner ()
bool initializeKPIECEPlanner ()
bool initializeLazyRRTPlanner ()
bool initializeLBKPIECEPlanner ()
bool initializePhysicalGroup ()
bool initializePlanner ()
bool initializeProjectionEvaluator ()
bool initializepRRTPlanner ()
bool initializepSBLPlanner ()
bool initializeRRTConnectPlanner ()
bool initializeRRTPlanner ()
bool initializeRRTStarPlanner ()
bool initializeSBLPlanner ()
bool setStartAndGoalStates (arm_navigation_msgs::GetMotionPlan::Request &request, arm_navigation_msgs::GetMotionPlan::Response &response)
bool transformConstraints (arm_navigation_msgs::GetMotionPlan::Request &request, arm_navigation_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_

Detailed Description

An instantiation of a particular planner for a specific group.

Definition at line 79 of file ompl_ros_planning_group.h.


Constructor & Destructor Documentation

Definition at line 83 of file ompl_ros_planning_group.h.


Member Function Documentation

Definition at line 399 of file ompl_ros_planning_group.cpp.

Definition at line 475 of file ompl_ros_planning_group.cpp.

Definition at line 467 of file ompl_ros_planning_group.cpp.

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.

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.

Parameters:
param_server_prefixThe param server namespace from which all data can be accessed
group_nameThe name of the group that this class will plan for
planner_config_nameThe planner configuration that this class will use
planning_monitorA copy of the planning monitor for this planner

Definition at line 42 of file ompl_ros_planning_group.cpp.

Definition at line 320 of file ompl_ros_planning_group.cpp.

Definition at line 246 of file ompl_ros_planning_group.cpp.

Definition at line 292 of file ompl_ros_planning_group.cpp.

Definition at line 229 of file ompl_ros_planning_group.cpp.

Definition at line 348 of file ompl_ros_planning_group.cpp.

Definition at line 83 of file ompl_ros_planning_group.cpp.

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.

Definition at line 105 of file ompl_ros_planning_group.cpp.

Definition at line 207 of file ompl_ros_planning_group.cpp.

Definition at line 275 of file ompl_ros_planning_group.cpp.

Definition at line 195 of file ompl_ros_planning_group.cpp.

Definition at line 161 of file ompl_ros_planning_group.cpp.

Definition at line 178 of file ompl_ros_planning_group.cpp.

Definition at line 263 of file ompl_ros_planning_group.cpp.

Initialize the state validity checker. This function must allocate and instantiate a state validity checker.

Implemented in ompl_ros_interface::OmplRosJointPlanner, ompl_ros_interface::OmplRosTaskSpacePlanner, and ompl_ros_interface::OmplRosRPYIKTaskSpacePlanner.

bool ompl_ros_interface::OmplRosPlanningGroup::omplPathGeometricToRobotTrajectory ( const ompl::geometric::PathGeometric &  path,
arm_navigation_msgs::RobotTrajectory robot_trajectory 
) [protected]

Definition at line 389 of file ompl_ros_planning_group.cpp.

Definition at line 488 of file ompl_ros_planning_group.cpp.

Definition at line 370 of file ompl_ros_planning_group.cpp.


Member Data Documentation

the name of the group

Definition at line 164 of file ompl_ros_planning_group.h.

Definition at line 162 of file ompl_ros_planning_group.h.

Definition at line 201 of file ompl_ros_planning_group.h.

Definition at line 190 of file ompl_ros_planning_group.h.

Definition at line 203 of file ompl_ros_planning_group.h.

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.

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.

Definition at line 198 of file ompl_ros_planning_group.h.

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.

A state validity checker.

Definition at line 182 of file ompl_ros_planning_group.h.


The documentation for this class was generated from the following files:


ompl_ros_interface
Author(s): Sachin Chitta
autogenerated on Thu Dec 12 2013 11:10:59