00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00037 #ifndef OMPL_ROS_IK_SAMPLER_H_
00038 #define OMPL_ROS_IK_SAMPLER_H_
00039
00040
00041 #include <ompl/base/GoalSampleableRegion.h>
00042 #include <ompl/base/GoalLazySamples.h>
00043 #include <ompl/base/ScopedState.h>
00044 #include <ompl/base/State.h>
00045
00046
00047 #include <planning_environment/monitors/planning_monitor.h>
00048 #include <planning_models/kinematic_model.h>
00049 #include <planning_models/kinematic_state.h>
00050
00051
00052 #include <ompl_ros_interface/ompl_ros_state_validity_checker.h>
00053 #include <ompl_ros_interface/ompl_ros_projection_evaluator.h>
00054 #include <ompl_ros_interface/ompl_ros_planner_config.h>
00055 #include <ompl_ros_interface/helpers/ompl_ros_conversions.h>
00056
00057
00058 #include <pluginlib/class_loader.h>
00059 #include <kinematics_base/kinematics_base.h>
00060
00061 namespace ompl_ros_interface
00062 {
00066 class OmplRosIKSampler
00067 {
00068 public:
00069
00073 OmplRosIKSampler(): kinematics_loader_("kinematics_base","kinematics::KinematicsBase")
00074 {
00075 }
00076
00085 bool initialize(const ompl::base::StateSpacePtr &state_space,
00086 const std::string &kinematics_solver_name,
00087 const std::string &group_name,
00088 const std::string &end_effector_name,
00089 const planning_environment::PlanningMonitor *planning_monitor);
00090
00097 bool configureOnRequest(const motion_planning_msgs::GetMotionPlan::Request &request,
00098 motion_planning_msgs::GetMotionPlan::Response &response,
00099 const unsigned int &max_sample_count = 100);
00100
00106 bool sampleGoal(const ompl::base::GoalLazySamples *gls, ompl::base::State *state);
00107
00113 bool sampleGoals(const ompl::base::GoalLazySamples *gls, ompl::base::State *state);
00114
00115 private:
00116
00117 std::vector<geometry_msgs::PoseStamped> ik_poses_;
00118 unsigned int max_sample_count_,num_samples_;
00119 unsigned int ik_poses_counter_;
00120 ompl::base::StateSpacePtr state_space_;
00121 kinematics::KinematicsBase* kinematics_solver_;
00122
00123 std::string kinematics_solver_name_, group_name_, end_effector_name_;
00124 pluginlib::ClassLoader<kinematics::KinematicsBase> kinematics_loader_;
00125 boost::shared_ptr<ompl::base::ScopedState<ompl::base::CompoundStateSpace> > scoped_state_;
00126 motion_planning_msgs::RobotState seed_state_, solution_state_;
00127
00128 ompl_ros_interface::OmplStateToRobotStateMapping ompl_state_to_robot_state_mapping_;
00129 ompl_ros_interface::RobotStateToOmplStateMapping robot_state_to_ompl_state_mapping_;
00130 const planning_environment::PlanningMonitor *planning_monitor_;
00131
00132 };
00133
00134 }
00135
00136 #endif //OMPL_ROS_IK_SAMPLER_