atrvjr_driver.cc
Go to the documentation of this file.
00001 /*
00002  *  ATRVJR Driver, modified by Mikhail Medvedev from
00003  *  B21 Driver - By David Lu!! 2/2010
00004  *  Modified from Player code
00005  *
00006  *  Player - One Hell of a Robot Server
00007  *  Copyright (C) 2000
00008  *     Brian Gerkey, Kasper Stoy, Richard Vaughan, & Andrew Howard
00009  *
00010  *
00011  *  This program is free software; you can redistribute it and/or modify
00012  *  it under the terms of the GNU General Public License as published by
00013  *  the Free Software Foundation; either version 2 of the License, or
00014  *  (at your option) any later version.
00015  *
00016  *  This program is distributed in the hope that it will be useful,
00017  *  but WITHOUT ANY WARRANTY; without even the implied warranty of
00018  *  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
00019  *  GNU General Public License for more details.
00020  *
00021  *  You should have received a copy of the GNU General Public License
00022  *  along with this program; if not, write to the Free Software
00023  *  Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA  02111-1307  USA
00024  *
00025  */
00026 
00027 #include <rflex/atrvjr_driver.h>
00028 #include <rflex/atrvjr_config.h>
00029 #include <math.h>
00030 
00031 ATRVJR::ATRVJR() {
00032     found_distance = false;
00033     bumps = new int*[2];
00034 
00035     for (int index=0;index<2;index++) {
00036         bumps[index] = new int[BUMPERS_PER[index]];
00037         for (int i=0;i<BUMPERS_PER[index];i++) {
00038             bumps[index][i] =0;
00039         }
00040     }
00041 
00042 }
00043 
00044 ATRVJR::~ATRVJR() {
00045     delete bumps[0];
00046     delete bumps[1];
00047     delete bumps;
00048 }
00049 
00050 float ATRVJR::getDistance() {
00051     if (!found_distance && isOdomReady()) {
00052         first_distance = distance;
00053         found_distance = true;
00054     }
00055 
00056     return (distance-first_distance) / (float) ODO_DISTANCE_CONVERSION;
00057 }
00058 
00059 float ATRVJR::getBearing() {
00060     return (bearing-HOME_BEARING) / (float) ODO_ANGLE_CONVERSION;
00061 }
00062 
00063 float ATRVJR::getTranslationalVelocity() const {
00064     return transVelocity / (float) ODO_DISTANCE_CONVERSION;
00065 }
00066 
00067 float ATRVJR::getRotationalVelocity() const {
00068     return rotVelocity / (float) ODO_ANGLE_CONVERSION;
00069 }
00070 
00071 float ATRVJR::getVoltage() const {
00072     if (voltage==0.0)
00073         return 0.0;
00074     else
00075         return voltage/100.0 + POWER_OFFSET;
00076 }
00077 
00078 bool ATRVJR::isPluggedIn() const {
00079     float v = getVoltage();
00080     if (v>PLUGGED_THRESHOLD)
00081         return true;
00082     else
00083         return false;
00084 }
00085 
00086 int ATRVJR::getNumBodySonars() const {
00087     return SONARS_PER_RING[BODY_INDEX];
00088 }
00089 
00090 int ATRVJR::getNumBaseSonars() const {
00091     return SONARS_PER_RING[BASE_INDEX];
00092 }
00093 
00094 void ATRVJR::getBodySonarReadings(float* readings) const {
00095     getSonarReadings(BODY_INDEX, readings);
00096 }
00097 
00098 void ATRVJR::getBaseSonarReadings(float* readings) const {
00099     getSonarReadings(BASE_INDEX, readings);
00100 }
00101 
00102 void ATRVJR::getBodySonarPoints(sensor_msgs::PointCloud* cloud) const {
00103     getSonarPoints(BODY_INDEX, cloud);
00104 }
00105 void ATRVJR::getBaseSonarPoints(sensor_msgs::PointCloud* cloud) const {
00106     getSonarPoints(BASE_INDEX, cloud);
00107 }
00108 
00109 int ATRVJR::getBodyBumps(sensor_msgs::PointCloud* cloud) const {
00110     return getBumps(BODY_INDEX, cloud);
00111 }
00112 
00113 int ATRVJR::getBaseBumps(sensor_msgs::PointCloud* cloud) const {
00114     return getBumps(BASE_INDEX, cloud);
00115 }
00116 
00117 void ATRVJR::setSonarPower(bool on) {
00118     unsigned long echo, ping, set, val;
00119     if (on) {
00120         echo = SONAR_ECHO_DELAY;
00121         ping = SONAR_PING_DELAY;
00122         set = SONAR_SET_DELAY;
00123         val = 2;
00124     } else {
00125         echo = ping = set = val = 0;
00126     }
00127     configureSonar(echo, ping, set, val);
00128 }
00129 
00130 
00131 void ATRVJR::setMovement( float tvel, float rvel,
00132                        float acceleration ) {
00133     setVelocity(tvel * ODO_DISTANCE_CONVERSION,
00134                 rvel * ODO_ANGLE_CONVERSION,
00135                 acceleration * ODO_DISTANCE_CONVERSION);
00136 }
00137 
00138 
00139 void ATRVJR::getSonarReadings(const int ringi, float* adjusted_ranges) const {
00140     int i = 0;
00141     for (int x = SONAR_RING_BANK_BOUND[ringi];x<SONAR_RING_BANK_BOUND[ringi+1];x++) {
00142         for (int y=0;y<SONARS_PER_BANK[x];y++) {
00143             int range = sonar_ranges[x*SONAR_MAX_PER_BANK+y];
00144             if (range > SONAR_MAX_RANGE)
00145                 range = SONAR_MAX_RANGE;
00146             float fRange = range / (float) RANGE_CONVERSION;
00147             adjusted_ranges[i] = fRange;
00148             i++;
00149         }
00150     }
00151 }
00152 
00153 void ATRVJR::getSonarPoints(const int ringi, sensor_msgs::PointCloud* cloud) const {
00154     int numSonar = SONARS_PER_RING[ringi];
00155     float* readings = new float[numSonar];
00156     getSonarReadings(ringi, readings);
00157     cloud->points.resize(numSonar);
00158     int c = 0;
00159     for (int i = 0; i < numSonar; ++i) {
00160         if (readings[i] < SONAR_MAX_RANGE/ (float) RANGE_CONVERSION) {
00161             double angle =  SONAR_RING_START_ANGLE[ringi] + SONAR_RING_ANGLE_INC[ringi]*i;
00162             angle *= M_PI / 180.0;
00163 
00164             double d = SONAR_RING_DIAMETER[ringi] + readings[i];
00165             cloud->points[c].x = cos(angle)*d;
00166             cloud->points[c].y = sin(angle)*d;
00167             cloud->points[c].z = SONAR_RING_HEIGHT[ringi];
00168             c++;
00169         }
00170     }
00171 }
00172 
00173 int ATRVJR::getBumps(const int index, sensor_msgs::PointCloud* cloud) const {
00174     int c = 0;
00175     double wedge = 2 * M_PI / BUMPERS_PER[index];
00176     double d = SONAR_RING_DIAMETER[index]*1.1;
00177     int total = 0;
00178     for (int i=0;i<BUMPERS_PER[index];i++) {
00179         int value = bumps[index][i];
00180         for (int j=0;j<4;j++) {
00181             int mask = 1 << j;
00182             if ((value & mask) > 0) {
00183                 total++;
00184             }
00185         }
00186     }
00187 
00188     cloud->points.resize(total);
00189     if (total==0)
00190         return 0;
00191     for (int i=0;i<BUMPERS_PER[index];i++) {
00192         int value = bumps[index][i];
00193         double angle = wedge * (2.5 - i);
00194         for (int j=0;j<4;j++) {
00195             int mask = 1 << j;
00196             if ((value & mask) > 0) {
00197                 double aoff = BUMPER_ANGLE_OFFSET[j]*wedge/3;
00198                 cloud->points[c].x = cos(angle-aoff)*d;
00199                 cloud->points[c].y = sin(angle-aoff)*d;
00200                 cloud->points[c].z = BUMPER_HEIGHT_OFFSET[index][j];
00201                 c++;
00202             }
00203         }
00204     }
00205     return total;
00206 
00207 }
00208 
00209 void ATRVJR::processDioEvent(unsigned char address, unsigned short data) {
00210 
00211     if (address == HEADING_HOME_ADDRESS) {
00212         home_bearing = bearing;
00213         //printf("ATRVJR Home %f \n", home_bearing / (float) ODO_ANGLE_CONVERSION);
00214     }// check if the dio packet came from a bumper packet
00215     else if ((address >= BUMPER_ADDRESS) && (address < (BUMPER_ADDRESS+BUMPER_COUNT))) {
00216         int index =0, rot = address - BUMPER_ADDRESS;
00217         if (rot > BUMPERS_PER[index]) {
00218             rot -= BUMPERS_PER[index];
00219             index++;
00220         }
00221         bumps[index][rot] = data;
00222     } else {
00223         //printf("ATRVJR DIO: address 0x%02x (%d) value 0x%02x (%d)\n", address, address, data, data);
00224     }
00225 }
00226 
00227 


rflex
Author(s): David V. Lu!!, Mikhail Medvedev
autogenerated on Fri Aug 28 2015 12:58:58