ptu46_driver.cc
Go to the documentation of this file.
00001 /*
00002  * PTU46 ROS Package
00003  * Copyright (C) 2009 Erik Karulf (erik@cse.wustl.edu)
00004  *
00005  */
00006 
00007 /*
00008  *  Player - One Hell of a Robot Server
00009  *  Copyright (C) 2000  Brian Gerkey   &  Kasper Stoy
00010  *                      gerkey@usc.edu    kaspers@robotics.usc.edu
00011  *
00012  * $Id$
00013  *
00014  * Author: Toby Collett (University of Auckland)
00015  * Date: 2003-02-10
00016  *
00017  */
00018 
00019 /*
00020  *  This program is free software; you can redistribute it and/or modify
00021  *  it under the terms of the GNU General Public License as published by
00022  *  the Free Software Foundation; either version 2 of the License, or
00023  *  (at your option) any later version.
00024  *
00025  *  This program is distributed in the hope that it will be useful,
00026  *  but WITHOUT ANY WARRANTY; without even the implied warranty of
00027  *  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
00028  *  GNU General Public License for more details.
00029  *
00030  *  You should have received a copy of the GNU General Public License
00031  *  along with this program; if not, write to the Free Software
00032  *  Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA  02111-1307  USA
00033  *
00034  */
00035 
00036 // class declaration
00037 #include <ptu46/ptu46_driver.h>
00038 
00039 // serial includes
00040 #include <sys/types.h>
00041 #include <sys/stat.h>
00042 #include <fcntl.h>
00043 #include <termios.h>
00044 #include <stdio.h>
00045 #include <strings.h>
00046 #include <unistd.h>
00047 #include <stdlib.h>
00048 #include <errno.h>
00049 #include <string.h>
00050 #include <math.h>
00051 
00052 namespace PTU46 {
00053 
00054 //
00055 // Pan-Tilt Control Class
00056 //
00057 
00058 // Constructor opens the serial port, and read the config info from it
00059 PTU46::PTU46(const char * port, int rate) {
00060     tr = pr = 1;
00061     fd = -1;
00062 
00063     // open the serial port
00064 
00065     fd = open(port, O_RDWR | O_NOCTTY | O_NDELAY);
00066     if ( fd<0 ) {
00067         fprintf(stderr, "Could not open serial device %s\n",port);
00068         return;
00069     }
00070     fcntl(fd,F_SETFL, 0);
00071 
00072     // save the current io settings
00073     tcgetattr(fd, &oldtio);
00074 
00075     // rtv - CBAUD is pre-POSIX and doesn't exist on OS X
00076     // should replace this with ispeed and ospeed instead.
00077 
00078     // set up new settings
00079     struct termios newtio;
00080     memset(&newtio, 0,sizeof(newtio));
00081     newtio.c_cflag = /*(rate & CBAUD) |*/ CS8 | CLOCAL | CREAD;
00082     newtio.c_iflag = IGNPAR;
00083     newtio.c_oflag = 0;
00084     newtio.c_lflag = ICANON;
00085 
00086     speed_t sp = B9600;
00087     switch (rate) {
00088     case 0:
00089         sp = B0;
00090         break;
00091     case 50:
00092         sp = B50;
00093         break;
00094     case 75:
00095         sp = B75;
00096         break;
00097     case 110:
00098         sp = B110;
00099         break;
00100     case 134:
00101         sp = B134;
00102         break;
00103     case 150:
00104         sp = B150;
00105         break;
00106     case 200:
00107         sp = B200;
00108         break;
00109     case 300:
00110         sp = B300;
00111         break;
00112     case 600:
00113         sp = B600;
00114         break;
00115     case 1200:
00116         sp = B1200;
00117         break;
00118     case 2400:
00119         sp = B2400;
00120         break;
00121     case 4800:
00122         sp = B4800;
00123         break;
00124     case 9600:
00125         sp = B9600;
00126         break;
00127     case 19200:
00128         sp = B19200;
00129         break;
00130     case 38400:
00131         sp = B38400;
00132         break;
00133     default:
00134         fprintf(stderr,"Failed to set serial baud rate: %d\n", rate);
00135         Disconnect();
00136         return;
00137     }
00138 
00139     if (cfsetispeed(&newtio, sp) < 0 ||   cfsetospeed(&newtio, sp) < 0) {
00140         fprintf(stderr,"Failed to set serial baud rate: %d\n", rate);
00141         Disconnect();
00142         return;
00143     }
00144     // activate new settings
00145     tcflush(fd, TCIFLUSH);
00146     tcsetattr(fd, TCSANOW, &newtio);
00147 
00148     // now set up the pan tilt camera
00149     Write(" "); // terse feedback
00150     usleep(100000);
00151     tcflush(fd, TCIFLUSH);
00152 
00153     Write("ft "); // terse feedback
00154     Write("ed "); // disable echo
00155     Write("ci "); // position mode
00156 
00157     // delay here so data has arrived at serial port so we can flush it
00158     usleep(200000);
00159     tcflush(fd, TCIFLUSH);
00160 
00161     // get pan tilt encoder res
00162     tr = GetRes(PTU46_TILT);
00163     pr = GetRes(PTU46_PAN);
00164 
00165     PMin = GetLimit(PTU46_PAN, PTU46_MIN);
00166     PMax = GetLimit(PTU46_PAN, PTU46_MAX);
00167     TMin = GetLimit(PTU46_TILT, PTU46_MIN);
00168     TMax = GetLimit(PTU46_TILT, PTU46_MAX);
00169     PSMin = GetLimit(PTU46_PAN, PTU46_MIN_SPEED);
00170     PSMax = GetLimit(PTU46_PAN, PTU46_MAX_SPEED);
00171     TSMin = GetLimit(PTU46_TILT, PTU46_MIN_SPEED);
00172     TSMax = GetLimit(PTU46_TILT, PTU46_MAX_SPEED);
00173 
00174     if (tr <= 0 || pr <= 0 || PMin == 0 || PMax == 0 || TMin == 0 || TMax == 0) {
00175         // if limit request failed try resetting the unit and then getting limits..
00176         Write(" r "); // reset pan-tilt unit (also clears any bad input on serial port)
00177 
00178         // wait for reset to complete
00179         int len = 0;
00180         char temp;
00181         char response[10] = "!T!T!P!P*";
00182 
00183         for (int i = 0; i < 9; ++i) {
00184             while ((len = read(fd, &temp, 1 )) == 0) {};
00185             if ((len != 1) || (temp != response[i])) {
00186                 fprintf(stderr,"Error Resetting Pan Tilt unit\n");
00187                 fprintf(stderr,"Stopping access to pan-tilt unit\n");
00188                 Disconnect();
00189             }
00190         }
00191 
00192         // delay here so data has arrived at serial port so we can flush it
00193         usleep(100000);
00194         tcflush(fd, TCIFLUSH);
00195 
00196 
00197         // get pan tilt encoder res
00198         tr = GetRes(PTU46_TILT);
00199         pr = GetRes(PTU46_PAN);
00200 
00201         PMin = GetLimit(PTU46_PAN, PTU46_MIN);
00202         PMax = GetLimit(PTU46_PAN, PTU46_MAX);
00203         TMin = GetLimit(PTU46_TILT, PTU46_MIN);
00204         TMax = GetLimit(PTU46_TILT, PTU46_MAX);
00205         PSMin = GetLimit(PTU46_PAN, PTU46_MIN_SPEED);
00206         PSMax = GetLimit(PTU46_PAN, PTU46_MAX_SPEED);
00207         TSMin = GetLimit(PTU46_TILT, PTU46_MIN_SPEED);
00208         TSMax = GetLimit(PTU46_TILT, PTU46_MAX_SPEED);
00209 
00210         if (tr <= 0 || pr <= 0 || PMin == 0 || PMax == 0 || TMin == 0 || TMax == 0) {
00211             // if it really failed give up and disable the driver
00212             fprintf(stderr,"Error getting pan-tilt resolution...is the serial port correct?\n");
00213             fprintf(stderr,"Stopping access to pan-tilt unit\n");
00214             Disconnect();
00215         }
00216     }
00217 }
00218 
00219 
00220 PTU46::~PTU46() {
00221     Disconnect();
00222 }
00223 
00224 void PTU46::Disconnect() {
00225     if (fd > 0) {
00226         // restore old port settings
00227         tcsetattr(fd, TCSANOW, &oldtio);
00228         // close the connection
00229         close(fd);
00230         fd = -1;
00231     }
00232 }
00233 
00234 int PTU46::Write(const char * data, int length) {
00235 
00236     if (fd < 0)
00237         return -1;
00238 
00239     // autocalculate if using short form
00240     if (length == 0)
00241         length = strlen(data);
00242 
00243     // ugly error handling, if write fails then shut down unit
00244     if (write(fd, data, length) < length) {
00245         fprintf(stderr,"Error writing to Pan Tilt Unit, disabling\n");
00246         Disconnect();
00247         return -1;
00248     }
00249     return 0;
00250 }
00251 
00252 
00253 // get radians/count resolution
00254 float PTU46::GetRes(char type) {
00255     if (fd < 0)
00256         return -1;
00257     char cmd[4] = " r ";
00258     cmd[0] = type;
00259 
00260     // get pan res
00261     int len = 0;
00262     Write(cmd);
00263     len = read(fd, buffer, PTU46_BUFFER_LEN );
00264 
00265     if (len < 3 || buffer[0] != '*') {
00266         fprintf(stderr,"Error getting pan-tilt res\n");
00267         return -1;
00268     }
00269 
00270     buffer[len] = '\0';
00271     double z = strtod(&buffer[2],NULL);
00272     z = z/3600; // degrees/count
00273     return  z*M_PI/180; //radians/count
00274 }
00275 
00276 // get position limit
00277 int PTU46::GetLimit(char type, char LimType) {
00278     if (fd < 0)
00279         return -1;
00280     char cmd[4] = "   ";
00281     cmd[0] = type;
00282     cmd[1] = LimType;
00283 
00284     // get limit
00285     int len = 0;
00286     Write(cmd);
00287     len = read(fd, buffer, PTU46_BUFFER_LEN );
00288 
00289     if (len < 3 || buffer[0] != '*') {
00290         fprintf(stderr,"Error getting pan-tilt limit\n");
00291         return -1;
00292     }
00293 
00294     buffer[len] = '\0';
00295     return strtol(&buffer[2],NULL,0);
00296 }
00297 
00298 
00299 // get position in radians
00300 float PTU46::GetPosition (char type) {
00301     if (fd < 0)
00302         return -1;
00303 
00304     char cmd[4] = " p ";
00305     cmd[0] = type;
00306 
00307     // get pan pos
00308     int len = 0;
00309     Write (cmd);
00310     len = read (fd, buffer, PTU46_BUFFER_LEN );
00311 
00312     if (len < 3 || buffer[0] != '*') {
00313         fprintf(stderr,"Error getting pan-tilt pos\n");
00314         return -1;
00315     }
00316 
00317     buffer[len] = '\0';
00318 
00319     return strtod (&buffer[2],NULL) * GetResolution(type);
00320 }
00321 
00322 
00323 // set position in radians
00324 bool PTU46::SetPosition (char type, float pos, bool Block) {
00325     if (fd < 0)
00326         return false;
00327 
00328     // get raw encoder count to move
00329     int Count = static_cast<int> (pos/GetResolution(type));
00330 
00331     // Check limits
00332     if (Count < (type == PTU46_TILT ? TMin : PMin) || Count > (type == PTU46_TILT ? TMax : PMax)) {
00333         fprintf (stderr,"Pan Tilt Value out of Range: %c %f(%d) (%d-%d)\n", type, pos, Count, (type == PTU46_TILT ? TMin : PMin),(type == PTU46_TILT ? TMax : PMax));
00334         return false;
00335     }
00336 
00337     char cmd[16];
00338     snprintf (cmd,16,"%cp%d ",type,Count);
00339 
00340     // set pos
00341     int len = 0;
00342     Write (cmd);
00343     len = read (fd, buffer, PTU46_BUFFER_LEN );
00344 
00345     if (len <= 0 || buffer[0] != '*') {
00346         fprintf(stderr,"Error setting pan-tilt pos\n");
00347         return false;
00348     }
00349 
00350     if (Block)
00351         while (GetPosition (type) != pos) {};
00352 
00353     return true;
00354 }
00355 
00356 // get speed in radians/sec
00357 float PTU46::GetSpeed (char type) {
00358     if (fd < 0)
00359         return -1;
00360 
00361     char cmd[4] = " s ";
00362     cmd[0] = type;
00363 
00364     // get speed
00365     int len = 0;
00366     Write (cmd);
00367     len = read (fd, buffer, PTU46_BUFFER_LEN );
00368 
00369     if (len < 3 || buffer[0] != '*') {
00370         fprintf (stderr,"Error getting pan-tilt speed\n");
00371         return -1;
00372     }
00373 
00374     buffer[len] = '\0';
00375 
00376     return strtod(&buffer[2],NULL) * GetResolution(type);
00377 }
00378 
00379 
00380 
00381 // set speed in radians/sec
00382 bool PTU46::SetSpeed (char type, float pos) {
00383     if (fd < 0)
00384         return false;
00385 
00386     // get raw encoder speed to move
00387     int Count = static_cast<int> (pos/GetResolution(type));
00388     // Check limits
00389     if (abs(Count) < (type == PTU46_TILT ? TSMin : PSMin) || abs(Count) > (type == PTU46_TILT ? TSMax : PSMax)) {
00390         fprintf (stderr,"Pan Tilt Speed Value out of Range: %c %f(%d) (%d-%d)\n", type, pos, Count, (type == PTU46_TILT ? TSMin : PSMin),(type == PTU46_TILT ? TSMax : PSMax));
00391         return false;
00392     }
00393 
00394     char cmd[16];
00395     snprintf (cmd,16,"%cs%d ",type,Count);
00396 
00397     // set speed
00398     int len = 0;
00399     Write (cmd);
00400     len = read (fd, buffer, PTU46_BUFFER_LEN );
00401 
00402     if (len <= 0 || buffer[0] != '*') {
00403         fprintf (stderr,"Error setting pan-tilt speed\n");
00404         return false;
00405     }
00406     return true;
00407 }
00408 
00409 
00410 // set movement mode (position/velocity)
00411 bool PTU46::SetMode (char type) {
00412     if (fd < 0)
00413         return false;
00414 
00415     char cmd[4] = "c  ";
00416     cmd[1] = type;
00417 
00418     // set mode
00419     int len = 0;
00420     Write (cmd);
00421     len = read (fd, buffer, PTU46_BUFFER_LEN );
00422 
00423     if (len <= 0 || buffer[0] != '*') {
00424         fprintf (stderr,"Error setting pan-tilt move mode\n");
00425         return false;
00426     }
00427     return true;
00428 }
00429 
00430 // get ptu mode
00431 char PTU46::GetMode () {
00432     if (fd < 0)
00433         return -1;
00434 
00435     // get pan tilt mode
00436     int len = 0;
00437     Write ("c ");
00438     len = read (fd, buffer, PTU46_BUFFER_LEN );
00439 
00440     if (len < 3 || buffer[0] != '*') {
00441         fprintf (stderr,"Error getting pan-tilt pos\n");
00442         return -1;
00443     }
00444 
00445     if (buffer[2] == 'p')
00446         return PTU46_VELOCITY;
00447     else if (buffer[2] == 'i')
00448         return PTU46_POSITION;
00449     else
00450         return -1;
00451 }
00452 
00453 }


ptu46
Author(s): Erik Karulf, David V. Lu!!
autogenerated on Fri Aug 28 2015 12:58:57