create.cpp
Go to the documentation of this file.
00001 #include <boost/bind.hpp>
00002 #include <boost/make_shared.hpp>
00003 #include <iostream>
00004 #include <cmath>
00005 #include <ctime>
00006 #include <assert.h>
00007 
00008 #include "create/create.h"
00009 
00010 #define GET_DATA(id) (data->getPacket(id)->getData())
00011 #define BOUND_CONST(val,min,max) (val<min?min:(val>max?max:val))
00012 #define BOUND(val,min,max) (val = BOUND_CONST(val,min,max))
00013 
00014 namespace create {
00015 
00016   namespace ublas = boost::numeric::ublas;
00017 
00018   // TODO: Handle SIGINT to do clean disconnect
00019 
00020   void Create::init() {
00021     mainMotorPower = 0;
00022     sideMotorPower = 0;
00023     vacuumMotorPower = 0;
00024     debrisLED = 0;
00025     spotLED = 0;
00026     dockLED = 0;
00027     checkLED = 0;
00028     powerLED = 0;
00029     powerLEDIntensity = 0;
00030     prevTicksLeft = 0;
00031     prevTicksRight = 0;
00032     totalLeftDist = 0.0;
00033     totalRightDist = 0.0;
00034     firstOnData = true;
00035     mode = MODE_OFF;
00036     pose.x = 0;
00037     pose.y = 0;
00038     pose.yaw = 0;
00039     pose.covariance = std::vector<float>(9, 0.0);
00040     vel.x = 0;
00041     vel.y = 0;
00042     vel.yaw = 0;
00043     vel.covariance = std::vector<float>(9, 0.0);
00044     poseCovar = Matrix(3, 3, 0.0);
00045     requestedLeftVel = 0;
00046     requestedRightVel = 0;
00047     data = boost::shared_ptr<Data>(new Data(model.getVersion()));
00048     if (model.getVersion() == V_1) {
00049       serial = boost::make_shared<SerialQuery>(data);
00050     } else {
00051       serial = boost::make_shared<SerialStream>(data);
00052     }
00053   }
00054 
00055   Create::Create(RobotModel m) : model(m) {
00056     init();
00057   }
00058 
00059   Create::Create(const std::string& dev, const int& baud, RobotModel m) : model(m) {
00060     init();
00061     serial->connect(dev, baud);
00062   }
00063 
00064   Create::~Create() {
00065     disconnect();
00066   }
00067 
00068   Create::Matrix Create::addMatrices(const Matrix &A, const Matrix &B) const {
00069     int rows = A.size1();
00070     int cols = A.size2();
00071 
00072     assert(rows == B.size1());
00073     assert(cols == B.size2());
00074 
00075     Matrix C(rows, cols);
00076     for (int i = 0; i < rows; i++) {
00077       for (int j = 0; j < cols; j++) {
00078         const float a = A(i, j);
00079         const float b = B(i, j);
00080         if (util::willFloatOverflow(a, b)) {
00081           // If overflow, set to float min or max depending on direction of overflow
00082           C(i, j) = (a < 0.0) ? std::numeric_limits<float>::min() : std::numeric_limits<float>::max();
00083         }
00084         else {
00085           C(i, j) = a + b;
00086         }
00087       }
00088     }
00089     return C;
00090   }
00091 
00092   void Create::onData() {
00093     if (firstOnData) {
00094       if (model.getVersion() >= V_3) {
00095         // Initialize tick counts
00096         prevTicksLeft = GET_DATA(ID_LEFT_ENC);
00097         prevTicksRight = GET_DATA(ID_RIGHT_ENC);
00098       }
00099       prevOnDataTime = util::getTimestamp();
00100       firstOnData = false;
00101     }
00102 
00103     // Get current time
00104     util::timestamp_t curTime = util::getTimestamp();
00105     float dt = (curTime - prevOnDataTime) / 1000000.0;
00106     float deltaDist, deltaX, deltaY, deltaYaw, leftWheelDist, rightWheelDist, wheelDistDiff;
00107 
00108     // Protocol versions 1 and 2 use distance and angle fields for odometry
00109     int16_t angleField;
00110     if (model.getVersion() <= V_2) {
00111       // This is a standards compliant way of doing unsigned to signed conversion
00112       uint16_t distanceRaw = GET_DATA(ID_DISTANCE);
00113       int16_t distance;
00114       std::memcpy(&distance, &distanceRaw, sizeof(distance));
00115       deltaDist = distance / 1000.0; // mm -> m
00116 
00117       // Angle is processed differently in versions 1 and 2
00118       uint16_t angleRaw = GET_DATA(ID_ANGLE);
00119       std::memcpy(&angleField, &angleRaw, sizeof(angleField));
00120     }
00121 
00122     if (model.getVersion() == V_1) {
00123       wheelDistDiff = 2.0 * angleField / 1000.0;
00124       leftWheelDist = deltaDist - (wheelDistDiff / 2.0);
00125       rightWheelDist = deltaDist + (wheelDistDiff / 2.0);
00126       deltaYaw = wheelDistDiff / model.getAxleLength();
00127     } else if (model.getVersion() == V_2) {
00128       /* * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * *
00129        * Certain older Creates have major problems with odometry                   *
00130        * http://answers.ros.org/question/31935/createroomba-odometry/              *
00131        *                                                                           *
00132        * All Creates have an issue with rounding of the angle field, which causes  *
00133        * major errors to accumulate in the odometry yaw.                           *
00134        * http://wiki.tekkotsu.org/index.php/Create_Odometry_Bug                    *
00135        * https://github.com/AutonomyLab/create_autonomy/issues/28                  *
00136        *                                                                           *
00137        * TODO: Consider using velocity command as substitute for pose estimation   *
00138        * to mitigate both of these problems.                                       *
00139        * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * */
00140       deltaYaw = angleField * (util::PI / 180.0); // D2R
00141       wheelDistDiff = model.getAxleLength() * deltaYaw;
00142       leftWheelDist = deltaDist - (wheelDistDiff / 2.0);
00143       rightWheelDist = deltaDist + (wheelDistDiff / 2.0);
00144     } else if (model.getVersion() >= V_3) {
00145       // Get cumulative ticks (wraps around at 65535)
00146       uint16_t totalTicksLeft = GET_DATA(ID_LEFT_ENC);
00147       uint16_t totalTicksRight = GET_DATA(ID_RIGHT_ENC);
00148       // Compute ticks since last update
00149       int ticksLeft = totalTicksLeft - prevTicksLeft;
00150       int ticksRight = totalTicksRight - prevTicksRight;
00151       prevTicksLeft = totalTicksLeft;
00152       prevTicksRight = totalTicksRight;
00153 
00154       // Handle wrap around
00155       if (fabs(ticksLeft) > 0.9 * util::V_3_MAX_ENCODER_TICKS) {
00156         ticksLeft = (ticksLeft % util::V_3_MAX_ENCODER_TICKS) + 1;
00157       }
00158       if (fabs(ticksRight) > 0.9 * util::V_3_MAX_ENCODER_TICKS) {
00159         ticksRight = (ticksRight % util::V_3_MAX_ENCODER_TICKS) + 1;
00160       }
00161 
00162       // Compute distance travelled by each wheel
00163       leftWheelDist = (ticksLeft / util::V_3_TICKS_PER_REV)
00164           * model.getWheelDiameter() * util::PI;
00165       rightWheelDist = (ticksRight / util::V_3_TICKS_PER_REV)
00166           * model.getWheelDiameter() * util::PI;
00167       deltaDist = (rightWheelDist + leftWheelDist) / 2.0;
00168 
00169       wheelDistDiff = rightWheelDist - leftWheelDist;
00170       deltaYaw = wheelDistDiff / model.getAxleLength();
00171     }
00172 
00173     // Moving straight
00174     if (fabs(wheelDistDiff) < util::EPS) {
00175       deltaX = deltaDist * cos(pose.yaw);
00176       deltaY = deltaDist * sin(pose.yaw);
00177     } else {
00178       float turnRadius = (model.getAxleLength() / 2.0) * (leftWheelDist + rightWheelDist) / wheelDistDiff;
00179       deltaX = turnRadius * (sin(pose.yaw + deltaYaw) - sin(pose.yaw));
00180       deltaY = -turnRadius * (cos(pose.yaw + deltaYaw) - cos(pose.yaw));
00181     }
00182 
00183     totalLeftDist += leftWheelDist;
00184     totalRightDist += rightWheelDist;
00185 
00186     if (fabs(dt) > util::EPS) {
00187       vel.x = deltaDist / dt;
00188       vel.y = 0.0;
00189       vel.yaw = deltaYaw / dt;
00190     } else {
00191       vel.x = 0.0;
00192       vel.y = 0.0;
00193       vel.yaw = 0.0;
00194     }
00195 
00196     // Update covariances
00197     // Ref: "Introduction to Autonomous Mobile Robots" (Siegwart 2004, page 189)
00198     float kr = 1.0; // TODO: Perform experiments to find these nondeterministic parameters
00199     float kl = 1.0;
00200     float cosYawAndHalfDelta = cos(pose.yaw + (deltaYaw / 2.0)); // deltaX?
00201     float sinYawAndHalfDelta = sin(pose.yaw + (deltaYaw / 2.0)); // deltaY?
00202     float distOverTwoWB = deltaDist / (model.getAxleLength() * 2.0);
00203 
00204     Matrix invCovar(2, 2);
00205     invCovar(0, 0) = kr * fabs(rightWheelDist);
00206     invCovar(0, 1) = 0.0;
00207     invCovar(1, 0) = 0.0;
00208     invCovar(1, 1) = kl * fabs(leftWheelDist);
00209 
00210     Matrix Finc(3, 2);
00211     Finc(0, 0) = (cosYawAndHalfDelta / 2.0) - (distOverTwoWB * sinYawAndHalfDelta);
00212     Finc(0, 1) = (cosYawAndHalfDelta / 2.0) + (distOverTwoWB * sinYawAndHalfDelta);
00213     Finc(1, 0) = (sinYawAndHalfDelta / 2.0) + (distOverTwoWB * cosYawAndHalfDelta);
00214     Finc(1, 1) = (sinYawAndHalfDelta / 2.0) - (distOverTwoWB * cosYawAndHalfDelta);
00215     Finc(2, 0) = (1.0 / model.getAxleLength());
00216     Finc(2, 1) = (-1.0 / model.getAxleLength());
00217     Matrix FincT = boost::numeric::ublas::trans(Finc);
00218 
00219     Matrix Fp(3, 3);
00220     Fp(0, 0) = 1.0;
00221     Fp(0, 1) = 0.0;
00222     Fp(0, 2) = (-deltaDist) * sinYawAndHalfDelta;
00223     Fp(1, 0) = 0.0;
00224     Fp(1, 1) = 1.0;
00225     Fp(1, 2) = deltaDist * cosYawAndHalfDelta;
00226     Fp(2, 0) = 0.0;
00227     Fp(2, 1) = 0.0;
00228     Fp(2, 2) = 1.0;
00229     Matrix FpT = boost::numeric::ublas::trans(Fp);
00230 
00231     Matrix velCovar = ublas::prod(invCovar, FincT);
00232     velCovar = ublas::prod(Finc, velCovar);
00233 
00234     vel.covariance[0] = velCovar(0, 0);
00235     vel.covariance[1] = velCovar(0, 1);
00236     vel.covariance[2] = velCovar(0, 2);
00237     vel.covariance[3] = velCovar(1, 0);
00238     vel.covariance[4] = velCovar(1, 1);
00239     vel.covariance[5] = velCovar(1, 2);
00240     vel.covariance[6] = velCovar(2, 0);
00241     vel.covariance[7] = velCovar(2, 1);
00242     vel.covariance[8] = velCovar(2, 2);
00243 
00244     Matrix poseCovarTmp = ublas::prod(poseCovar, FpT);
00245     poseCovarTmp = ublas::prod(Fp, poseCovarTmp);
00246     poseCovar = addMatrices(poseCovarTmp, velCovar);
00247 
00248     pose.covariance[0] = poseCovar(0, 0);
00249     pose.covariance[1] = poseCovar(0, 1);
00250     pose.covariance[2] = poseCovar(0, 2);
00251     pose.covariance[3] = poseCovar(1, 0);
00252     pose.covariance[4] = poseCovar(1, 1);
00253     pose.covariance[5] = poseCovar(1, 2);
00254     pose.covariance[6] = poseCovar(2, 0);
00255     pose.covariance[7] = poseCovar(2, 1);
00256     pose.covariance[8] = poseCovar(2, 2);
00257 
00258     // Update pose
00259     pose.x += deltaX;
00260     pose.y += deltaY;
00261     pose.yaw = util::normalizeAngle(pose.yaw + deltaYaw);
00262 
00263     prevOnDataTime = curTime;
00264 
00265     // Make user registered callbacks, if any
00266     // TODO
00267   }
00268 
00269   bool Create::connect(const std::string& port, const int& baud) {
00270     bool timeout = false;
00271     time_t start, now;
00272     float maxWait = 30; // seconds
00273     float retryInterval = 5; //seconds
00274     time(&start);
00275     while (!serial->connect(port, baud, boost::bind(&Create::onData, this)) && !timeout) {
00276       time(&now);
00277       if (difftime(now, start) > maxWait) {
00278         timeout = true;
00279         CERR("[create::Create] ", "failed to connect over serial: timeout");
00280       }
00281       else {
00282         usleep(retryInterval * 1000000);
00283         COUT("[create::Create] ", "retrying to establish serial connection...");
00284       }
00285     }
00286 
00287     return !timeout;
00288   }
00289 
00290   void Create::disconnect() {
00291     serial->disconnect();
00292     firstOnData = true;
00293   }
00294 
00295   //void Create::reset() {
00296   //  serial->sendOpcode(OC_RESET);
00297   //  serial->reset(); // better
00298     // TODO : Should we request reading packets again?
00299   //}
00300 
00301   bool Create::setMode(const CreateMode& mode) {
00302     if (model.getVersion() == V_1){
00303       // Switch to safe mode (required for compatibility with V_1)
00304       if (!(serial->sendOpcode(OC_START) && serial->sendOpcode(OC_CONTROL))) return false;
00305     }
00306     bool ret;
00307     switch (mode) {
00308       case MODE_OFF:
00309         if (model.getVersion() == V_2) {
00310           CERR("[create::Create] ", "protocol version 2 does not support turning robot off");
00311           ret = false;
00312         } else {
00313           ret = serial->sendOpcode(OC_POWER);
00314         }
00315         break;
00316       case MODE_PASSIVE:
00317         ret = serial->sendOpcode(OC_START);
00318         break;
00319       case MODE_SAFE:
00320         if (model.getVersion() > V_1) {
00321           ret = serial->sendOpcode(OC_SAFE);
00322         }
00323         break;
00324       case MODE_FULL:
00325         ret = serial->sendOpcode(OC_FULL);
00326         break;
00327       default:
00328         CERR("[create::Create] ", "cannot set robot to mode '" << mode << "'");
00329         ret = false;
00330     }
00331     if (ret) {
00332       this->mode = mode;
00333     }
00334     return ret;
00335   }
00336 
00337   bool Create::clean(const CleanMode& mode) {
00338     return serial->sendOpcode((Opcode) mode);
00339   }
00340 
00341   bool Create::dock() const {
00342     return serial->sendOpcode(OC_DOCK);
00343   }
00344 
00345   bool Create::setDate(const DayOfWeek& day, const uint8_t& hour, const uint8_t& min) const {
00346     if (day < 0 || day > 6 ||
00347         hour < 0 || hour > 23 ||
00348         min < 0 || min > 59)
00349       return false;
00350 
00351     uint8_t cmd[4] = { OC_DATE, day, hour, min };
00352     return serial->send(cmd, 4);
00353   }
00354 
00355   bool Create::driveRadius(const float& vel, const float& radius) {
00356     // Bound velocity
00357     float boundedVel = BOUND_CONST(vel, -model.getMaxVelocity(), model.getMaxVelocity());
00358 
00359     // Expects each parameter as two bytes each and in millimeters
00360     int16_t vel_mm = roundf(boundedVel * 1000);
00361     int16_t radius_mm = roundf(radius * 1000);
00362 
00363     // Bound radius if not a special case
00364     if (radius_mm != 32768 && radius_mm != 32767 &&
00365         radius_mm != -1 && radius_mm != 1) {
00366       BOUND(radius_mm, -util::MAX_RADIUS * 1000, util::MAX_RADIUS * 1000);
00367     }
00368 
00369     uint8_t cmd[5] = { OC_DRIVE,
00370                        vel_mm >> 8,
00371                        vel_mm & 0xff,
00372                        radius_mm >> 8,
00373                        radius_mm & 0xff
00374                      };
00375 
00376     return serial->send(cmd, 5);
00377   }
00378 
00379   bool Create::driveWheels(const float& leftVel, const float& rightVel) {
00380     const float boundedLeftVel = BOUND_CONST(leftVel, -model.getMaxVelocity(), model.getMaxVelocity());
00381     const float boundedRightVel = BOUND_CONST(rightVel, -model.getMaxVelocity(), model.getMaxVelocity());
00382     requestedLeftVel = boundedLeftVel;
00383     requestedRightVel = boundedRightVel;
00384     if (model.getVersion() > V_1) {
00385       int16_t leftCmd = roundf(boundedLeftVel * 1000);
00386       int16_t rightCmd = roundf(boundedRightVel * 1000);
00387 
00388       uint8_t cmd[5] = { OC_DRIVE_DIRECT,
00389                          rightCmd >> 8,
00390                          rightCmd & 0xff,
00391                          leftCmd >> 8,
00392                          leftCmd & 0xff
00393                        };
00394       return serial->send(cmd, 5);
00395     } else {
00396       float radius;
00397       // Prevent divide by zero when driving straight
00398       if (boundedLeftVel != boundedRightVel) {
00399         radius = -((model.getAxleLength() / 2.0) * (boundedLeftVel + boundedRightVel)) /
00400           (boundedLeftVel - boundedRightVel);
00401       } else {
00402         radius = util::STRAIGHT_RADIUS;
00403       }
00404 
00405       float vel;
00406       // Fix signs for spin in place
00407       if (boundedLeftVel == -boundedRightVel || std::abs(roundf(radius * 1000)) <= 1) {
00408         radius = util::IN_PLACE_RADIUS;
00409         vel = boundedRightVel;
00410       } else {
00411         vel = (std::abs(boundedLeftVel) + std::abs(boundedRightVel)) / 2.0 * ((boundedLeftVel + boundedRightVel) > 0 ? 1.0 : -1.0);
00412       }
00413 
00414       // Radius turns have a maximum radius of 2.0 meters
00415       // When the radius is > 2 but <= 10, use a 2 meter radius
00416       // When it is > 10, drive straight
00417       // TODO: alternate between these 2 meter radius and straight to
00418       // fake a larger radius
00419       if (radius > 10.0) {
00420         radius = util::STRAIGHT_RADIUS;
00421       }
00422 
00423       return driveRadius(vel, radius);
00424     }
00425   }
00426 
00427   bool Create::drive(const float& xVel, const float& angularVel) {
00428     // Compute left and right wheel velocities
00429     float leftVel = xVel - ((model.getAxleLength() / 2.0) * angularVel);
00430     float rightVel = xVel + ((model.getAxleLength() / 2.0) * angularVel);
00431     return driveWheels(leftVel, rightVel);
00432   }
00433 
00434   bool Create::setAllMotors(const float& main, const float& side, const float& vacuum) {
00435     if (main < -1.0 || main > 1.0 ||
00436         side < -1.0 || side > 1.0 ||
00437         vacuum < -1.0 || vacuum > 1.0)
00438       return false;
00439 
00440     mainMotorPower = roundf(main * 127);
00441     sideMotorPower = roundf(side * 127);
00442     vacuumMotorPower = roundf(vacuum * 127);
00443 
00444     uint8_t cmd[4] = { OC_MOTORS_PWM,
00445                         mainMotorPower,
00446                         sideMotorPower,
00447                         vacuumMotorPower
00448                       };
00449 
00450     return serial->send(cmd, 4);
00451   }
00452 
00453   bool Create::setMainMotor(const float& main) {
00454     return setAllMotors(main, sideMotorPower, vacuumMotorPower);
00455   }
00456 
00457   bool Create::setSideMotor(const float& side) {
00458     return setAllMotors(mainMotorPower, side, vacuumMotorPower);
00459   }
00460 
00461   bool Create::setVacuumMotor(const float& vacuum) {
00462     return setAllMotors(mainMotorPower, sideMotorPower, vacuum);
00463   }
00464 
00465   bool Create::updateLEDs() {
00466     uint8_t LEDByte = debrisLED + spotLED + dockLED + checkLED;
00467     uint8_t cmd[4] = { OC_LEDS,
00468                         LEDByte,
00469                         powerLED,
00470                         powerLEDIntensity
00471                       };
00472 
00473     return serial->send(cmd, 4);
00474   }
00475 
00476   bool Create::enableDebrisLED(const bool& enable) {
00477     if (enable)
00478       debrisLED = LED_DEBRIS;
00479     else
00480       debrisLED = 0;
00481     return updateLEDs();
00482   }
00483 
00484   bool Create::enableSpotLED(const bool& enable) {
00485     if (enable)
00486       spotLED = LED_SPOT;
00487     else
00488       spotLED = 0;
00489     return updateLEDs();
00490   }
00491 
00492   bool Create::enableDockLED(const bool& enable) {
00493     if (enable)
00494       dockLED = LED_DOCK;
00495     else
00496       dockLED = 0;
00497     return updateLEDs();
00498   }
00499 
00500   bool Create::enableCheckRobotLED(const bool& enable) {
00501     if (enable)
00502       checkLED = LED_CHECK;
00503     else
00504       checkLED = 0;
00505     return updateLEDs();
00506   }
00507 
00508   bool Create::setPowerLED(const uint8_t& power, const uint8_t& intensity) {
00509     powerLED = power;
00510     powerLEDIntensity = intensity;
00511     return updateLEDs();
00512   }
00513 
00514   //void Create::setDigits(uint8_t digit1, uint8_t digit2,
00515   //                       uint8_t digit3, uint8_t digit4) {
00516   //}
00517 
00518   bool Create::setDigitsASCII(const uint8_t& digit1, const uint8_t& digit2,
00519                               const uint8_t& digit3, const uint8_t& digit4) const {
00520     if (digit1 < 32 || digit1 > 126 ||
00521         digit2 < 32 || digit2 > 126 ||
00522         digit3 < 32 || digit3 > 126 ||
00523         digit4 < 32 || digit4 > 126)
00524       return false;
00525 
00526     uint8_t cmd[5] = { OC_DIGIT_LEDS_ASCII,
00527                         digit1,
00528                         digit2,
00529                         digit3,
00530                         digit4
00531                       };
00532 
00533     return serial->send(cmd, 5);
00534   }
00535 
00536   bool Create::defineSong(const uint8_t& songNumber,
00537                           const uint8_t& songLength,
00538                           const uint8_t* notes,
00539                           const float* durations) const {
00540     int i, j;
00541     uint8_t duration;
00542     uint8_t cmd[2 * songLength + 3];
00543     cmd[0] = OC_SONG;
00544     cmd[1] = songNumber;
00545     cmd[2] = songLength;
00546     j = 0;
00547     for (i = 3; i < 2 * songLength + 3; i = i + 2) {
00548       if (durations[j] < 0 || durations[j] >= 4)
00549         return false;
00550       duration = durations[j] * 64;
00551       cmd[i] = notes[j];
00552       cmd[i + 1] = duration;
00553       j++;
00554     }
00555 
00556     return serial->send(cmd, 2 * songLength + 3);
00557   }
00558 
00559   bool Create::playSong(const uint8_t& songNumber) const {
00560     if (songNumber < 0 || songNumber > 4)
00561       return false;
00562     uint8_t cmd[2] = { OC_PLAY, songNumber };
00563     return serial->send(cmd, 2);
00564   }
00565 
00566   bool Create::isWheeldrop() const {
00567     if (data->isValidPacketID(ID_BUMP_WHEELDROP)) {
00568       return (GET_DATA(ID_BUMP_WHEELDROP) & 0x0C) != 0;
00569     }
00570     else {
00571       CERR("[create::Create] ", "Wheeldrop sensor not supported!");
00572       return false;
00573     }
00574   }
00575 
00576   bool Create::isLeftBumper() const {
00577     if (data->isValidPacketID(ID_BUMP_WHEELDROP)) {
00578       return (GET_DATA(ID_BUMP_WHEELDROP) & 0x02) != 0;
00579     }
00580     else {
00581       CERR("[create::Create] ", "Left bumper not supported!");
00582       return false;
00583     }
00584   }
00585 
00586   bool Create::isRightBumper() const {
00587     if (data->isValidPacketID(ID_BUMP_WHEELDROP)) {
00588       return (GET_DATA(ID_BUMP_WHEELDROP) & 0x01) != 0;
00589     }
00590     else {
00591       CERR("[create::Create] ", "Right bumper not supported!");
00592       return false;
00593     }
00594   }
00595 
00596   bool Create::isWall() const {
00597     if (data->isValidPacketID(ID_WALL)) {
00598       return GET_DATA(ID_WALL) == 1;
00599     }
00600     else {
00601       CERR("[create::Create] ", "Wall sensor not supported!");
00602       return false;
00603     }
00604   }
00605 
00606   bool Create::isCliff() const {
00607     if (data->isValidPacketID(ID_CLIFF_LEFT) &&
00608         data->isValidPacketID(ID_CLIFF_FRONT_LEFT) &&
00609         data->isValidPacketID(ID_CLIFF_FRONT_RIGHT) &&
00610         data->isValidPacketID(ID_CLIFF_RIGHT)) {
00611       return GET_DATA(ID_CLIFF_LEFT) == 1 ||
00612              GET_DATA(ID_CLIFF_FRONT_LEFT) == 1 ||
00613              GET_DATA(ID_CLIFF_FRONT_RIGHT) == 1 ||
00614              GET_DATA(ID_CLIFF_RIGHT) == 1;
00615     }
00616     else {
00617       CERR("[create::Create] ", "Cliff sensors not supported!");
00618       return false;
00619     }
00620   }
00621 
00622   bool Create::isVirtualWall() const {
00623     if (data->isValidPacketID(ID_VIRTUAL_WALL)) {
00624       return GET_DATA(ID_VIRTUAL_WALL);
00625     }
00626     else {
00627       CERR("[create::Create] ", "Virtual Wall sensor not supported!");
00628       return false;
00629     }
00630   }
00631 
00632   uint8_t Create::getDirtDetect() const {
00633     if (data->isValidPacketID(ID_DIRT_DETECT_LEFT)) {
00634       return GET_DATA(ID_DIRT_DETECT_LEFT);
00635     }
00636     else {
00637       CERR("[create::Create] ", "Dirt detector not supported!");
00638       return -1;
00639     }
00640   }
00641 
00642   uint8_t Create::getIROmni() const {
00643     if (data->isValidPacketID(ID_IR_OMNI)) {
00644       return GET_DATA(ID_IR_OMNI);
00645     }
00646     else {
00647       CERR("[create::Create] ", "Omni IR sensor not supported!");
00648       return -1;
00649     }
00650   }
00651 
00652   uint8_t Create::getIRLeft() const {
00653     if (data->isValidPacketID(ID_IR_LEFT)) {
00654       return GET_DATA(ID_IR_LEFT);
00655     }
00656     else {
00657       CERR("[create::Create] ", "Left IR sensor not supported!");
00658       return -1;
00659     }
00660   }
00661 
00662   uint8_t Create::getIRRight() const {
00663     if (data->isValidPacketID(ID_IR_RIGHT)) {
00664       return GET_DATA(ID_IR_RIGHT);
00665     }
00666     else {
00667       CERR("[create::Create] ", "Right IR sensor not supported!");
00668       return -1;
00669     }
00670   }
00671 
00672   ChargingState Create::getChargingState() const {
00673     if (data->isValidPacketID(ID_CHARGE_STATE)) {
00674       uint8_t chargeState = GET_DATA(ID_CHARGE_STATE);
00675       assert(chargeState >= 0);
00676       assert(chargeState <= 5);
00677       return (ChargingState) chargeState;
00678     }
00679     else {
00680       CERR("[create::Create] ", "Charging state not supported!");
00681       return CHARGE_FAULT;
00682     }
00683   }
00684 
00685   bool Create::isCleanButtonPressed() const {
00686     if (data->isValidPacketID(ID_BUTTONS)) {
00687       return (GET_DATA(ID_BUTTONS) & 0x01) != 0;
00688     }
00689     else {
00690       CERR("[create::Create] ", "Buttons not supported!");
00691       return false;
00692     }
00693   }
00694 
00695   // Not supported by any 600 series firmware
00696   bool Create::isClockButtonPressed() const {
00697     CERR("[create::Create] ", "Clock button is not supported!");
00698     if (data->isValidPacketID(ID_BUTTONS)) {
00699       return (GET_DATA(ID_BUTTONS) & 0x80) != 0;
00700     }
00701     else {
00702       CERR("[create::Create] ", "Buttons not supported!");
00703       return false;
00704     }
00705   }
00706 
00707   // Not supported by any 600 series firmware
00708   bool Create::isScheduleButtonPressed() const {
00709     CERR("[create::Create] ", "Schedule button is not supported!");
00710     if (data->isValidPacketID(ID_BUTTONS)) {
00711       return (GET_DATA(ID_BUTTONS) & 0x40) != 0;
00712     }
00713     else {
00714       CERR("[create::Create] ", "Buttons not supported!");
00715       return false;
00716     }
00717   }
00718 
00719   bool Create::isDayButtonPressed() const {
00720     if (data->isValidPacketID(ID_BUTTONS)) {
00721       return (GET_DATA(ID_BUTTONS) & 0x20) != 0;
00722     }
00723     else {
00724       CERR("[create::Create] ", "Buttons not supported!");
00725       return false;
00726     }
00727   }
00728 
00729   bool Create::isHourButtonPressed() const {
00730     if (data->isValidPacketID(ID_BUTTONS)) {
00731       return (GET_DATA(ID_BUTTONS) & 0x10) != 0;
00732     }
00733     else {
00734       CERR("[create::Create] ", "Buttons not supported!");
00735       return false;
00736     }
00737   }
00738 
00739   bool Create::isMinButtonPressed() const {
00740     if (data->isValidPacketID(ID_BUTTONS)) {
00741       return (GET_DATA(ID_BUTTONS) & 0x08) != 0;
00742     }
00743     else {
00744       CERR("[create::Create] ", "Buttons not supported!");
00745       return false;
00746     }
00747   }
00748 
00749   bool Create::isDockButtonPressed() const {
00750     if (data->isValidPacketID(ID_BUTTONS)) {
00751       return (GET_DATA(ID_BUTTONS) & 0x04) != 0;
00752     }
00753     else {
00754       CERR("[create::Create] ", "Buttons not supported!");
00755       return false;
00756     }
00757   }
00758 
00759   bool Create::isSpotButtonPressed() const {
00760     if (data->isValidPacketID(ID_BUTTONS)) {
00761       return (GET_DATA(ID_BUTTONS) & 0x02) != 0;
00762     }
00763     else {
00764       CERR("[create::Create] ", "Buttons not supported!");
00765       return false;
00766     }
00767   }
00768 
00769   float Create::getVoltage() const {
00770     if (data->isValidPacketID(ID_VOLTAGE)) {
00771       return (GET_DATA(ID_VOLTAGE) / 1000.0);
00772     }
00773     else {
00774       CERR("[create::Create] ", "Voltage sensor not supported!");
00775       return 0;
00776     }
00777   }
00778 
00779   float Create::getCurrent() const {
00780     if (data->isValidPacketID(ID_VOLTAGE)) {
00781       return (((int16_t)GET_DATA(ID_CURRENT)) / 1000.0);
00782     }
00783     else {
00784       CERR("[create::Create] ", "Current sensor not supported!");
00785       return 0;
00786     }
00787   }
00788 
00789   int8_t Create::getTemperature() const {
00790     if (data->isValidPacketID(ID_TEMP)) {
00791       return (int8_t) GET_DATA(ID_TEMP);
00792     }
00793     else {
00794       CERR("[create::Create] ", "Temperature sensor not supported!");
00795       return 0;
00796     }
00797   }
00798 
00799   float Create::getBatteryCharge() const {
00800     if (data->isValidPacketID(ID_CHARGE)) {
00801       return (GET_DATA(ID_CHARGE) / 1000.0);
00802     }
00803     else {
00804       CERR("[create::Create] ", "Battery charge not supported!");
00805       return 0;
00806     }
00807   }
00808 
00809   float Create::getBatteryCapacity() const {
00810     if (data->isValidPacketID(ID_CAPACITY)) {
00811       return (GET_DATA(ID_CAPACITY) / 1000.0);
00812     }
00813     else {
00814       CERR("[create::Create] ", "Battery capacity not supported!");
00815       return 0;
00816     }
00817   }
00818 
00819   bool Create::isLightBumperLeft() const {
00820     if (data->isValidPacketID(ID_LIGHT)) {
00821       return (GET_DATA(ID_LIGHT) & 0x01) != 0;
00822     }
00823     else {
00824       CERR("[create::Create] ", "Light sensors not supported!");
00825       return false;
00826     }
00827   }
00828 
00829   bool Create::isLightBumperFrontLeft() const {
00830     if (data->isValidPacketID(ID_LIGHT)) {
00831       return (GET_DATA(ID_LIGHT) & 0x02) != 0;
00832     }
00833     else {
00834       CERR("[create::Create] ", "Light sensors not supported!");
00835       return false;
00836     }
00837   }
00838 
00839   bool Create::isLightBumperCenterLeft() const {
00840     if (data->isValidPacketID(ID_LIGHT)) {
00841       return (GET_DATA(ID_LIGHT) & 0x04) != 0;
00842     }
00843     else {
00844       CERR("[create::Create] ", "Light sensors not supported!");
00845       return false;
00846     }
00847   }
00848 
00849   bool Create::isLightBumperCenterRight() const {
00850     if (data->isValidPacketID(ID_LIGHT)) {
00851       return (GET_DATA(ID_LIGHT) & 0x08) != 0;
00852     }
00853     else {
00854       CERR("[create::Create] ", "Light sensors not supported!");
00855       return false;
00856     }
00857   }
00858 
00859   bool Create::isLightBumperFrontRight() const {
00860     if (data->isValidPacketID(ID_LIGHT)) {
00861       return (GET_DATA(ID_LIGHT) & 0x10) != 0;
00862     }
00863     else {
00864       CERR("[create::Create] ", "Light sensors not supported!");
00865       return false;
00866     }
00867   }
00868 
00869   bool Create::isLightBumperRight() const {
00870     if (data->isValidPacketID(ID_LIGHT)) {
00871       return (GET_DATA(ID_LIGHT) & 0x20) != 0;
00872     }
00873     else {
00874       CERR("[create::Create] ", "Light sensors not supported!");
00875       return false;
00876     }
00877   }
00878 
00879   uint16_t Create::getLightSignalLeft() const {
00880     if (data->isValidPacketID(ID_LIGHT_LEFT)) {
00881       return GET_DATA(ID_LIGHT_LEFT);
00882     }
00883     else {
00884       CERR("[create::Create] ", "Light sensors not supported!");
00885       return 0;
00886     }
00887   }
00888 
00889   uint16_t Create::getLightSignalFrontLeft() const {
00890     if (data->isValidPacketID(ID_LIGHT_FRONT_LEFT)) {
00891       return GET_DATA(ID_LIGHT_FRONT_LEFT);
00892     }
00893     else {
00894       CERR("[create::Create] ", "Light sensors not supported!");
00895       return 0;
00896     }
00897   }
00898 
00899   uint16_t Create::getLightSignalCenterLeft() const {
00900     if (data->isValidPacketID(ID_LIGHT_CENTER_LEFT)) {
00901       return GET_DATA(ID_LIGHT_CENTER_LEFT);
00902     }
00903     else {
00904       CERR("[create::Create] ", "Light sensors not supported!");
00905       return 0;
00906     }
00907   }
00908 
00909   uint16_t Create::getLightSignalRight() const {
00910     if (data->isValidPacketID(ID_LIGHT_RIGHT)) {
00911       return GET_DATA(ID_LIGHT_RIGHT);
00912     }
00913     else {
00914       CERR("[create::Create] ", "Light sensors not supported!");
00915       return 0;
00916     }
00917   }
00918 
00919   uint16_t Create::getLightSignalFrontRight() const {
00920     if (data->isValidPacketID(ID_LIGHT_FRONT_RIGHT)) {
00921       return GET_DATA(ID_LIGHT_FRONT_RIGHT);
00922     }
00923     else {
00924       CERR("[create::Create] ", "Light sensors not supported!");
00925       return 0;
00926     }
00927   }
00928 
00929   uint16_t Create::getLightSignalCenterRight() const {
00930     if (data->isValidPacketID(ID_LIGHT_CENTER_RIGHT)) {
00931       return GET_DATA(ID_LIGHT_CENTER_RIGHT);
00932     }
00933     else {
00934       CERR("[create::Create] ", "Light sensors not supported!");
00935       return 0;
00936     }
00937   }
00938 
00939   bool Create::isMovingForward() const {
00940     if (data->isValidPacketID(ID_STASIS)) {
00941       return GET_DATA(ID_STASIS) == 1;
00942     }
00943     else {
00944       CERR("[create::Create] ", "Stasis sensor not supported!");
00945       return false;
00946     }
00947   }
00948 
00949   float Create::getLeftWheelDistance() const {
00950     return totalLeftDist;
00951   }
00952 
00953   float Create::getRightWheelDistance() const {
00954     return totalRightDist;
00955   }
00956 
00957   float Create::getRequestedLeftWheelVel() const {
00958     return requestedLeftVel;
00959   }
00960 
00961   float Create::getRequestedRightWheelVel() const {
00962     return requestedRightVel;
00963   }
00964 
00965   create::CreateMode Create::getMode() {
00966     if (data->isValidPacketID(ID_OI_MODE)) {
00967       mode = (create::CreateMode) GET_DATA(ID_OI_MODE);
00968     }
00969     return mode;
00970   }
00971 
00972   Pose Create::getPose() const {
00973     return pose;
00974   }
00975 
00976   Vel Create::getVel() const {
00977     return vel;
00978   }
00979 
00980   uint64_t Create::getNumCorruptPackets() const {
00981     return serial->getNumCorruptPackets();
00982   }
00983 
00984   uint64_t Create::getTotalPackets() const {
00985     return serial->getTotalPackets();
00986   }
00987 
00988 } // end namespace


libcreate
Author(s): Jacob Perron
autogenerated on Sat Nov 26 2016 03:41:46