driver.h
Go to the documentation of this file.
00001 /*
00002  * flir_ptu_driver ROS package
00003  * Copyright (C) 2014 Mike Purvis (mpurvis@clearpathrobotics.com)
00004  *
00005  * PTU ROS Package
00006  * Copyright (C) 2009 Erik Karulf (erik@cse.wustl.edu)
00007  *
00008  * Author: Toby Collett (University of Auckland)
00009  * Date: 2003-02-10
00010  *
00011  * Player - One Hell of a Robot Server
00012  * Copyright (C) 2000  Brian Gerkey   &  Kasper Stoy
00013  *                     gerkey@usc.edu    kaspers@robotics.usc.edu
00014  *
00015  *  This program is free software; you can redistribute it and/or modify
00016  *  it under the terms of the GNU General Public License as published by
00017  *  the Free Software Foundation; either version 2 of the License, or
00018  *  (at your option) any later version.
00019  *
00020  *  This program is distributed in the hope that it will be useful,
00021  *  but WITHOUT ANY WARRANTY; without even the implied warranty of
00022  *  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
00023  *  GNU General Public License for more details.
00024  *
00025  *  You should have received a copy of the GNU General Public License
00026  *  along with this program; if not, write to the Free Software
00027  *  Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA  02111-1307  USA
00028  *
00029  */
00030 
00031 #ifndef FLIR_PTU_DRIVER_DRIVER_H
00032 #define FLIR_PTU_DRIVER_DRIVER_H
00033 
00034 // serial defines
00035 #define PTU_DEFAULT_BAUD 9600
00036 #define PTU_BUFFER_LEN 255
00037 #define PTU_DEFAULT_PORT "/dev/ttyUSB0"
00038 #define PTU_DEFAULT_HZ 10
00039 #define PTU_DEFAULT_VEL 0.0
00040 
00041 // command defines
00042 #define PTU_PAN 'p'
00043 #define PTU_TILT 't'
00044 #define PTU_MIN 'n'
00045 #define PTU_MAX 'x'
00046 #define PTU_MIN_SPEED 'l'
00047 #define PTU_MAX_SPEED 'u'
00048 #define PTU_VELOCITY 'v'
00049 #define PTU_POSITION 'i'
00050 
00051 #include <string>
00052 
00053 namespace serial
00054 {
00055 class Serial;
00056 }
00057 
00058 namespace flir_ptu_driver
00059 {
00060 
00061 class PTU
00062 {
00063 public:
00067   explicit PTU(serial::Serial* ser) :
00068     ser_(ser), initialized_(false)
00069   {
00070   }
00071 
00073   bool initialize();
00074 
00076   bool disableLimits();
00077 
00079   bool initialized();
00080 
00085   float getPosition(char type);
00086 
00091   float getSpeed(char type);
00092 
00097   float getResolution(char type)
00098   {
00099     return (type == PTU_TILT ? tr : pr);
00100   }
00101 
00106   float getMin(char type)
00107   {
00108     return getResolution(type) * (type == PTU_TILT ? TMin : PMin);
00109   }
00114   float getMax(char type)
00115   {
00116     return getResolution(type) * (type == PTU_TILT ? TMax : PMax);
00117   }
00118 
00123   float getMinSpeed(char type)
00124   {
00125     return getResolution(type) * (type == PTU_TILT ? TSMin : PSMin);
00126   }
00131   float getMaxSpeed(char type)
00132   {
00133     return getResolution(type) * (type == PTU_TILT ? TSMax : PSMax);
00134   }
00135 
00144   bool setPosition(char type, float pos, bool Block = false);
00145 
00152   bool setSpeed(char type, float speed);
00153 
00159   bool setMode(char type);
00160 
00165   char getMode();
00166 
00167   bool home();
00168 
00169 private:
00174   float getRes(char type);
00175 
00182   int getLimit(char type, char limType);
00183 
00184   // Position Limits
00185   int TMin;  
00186   int TMax;  
00187   int PMin;  
00188   int PMax;  
00189   bool Lim;  
00190 
00191   // Speed Limits
00192   int TSMin;  
00193   int TSMax;  
00194   int PSMin;  
00195   int PSMax;  
00196 
00197 protected:
00203   std::string sendCommand(std::string command);
00204 
00205   serial::Serial* ser_;
00206   bool initialized_;
00207 
00208   float tr;  
00209   float pr;  
00210 };
00211 
00212 }  // namespace flir_ptu_driver
00213 
00214 #endif  // FLIR_PTU_DRIVER_DRIVER_H


flir_ptu_driver
Author(s): Erik Karulf , David V. Lu , Nick Hawes
autogenerated on Tue Mar 19 2019 09:36:57