tibi_dabo_laser_3d_driver.h
Go to the documentation of this file.
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 _tibi_dabo_laser_3d_driver_h_
00026 #define _tibi_dabo_laser_3d_driver_h_
00027 
00028 #include <iri_base_driver/iri_base_driver.h>
00029 #include <tibi_dabo_laser_3d/TibiDaboLaser3dConfig.h>
00030 
00031 //include tibi_dabo_laser_3d_driver main library
00032 #include "dynamixel_motor.h"
00033 
00034 typedef enum {left_right_scan=0,right_left_scan=1} scan_dir;
00035 
00055 class TibiDaboLaser3dDriver : public iri_base_driver::IriBaseDriver
00056 {
00057   private:
00058     // private attributes and methods
00059     CDynamixelMotor *servo;
00060     // Dynamixel bus configuration
00061     std::string serial_number;
00062     int baudrate;
00063     // servo configuration
00064     unsigned char servo_id; 
00065     std::string servo_config_file;
00066     // motion configuration
00067     double new_velocity;
00068     double new_max_angle;
00069     double new_min_angle;
00070     double current_velocity;
00071     double current_max_angle;
00072     double current_min_angle;
00073     bool scan_enabled;
00074     double fixed_angle;
00075     scan_dir dir;
00076   public:
00083     typedef tibi_dabo_laser_3d::TibiDaboLaser3dConfig Config;
00084 
00091     Config config_;
00092 
00101     TibiDaboLaser3dDriver(void);
00102 
00113     bool openDriver(void);
00114 
00125     bool closeDriver(void);
00126 
00137     bool startDriver(void);
00138 
00149     bool stopDriver(void);
00150 
00162     void config_update(Config& new_cfg, uint32_t level=0);
00163 
00164     // here define all tibi_dabo_laser_3d_driver interface methods to retrieve and set
00165     // the driver parameters
00170     void start_scan(void);
00175     bool is_scan_done(void);
00180     double get_current_angle(void);
00185     double get_current_velocity(void);
00190     bool is_scan_enabled(void);
00195     double get_fixed_angle(void);
00200     void move_absolute_angle(double angle);
00201 
00208     ~TibiDaboLaser3dDriver(void);
00209 };
00210 
00211 #endif


tibi_dabo_laser_3d
Author(s): Sergi Hernandez Juan
autogenerated on Fri Dec 6 2013 23:22:07