$search
Inherits from ompl::base::GoalSampleableRegion and can be used to sample goals using IK. More...
#include <ompl_ros_ik_goal_sampleable_region.h>
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::KinematicsBase * | kinematics_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_ |
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.
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.
space_information | An instance of the space information to use for initialization |
Definition at line 74 of file ompl_ros_ik_goal_sampleable_region.h.
bool ompl_ros_interface::OmplRosIKSampleableRegion::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.
request | The request that the planner gets | |
response | The response to the planning request |
Definition at line 83 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.
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.
Definition at line 120 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.
state | - The state to be sampled and filled in |
Definition at line 125 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 138 of file ompl_ros_ik_goal_sampleable_region.cpp.
const planning_environment::CollisionModelsInterface* ompl_ros_interface::OmplRosIKSampleableRegion::collision_models_interface_ [private] |
Definition at line 134 of file ompl_ros_ik_goal_sampleable_region.h.
std::string ompl_ros_interface::OmplRosIKSampleableRegion::end_effector_name_ [private] |
Definition at line 127 of file ompl_ros_ik_goal_sampleable_region.h.
std::string ompl_ros_interface::OmplRosIKSampleableRegion::group_name_ [private] |
Definition at line 127 of file ompl_ros_ik_goal_sampleable_region.h.
std::vector<geometry_msgs::PoseStamped> ompl_ros_interface::OmplRosIKSampleableRegion::ik_poses_ [private] |
Definition at line 121 of file ompl_ros_ik_goal_sampleable_region.h.
unsigned int ompl_ros_interface::OmplRosIKSampleableRegion::ik_poses_counter_ [private] |
Definition at line 123 of file ompl_ros_ik_goal_sampleable_region.h.
pluginlib::ClassLoader<kinematics::KinematicsBase> ompl_ros_interface::OmplRosIKSampleableRegion::kinematics_loader_ [private] |
Definition at line 128 of file ompl_ros_ik_goal_sampleable_region.h.
kinematics::KinematicsBase* ompl_ros_interface::OmplRosIKSampleableRegion::kinematics_solver_ [private] |
Definition at line 125 of file ompl_ros_ik_goal_sampleable_region.h.
std::string ompl_ros_interface::OmplRosIKSampleableRegion::kinematics_solver_name_ [private] |
Definition at line 127 of file ompl_ros_ik_goal_sampleable_region.h.
unsigned int ompl_ros_interface::OmplRosIKSampleableRegion::max_sample_count_ [private] |
Definition at line 122 of file ompl_ros_ik_goal_sampleable_region.h.
ompl_ros_interface::OmplStateToRobotStateMapping ompl_ros_interface::OmplRosIKSampleableRegion::ompl_state_to_robot_state_mapping_ [private] |
Definition at line 132 of file ompl_ros_ik_goal_sampleable_region.h.
ompl_ros_interface::RobotStateToOmplStateMapping ompl_ros_interface::OmplRosIKSampleableRegion::robot_state_to_ompl_state_mapping_ [private] |
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.
arm_navigation_msgs::RobotState ompl_ros_interface::OmplRosIKSampleableRegion::seed_state_ [private] |
Definition at line 130 of file ompl_ros_ik_goal_sampleable_region.h.
arm_navigation_msgs::RobotState ompl_ros_interface::OmplRosIKSampleableRegion::solution_state_ [private] |
Definition at line 130 of file ompl_ros_ik_goal_sampleable_region.h.
ompl::base::StateSpacePtr ompl_ros_interface::OmplRosIKSampleableRegion::state_space_ [private] |
Definition at line 124 of file ompl_ros_ik_goal_sampleable_region.h.