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_PLANNING_GROUP_H_
00038 #define OMPL_ROS_PLANNING_GROUP_H_
00039
00040
00041 #include <ros/ros.h>
00042 #include <ros/console.h>
00043
00044
00045 #include <motion_planning_msgs/ArmNavigationErrorCodes.h>
00046 #include <motion_planning_msgs/RobotTrajectory.h>
00047
00048
00049 #include <planning_environment/monitors/planning_monitor.h>
00050 #include <planning_models/kinematic_model.h>
00051 #include <planning_models/kinematic_state.h>
00052
00053
00054 #include <ompl_ros_interface/ompl_ros_state_validity_checker.h>
00055 #include <ompl_ros_interface/ompl_ros_projection_evaluator.h>
00056 #include <ompl_ros_interface/ompl_ros_planner_config.h>
00057 #include <ompl_ros_interface/helpers/ompl_ros_conversions.h>
00058
00059
00060 #include <ompl/geometric/SimpleSetup.h>
00061 #include <ompl/geometric/planners/rrt/RRT.h>
00062 #include <ompl/geometric/planners/rrt/RRTConnect.h>
00063 #include <ompl/geometric/planners/rrt/pRRT.h>
00064 #include <ompl/geometric/planners/rrt/LazyRRT.h>
00065 #include <ompl/geometric/planners/est/EST.h>
00066 #include <ompl/geometric/planners/sbl/SBL.h>
00067 #include <ompl/geometric/planners/sbl/pSBL.h>
00068 #include <ompl/geometric/planners/kpiece/KPIECE1.h>
00069 #include <ompl/geometric/planners/kpiece/LBKPIECE1.h>
00070
00071 namespace ompl_ros_interface
00072 {
00077 class OmplRosPlanningGroup
00078 {
00079 public:
00080
00081 OmplRosPlanningGroup(){}
00082
00090 bool initialize(const ros::NodeHandle &node_handle,
00091 const std::string &group_name,
00092 const std::string &planner_config_name,
00093 planning_environment::PlanningMonitor *planning_monitor);
00094
00095
00096
00097
00098 std::string getName()
00099 {
00100 return group_name_;
00101 };
00102
00103
00104
00105
00106 std::string getFrameId()
00107 {
00108 return planning_monitor_->getWorldFrameId();
00109 }
00110
00111
00112
00113
00114
00115
00116 bool computePlan(motion_planning_msgs::GetMotionPlan::Request &request,
00117 motion_planning_msgs::GetMotionPlan::Response &response);
00118
00122 boost::shared_ptr<ompl::geometric::SimpleSetup> planner_;
00123
00124 protected:
00125
00126
00127
00128
00129
00130
00131 virtual bool isRequestValid(motion_planning_msgs::GetMotionPlan::Request &request,
00132 motion_planning_msgs::GetMotionPlan::Response &response) = 0;
00133
00134
00135
00136
00137
00138
00139 virtual bool setStart(motion_planning_msgs::GetMotionPlan::Request &request,
00140 motion_planning_msgs::GetMotionPlan::Response &response) = 0;
00141
00142
00143
00144
00145
00146
00147 virtual bool setGoal(motion_planning_msgs::GetMotionPlan::Request &request,
00148 motion_planning_msgs::GetMotionPlan::Response &response) = 0;
00149
00153 virtual bool initializeStateValidityChecker(ompl_ros_interface::OmplRosStateValidityCheckerPtr &state_validity_checker) =0;
00154
00158 virtual bool initializePlanningStateSpace(ompl::base::StateSpacePtr &state_space) = 0;
00159
00160 std::string group_name_;
00161
00162 planning_environment::PlanningMonitor *planning_monitor_;
00163
00164 ompl::base::StateSpacePtr state_space_;
00165
00170 const planning_models::KinematicModel::JointModelGroup* physical_joint_group_;
00171
00175 planning_models::KinematicState::JointStateGroup* physical_joint_state_group_;
00176
00180 ompl_ros_interface::OmplRosStateValidityCheckerPtr state_validity_checker_;
00181
00185 virtual motion_planning_msgs::RobotTrajectory getSolutionPath() = 0;
00186
00187 protected:
00188 ros::NodeHandle node_handle_;
00189 bool omplPathGeometricToRobotTrajectory(const ompl::geometric::PathGeometric &path,
00190 motion_planning_msgs::RobotTrajectory &robot_trajectory);
00191 bool finish(const bool &result);
00192
00193 private:
00194
00195 std::string planner_config_name_;
00196 boost::shared_ptr<ompl_ros_interface::PlannerConfig> planner_config_;
00197
00198
00199 boost::scoped_ptr<planning_models::KinematicState> kinematic_state_;
00200
00201 ompl::base::PlannerPtr ompl_planner_;
00202
00203 bool initializeProjectionEvaluator();
00204
00205 bool initializePhysicalGroup();
00206
00207 bool initializePlanner();
00208 bool initializeESTPlanner();
00209 bool initializeSBLPlanner();
00210 bool initializeRRTPlanner();
00211 bool initializepRRTPlanner();
00212 bool initializepSBLPlanner();
00213 bool initializeKPIECEPlanner();
00214 bool initializeLazyRRTPlanner();
00215 bool initializeLBKPIECEPlanner();
00216 bool initializeRRTConnectPlanner();
00217
00218
00219 bool configurePlanningMonitor(motion_planning_msgs::GetMotionPlan::Request &request,
00220 motion_planning_msgs::GetMotionPlan::Response &response,
00221 planning_models::KinematicState *kinematic_state);
00222
00223 bool transformConstraints(motion_planning_msgs::GetMotionPlan::Request &request,
00224 motion_planning_msgs::GetMotionPlan::Response &response);
00225
00226 bool setStartAndGoalStates(motion_planning_msgs::GetMotionPlan::Request &request,
00227 motion_planning_msgs::GetMotionPlan::Response &response);
00228
00229
00230 };
00231 }
00232 #endif //OMPL_ROS_PLANNING_GROUP_H_