driver.cpp
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 #include <boost/lexical_cast.hpp>
00032 #include <boost/algorithm/string/trim.hpp>
00033 #include <flir_ptu_driver/driver.h>
00034 #include <serial/serial.h>
00035 #include <ros/console.h>
00036 
00037 #include <math.h>
00038 #include <string>
00039 
00040 using boost::lexical_cast;
00041 
00042 
00043 namespace flir_ptu_driver
00044 {
00045 
00049 template<typename T>
00050 T parseResponse(std::string responseBuffer)
00051 {
00052   std::string trimmed = responseBuffer.substr(1);
00053   boost::trim(trimmed);
00054   T parsed = lexical_cast<T>(trimmed);
00055   ROS_DEBUG_STREAM("Parsed response value: " << parsed);
00056   return parsed;
00057 }
00058 
00059 bool PTU::initialized()
00060 {
00061   return !!ser_ && ser_->isOpen() && initialized_;
00062 }
00063 
00064 bool PTU::initialize()
00065 {
00066   ser_->write("ft ");  // terse feedback
00067   ser_->write("ed ");  // disable echo
00068   ser_->write("ci ");  // position mode
00069   ser_->read(20);
00070 
00071   // get pan tilt encoder res
00072   tr = getRes(PTU_TILT);
00073   pr = getRes(PTU_PAN);
00074 
00075   PMin = getLimit(PTU_PAN, PTU_MIN);
00076   PMax = getLimit(PTU_PAN, PTU_MAX);
00077   TMin = getLimit(PTU_TILT, PTU_MIN);
00078   TMax = getLimit(PTU_TILT, PTU_MAX);
00079   PSMin = getLimit(PTU_PAN, PTU_MIN_SPEED);
00080   PSMax = getLimit(PTU_PAN, PTU_MAX_SPEED);
00081   TSMin = getLimit(PTU_TILT, PTU_MIN_SPEED);
00082   TSMax = getLimit(PTU_TILT, PTU_MAX_SPEED);
00083 
00084   if (tr <= 0 || pr <= 0 || PMin == -1 || PMax == -1 || TMin == -1 || TMax == -1)
00085   {
00086     initialized_ = false;
00087   }
00088   else
00089   {
00090     initialized_ = true;
00091   }
00092 
00093   return initialized();
00094 }
00095 
00096 std::string PTU::sendCommand(std::string command)
00097 {
00098   ser_->write(command);
00099   ROS_DEBUG_STREAM("TX: " << command);
00100   std::string buffer = ser_->readline(PTU_BUFFER_LEN);
00101   ROS_DEBUG_STREAM("RX: " << buffer);
00102   return buffer;
00103 }
00104 
00105 bool PTU::home()
00106 {
00107   ROS_INFO("Sending command to reset PTU.");
00108 
00109   // Issue reset command
00110   ser_->flush();
00111   ser_->write(" r ");
00112 
00113   std::string actual_response, expected_response("!T!T!P!P*");
00114 
00115   // 30 seconds to receive full confirmation of reset action completed.
00116   for (int i = 0; i < 300; i++)
00117   {
00118     usleep(100000);
00119 
00120     if (ser_->available() >= expected_response.length())
00121     {
00122       ROS_INFO("PTU reset command response received.");
00123       ser_->read(actual_response, expected_response.length());
00124       return (actual_response == expected_response);
00125     }
00126   }
00127 
00128   ROS_WARN("PTU reset command response not received before timeout.");
00129   return false;
00130 }
00131 
00132 // get radians/count resolution
00133 float PTU::getRes(char type)
00134 {
00135   if (!ser_ || !ser_->isOpen()) return -1;
00136 
00137   std::string buffer = sendCommand(std::string() + type + "r ");
00138 
00139   if (buffer.length() < 3 || buffer[0] != '*')
00140   {
00141     ROS_ERROR("Error getting pan-tilt res");
00142     return -1;
00143   }
00144 
00145   double z = parseResponse<double>(buffer);
00146   z = z / 3600;  // degrees/count
00147   return z * M_PI / 180;  // radians/count
00148 }
00149 
00150 // get position limit
00151 int PTU::getLimit(char type, char limType)
00152 {
00153   if (!ser_ || !ser_->isOpen()) return -1;
00154 
00155   std::string buffer = sendCommand(std::string() + type + limType + " ");
00156 
00157   if (buffer.length() < 3 || buffer[0] != '*')
00158   {
00159     ROS_ERROR("Error getting pan-tilt limit");
00160     return -1;
00161   }
00162 
00163   return parseResponse<int>(buffer);
00164 }
00165 
00166 
00167 // get position in radians
00168 float PTU::getPosition(char type)
00169 {
00170   if (!initialized()) return -1;
00171 
00172   std::string buffer = sendCommand(std::string() + type + "p ");
00173 
00174   if (buffer.length() < 3 || buffer[0] != '*')
00175   {
00176     ROS_ERROR("Error getting pan-tilt pos");
00177     return -1;
00178   }
00179 
00180   return parseResponse<double>(buffer) * getResolution(type);
00181 }
00182 
00183 
00184 // set position in radians
00185 bool PTU::setPosition(char type, float pos, bool block)
00186 {
00187   if (!initialized()) return false;
00188 
00189   // get raw encoder count to move
00190   int count = static_cast<int>(pos / getResolution(type));
00191 
00192   // Check limits
00193   if (count < (type == PTU_TILT ? TMin : PMin) || count > (type == PTU_TILT ? TMax : PMax))
00194   {
00195     ROS_ERROR("Pan Tilt Value out of Range: %c %f(%d) (%d-%d)\n",
00196               type, pos, count, (type == PTU_TILT ? TMin : PMin), (type == PTU_TILT ? TMax : PMax));
00197     return false;
00198   }
00199 
00200   std::string buffer = sendCommand(std::string() + type + "p" +
00201                                    lexical_cast<std::string>(count) + " ");
00202 
00203   if (buffer.empty() || buffer[0] != '*')
00204   {
00205     ROS_ERROR("Error setting pan-tilt pos");
00206     return false;
00207   }
00208 
00209   if (block)
00210     while (getPosition(type) != pos) {};
00211 
00212   return true;
00213 }
00214 
00215 // get speed in radians/sec
00216 float PTU::getSpeed(char type)
00217 {
00218   if (!initialized()) return -1;
00219 
00220   std::string buffer = sendCommand(std::string() + type + "s ");
00221 
00222   if (buffer.length() < 3 || buffer[0] != '*')
00223   {
00224     ROS_ERROR("Error getting pan-tilt speed");
00225     return -1;
00226   }
00227 
00228   return parseResponse<double>(buffer) * getResolution(type);
00229 }
00230 
00231 
00232 
00233 // set speed in radians/sec
00234 bool PTU::setSpeed(char type, float pos)
00235 {
00236   if (!initialized()) return false;
00237 
00238   // get raw encoder speed to move
00239   int count = static_cast<int>(pos / getResolution(type));
00240 
00241   // Check limits
00242   if (abs(count) < (type == PTU_TILT ? TSMin : PSMin) || abs(count) > (type == PTU_TILT ? TSMax : PSMax))
00243   {
00244     ROS_ERROR("Pan Tilt Speed Value out of Range: %c %f(%d) (%d-%d)\n",
00245               type, pos, count, (type == PTU_TILT ? TSMin : PSMin), (type == PTU_TILT ? TSMax : PSMax));
00246     return false;
00247   }
00248 
00249   std::string buffer = sendCommand(std::string() + type + "s" +
00250                                    lexical_cast<std::string>(count) + " ");
00251 
00252   if (buffer.empty() || buffer[0] != '*')
00253   {
00254     ROS_ERROR("Error setting pan-tilt speed\n");
00255     return false;
00256   }
00257 
00258   return true;
00259 }
00260 
00261 
00262 // set movement mode (position/velocity)
00263 bool PTU::setMode(char type)
00264 {
00265   if (!initialized()) return false;
00266 
00267   std::string buffer = sendCommand(std::string("c") + type + " ");
00268 
00269   if (buffer.empty() || buffer[0] != '*')
00270   {
00271     ROS_ERROR("Error setting pan-tilt move mode");
00272     return false;
00273   }
00274 
00275   return true;
00276 }
00277 
00278 // get ptu mode
00279 char PTU::getMode()
00280 {
00281   if (!initialized()) return -1;
00282 
00283   // get pan tilt mode
00284   std::string buffer = sendCommand("c ");
00285 
00286   if (buffer.length() < 3 || buffer[0] != '*')
00287   {
00288     ROS_ERROR("Error getting pan-tilt pos");
00289     return -1;
00290   }
00291 
00292   if (buffer[2] == 'p')
00293     return PTU_VELOCITY;
00294   else if (buffer[2] == 'i')
00295     return PTU_POSITION;
00296   else
00297     return -1;
00298 }
00299 
00300 }  // namespace flir_ptu_driver


flir_ptu_driver
Author(s): Erik Karulf , David V. Lu , Nick Hawes
autogenerated on Fri Aug 28 2015 10:39:27