ompl_ros_interface::OmplRosIKSampler Class Reference

#include <ompl_ros_ik_sampler.h>

List of all members.

Public Member Functions

bool configureOnRequest (const motion_planning_msgs::GetMotionPlan::Request &request, motion_planning_msgs::GetMotionPlan::Response &response, const unsigned int &max_sample_count=100)
 Configure the kinematics solver when a request is received.
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::PlanningMonitor *planning_monitor)
 Initialize the sampler.
 OmplRosIKSampler ()
 Default constructor.
bool sampleGoal (const ompl::base::GoalLazySamples *gls, ompl::base::State *state)
 Sample a state in the goal region.
bool sampleGoals (const ompl::base::GoalLazySamples *gls, ompl::base::State *state)
 Sample a state in the goal region.

Private Attributes

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::KinematicsBase * kinematics_solver_
std::string kinematics_solver_name_
unsigned int max_sample_count_
unsigned int num_samples_
ompl_ros_interface::OmplStateToRobotStateMapping ompl_state_to_robot_state_mapping_
const
planning_environment::PlanningMonitor * 
planning_monitor_
ompl_ros_interface::RobotStateToOmplStateMapping robot_state_to_ompl_state_mapping_
boost::shared_ptr
< ompl::base::ScopedState
< ompl::base::CompoundStateSpace > > 
scoped_state_
motion_planning_msgs::RobotState seed_state_
motion_planning_msgs::RobotState solution_state_
ompl::base::StateSpacePtr state_space_

Detailed Description

Definition at line 47 of file ompl_ros_ik_sampler.h.


Constructor & Destructor Documentation

ompl_ros_interface::OmplRosIKSampler::OmplRosIKSampler (  )  [inline]

Default constructor.

Definition at line 54 of file ompl_ros_ik_sampler.h.


Member Function Documentation

bool ompl_ros_interface::OmplRosIKSampler::configureOnRequest ( const motion_planning_msgs::GetMotionPlan::Request &  request,
motion_planning_msgs::GetMotionPlan::Response &  response,
const unsigned int &  max_sample_count = 100 
)

Configure the kinematics solver when a request is received.

Parameters:
request - The motion planning request
response - The response to the motion planning request. Use this to fill in any error codes
max_sample_count - The maximum number of samples that the IK should generate

Definition at line 101 of file ompl_ros_ik_sampler.cpp.

bool ompl_ros_interface::OmplRosIKSampler::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::PlanningMonitor *  planning_monitor 
)

Initialize the sampler.

Parameters:
state_space - The state manifld that the planner is operating on
kinematics_solver_name - The name of the plugin that the kinematics solver will use
group_name - The name of the group that this solver is operating on
end_effector_name - The name of the end effector for this group
planning_monitor - A pointer to an instance of the planning monitor

Definition at line 41 of file ompl_ros_ik_sampler.cpp.

bool ompl_ros_interface::OmplRosIKSampler::sampleGoal ( const ompl::base::GoalLazySamples *  gls,
ompl::base::State *  state 
)

Sample a state in the goal region.

Parameters:
gls - A pointer to an instance of a goal lazy sampling object
state - The state to be returned

Definition at line 141 of file ompl_ros_ik_sampler.cpp.

bool ompl_ros_interface::OmplRosIKSampler::sampleGoals ( const ompl::base::GoalLazySamples *  gls,
ompl::base::State *  state 
)

Sample a state in the goal region.

Parameters:
gls - A pointer to an instance of a goal lazy sampling object
state - The state to be returned

Definition at line 170 of file ompl_ros_ik_sampler.cpp.


Member Data Documentation

Definition at line 104 of file ompl_ros_ik_sampler.h.

Definition at line 104 of file ompl_ros_ik_sampler.h.

std::vector<geometry_msgs::PoseStamped> ompl_ros_interface::OmplRosIKSampler::ik_poses_ [private]

Definition at line 98 of file ompl_ros_ik_sampler.h.

Definition at line 100 of file ompl_ros_ik_sampler.h.

pluginlib::ClassLoader<kinematics::KinematicsBase> ompl_ros_interface::OmplRosIKSampler::kinematics_loader_ [private]

Definition at line 105 of file ompl_ros_ik_sampler.h.

kinematics::KinematicsBase* ompl_ros_interface::OmplRosIKSampler::kinematics_solver_ [private]

Definition at line 102 of file ompl_ros_ik_sampler.h.

Definition at line 104 of file ompl_ros_ik_sampler.h.

Definition at line 99 of file ompl_ros_ik_sampler.h.

Definition at line 99 of file ompl_ros_ik_sampler.h.

Definition at line 109 of file ompl_ros_ik_sampler.h.

const planning_environment::PlanningMonitor* ompl_ros_interface::OmplRosIKSampler::planning_monitor_ [private]

Definition at line 111 of file ompl_ros_ik_sampler.h.

Definition at line 110 of file ompl_ros_ik_sampler.h.

boost::shared_ptr<ompl::base::ScopedState<ompl::base::CompoundStateSpace> > ompl_ros_interface::OmplRosIKSampler::scoped_state_ [private]

Definition at line 106 of file ompl_ros_ik_sampler.h.

motion_planning_msgs::RobotState ompl_ros_interface::OmplRosIKSampler::seed_state_ [private]

Definition at line 107 of file ompl_ros_ik_sampler.h.

motion_planning_msgs::RobotState ompl_ros_interface::OmplRosIKSampler::solution_state_ [private]

Definition at line 107 of file ompl_ros_ik_sampler.h.

ompl::base::StateSpacePtr ompl_ros_interface::OmplRosIKSampler::state_space_ [private]

Definition at line 101 of file ompl_ros_ik_sampler.h.


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


ompl_ros_interface
Author(s): Sachin Chitta
autogenerated on Fri Jan 11 10:08:05 2013