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
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
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
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
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
00109 int16_t angleField;
00110 if (model.getVersion() <= V_2) {
00111
00112 uint16_t distanceRaw = GET_DATA(ID_DISTANCE);
00113 int16_t distance;
00114 std::memcpy(&distance, &distanceRaw, sizeof(distance));
00115 deltaDist = distance / 1000.0;
00116
00117
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
00130
00131
00132
00133
00134
00135
00136
00137
00138
00139
00140 deltaYaw = angleField * (util::PI / 180.0);
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
00146 uint16_t totalTicksLeft = GET_DATA(ID_LEFT_ENC);
00147 uint16_t totalTicksRight = GET_DATA(ID_RIGHT_ENC);
00148
00149 int ticksLeft = totalTicksLeft - prevTicksLeft;
00150 int ticksRight = totalTicksRight - prevTicksRight;
00151 prevTicksLeft = totalTicksLeft;
00152 prevTicksRight = totalTicksRight;
00153
00154
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
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 measuredLeftVel = leftWheelDist / dt;
00174 measuredRightVel = rightWheelDist / dt;
00175
00176
00177 if (fabs(wheelDistDiff) < util::EPS) {
00178 deltaX = deltaDist * cos(pose.yaw);
00179 deltaY = deltaDist * sin(pose.yaw);
00180 } else {
00181 float turnRadius = (model.getAxleLength() / 2.0) * (leftWheelDist + rightWheelDist) / wheelDistDiff;
00182 deltaX = turnRadius * (sin(pose.yaw + deltaYaw) - sin(pose.yaw));
00183 deltaY = -turnRadius * (cos(pose.yaw + deltaYaw) - cos(pose.yaw));
00184 }
00185
00186 totalLeftDist += leftWheelDist;
00187 totalRightDist += rightWheelDist;
00188
00189 if (fabs(dt) > util::EPS) {
00190 vel.x = deltaDist / dt;
00191 vel.y = 0.0;
00192 vel.yaw = deltaYaw / dt;
00193 } else {
00194 vel.x = 0.0;
00195 vel.y = 0.0;
00196 vel.yaw = 0.0;
00197 }
00198
00199
00200
00201 float kr = 1.0;
00202 float kl = 1.0;
00203 float cosYawAndHalfDelta = cos(pose.yaw + (deltaYaw / 2.0));
00204 float sinYawAndHalfDelta = sin(pose.yaw + (deltaYaw / 2.0));
00205 float distOverTwoWB = deltaDist / (model.getAxleLength() * 2.0);
00206
00207 Matrix invCovar(2, 2);
00208 invCovar(0, 0) = kr * fabs(rightWheelDist);
00209 invCovar(0, 1) = 0.0;
00210 invCovar(1, 0) = 0.0;
00211 invCovar(1, 1) = kl * fabs(leftWheelDist);
00212
00213 Matrix Finc(3, 2);
00214 Finc(0, 0) = (cosYawAndHalfDelta / 2.0) - (distOverTwoWB * sinYawAndHalfDelta);
00215 Finc(0, 1) = (cosYawAndHalfDelta / 2.0) + (distOverTwoWB * sinYawAndHalfDelta);
00216 Finc(1, 0) = (sinYawAndHalfDelta / 2.0) + (distOverTwoWB * cosYawAndHalfDelta);
00217 Finc(1, 1) = (sinYawAndHalfDelta / 2.0) - (distOverTwoWB * cosYawAndHalfDelta);
00218 Finc(2, 0) = (1.0 / model.getAxleLength());
00219 Finc(2, 1) = (-1.0 / model.getAxleLength());
00220 Matrix FincT = boost::numeric::ublas::trans(Finc);
00221
00222 Matrix Fp(3, 3);
00223 Fp(0, 0) = 1.0;
00224 Fp(0, 1) = 0.0;
00225 Fp(0, 2) = (-deltaDist) * sinYawAndHalfDelta;
00226 Fp(1, 0) = 0.0;
00227 Fp(1, 1) = 1.0;
00228 Fp(1, 2) = deltaDist * cosYawAndHalfDelta;
00229 Fp(2, 0) = 0.0;
00230 Fp(2, 1) = 0.0;
00231 Fp(2, 2) = 1.0;
00232 Matrix FpT = boost::numeric::ublas::trans(Fp);
00233
00234 Matrix velCovar = ublas::prod(invCovar, FincT);
00235 velCovar = ublas::prod(Finc, velCovar);
00236
00237 vel.covariance[0] = velCovar(0, 0);
00238 vel.covariance[1] = velCovar(0, 1);
00239 vel.covariance[2] = velCovar(0, 2);
00240 vel.covariance[3] = velCovar(1, 0);
00241 vel.covariance[4] = velCovar(1, 1);
00242 vel.covariance[5] = velCovar(1, 2);
00243 vel.covariance[6] = velCovar(2, 0);
00244 vel.covariance[7] = velCovar(2, 1);
00245 vel.covariance[8] = velCovar(2, 2);
00246
00247 Matrix poseCovarTmp = ublas::prod(poseCovar, FpT);
00248 poseCovarTmp = ublas::prod(Fp, poseCovarTmp);
00249 poseCovar = addMatrices(poseCovarTmp, velCovar);
00250
00251 pose.covariance[0] = poseCovar(0, 0);
00252 pose.covariance[1] = poseCovar(0, 1);
00253 pose.covariance[2] = poseCovar(0, 2);
00254 pose.covariance[3] = poseCovar(1, 0);
00255 pose.covariance[4] = poseCovar(1, 1);
00256 pose.covariance[5] = poseCovar(1, 2);
00257 pose.covariance[6] = poseCovar(2, 0);
00258 pose.covariance[7] = poseCovar(2, 1);
00259 pose.covariance[8] = poseCovar(2, 2);
00260
00261
00262 pose.x += deltaX;
00263 pose.y += deltaY;
00264 pose.yaw = util::normalizeAngle(pose.yaw + deltaYaw);
00265
00266 prevOnDataTime = curTime;
00267
00268
00269
00270 }
00271
00272 bool Create::connect(const std::string& port, const int& baud) {
00273 bool timeout = false;
00274 time_t start, now;
00275 float maxWait = 30;
00276 float retryInterval = 5;
00277 time(&start);
00278 while (!serial->connect(port, baud, boost::bind(&Create::onData, this)) && !timeout) {
00279 time(&now);
00280 if (difftime(now, start) > maxWait) {
00281 timeout = true;
00282 CERR("[create::Create] ", "failed to connect over serial: timeout");
00283 }
00284 else {
00285 usleep(retryInterval * 1000000);
00286 COUT("[create::Create] ", "retrying to establish serial connection...");
00287 }
00288 }
00289
00290 return !timeout;
00291 }
00292
00293 void Create::disconnect() {
00294 serial->disconnect();
00295 firstOnData = true;
00296 }
00297
00298
00299
00300
00301
00302
00303
00304 bool Create::setMode(const CreateMode& mode) {
00305 if (model.getVersion() == V_1){
00306
00307 if (!(serial->sendOpcode(OC_START) && serial->sendOpcode(OC_CONTROL))) return false;
00308 }
00309 bool ret;
00310 switch (mode) {
00311 case MODE_OFF:
00312 if (model.getVersion() == V_2) {
00313 CERR("[create::Create] ", "protocol version 2 does not support turning robot off");
00314 ret = false;
00315 } else {
00316 ret = serial->sendOpcode(OC_POWER);
00317 }
00318 break;
00319 case MODE_PASSIVE:
00320 ret = serial->sendOpcode(OC_START);
00321 break;
00322 case MODE_SAFE:
00323 if (model.getVersion() > V_1) {
00324 ret = serial->sendOpcode(OC_SAFE);
00325 }
00326 break;
00327 case MODE_FULL:
00328 ret = serial->sendOpcode(OC_FULL);
00329 break;
00330 default:
00331 CERR("[create::Create] ", "cannot set robot to mode '" << mode << "'");
00332 ret = false;
00333 }
00334 if (ret) {
00335 this->mode = mode;
00336 }
00337 return ret;
00338 }
00339
00340 bool Create::clean(const CleanMode& mode) {
00341 return serial->sendOpcode((Opcode) mode);
00342 }
00343
00344 bool Create::dock() const {
00345 return serial->sendOpcode(OC_DOCK);
00346 }
00347
00348 bool Create::setDate(const DayOfWeek& day, const uint8_t& hour, const uint8_t& min) const {
00349 if (day < 0 || day > 6 ||
00350 hour < 0 || hour > 23 ||
00351 min < 0 || min > 59)
00352 return false;
00353
00354 uint8_t cmd[4] = { OC_DATE, day, hour, min };
00355 return serial->send(cmd, 4);
00356 }
00357
00358 bool Create::driveRadius(const float& vel, const float& radius) {
00359
00360 float boundedVel = BOUND_CONST(vel, -model.getMaxVelocity(), model.getMaxVelocity());
00361
00362
00363 int16_t vel_mm = roundf(boundedVel * 1000);
00364 int16_t radius_mm = roundf(radius * 1000);
00365
00366
00367 if (radius_mm != 32768 && radius_mm != 32767 &&
00368 radius_mm != -1 && radius_mm != 1) {
00369 BOUND(radius_mm, -util::MAX_RADIUS * 1000, util::MAX_RADIUS * 1000);
00370 }
00371
00372 uint8_t cmd[5] = { OC_DRIVE,
00373 static_cast<uint8_t>(vel_mm >> 8),
00374 static_cast<uint8_t>(vel_mm & 0xff),
00375 static_cast<uint8_t>(radius_mm >> 8),
00376 static_cast<uint8_t>(radius_mm & 0xff)
00377 };
00378
00379 return serial->send(cmd, 5);
00380 }
00381
00382 bool Create::driveWheels(const float& leftVel, const float& rightVel) {
00383 const float boundedLeftVel = BOUND_CONST(leftVel, -model.getMaxVelocity(), model.getMaxVelocity());
00384 const float boundedRightVel = BOUND_CONST(rightVel, -model.getMaxVelocity(), model.getMaxVelocity());
00385 requestedLeftVel = boundedLeftVel;
00386 requestedRightVel = boundedRightVel;
00387 if (model.getVersion() > V_1) {
00388 int16_t leftCmd = roundf(boundedLeftVel * 1000);
00389 int16_t rightCmd = roundf(boundedRightVel * 1000);
00390
00391 uint8_t cmd[5] = { OC_DRIVE_DIRECT,
00392 static_cast<uint8_t>(rightCmd >> 8),
00393 static_cast<uint8_t>(rightCmd & 0xff),
00394 static_cast<uint8_t>(leftCmd >> 8),
00395 static_cast<uint8_t>(leftCmd & 0xff)
00396 };
00397 return serial->send(cmd, 5);
00398 } else {
00399 float radius;
00400
00401 if (boundedLeftVel != boundedRightVel) {
00402 radius = -((model.getAxleLength() / 2.0) * (boundedLeftVel + boundedRightVel)) /
00403 (boundedLeftVel - boundedRightVel);
00404 } else {
00405 radius = util::STRAIGHT_RADIUS;
00406 }
00407
00408 float vel;
00409
00410 if (boundedLeftVel == -boundedRightVel || std::abs(roundf(radius * 1000)) <= 1) {
00411 radius = util::IN_PLACE_RADIUS;
00412 vel = boundedRightVel;
00413 } else {
00414 vel = (std::abs(boundedLeftVel) + std::abs(boundedRightVel)) / 2.0 * ((boundedLeftVel + boundedRightVel) > 0 ? 1.0 : -1.0);
00415 }
00416
00417
00418
00419
00420
00421
00422 if (radius > 10.0) {
00423 radius = util::STRAIGHT_RADIUS;
00424 }
00425
00426 return driveRadius(vel, radius);
00427 }
00428 }
00429
00430 bool Create::driveWheelsPwm(const float& leftWheel, const float& rightWheel)
00431 {
00432 static const int16_t PWM_COUNTS = 255;
00433
00434 if (leftWheel < -1.0 || leftWheel > 1.0 ||
00435 rightWheel < -1.0 || rightWheel > 1.0)
00436 return false;
00437
00438 int16_t leftPwm = roundf(leftWheel * PWM_COUNTS);
00439 int16_t rightPwm = roundf(rightWheel * PWM_COUNTS);
00440
00441 uint8_t cmd[5] = { OC_DRIVE_PWM,
00442 static_cast<uint8_t>(rightPwm >> 8),
00443 static_cast<uint8_t>(rightPwm & 0xff),
00444 static_cast<uint8_t>(leftPwm >> 8),
00445 static_cast<uint8_t>(leftPwm & 0xff)
00446 };
00447
00448 return serial->send(cmd, 5);
00449 }
00450
00451 bool Create::drive(const float& xVel, const float& angularVel) {
00452
00453 float leftVel = xVel - ((model.getAxleLength() / 2.0) * angularVel);
00454 float rightVel = xVel + ((model.getAxleLength() / 2.0) * angularVel);
00455 return driveWheels(leftVel, rightVel);
00456 }
00457
00458 bool Create::setAllMotors(const float& main, const float& side, const float& vacuum) {
00459 if (main < -1.0 || main > 1.0 ||
00460 side < -1.0 || side > 1.0 ||
00461 vacuum < -1.0 || vacuum > 1.0)
00462 return false;
00463
00464 mainMotorPower = roundf(main * 127);
00465 sideMotorPower = roundf(side * 127);
00466 vacuumMotorPower = roundf(vacuum * 127);
00467
00468 uint8_t cmd[4] = { OC_MOTORS_PWM,
00469 mainMotorPower,
00470 sideMotorPower,
00471 vacuumMotorPower
00472 };
00473
00474 return serial->send(cmd, 4);
00475 }
00476
00477 bool Create::setMainMotor(const float& main) {
00478 return setAllMotors(main, sideMotorPower, vacuumMotorPower);
00479 }
00480
00481 bool Create::setSideMotor(const float& side) {
00482 return setAllMotors(mainMotorPower, side, vacuumMotorPower);
00483 }
00484
00485 bool Create::setVacuumMotor(const float& vacuum) {
00486 return setAllMotors(mainMotorPower, sideMotorPower, vacuum);
00487 }
00488
00489 bool Create::updateLEDs() {
00490 uint8_t LEDByte = debrisLED + spotLED + dockLED + checkLED;
00491 uint8_t cmd[4] = { OC_LEDS,
00492 LEDByte,
00493 powerLED,
00494 powerLEDIntensity
00495 };
00496
00497 return serial->send(cmd, 4);
00498 }
00499
00500 bool Create::enableDebrisLED(const bool& enable) {
00501 if (enable)
00502 debrisLED = LED_DEBRIS;
00503 else
00504 debrisLED = 0;
00505 return updateLEDs();
00506 }
00507
00508 bool Create::enableSpotLED(const bool& enable) {
00509 if (enable)
00510 spotLED = LED_SPOT;
00511 else
00512 spotLED = 0;
00513 return updateLEDs();
00514 }
00515
00516 bool Create::enableDockLED(const bool& enable) {
00517 if (enable)
00518 dockLED = LED_DOCK;
00519 else
00520 dockLED = 0;
00521 return updateLEDs();
00522 }
00523
00524 bool Create::enableCheckRobotLED(const bool& enable) {
00525 if (enable)
00526 checkLED = LED_CHECK;
00527 else
00528 checkLED = 0;
00529 return updateLEDs();
00530 }
00531
00532 bool Create::setPowerLED(const uint8_t& power, const uint8_t& intensity) {
00533 powerLED = power;
00534 powerLEDIntensity = intensity;
00535 return updateLEDs();
00536 }
00537
00538
00539
00540
00541
00542 bool Create::setDigitsASCII(const uint8_t& digit1, const uint8_t& digit2,
00543 const uint8_t& digit3, const uint8_t& digit4) const {
00544 if (digit1 < 32 || digit1 > 126 ||
00545 digit2 < 32 || digit2 > 126 ||
00546 digit3 < 32 || digit3 > 126 ||
00547 digit4 < 32 || digit4 > 126)
00548 return false;
00549
00550 uint8_t cmd[5] = { OC_DIGIT_LEDS_ASCII,
00551 digit1,
00552 digit2,
00553 digit3,
00554 digit4
00555 };
00556
00557 return serial->send(cmd, 5);
00558 }
00559
00560 bool Create::defineSong(const uint8_t& songNumber,
00561 const uint8_t& songLength,
00562 const uint8_t* notes,
00563 const float* durations) const {
00564 int i, j;
00565 uint8_t duration;
00566 uint8_t cmd[2 * songLength + 3];
00567 cmd[0] = OC_SONG;
00568 cmd[1] = songNumber;
00569 cmd[2] = songLength;
00570 j = 0;
00571 for (i = 3; i < 2 * songLength + 3; i = i + 2) {
00572 if (durations[j] < 0 || durations[j] >= 4)
00573 return false;
00574 duration = durations[j] * 64;
00575 cmd[i] = notes[j];
00576 cmd[i + 1] = duration;
00577 j++;
00578 }
00579
00580 return serial->send(cmd, 2 * songLength + 3);
00581 }
00582
00583 bool Create::playSong(const uint8_t& songNumber) const {
00584 if (songNumber < 0 || songNumber > 4)
00585 return false;
00586 uint8_t cmd[2] = { OC_PLAY, songNumber };
00587 return serial->send(cmd, 2);
00588 }
00589
00590 bool Create::isWheeldrop() const {
00591 if (data->isValidPacketID(ID_BUMP_WHEELDROP)) {
00592 return (GET_DATA(ID_BUMP_WHEELDROP) & 0x0C) != 0;
00593 }
00594 else {
00595 CERR("[create::Create] ", "Wheeldrop sensor not supported!");
00596 return false;
00597 }
00598 }
00599
00600 bool Create::isLeftBumper() const {
00601 if (data->isValidPacketID(ID_BUMP_WHEELDROP)) {
00602 return (GET_DATA(ID_BUMP_WHEELDROP) & 0x02) != 0;
00603 }
00604 else {
00605 CERR("[create::Create] ", "Left bumper not supported!");
00606 return false;
00607 }
00608 }
00609
00610 bool Create::isRightBumper() const {
00611 if (data->isValidPacketID(ID_BUMP_WHEELDROP)) {
00612 return (GET_DATA(ID_BUMP_WHEELDROP) & 0x01) != 0;
00613 }
00614 else {
00615 CERR("[create::Create] ", "Right bumper not supported!");
00616 return false;
00617 }
00618 }
00619
00620 bool Create::isWall() const {
00621 if (data->isValidPacketID(ID_WALL)) {
00622 return GET_DATA(ID_WALL) == 1;
00623 }
00624 else {
00625 CERR("[create::Create] ", "Wall sensor not supported!");
00626 return false;
00627 }
00628 }
00629
00630 bool Create::isCliff() const {
00631 if (data->isValidPacketID(ID_CLIFF_LEFT) &&
00632 data->isValidPacketID(ID_CLIFF_FRONT_LEFT) &&
00633 data->isValidPacketID(ID_CLIFF_FRONT_RIGHT) &&
00634 data->isValidPacketID(ID_CLIFF_RIGHT)) {
00635 return GET_DATA(ID_CLIFF_LEFT) == 1 ||
00636 GET_DATA(ID_CLIFF_FRONT_LEFT) == 1 ||
00637 GET_DATA(ID_CLIFF_FRONT_RIGHT) == 1 ||
00638 GET_DATA(ID_CLIFF_RIGHT) == 1;
00639 }
00640 else {
00641 CERR("[create::Create] ", "Cliff sensors not supported!");
00642 return false;
00643 }
00644 }
00645
00646 bool Create::isVirtualWall() const {
00647 if (data->isValidPacketID(ID_VIRTUAL_WALL)) {
00648 return GET_DATA(ID_VIRTUAL_WALL);
00649 }
00650 else {
00651 CERR("[create::Create] ", "Virtual Wall sensor not supported!");
00652 return false;
00653 }
00654 }
00655
00656 uint8_t Create::getDirtDetect() const {
00657 if (data->isValidPacketID(ID_DIRT_DETECT_LEFT)) {
00658 return GET_DATA(ID_DIRT_DETECT_LEFT);
00659 }
00660 else {
00661 CERR("[create::Create] ", "Dirt detector not supported!");
00662 return -1;
00663 }
00664 }
00665
00666 uint8_t Create::getIROmni() const {
00667 if (data->isValidPacketID(ID_IR_OMNI)) {
00668 return GET_DATA(ID_IR_OMNI);
00669 }
00670 else {
00671 CERR("[create::Create] ", "Omni IR sensor not supported!");
00672 return -1;
00673 }
00674 }
00675
00676 uint8_t Create::getIRLeft() const {
00677 if (data->isValidPacketID(ID_IR_LEFT)) {
00678 return GET_DATA(ID_IR_LEFT);
00679 }
00680 else {
00681 CERR("[create::Create] ", "Left IR sensor not supported!");
00682 return -1;
00683 }
00684 }
00685
00686 uint8_t Create::getIRRight() const {
00687 if (data->isValidPacketID(ID_IR_RIGHT)) {
00688 return GET_DATA(ID_IR_RIGHT);
00689 }
00690 else {
00691 CERR("[create::Create] ", "Right IR sensor not supported!");
00692 return -1;
00693 }
00694 }
00695
00696 ChargingState Create::getChargingState() const {
00697 if (data->isValidPacketID(ID_CHARGE_STATE)) {
00698 uint8_t chargeState = GET_DATA(ID_CHARGE_STATE);
00699 assert(chargeState >= 0);
00700 assert(chargeState <= 5);
00701 return (ChargingState) chargeState;
00702 }
00703 else {
00704 CERR("[create::Create] ", "Charging state not supported!");
00705 return CHARGE_FAULT;
00706 }
00707 }
00708
00709 bool Create::isCleanButtonPressed() const {
00710 if (data->isValidPacketID(ID_BUTTONS)) {
00711 return (GET_DATA(ID_BUTTONS) & 0x01) != 0;
00712 }
00713 else {
00714 CERR("[create::Create] ", "Buttons not supported!");
00715 return false;
00716 }
00717 }
00718
00719
00720 bool Create::isClockButtonPressed() const {
00721 CERR("[create::Create] ", "Clock button is not supported!");
00722 if (data->isValidPacketID(ID_BUTTONS)) {
00723 return (GET_DATA(ID_BUTTONS) & 0x80) != 0;
00724 }
00725 else {
00726 CERR("[create::Create] ", "Buttons not supported!");
00727 return false;
00728 }
00729 }
00730
00731
00732 bool Create::isScheduleButtonPressed() const {
00733 CERR("[create::Create] ", "Schedule button is not supported!");
00734 if (data->isValidPacketID(ID_BUTTONS)) {
00735 return (GET_DATA(ID_BUTTONS) & 0x40) != 0;
00736 }
00737 else {
00738 CERR("[create::Create] ", "Buttons not supported!");
00739 return false;
00740 }
00741 }
00742
00743 bool Create::isDayButtonPressed() const {
00744 if (data->isValidPacketID(ID_BUTTONS)) {
00745 return (GET_DATA(ID_BUTTONS) & 0x20) != 0;
00746 }
00747 else {
00748 CERR("[create::Create] ", "Buttons not supported!");
00749 return false;
00750 }
00751 }
00752
00753 bool Create::isHourButtonPressed() const {
00754 if (data->isValidPacketID(ID_BUTTONS)) {
00755 return (GET_DATA(ID_BUTTONS) & 0x10) != 0;
00756 }
00757 else {
00758 CERR("[create::Create] ", "Buttons not supported!");
00759 return false;
00760 }
00761 }
00762
00763 bool Create::isMinButtonPressed() const {
00764 if (data->isValidPacketID(ID_BUTTONS)) {
00765 return (GET_DATA(ID_BUTTONS) & 0x08) != 0;
00766 }
00767 else {
00768 CERR("[create::Create] ", "Buttons not supported!");
00769 return false;
00770 }
00771 }
00772
00773 bool Create::isDockButtonPressed() const {
00774 if (data->isValidPacketID(ID_BUTTONS)) {
00775 return (GET_DATA(ID_BUTTONS) & 0x04) != 0;
00776 }
00777 else {
00778 CERR("[create::Create] ", "Buttons not supported!");
00779 return false;
00780 }
00781 }
00782
00783 bool Create::isSpotButtonPressed() const {
00784 if (data->isValidPacketID(ID_BUTTONS)) {
00785 return (GET_DATA(ID_BUTTONS) & 0x02) != 0;
00786 }
00787 else {
00788 CERR("[create::Create] ", "Buttons not supported!");
00789 return false;
00790 }
00791 }
00792
00793 float Create::getVoltage() const {
00794 if (data->isValidPacketID(ID_VOLTAGE)) {
00795 return (GET_DATA(ID_VOLTAGE) / 1000.0);
00796 }
00797 else {
00798 CERR("[create::Create] ", "Voltage sensor not supported!");
00799 return 0;
00800 }
00801 }
00802
00803 float Create::getCurrent() const {
00804 if (data->isValidPacketID(ID_VOLTAGE)) {
00805 return (((int16_t)GET_DATA(ID_CURRENT)) / 1000.0);
00806 }
00807 else {
00808 CERR("[create::Create] ", "Current sensor not supported!");
00809 return 0;
00810 }
00811 }
00812
00813 int8_t Create::getTemperature() const {
00814 if (data->isValidPacketID(ID_TEMP)) {
00815 return (int8_t) GET_DATA(ID_TEMP);
00816 }
00817 else {
00818 CERR("[create::Create] ", "Temperature sensor not supported!");
00819 return 0;
00820 }
00821 }
00822
00823 float Create::getBatteryCharge() const {
00824 if (data->isValidPacketID(ID_CHARGE)) {
00825 return (GET_DATA(ID_CHARGE) / 1000.0);
00826 }
00827 else {
00828 CERR("[create::Create] ", "Battery charge not supported!");
00829 return 0;
00830 }
00831 }
00832
00833 float Create::getBatteryCapacity() const {
00834 if (data->isValidPacketID(ID_CAPACITY)) {
00835 return (GET_DATA(ID_CAPACITY) / 1000.0);
00836 }
00837 else {
00838 CERR("[create::Create] ", "Battery capacity not supported!");
00839 return 0;
00840 }
00841 }
00842
00843 bool Create::isLightBumperLeft() const {
00844 if (data->isValidPacketID(ID_LIGHT)) {
00845 return (GET_DATA(ID_LIGHT) & 0x01) != 0;
00846 }
00847 else {
00848 CERR("[create::Create] ", "Light sensors not supported!");
00849 return false;
00850 }
00851 }
00852
00853 bool Create::isLightBumperFrontLeft() const {
00854 if (data->isValidPacketID(ID_LIGHT)) {
00855 return (GET_DATA(ID_LIGHT) & 0x02) != 0;
00856 }
00857 else {
00858 CERR("[create::Create] ", "Light sensors not supported!");
00859 return false;
00860 }
00861 }
00862
00863 bool Create::isLightBumperCenterLeft() const {
00864 if (data->isValidPacketID(ID_LIGHT)) {
00865 return (GET_DATA(ID_LIGHT) & 0x04) != 0;
00866 }
00867 else {
00868 CERR("[create::Create] ", "Light sensors not supported!");
00869 return false;
00870 }
00871 }
00872
00873 bool Create::isLightBumperCenterRight() const {
00874 if (data->isValidPacketID(ID_LIGHT)) {
00875 return (GET_DATA(ID_LIGHT) & 0x08) != 0;
00876 }
00877 else {
00878 CERR("[create::Create] ", "Light sensors not supported!");
00879 return false;
00880 }
00881 }
00882
00883 bool Create::isLightBumperFrontRight() const {
00884 if (data->isValidPacketID(ID_LIGHT)) {
00885 return (GET_DATA(ID_LIGHT) & 0x10) != 0;
00886 }
00887 else {
00888 CERR("[create::Create] ", "Light sensors not supported!");
00889 return false;
00890 }
00891 }
00892
00893 bool Create::isLightBumperRight() const {
00894 if (data->isValidPacketID(ID_LIGHT)) {
00895 return (GET_DATA(ID_LIGHT) & 0x20) != 0;
00896 }
00897 else {
00898 CERR("[create::Create] ", "Light sensors not supported!");
00899 return false;
00900 }
00901 }
00902
00903 uint16_t Create::getLightSignalLeft() const {
00904 if (data->isValidPacketID(ID_LIGHT_LEFT)) {
00905 return GET_DATA(ID_LIGHT_LEFT);
00906 }
00907 else {
00908 CERR("[create::Create] ", "Light sensors not supported!");
00909 return 0;
00910 }
00911 }
00912
00913 uint16_t Create::getLightSignalFrontLeft() const {
00914 if (data->isValidPacketID(ID_LIGHT_FRONT_LEFT)) {
00915 return GET_DATA(ID_LIGHT_FRONT_LEFT);
00916 }
00917 else {
00918 CERR("[create::Create] ", "Light sensors not supported!");
00919 return 0;
00920 }
00921 }
00922
00923 uint16_t Create::getLightSignalCenterLeft() const {
00924 if (data->isValidPacketID(ID_LIGHT_CENTER_LEFT)) {
00925 return GET_DATA(ID_LIGHT_CENTER_LEFT);
00926 }
00927 else {
00928 CERR("[create::Create] ", "Light sensors not supported!");
00929 return 0;
00930 }
00931 }
00932
00933 uint16_t Create::getLightSignalRight() const {
00934 if (data->isValidPacketID(ID_LIGHT_RIGHT)) {
00935 return GET_DATA(ID_LIGHT_RIGHT);
00936 }
00937 else {
00938 CERR("[create::Create] ", "Light sensors not supported!");
00939 return 0;
00940 }
00941 }
00942
00943 uint16_t Create::getLightSignalFrontRight() const {
00944 if (data->isValidPacketID(ID_LIGHT_FRONT_RIGHT)) {
00945 return GET_DATA(ID_LIGHT_FRONT_RIGHT);
00946 }
00947 else {
00948 CERR("[create::Create] ", "Light sensors not supported!");
00949 return 0;
00950 }
00951 }
00952
00953 uint16_t Create::getLightSignalCenterRight() const {
00954 if (data->isValidPacketID(ID_LIGHT_CENTER_RIGHT)) {
00955 return GET_DATA(ID_LIGHT_CENTER_RIGHT);
00956 }
00957 else {
00958 CERR("[create::Create] ", "Light sensors not supported!");
00959 return 0;
00960 }
00961 }
00962
00963 bool Create::isMovingForward() const {
00964 if (data->isValidPacketID(ID_STASIS)) {
00965 return GET_DATA(ID_STASIS) == 1;
00966 }
00967 else {
00968 CERR("[create::Create] ", "Stasis sensor not supported!");
00969 return false;
00970 }
00971 }
00972
00973 float Create::getLeftWheelDistance() const {
00974 return totalLeftDist;
00975 }
00976
00977 float Create::getRightWheelDistance() const {
00978 return totalRightDist;
00979 }
00980
00981 float Create::getMeasuredLeftWheelVel() const {
00982 return measuredLeftVel;
00983 }
00984
00985 float Create::getMeasuredRightWheelVel() const {
00986 return measuredRightVel;
00987 }
00988
00989 float Create::getRequestedLeftWheelVel() const {
00990 return requestedLeftVel;
00991 }
00992
00993 float Create::getRequestedRightWheelVel() const {
00994 return requestedRightVel;
00995 }
00996
00997 create::CreateMode Create::getMode() {
00998 if (data->isValidPacketID(ID_OI_MODE)) {
00999 mode = (create::CreateMode) GET_DATA(ID_OI_MODE);
01000 }
01001 return mode;
01002 }
01003
01004 Pose Create::getPose() const {
01005 return pose;
01006 }
01007
01008 Vel Create::getVel() const {
01009 return vel;
01010 }
01011
01012 uint64_t Create::getNumCorruptPackets() const {
01013 return serial->getNumCorruptPackets();
01014 }
01015
01016 uint64_t Create::getTotalPackets() const {
01017 return serial->getTotalPackets();
01018 }
01019
01020 }