$search
00001 /********************************************************************* 00002 * Software License Agreement (BSD License) 00003 * 00004 * Copyright (c) 2010, 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_STATE_VALIDITY_CHECKER_ 00038 #define OMPL_ROS_STATE_VALIDITY_CHECKER_ 00039 00040 #include <planning_environment/models/collision_models_interface.h> 00041 #include <planning_environment/util/kinematic_state_constraint_evaluator.h> 00042 #include <arm_navigation_msgs/GetMotionPlan.h> 00043 00044 #include <ompl_ros_interface/helpers/ompl_ros_conversions.h> 00045 00046 #include <ompl/base/StateValidityChecker.h> 00047 #include <ompl/base/State.h> 00048 00049 00050 namespace ompl_ros_interface 00051 { 00056 class OmplRosStateValidityChecker : public ompl::base::StateValidityChecker 00057 { 00058 public: 00064 OmplRosStateValidityChecker(ompl::base::SpaceInformation *si, 00065 planning_environment::CollisionModelsInterface *cmi) : 00066 ompl::base::StateValidityChecker(si), 00067 collision_models_interface_(cmi) 00068 { 00069 } 00070 00072 virtual bool isValid (const ompl::base::State *ompl_state) const = 0; 00073 00075 void printSettings(std::ostream &out) const; 00076 00077 /* 00078 @brief Configure the state validity checker on request - this sets the current kinematic state, a pointer to the 00079 physical joint state group that this planner is planning for and passes in the request 00080 @param kinematic_state A pointer to the kinematic state containing joint values for the entire robot 00081 @param physical_joint_state_group A pointer to the joint state for the group that this planner is planning for 00082 @param request The motion planning request 00083 */ 00084 virtual void configureOnRequest(planning_models::KinematicState *kinematic_state, 00085 planning_models::KinematicState::JointStateGroup *physical_joint_state_group, 00086 const arm_navigation_msgs::GetMotionPlan::Request &request); 00087 00088 /* 00089 @brief Return the error code for the last state checked. 00090 @return The error code for the last state that was checked. 00091 */ 00092 arm_navigation_msgs::ArmNavigationErrorCodes getLastErrorCode() 00093 { 00094 return error_code_; 00095 } 00096 00097 /* 00098 @brief A non-const version of isValid designed to fill in the last error code 00099 @param ompl_state The state that needs to be checked 00100 */ 00101 virtual bool isStateValid(const ompl::base::State *ompl_state) = 0; 00102 00103 protected: 00104 planning_models::KinematicState::JointStateGroup *joint_state_group_; 00105 planning_environment::CollisionModelsInterface* collision_models_interface_; 00106 planning_models::KinematicState *kinematic_state_; 00107 00108 planning_environment::KinematicConstraintEvaluatorSet path_constraint_evaluator_set_; 00109 planning_environment::KinematicConstraintEvaluatorSet goal_constraint_evaluator_set_; 00110 arm_navigation_msgs::ArmNavigationErrorCodes error_code_; 00111 sensor_msgs::JointState joint_state_; 00112 arm_navigation_msgs::Constraints getPhysicalConstraints(const arm_navigation_msgs::Constraints &constraints); 00113 }; 00114 00115 typedef boost::shared_ptr<ompl_ros_interface::OmplRosStateValidityChecker> OmplRosStateValidityCheckerPtr; 00116 00117 } 00118 00119 #endif 00120