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 _hokuyo_laser_driver_h_ 00026 #define _hokuyo_laser_driver_h_ 00027 00028 #include "iri_base_driver/iri_base_driver.h" 00029 #include "iri_hokuyo_laser/HokuyoLaserConfig.h" 00030 00031 //include hokuyo_laser_driver main library 00032 #include "hokuyo.h" 00033 00053 class HokuyoLaserDriver : public iri_base_driver::IriBaseDriver 00054 { 00055 private: 00056 // private attributes and methods 00057 CHokuyo *laser; 00058 CMutex driver_access; 00059 int number_of_scans; 00060 std::string id; 00061 THokuyo_serial_config usb_cfg; 00062 THokuyo_ethernet_config eth_cfg; 00063 THokuyo_specs specs; 00064 std::string ip; 00065 std::string port; 00066 bool use_eth; 00067 00068 public: 00069 00070 float range_min; 00071 float range_max; 00072 float angle_increment; 00073 float angle_min; 00074 float angle_max; 00075 float scan_time; 00076 float time_increment; 00077 std::string frame_id; 00078 std::list<std::string> evnts; 00079 00086 typedef iri_hokuyo_laser::HokuyoLaserConfig Config; 00087 00094 Config config_; 00095 00104 HokuyoLaserDriver(); 00105 00116 bool openDriver(void); 00117 00128 bool closeDriver(void); 00129 00140 bool startDriver(void); 00141 00152 bool stopDriver(void); 00153 00165 void config_update(const Config& new_cfg, uint32_t level=0); 00166 00167 // here define all hokuyo_laser_driver interface methods to retrieve and set 00168 // the driver parameters 00169 00176 ~HokuyoLaserDriver(); 00177 00179 void getScan(THokuyo_scan & scan); 00180 00181 THokuyo_scan_config translateConfig(Config & cfg); 00182 }; 00183 00184 #endif