$search
00001 /********************************************************************* 00002 * Software License Agreement (BSD License) 00003 * 00004 * Copyright (c) 2008, Willow Garage, Inc. 00005 * All rights reserved. 00006 * 00007 * Redistribution and use in source and binary forms, with or without 00008 * modification, are permitted provided that the following conditions 00009 * are met: 00010 * 00011 * * Redistributions of source code must retain the above copyright 00012 * notice, this list of conditions and the following disclaimer. 00013 * * Redistributions in binary form must reproduce the above 00014 * copyright notice, this list of conditions and the following 00015 * disclaimer in the documentation and/or other materials provided 00016 * with the distribution. 00017 * * Neither the name of Willow Garage, Inc. nor the names of its 00018 * contributors may be used to endorse or promote products derived 00019 * from this software without specific prior written permission. 00020 * 00021 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00022 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00023 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00024 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00025 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00026 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00027 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00028 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00029 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00030 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00031 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00032 * POSSIBILITY OF SUCH DAMAGE. 00033 *********************************************************************/ 00034 00037 #ifndef OMPL_ROS_PLANNING_GROUP_H_ 00038 #define OMPL_ROS_PLANNING_GROUP_H_ 00039 00040 // ROS 00041 #include <ros/ros.h> 00042 #include <ros/console.h> 00043 00044 // ROS msgs 00045 #include <arm_navigation_msgs/ArmNavigationErrorCodes.h> 00046 #include <arm_navigation_msgs/RobotTrajectory.h> 00047 00048 // Planning environment and models 00049 #include <planning_environment/models/collision_models_interface.h> 00050 #include <planning_models/kinematic_model.h> 00051 #include <planning_models/kinematic_state.h> 00052 00053 // OMPL ROS Interface 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 // OMPL 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/BKPIECE1.h> 00070 #include <ompl/geometric/planners/kpiece/LBKPIECE1.h> 00071 #include <ompl/contrib/rrt_star/RRTstar.h> 00072 00073 namespace ompl_ros_interface 00074 { 00079 class OmplRosPlanningGroup 00080 { 00081 public: 00082 00083 OmplRosPlanningGroup(){} 00084 00092 bool initialize(const ros::NodeHandle &node_handle, 00093 const std::string &group_name, 00094 const std::string &planner_config_name, 00095 planning_environment::CollisionModelsInterface *cmi); 00096 00097 /* 00098 @brief Return the name of the group this planner is operating on 00099 */ 00100 std::string getName() 00101 { 00102 return group_name_; 00103 }; 00104 00105 /* 00106 @brief Return the planning frame id 00107 */ 00108 std::string getFrameId() 00109 { 00110 return collision_models_interface_->getWorldFrameId(); 00111 } 00112 00113 /* 00114 @brief Compute the plan 00115 @param The motion planning request 00116 @param The motion planner response 00117 */ 00118 bool computePlan(arm_navigation_msgs::GetMotionPlan::Request &request, 00119 arm_navigation_msgs::GetMotionPlan::Response &response); 00120 00124 boost::shared_ptr<ompl::geometric::SimpleSetup> planner_; 00125 00126 protected: 00127 00128 /* 00129 @brief Check whether the request is valid. This function must be implemented by every derived class. 00130 @param The motion planning request 00131 @param The motion planner response 00132 */ 00133 virtual bool isRequestValid(arm_navigation_msgs::GetMotionPlan::Request &request, 00134 arm_navigation_msgs::GetMotionPlan::Response &response) = 0; 00135 00136 /* 00137 @brief Set the start. This function must be implemented by every derived class. 00138 @param The motion planning request 00139 @param The motion planner response 00140 */ 00141 virtual bool setStart(arm_navigation_msgs::GetMotionPlan::Request &request, 00142 arm_navigation_msgs::GetMotionPlan::Response &response) = 0; 00143 00144 /* 00145 @brief Set the start. This function must be implemented by every derived class. 00146 @param The motion planning request 00147 @param The motion planner response 00148 */ 00149 virtual bool setGoal(arm_navigation_msgs::GetMotionPlan::Request &request, 00150 arm_navigation_msgs::GetMotionPlan::Response &response) = 0; 00151 00155 virtual bool initializeStateValidityChecker(ompl_ros_interface::OmplRosStateValidityCheckerPtr &state_validity_checker) =0; 00156 00160 virtual bool initializePlanningStateSpace(ompl::base::StateSpacePtr &state_space) = 0; 00161 00162 std::string group_name_; 00163 00164 planning_environment::CollisionModelsInterface* collision_models_interface_; 00165 00166 ompl::base::StateSpacePtr state_space_; 00167 00172 const planning_models::KinematicModel::JointModelGroup* physical_joint_group_; 00173 00177 planning_models::KinematicState::JointStateGroup* physical_joint_state_group_; 00178 00182 ompl_ros_interface::OmplRosStateValidityCheckerPtr state_validity_checker_; 00183 00187 virtual arm_navigation_msgs::RobotTrajectory getSolutionPath() = 0; 00188 00189 protected: 00190 ros::NodeHandle node_handle_; 00191 bool omplPathGeometricToRobotTrajectory(const ompl::geometric::PathGeometric &path, 00192 arm_navigation_msgs::RobotTrajectory &robot_trajectory); 00193 bool finish(const bool &result); 00194 00195 private: 00196 00197 std::string planner_config_name_; 00198 boost::shared_ptr<ompl_ros_interface::PlannerConfig> planner_config_; 00199 00200 // The kinematic state 00201 boost::scoped_ptr<planning_models::KinematicState> kinematic_state_; 00202 00203 ompl::base::PlannerPtr ompl_planner_; 00204 00205 bool initializeProjectionEvaluator(); 00206 00207 bool initializePhysicalGroup(); 00208 00209 bool initializePlanner(); 00210 bool initializeESTPlanner(); 00211 bool initializeSBLPlanner(); 00212 bool initializeRRTPlanner(); 00213 bool initializepRRTPlanner(); 00214 bool initializepSBLPlanner(); 00215 bool initializeKPIECEPlanner(); 00216 bool initializeLazyRRTPlanner(); 00217 bool initializeLBKPIECEPlanner(); 00218 bool initializeRRTConnectPlanner(); 00219 bool initializeRRTStarPlanner(); 00220 bool initializeBKPIECEPlanner(); 00221 00222 00223 bool configureStateValidityChecker(arm_navigation_msgs::GetMotionPlan::Request &request, 00224 arm_navigation_msgs::GetMotionPlan::Response &response, 00225 planning_models::KinematicState *kinematic_state); 00226 00227 bool transformConstraints(arm_navigation_msgs::GetMotionPlan::Request &request, 00228 arm_navigation_msgs::GetMotionPlan::Response &response); 00229 00230 bool setStartAndGoalStates(arm_navigation_msgs::GetMotionPlan::Request &request, 00231 arm_navigation_msgs::GetMotionPlan::Response &response); 00232 00233 00234 }; 00235 } 00236 #endif //OMPL_ROS_PLANNING_GROUP_H_