Public Member Functions | Private Member Functions | Private Attributes
ompl_ros_interface::OmplRosIKSampleableRegion Class Reference

Inherits from ompl::base::GoalSampleableRegion and can be used to sample goals using IK. More...

#include <ompl_ros_ik_goal_sampleable_region.h>

List of all members.

Public Member Functions

bool configureOnRequest (const arm_navigation_msgs::GetMotionPlan::Request &request, arm_navigation_msgs::GetMotionPlan::Response &response, const unsigned int &max_sample_count=100)
 Configure the GoalSampleableRegion when a request is received. This is typically a one time configuration for each planning request.
bool initialize (const ompl::base::StateSpacePtr &state_space, const std::string &kinematics_solver_name, const std::string &group_name, const std::string &end_effector_name, const planning_environment::CollisionModelsInterface *cmi)
 Initialize the goal sampleable region.
virtual unsigned int maxSampleCount (void) const
 Get the maximum sample count.
 OmplRosIKSampleableRegion (const ompl::base::SpaceInformationPtr &space_information)
 Inherits from ompl::base::GoalSampleableRegion and can be used to sample goals using IK.
virtual void sampleGoal (ompl::base::State *state) const
 Sample a goal in the goal sampleable region.

Private Member Functions

void sampleGoals (const unsigned int &number_goals, std::vector< arm_navigation_msgs::RobotState > &sampled_states_vector) const

Private Attributes

const
planning_environment::CollisionModelsInterface
collision_models_interface_
std::string end_effector_name_
std::string group_name_
std::vector
< geometry_msgs::PoseStamped > 
ik_poses_
unsigned int ik_poses_counter_
pluginlib::ClassLoader
< kinematics::KinematicsBase
kinematics_loader_
kinematics::KinematicsBasekinematics_solver_
std::string kinematics_solver_name_
unsigned int max_sample_count_
ompl_ros_interface::OmplStateToRobotStateMapping ompl_state_to_robot_state_mapping_
ompl_ros_interface::RobotStateToOmplStateMapping robot_state_to_ompl_state_mapping_
ompl::base::ScopedState
< ompl::base::CompoundStateSpace > 
scoped_state_
arm_navigation_msgs::RobotState seed_state_
arm_navigation_msgs::RobotState solution_state_
ompl::base::StateSpacePtr state_space_

Detailed Description

Inherits from ompl::base::GoalSampleableRegion and can be used to sample goals using IK.

Definition at line 67 of file ompl_ros_ik_goal_sampleable_region.h.


Constructor & Destructor Documentation

ompl_ros_interface::OmplRosIKSampleableRegion::OmplRosIKSampleableRegion ( const ompl::base::SpaceInformationPtr &  space_information) [inline]

Inherits from ompl::base::GoalSampleableRegion and can be used to sample goals using IK.

Parameters:
space_informationAn instance of the space information to use for initialization

Definition at line 74 of file ompl_ros_ik_goal_sampleable_region.h.


Member Function Documentation

Configure the GoalSampleableRegion when a request is received. This is typically a one time configuration for each planning request.

Parameters:
requestThe request that the planner gets
responseThe response to the planning request

Definition at line 104 of file ompl_ros_ik_goal_sampleable_region.cpp.

bool ompl_ros_interface::OmplRosIKSampleableRegion::initialize ( const ompl::base::StateSpacePtr &  state_space,
const std::string &  kinematics_solver_name,
const std::string &  group_name,
const std::string &  end_effector_name,
const planning_environment::CollisionModelsInterface cmi 
)

Initialize the goal sampleable region.

Parameters:
state_space- The state space to use for initialization of the goal sampleable region
kinematics_solver_name- The name of the kinematics solver to be used to populate the goal sampleable region
group_name- The name of the group
end_effector_name- The name of the end effector for this particular group
planning_monitor- A pointer to the planning monitor

Definition at line 41 of file ompl_ros_ik_goal_sampleable_region.cpp.

unsigned int ompl_ros_interface::OmplRosIKSampleableRegion::maxSampleCount ( void  ) const [virtual]

Get the maximum sample count.

Returns:
maximum sample count

Definition at line 141 of file ompl_ros_ik_goal_sampleable_region.cpp.

void ompl_ros_interface::OmplRosIKSampleableRegion::sampleGoal ( ompl::base::State *  state) const [virtual]

Sample a goal in the goal sampleable region.

Parameters:
state- The state to be sampled and filled in

Definition at line 146 of file ompl_ros_ik_goal_sampleable_region.cpp.

void ompl_ros_interface::OmplRosIKSampleableRegion::sampleGoals ( const unsigned int &  number_goals,
std::vector< arm_navigation_msgs::RobotState > &  sampled_states_vector 
) const [private]

Definition at line 159 of file ompl_ros_ik_goal_sampleable_region.cpp.


Member Data Documentation

Definition at line 134 of file ompl_ros_ik_goal_sampleable_region.h.

Definition at line 127 of file ompl_ros_ik_goal_sampleable_region.h.

Definition at line 127 of file ompl_ros_ik_goal_sampleable_region.h.

Definition at line 121 of file ompl_ros_ik_goal_sampleable_region.h.

Definition at line 123 of file ompl_ros_ik_goal_sampleable_region.h.

Definition at line 128 of file ompl_ros_ik_goal_sampleable_region.h.

Definition at line 125 of file ompl_ros_ik_goal_sampleable_region.h.

Definition at line 127 of file ompl_ros_ik_goal_sampleable_region.h.

Definition at line 122 of file ompl_ros_ik_goal_sampleable_region.h.

Definition at line 132 of file ompl_ros_ik_goal_sampleable_region.h.

Definition at line 133 of file ompl_ros_ik_goal_sampleable_region.h.

ompl::base::ScopedState<ompl::base::CompoundStateSpace> ompl_ros_interface::OmplRosIKSampleableRegion::scoped_state_ [private]

Definition at line 129 of file ompl_ros_ik_goal_sampleable_region.h.

Definition at line 130 of file ompl_ros_ik_goal_sampleable_region.h.

Definition at line 130 of file ompl_ros_ik_goal_sampleable_region.h.

Definition at line 124 of file ompl_ros_ik_goal_sampleable_region.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