00001 // Copyright (C) 2010-2011 Institut de Robotica i Informatica Industrial, CSIC-UPC. 00002 // Author 00003 // All rights reserved. 00004 // 00005 // This file is part of iri-ros-pkg 00006 // iri-ros-pkg is free software: you can redistribute it and/or modify 00007 // it under the terms of the GNU Lesser General Public License as published by 00008 // the Free Software Foundation, either version 3 of the License, or 00009 // at your option) any later version. 00010 // 00011 // This program is distributed in the hope that it will be useful, 00012 // but WITHOUT ANY WARRANTY; without even the implied warranty of 00013 // MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 00014 // GNU Lesser General Public License for more details. 00015 // 00016 // You should have received a copy of the GNU Lesser General Public License 00017 // along with this program. If not, see <http://www.gnu.org/licenses/>. 00018 // 00019 // IMPORTANT NOTE: This code has been generated through a script from the 00020 // iri_ros_scripts. Please do NOT delete any comments to guarantee the correctness 00021 // of the scripts. ROS topics can be easly add by using those scripts. Please 00022 // refer to the IRI wiki page for more information: 00023 // http://wikiri.upc.es/index.php/Robotics_Lab 00024 00025 #ifndef _wam_cartesian_planning_alg_h_ 00026 #define _wam_cartesian_planning_alg_h_ 00027 00028 00029 #include <iri_wam_cartesian_planning/WamCartesianPlanningConfig.h> 00030 #include <ompl/base/SpaceInformation.h> 00031 #include <ompl/base/spaces/SE3StateSpace.h> 00032 #include <ompl/geometric/planners/rrt/RRTConnect.h> 00033 #include <ompl/geometric/SimpleSetup.h> 00034 #include <ompl/config.h> 00035 00036 #include "mutex.h" 00037 00038 //include wam_cartesian_planning_alg main library 00039 00040 #include <geometry_msgs/PoseStamped.h> 00041 #include <iostream> 00042 #include <fstream> 00043 #include <stdio.h> 00051 class WamCartesianPlanningAlgorithm 00052 { 00053 protected: 00060 CMutex alg_mutex_; 00061 00062 // private attributes and methods 00063 00064 public: 00071 typedef iri_wam_cartesian_planning::WamCartesianPlanningConfig Config; 00072 00079 Config config_; 00080 00089 WamCartesianPlanningAlgorithm(void); 00090 00096 void lock(void) { alg_mutex_.enter(); }; 00097 00103 void unlock(void) { alg_mutex_.exit(); }; 00104 00112 bool try_enter(void) { return alg_mutex_.try_enter(); }; 00113 00125 void config_update(Config& new_cfg, uint32_t level=0); 00126 00127 // here define all wam_cartesian_planning_alg interface methods to retrieve and set 00128 // the driver parameters 00129 00136 ~WamCartesianPlanningAlgorithm(void); 00137 00138 static bool isStateValid(const ompl::base::State *state); 00139 void planWithSimpleSetup(ompl::base::ScopedState<ompl::base::SE3StateSpace>& start,ompl::base::ScopedState<ompl::base::SE3StateSpace>& goal, const int& st,std::vector<geometry_msgs::PoseStamped>& vector); 00140 void writeFile(ompl::geometric::PathGeometric& path,std::string& pathDir); 00141 void omplToRos(ompl::geometric::PathGeometric& path, std::vector<geometry_msgs::PoseStamped>& vect); 00142 00143 ompl::base::StateSpacePtr space; 00144 00145 00146 }; 00147 00148 #endif