$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_IK_SAMPLER_H_ 00038 #define OMPL_ROS_IK_SAMPLER_H_ 00039 00040 // OMPL 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 // Planning environment and models 00047 #include <planning_environment/models/collision_models_interface.h> 00048 #include <planning_models/kinematic_model.h> 00049 #include <planning_models/kinematic_state.h> 00050 00051 // OMPL ROS Interface 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 // Kinematics 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::CollisionModelsInterface *cmi); 00090 00097 bool configureOnRequest(const arm_navigation_msgs::GetMotionPlan::Request &request, 00098 arm_navigation_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 arm_navigation_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::CollisionModelsInterface *collision_models_interface_; 00131 00132 }; 00133 00134 } 00135 00136 #endif //OMPL_ROS_IK_SAMPLER_