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_JOINT_PLANNER_H_ 00038 #define OMPL_ROS_JOINT_PLANNER_H_ 00039 00040 // OMPL ROS Interface 00041 #include <ompl_ros_interface/state_validity_checkers/ompl_ros_joint_state_validity_checker.h> 00042 #include <ompl_ros_interface/ompl_ros_planning_group.h> 00043 #include <ompl_ros_interface/ik/ompl_ros_ik_sampler.h> 00044 00045 // OMPL 00046 #include <ompl/base/GoalLazySamples.h> 00047 00048 namespace ompl_ros_interface 00049 { 00054 class OmplRosJointPlanner: public OmplRosPlanningGroup 00055 { 00056 public: 00057 00058 OmplRosJointPlanner():ik_sampler_available_(false){} 00059 ~OmplRosJointPlanner(){} 00060 00061 protected: 00062 00066 virtual bool isRequestValid(motion_planning_msgs::GetMotionPlan::Request &request, 00067 motion_planning_msgs::GetMotionPlan::Response &response); 00068 00072 virtual bool setStart(motion_planning_msgs::GetMotionPlan::Request &request, 00073 motion_planning_msgs::GetMotionPlan::Response &response); 00074 00078 virtual bool setGoal(motion_planning_msgs::GetMotionPlan::Request &request, 00079 motion_planning_msgs::GetMotionPlan::Response &response); 00080 00084 virtual bool initializeStateValidityChecker(ompl_ros_interface::OmplRosStateValidityCheckerPtr &state_validity_checker); 00085 00089 virtual bool initializePlanningStateSpace(ompl::base::StateSpacePtr &state_space); 00090 00094 virtual motion_planning_msgs::RobotTrajectory getSolutionPath(); 00095 00096 private: 00097 00098 //Mappings in between ompl state and robot state, these are used for efficiency 00099 motion_planning_msgs::RobotState robot_state_; //message representation of the state that this class is planning for 00100 ompl_ros_interface::OmplStateToRobotStateMapping ompl_state_to_robot_state_mapping_; 00101 ompl_ros_interface::RobotStateToOmplStateMapping robot_state_to_ompl_state_mapping_; 00102 00103 //Mappings between ompl state and kinematic state, these are used for efficiency 00104 ompl_ros_interface::OmplStateToKinematicStateMapping ompl_state_to_kinematic_state_mapping_; 00105 ompl_ros_interface::KinematicStateToOmplStateMapping kinematic_state_to_ompl_state_mapping_; 00106 00107 bool setPoseGoal(motion_planning_msgs::GetMotionPlan::Request &request, 00108 motion_planning_msgs::GetMotionPlan::Response &response); 00109 00110 bool setJointGoal(motion_planning_msgs::GetMotionPlan::Request &request, 00111 motion_planning_msgs::GetMotionPlan::Response &response); 00112 00113 std::string kinematics_solver_name_; 00114 00115 std::string end_effector_name_; 00116 00117 ompl_ros_interface::OmplRosIKSampler ik_sampler_; 00118 00119 bool ik_sampler_available_; 00120 00121 }; 00122 } 00123 #endif //OMPL_ROS_JOINT_PLANNER_H_