create.cpp
Go to the documentation of this file.
1 #include <boost/bind.hpp>
2 #include <boost/make_shared.hpp>
3 #include <iostream>
4 #include <cmath>
5 #include <ctime>
6 #include <assert.h>
7 
8 #include "create/create.h"
9 
10 #define GET_DATA(id) (data->getPacket(id)->getData())
11 #define BOUND_CONST(val,min,max) (val<min?min:(val>max?max:val))
12 #define BOUND(val,min,max) (val = BOUND_CONST(val,min,max))
13 
14 namespace create {
15 
16  namespace ublas = boost::numeric::ublas;
17 
18  // TODO: Handle SIGINT to do clean disconnect
19 
20  void Create::init() {
21  mainMotorPower = 0;
22  sideMotorPower = 0;
23  vacuumMotorPower = 0;
24  debrisLED = 0;
25  spotLED = 0;
26  dockLED = 0;
27  checkLED = 0;
28  powerLED = 0;
30  prevTicksLeft = 0;
31  prevTicksRight = 0;
32  totalLeftDist = 0.0;
33  totalRightDist = 0.0;
34  firstOnData = true;
35  mode = MODE_OFF;
36  pose.x = 0;
37  pose.y = 0;
38  pose.yaw = 0;
39  pose.covariance = std::vector<float>(9, 0.0);
40  vel.x = 0;
41  vel.y = 0;
42  vel.yaw = 0;
43  vel.covariance = std::vector<float>(9, 0.0);
44  poseCovar = Matrix(3, 3, 0.0);
45  requestedLeftVel = 0;
47  data = boost::shared_ptr<Data>(new Data(model.getVersion()));
48  if (model.getVersion() == V_1) {
49  serial = boost::make_shared<SerialQuery>(data);
50  } else {
51  serial = boost::make_shared<SerialStream>(data);
52  }
53  }
54 
56  init();
57  }
58 
59  Create::Create(const std::string& dev, const int& baud, RobotModel m) : model(m) {
60  init();
61  serial->connect(dev, baud);
62  }
63 
65  disconnect();
66  }
67 
68  Create::Matrix Create::addMatrices(const Matrix &A, const Matrix &B) const {
69  int rows = A.size1();
70  int cols = A.size2();
71 
72  assert(rows == B.size1());
73  assert(cols == B.size2());
74 
75  Matrix C(rows, cols);
76  for (int i = 0; i < rows; i++) {
77  for (int j = 0; j < cols; j++) {
78  const float a = A(i, j);
79  const float b = B(i, j);
80  if (util::willFloatOverflow(a, b)) {
81  // If overflow, set to float min or max depending on direction of overflow
82  C(i, j) = (a < 0.0) ? std::numeric_limits<float>::min() : std::numeric_limits<float>::max();
83  }
84  else {
85  C(i, j) = a + b;
86  }
87  }
88  }
89  return C;
90  }
91 
92  void Create::onData() {
93  if (firstOnData) {
94  if (model.getVersion() >= V_3) {
95  // Initialize tick counts
98  }
100  firstOnData = false;
101  }
102 
103  // Get current time
105  float dt = (curTime - prevOnDataTime) / 1000000.0;
106  float deltaDist, deltaX, deltaY, deltaYaw, leftWheelDist, rightWheelDist, wheelDistDiff;
107 
108  // Protocol versions 1 and 2 use distance and angle fields for odometry
109  int16_t angleField;
110  if (model.getVersion() <= V_2) {
111  // This is a standards compliant way of doing unsigned to signed conversion
112  uint16_t distanceRaw = GET_DATA(ID_DISTANCE);
113  int16_t distance;
114  std::memcpy(&distance, &distanceRaw, sizeof(distance));
115  deltaDist = distance / 1000.0; // mm -> m
116 
117  // Angle is processed differently in versions 1 and 2
118  uint16_t angleRaw = GET_DATA(ID_ANGLE);
119  std::memcpy(&angleField, &angleRaw, sizeof(angleField));
120  }
121 
122  if (model.getVersion() == V_1) {
123  wheelDistDiff = 2.0 * angleField / 1000.0;
124  leftWheelDist = deltaDist - (wheelDistDiff / 2.0);
125  rightWheelDist = deltaDist + (wheelDistDiff / 2.0);
126  deltaYaw = wheelDistDiff / model.getAxleLength();
127  } else if (model.getVersion() == V_2) {
128  /* * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * *
129  * Certain older Creates have major problems with odometry *
130  * http://answers.ros.org/question/31935/createroomba-odometry/ *
131  * *
132  * All Creates have an issue with rounding of the angle field, which causes *
133  * major errors to accumulate in the odometry yaw. *
134  * http://wiki.tekkotsu.org/index.php/Create_Odometry_Bug *
135  * https://github.com/AutonomyLab/create_autonomy/issues/28 *
136  * *
137  * TODO: Consider using velocity command as substitute for pose estimation *
138  * to mitigate both of these problems. *
139  * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * */
140  deltaYaw = angleField * (util::PI / 180.0); // D2R
141  wheelDistDiff = model.getAxleLength() * deltaYaw;
142  leftWheelDist = deltaDist - (wheelDistDiff / 2.0);
143  rightWheelDist = deltaDist + (wheelDistDiff / 2.0);
144  } else if (model.getVersion() >= V_3) {
145  // Get cumulative ticks (wraps around at 65535)
146  uint16_t totalTicksLeft = GET_DATA(ID_LEFT_ENC);
147  uint16_t totalTicksRight = GET_DATA(ID_RIGHT_ENC);
148  // Compute ticks since last update
149  int ticksLeft = totalTicksLeft - prevTicksLeft;
150  int ticksRight = totalTicksRight - prevTicksRight;
151  prevTicksLeft = totalTicksLeft;
152  prevTicksRight = totalTicksRight;
153 
154  // Handle wrap around
155  if (fabs(ticksLeft) > 0.9 * util::V_3_MAX_ENCODER_TICKS) {
156  ticksLeft = (ticksLeft % util::V_3_MAX_ENCODER_TICKS) + 1;
157  }
158  if (fabs(ticksRight) > 0.9 * util::V_3_MAX_ENCODER_TICKS) {
159  ticksRight = (ticksRight % util::V_3_MAX_ENCODER_TICKS) + 1;
160  }
161 
162  // Compute distance travelled by each wheel
163  leftWheelDist = (ticksLeft / util::V_3_TICKS_PER_REV)
165  rightWheelDist = (ticksRight / util::V_3_TICKS_PER_REV)
167  deltaDist = (rightWheelDist + leftWheelDist) / 2.0;
168 
169  wheelDistDiff = rightWheelDist - leftWheelDist;
170  deltaYaw = wheelDistDiff / model.getAxleLength();
171  }
172 
173  measuredLeftVel = leftWheelDist / dt;
174  measuredRightVel = rightWheelDist / dt;
175 
176  // Moving straight
177  if (fabs(wheelDistDiff) < util::EPS) {
178  deltaX = deltaDist * cos(pose.yaw);
179  deltaY = deltaDist * sin(pose.yaw);
180  } else {
181  float turnRadius = (model.getAxleLength() / 2.0) * (leftWheelDist + rightWheelDist) / wheelDistDiff;
182  deltaX = turnRadius * (sin(pose.yaw + deltaYaw) - sin(pose.yaw));
183  deltaY = -turnRadius * (cos(pose.yaw + deltaYaw) - cos(pose.yaw));
184  }
185 
186  totalLeftDist += leftWheelDist;
187  totalRightDist += rightWheelDist;
188 
189  if (fabs(dt) > util::EPS) {
190  vel.x = deltaDist / dt;
191  vel.y = 0.0;
192  vel.yaw = deltaYaw / dt;
193  } else {
194  vel.x = 0.0;
195  vel.y = 0.0;
196  vel.yaw = 0.0;
197  }
198 
199  // Update covariances
200  // Ref: "Introduction to Autonomous Mobile Robots" (Siegwart 2004, page 189)
201  float kr = 1.0; // TODO: Perform experiments to find these nondeterministic parameters
202  float kl = 1.0;
203  float cosYawAndHalfDelta = cos(pose.yaw + (deltaYaw / 2.0)); // deltaX?
204  float sinYawAndHalfDelta = sin(pose.yaw + (deltaYaw / 2.0)); // deltaY?
205  float distOverTwoWB = deltaDist / (model.getAxleLength() * 2.0);
206 
207  Matrix invCovar(2, 2);
208  invCovar(0, 0) = kr * fabs(rightWheelDist);
209  invCovar(0, 1) = 0.0;
210  invCovar(1, 0) = 0.0;
211  invCovar(1, 1) = kl * fabs(leftWheelDist);
212 
213  Matrix Finc(3, 2);
214  Finc(0, 0) = (cosYawAndHalfDelta / 2.0) - (distOverTwoWB * sinYawAndHalfDelta);
215  Finc(0, 1) = (cosYawAndHalfDelta / 2.0) + (distOverTwoWB * sinYawAndHalfDelta);
216  Finc(1, 0) = (sinYawAndHalfDelta / 2.0) + (distOverTwoWB * cosYawAndHalfDelta);
217  Finc(1, 1) = (sinYawAndHalfDelta / 2.0) - (distOverTwoWB * cosYawAndHalfDelta);
218  Finc(2, 0) = (1.0 / model.getAxleLength());
219  Finc(2, 1) = (-1.0 / model.getAxleLength());
220  Matrix FincT = boost::numeric::ublas::trans(Finc);
221 
222  Matrix Fp(3, 3);
223  Fp(0, 0) = 1.0;
224  Fp(0, 1) = 0.0;
225  Fp(0, 2) = (-deltaDist) * sinYawAndHalfDelta;
226  Fp(1, 0) = 0.0;
227  Fp(1, 1) = 1.0;
228  Fp(1, 2) = deltaDist * cosYawAndHalfDelta;
229  Fp(2, 0) = 0.0;
230  Fp(2, 1) = 0.0;
231  Fp(2, 2) = 1.0;
232  Matrix FpT = boost::numeric::ublas::trans(Fp);
233 
234  Matrix velCovar = ublas::prod(invCovar, FincT);
235  velCovar = ublas::prod(Finc, velCovar);
236 
237  vel.covariance[0] = velCovar(0, 0);
238  vel.covariance[1] = velCovar(0, 1);
239  vel.covariance[2] = velCovar(0, 2);
240  vel.covariance[3] = velCovar(1, 0);
241  vel.covariance[4] = velCovar(1, 1);
242  vel.covariance[5] = velCovar(1, 2);
243  vel.covariance[6] = velCovar(2, 0);
244  vel.covariance[7] = velCovar(2, 1);
245  vel.covariance[8] = velCovar(2, 2);
246 
247  Matrix poseCovarTmp = ublas::prod(poseCovar, FpT);
248  poseCovarTmp = ublas::prod(Fp, poseCovarTmp);
249  poseCovar = addMatrices(poseCovarTmp, velCovar);
250 
251  pose.covariance[0] = poseCovar(0, 0);
252  pose.covariance[1] = poseCovar(0, 1);
253  pose.covariance[2] = poseCovar(0, 2);
254  pose.covariance[3] = poseCovar(1, 0);
255  pose.covariance[4] = poseCovar(1, 1);
256  pose.covariance[5] = poseCovar(1, 2);
257  pose.covariance[6] = poseCovar(2, 0);
258  pose.covariance[7] = poseCovar(2, 1);
259  pose.covariance[8] = poseCovar(2, 2);
260 
261  // Update pose
262  pose.x += deltaX;
263  pose.y += deltaY;
264  pose.yaw = util::normalizeAngle(pose.yaw + deltaYaw);
265 
266  prevOnDataTime = curTime;
267 
268  // Make user registered callbacks, if any
269  // TODO
270  }
271 
272  bool Create::connect(const std::string& port, const int& baud) {
273  bool timeout = false;
274  time_t start, now;
275  float maxWait = 30; // seconds
276  float retryInterval = 5; //seconds
277  time(&start);
278  while (!serial->connect(port, baud, boost::bind(&Create::onData, this)) && !timeout) {
279  time(&now);
280  if (difftime(now, start) > maxWait) {
281  timeout = true;
282  CERR("[create::Create] ", "failed to connect over serial: timeout");
283  }
284  else {
285  usleep(retryInterval * 1000000);
286  COUT("[create::Create] ", "retrying to establish serial connection...");
287  }
288  }
289 
290  return !timeout;
291  }
292 
294  serial->disconnect();
295  firstOnData = true;
296  }
297 
298  //void Create::reset() {
299  // serial->sendOpcode(OC_RESET);
300  // serial->reset(); // better
301  // TODO : Should we request reading packets again?
302  //}
303 
305  if (model.getVersion() == V_1){
306  // Switch to safe mode (required for compatibility with V_1)
307  if (!(serial->sendOpcode(OC_START) && serial->sendOpcode(OC_CONTROL))) return false;
308  }
309  bool ret;
310  switch (mode) {
311  case MODE_OFF:
312  if (model.getVersion() == V_2) {
313  CERR("[create::Create] ", "protocol version 2 does not support turning robot off");
314  ret = false;
315  } else {
316  ret = serial->sendOpcode(OC_POWER);
317  }
318  break;
319  case MODE_PASSIVE:
320  ret = serial->sendOpcode(OC_START);
321  break;
322  case MODE_SAFE:
323  if (model.getVersion() > V_1) {
324  ret = serial->sendOpcode(OC_SAFE);
325  }
326  break;
327  case MODE_FULL:
328  ret = serial->sendOpcode(OC_FULL);
329  break;
330  default:
331  CERR("[create::Create] ", "cannot set robot to mode '" << mode << "'");
332  ret = false;
333  }
334  if (ret) {
335  this->mode = mode;
336  }
337  return ret;
338  }
339 
340  bool Create::clean(const CleanMode& mode) {
341  return serial->sendOpcode((Opcode) mode);
342  }
343 
344  bool Create::dock() const {
345  return serial->sendOpcode(OC_DOCK);
346  }
347 
348  bool Create::setDate(const DayOfWeek& day, const uint8_t& hour, const uint8_t& min) const {
349  if (day < 0 || day > 6 ||
350  hour < 0 || hour > 23 ||
351  min < 0 || min > 59)
352  return false;
353 
354  uint8_t cmd[4] = { OC_DATE, day, hour, min };
355  return serial->send(cmd, 4);
356  }
357 
358  bool Create::driveRadius(const float& vel, const float& radius) {
359  // Bound velocity
360  float boundedVel = BOUND_CONST(vel, -model.getMaxVelocity(), model.getMaxVelocity());
361 
362  // Expects each parameter as two bytes each and in millimeters
363  int16_t vel_mm = roundf(boundedVel * 1000);
364  int16_t radius_mm = roundf(radius * 1000);
365 
366  // Bound radius if not a special case
367  if (radius_mm != 32768 && radius_mm != 32767 &&
368  radius_mm != -1 && radius_mm != 1) {
369  BOUND(radius_mm, -util::MAX_RADIUS * 1000, util::MAX_RADIUS * 1000);
370  }
371 
372  uint8_t cmd[5] = { OC_DRIVE,
373  static_cast<uint8_t>(vel_mm >> 8),
374  static_cast<uint8_t>(vel_mm & 0xff),
375  static_cast<uint8_t>(radius_mm >> 8),
376  static_cast<uint8_t>(radius_mm & 0xff)
377  };
378 
379  return serial->send(cmd, 5);
380  }
381 
382  bool Create::driveWheels(const float& leftVel, const float& rightVel) {
383  const float boundedLeftVel = BOUND_CONST(leftVel, -model.getMaxVelocity(), model.getMaxVelocity());
384  const float boundedRightVel = BOUND_CONST(rightVel, -model.getMaxVelocity(), model.getMaxVelocity());
385  requestedLeftVel = boundedLeftVel;
386  requestedRightVel = boundedRightVel;
387  if (model.getVersion() > V_1) {
388  int16_t leftCmd = roundf(boundedLeftVel * 1000);
389  int16_t rightCmd = roundf(boundedRightVel * 1000);
390 
391  uint8_t cmd[5] = { OC_DRIVE_DIRECT,
392  static_cast<uint8_t>(rightCmd >> 8),
393  static_cast<uint8_t>(rightCmd & 0xff),
394  static_cast<uint8_t>(leftCmd >> 8),
395  static_cast<uint8_t>(leftCmd & 0xff)
396  };
397  return serial->send(cmd, 5);
398  } else {
399  float radius;
400  // Prevent divide by zero when driving straight
401  if (boundedLeftVel != boundedRightVel) {
402  radius = -((model.getAxleLength() / 2.0) * (boundedLeftVel + boundedRightVel)) /
403  (boundedLeftVel - boundedRightVel);
404  } else {
405  radius = util::STRAIGHT_RADIUS;
406  }
407 
408  float vel;
409  // Fix signs for spin in place
410  if (boundedLeftVel == -boundedRightVel || std::abs(roundf(radius * 1000)) <= 1) {
411  radius = util::IN_PLACE_RADIUS;
412  vel = boundedRightVel;
413  } else {
414  vel = (std::abs(boundedLeftVel) + std::abs(boundedRightVel)) / 2.0 * ((boundedLeftVel + boundedRightVel) > 0 ? 1.0 : -1.0);
415  }
416 
417  // Radius turns have a maximum radius of 2.0 meters
418  // When the radius is > 2 but <= 10, use a 2 meter radius
419  // When it is > 10, drive straight
420  // TODO: alternate between these 2 meter radius and straight to
421  // fake a larger radius
422  if (radius > 10.0) {
423  radius = util::STRAIGHT_RADIUS;
424  }
425 
426  return driveRadius(vel, radius);
427  }
428  }
429 
430  bool Create::driveWheelsPwm(const float& leftWheel, const float& rightWheel)
431  {
432  static const int16_t PWM_COUNTS = 255;
433 
434  if (leftWheel < -1.0 || leftWheel > 1.0 ||
435  rightWheel < -1.0 || rightWheel > 1.0)
436  return false;
437 
438  int16_t leftPwm = roundf(leftWheel * PWM_COUNTS);
439  int16_t rightPwm = roundf(rightWheel * PWM_COUNTS);
440 
441  uint8_t cmd[5] = { OC_DRIVE_PWM,
442  static_cast<uint8_t>(rightPwm >> 8),
443  static_cast<uint8_t>(rightPwm & 0xff),
444  static_cast<uint8_t>(leftPwm >> 8),
445  static_cast<uint8_t>(leftPwm & 0xff)
446  };
447 
448  return serial->send(cmd, 5);
449  }
450 
451  bool Create::drive(const float& xVel, const float& angularVel) {
452  // Compute left and right wheel velocities
453  float leftVel = xVel - ((model.getAxleLength() / 2.0) * angularVel);
454  float rightVel = xVel + ((model.getAxleLength() / 2.0) * angularVel);
455  return driveWheels(leftVel, rightVel);
456  }
457 
458  bool Create::setAllMotors(const float& main, const float& side, const float& vacuum) {
459  if (main < -1.0 || main > 1.0 ||
460  side < -1.0 || side > 1.0 ||
461  vacuum < -1.0 || vacuum > 1.0)
462  return false;
463 
464  mainMotorPower = roundf(main * 127);
465  sideMotorPower = roundf(side * 127);
466  vacuumMotorPower = roundf(vacuum * 127);
467 
468  uint8_t cmd[4] = { OC_MOTORS_PWM,
472  };
473 
474  return serial->send(cmd, 4);
475  }
476 
477  bool Create::setMainMotor(const float& main) {
479  }
480 
481  bool Create::setSideMotor(const float& side) {
483  }
484 
485  bool Create::setVacuumMotor(const float& vacuum) {
486  return setAllMotors(mainMotorPower, sideMotorPower, vacuum);
487  }
488 
490  uint8_t LEDByte = debrisLED + spotLED + dockLED + checkLED;
491  uint8_t cmd[4] = { OC_LEDS,
492  LEDByte,
493  powerLED,
495  };
496 
497  return serial->send(cmd, 4);
498  }
499 
500  bool Create::enableDebrisLED(const bool& enable) {
501  if (enable)
503  else
504  debrisLED = 0;
505  return updateLEDs();
506  }
507 
508  bool Create::enableSpotLED(const bool& enable) {
509  if (enable)
510  spotLED = LED_SPOT;
511  else
512  spotLED = 0;
513  return updateLEDs();
514  }
515 
516  bool Create::enableDockLED(const bool& enable) {
517  if (enable)
518  dockLED = LED_DOCK;
519  else
520  dockLED = 0;
521  return updateLEDs();
522  }
523 
524  bool Create::enableCheckRobotLED(const bool& enable) {
525  if (enable)
527  else
528  checkLED = 0;
529  return updateLEDs();
530  }
531 
532  bool Create::setPowerLED(const uint8_t& power, const uint8_t& intensity) {
533  powerLED = power;
534  powerLEDIntensity = intensity;
535  return updateLEDs();
536  }
537 
538  //void Create::setDigits(uint8_t digit1, uint8_t digit2,
539  // uint8_t digit3, uint8_t digit4) {
540  //}
541 
542  bool Create::setDigitsASCII(const uint8_t& digit1, const uint8_t& digit2,
543  const uint8_t& digit3, const uint8_t& digit4) const {
544  if (digit1 < 32 || digit1 > 126 ||
545  digit2 < 32 || digit2 > 126 ||
546  digit3 < 32 || digit3 > 126 ||
547  digit4 < 32 || digit4 > 126)
548  return false;
549 
550  uint8_t cmd[5] = { OC_DIGIT_LEDS_ASCII,
551  digit1,
552  digit2,
553  digit3,
554  digit4
555  };
556 
557  return serial->send(cmd, 5);
558  }
559 
560  bool Create::defineSong(const uint8_t& songNumber,
561  const uint8_t& songLength,
562  const uint8_t* notes,
563  const float* durations) const {
564  int i, j;
565  uint8_t duration;
566  uint8_t cmd[2 * songLength + 3];
567  cmd[0] = OC_SONG;
568  cmd[1] = songNumber;
569  cmd[2] = songLength;
570  j = 0;
571  for (i = 3; i < 2 * songLength + 3; i = i + 2) {
572  if (durations[j] < 0 || durations[j] >= 4)
573  return false;
574  duration = durations[j] * 64;
575  cmd[i] = notes[j];
576  cmd[i + 1] = duration;
577  j++;
578  }
579 
580  return serial->send(cmd, 2 * songLength + 3);
581  }
582 
583  bool Create::playSong(const uint8_t& songNumber) const {
584  if (songNumber < 0 || songNumber > 4)
585  return false;
586  uint8_t cmd[2] = { OC_PLAY, songNumber };
587  return serial->send(cmd, 2);
588  }
589 
590  bool Create::isWheeldrop() const {
591  if (data->isValidPacketID(ID_BUMP_WHEELDROP)) {
592  return (GET_DATA(ID_BUMP_WHEELDROP) & 0x0C) != 0;
593  }
594  else {
595  CERR("[create::Create] ", "Wheeldrop sensor not supported!");
596  return false;
597  }
598  }
599 
600  bool Create::isLeftBumper() const {
601  if (data->isValidPacketID(ID_BUMP_WHEELDROP)) {
602  return (GET_DATA(ID_BUMP_WHEELDROP) & 0x02) != 0;
603  }
604  else {
605  CERR("[create::Create] ", "Left bumper not supported!");
606  return false;
607  }
608  }
609 
610  bool Create::isRightBumper() const {
611  if (data->isValidPacketID(ID_BUMP_WHEELDROP)) {
612  return (GET_DATA(ID_BUMP_WHEELDROP) & 0x01) != 0;
613  }
614  else {
615  CERR("[create::Create] ", "Right bumper not supported!");
616  return false;
617  }
618  }
619 
620  bool Create::isWall() const {
621  if (data->isValidPacketID(ID_WALL)) {
622  return GET_DATA(ID_WALL) == 1;
623  }
624  else {
625  CERR("[create::Create] ", "Wall sensor not supported!");
626  return false;
627  }
628  }
629 
630  bool Create::isCliff() const {
631  if (data->isValidPacketID(ID_CLIFF_LEFT) &&
632  data->isValidPacketID(ID_CLIFF_FRONT_LEFT) &&
633  data->isValidPacketID(ID_CLIFF_FRONT_RIGHT) &&
634  data->isValidPacketID(ID_CLIFF_RIGHT)) {
635  return GET_DATA(ID_CLIFF_LEFT) == 1 ||
638  GET_DATA(ID_CLIFF_RIGHT) == 1;
639  }
640  else {
641  CERR("[create::Create] ", "Cliff sensors not supported!");
642  return false;
643  }
644  }
645 
646  bool Create::isVirtualWall() const {
647  if (data->isValidPacketID(ID_VIRTUAL_WALL)) {
648  return GET_DATA(ID_VIRTUAL_WALL);
649  }
650  else {
651  CERR("[create::Create] ", "Virtual Wall sensor not supported!");
652  return false;
653  }
654  }
655 
656  uint8_t Create::getDirtDetect() const {
657  if (data->isValidPacketID(ID_DIRT_DETECT_LEFT)) {
659  }
660  else {
661  CERR("[create::Create] ", "Dirt detector not supported!");
662  return -1;
663  }
664  }
665 
666  uint8_t Create::getIROmni() const {
667  if (data->isValidPacketID(ID_IR_OMNI)) {
668  return GET_DATA(ID_IR_OMNI);
669  }
670  else {
671  CERR("[create::Create] ", "Omni IR sensor not supported!");
672  return -1;
673  }
674  }
675 
676  uint8_t Create::getIRLeft() const {
677  if (data->isValidPacketID(ID_IR_LEFT)) {
678  return GET_DATA(ID_IR_LEFT);
679  }
680  else {
681  CERR("[create::Create] ", "Left IR sensor not supported!");
682  return -1;
683  }
684  }
685 
686  uint8_t Create::getIRRight() const {
687  if (data->isValidPacketID(ID_IR_RIGHT)) {
688  return GET_DATA(ID_IR_RIGHT);
689  }
690  else {
691  CERR("[create::Create] ", "Right IR sensor not supported!");
692  return -1;
693  }
694  }
695 
697  if (data->isValidPacketID(ID_CHARGE_STATE)) {
698  uint8_t chargeState = GET_DATA(ID_CHARGE_STATE);
699  assert(chargeState >= 0);
700  assert(chargeState <= 5);
701  return (ChargingState) chargeState;
702  }
703  else {
704  CERR("[create::Create] ", "Charging state not supported!");
705  return CHARGE_FAULT;
706  }
707  }
708 
710  if (data->isValidPacketID(ID_BUTTONS)) {
711  return (GET_DATA(ID_BUTTONS) & 0x01) != 0;
712  }
713  else {
714  CERR("[create::Create] ", "Buttons not supported!");
715  return false;
716  }
717  }
718 
719  // Not supported by any 600 series firmware
721  CERR("[create::Create] ", "Clock button is not supported!");
722  if (data->isValidPacketID(ID_BUTTONS)) {
723  return (GET_DATA(ID_BUTTONS) & 0x80) != 0;
724  }
725  else {
726  CERR("[create::Create] ", "Buttons not supported!");
727  return false;
728  }
729  }
730 
731  // Not supported by any 600 series firmware
733  CERR("[create::Create] ", "Schedule button is not supported!");
734  if (data->isValidPacketID(ID_BUTTONS)) {
735  return (GET_DATA(ID_BUTTONS) & 0x40) != 0;
736  }
737  else {
738  CERR("[create::Create] ", "Buttons not supported!");
739  return false;
740  }
741  }
742 
744  if (data->isValidPacketID(ID_BUTTONS)) {
745  return (GET_DATA(ID_BUTTONS) & 0x20) != 0;
746  }
747  else {
748  CERR("[create::Create] ", "Buttons not supported!");
749  return false;
750  }
751  }
752 
754  if (data->isValidPacketID(ID_BUTTONS)) {
755  return (GET_DATA(ID_BUTTONS) & 0x10) != 0;
756  }
757  else {
758  CERR("[create::Create] ", "Buttons not supported!");
759  return false;
760  }
761  }
762 
764  if (data->isValidPacketID(ID_BUTTONS)) {
765  return (GET_DATA(ID_BUTTONS) & 0x08) != 0;
766  }
767  else {
768  CERR("[create::Create] ", "Buttons not supported!");
769  return false;
770  }
771  }
772 
774  if (data->isValidPacketID(ID_BUTTONS)) {
775  return (GET_DATA(ID_BUTTONS) & 0x04) != 0;
776  }
777  else {
778  CERR("[create::Create] ", "Buttons not supported!");
779  return false;
780  }
781  }
782 
784  if (data->isValidPacketID(ID_BUTTONS)) {
785  return (GET_DATA(ID_BUTTONS) & 0x02) != 0;
786  }
787  else {
788  CERR("[create::Create] ", "Buttons not supported!");
789  return false;
790  }
791  }
792 
793  float Create::getVoltage() const {
794  if (data->isValidPacketID(ID_VOLTAGE)) {
795  return (GET_DATA(ID_VOLTAGE) / 1000.0);
796  }
797  else {
798  CERR("[create::Create] ", "Voltage sensor not supported!");
799  return 0;
800  }
801  }
802 
803  float Create::getCurrent() const {
804  if (data->isValidPacketID(ID_VOLTAGE)) {
805  return (((int16_t)GET_DATA(ID_CURRENT)) / 1000.0);
806  }
807  else {
808  CERR("[create::Create] ", "Current sensor not supported!");
809  return 0;
810  }
811  }
812 
813  int8_t Create::getTemperature() const {
814  if (data->isValidPacketID(ID_TEMP)) {
815  return (int8_t) GET_DATA(ID_TEMP);
816  }
817  else {
818  CERR("[create::Create] ", "Temperature sensor not supported!");
819  return 0;
820  }
821  }
822 
823  float Create::getBatteryCharge() const {
824  if (data->isValidPacketID(ID_CHARGE)) {
825  return (GET_DATA(ID_CHARGE) / 1000.0);
826  }
827  else {
828  CERR("[create::Create] ", "Battery charge not supported!");
829  return 0;
830  }
831  }
832 
834  if (data->isValidPacketID(ID_CAPACITY)) {
835  return (GET_DATA(ID_CAPACITY) / 1000.0);
836  }
837  else {
838  CERR("[create::Create] ", "Battery capacity not supported!");
839  return 0;
840  }
841  }
842 
844  if (data->isValidPacketID(ID_LIGHT)) {
845  return (GET_DATA(ID_LIGHT) & 0x01) != 0;
846  }
847  else {
848  CERR("[create::Create] ", "Light sensors not supported!");
849  return false;
850  }
851  }
852 
854  if (data->isValidPacketID(ID_LIGHT)) {
855  return (GET_DATA(ID_LIGHT) & 0x02) != 0;
856  }
857  else {
858  CERR("[create::Create] ", "Light sensors not supported!");
859  return false;
860  }
861  }
862 
864  if (data->isValidPacketID(ID_LIGHT)) {
865  return (GET_DATA(ID_LIGHT) & 0x04) != 0;
866  }
867  else {
868  CERR("[create::Create] ", "Light sensors not supported!");
869  return false;
870  }
871  }
872 
874  if (data->isValidPacketID(ID_LIGHT)) {
875  return (GET_DATA(ID_LIGHT) & 0x08) != 0;
876  }
877  else {
878  CERR("[create::Create] ", "Light sensors not supported!");
879  return false;
880  }
881  }
882 
884  if (data->isValidPacketID(ID_LIGHT)) {
885  return (GET_DATA(ID_LIGHT) & 0x10) != 0;
886  }
887  else {
888  CERR("[create::Create] ", "Light sensors not supported!");
889  return false;
890  }
891  }
892 
894  if (data->isValidPacketID(ID_LIGHT)) {
895  return (GET_DATA(ID_LIGHT) & 0x20) != 0;
896  }
897  else {
898  CERR("[create::Create] ", "Light sensors not supported!");
899  return false;
900  }
901  }
902 
903  uint16_t Create::getLightSignalLeft() const {
904  if (data->isValidPacketID(ID_LIGHT_LEFT)) {
905  return GET_DATA(ID_LIGHT_LEFT);
906  }
907  else {
908  CERR("[create::Create] ", "Light sensors not supported!");
909  return 0;
910  }
911  }
912 
914  if (data->isValidPacketID(ID_LIGHT_FRONT_LEFT)) {
916  }
917  else {
918  CERR("[create::Create] ", "Light sensors not supported!");
919  return 0;
920  }
921  }
922 
924  if (data->isValidPacketID(ID_LIGHT_CENTER_LEFT)) {
926  }
927  else {
928  CERR("[create::Create] ", "Light sensors not supported!");
929  return 0;
930  }
931  }
932 
933  uint16_t Create::getLightSignalRight() const {
934  if (data->isValidPacketID(ID_LIGHT_RIGHT)) {
935  return GET_DATA(ID_LIGHT_RIGHT);
936  }
937  else {
938  CERR("[create::Create] ", "Light sensors not supported!");
939  return 0;
940  }
941  }
942 
944  if (data->isValidPacketID(ID_LIGHT_FRONT_RIGHT)) {
946  }
947  else {
948  CERR("[create::Create] ", "Light sensors not supported!");
949  return 0;
950  }
951  }
952 
954  if (data->isValidPacketID(ID_LIGHT_CENTER_RIGHT)) {
956  }
957  else {
958  CERR("[create::Create] ", "Light sensors not supported!");
959  return 0;
960  }
961  }
962 
963  bool Create::isMovingForward() const {
964  if (data->isValidPacketID(ID_STASIS)) {
965  return GET_DATA(ID_STASIS) == 1;
966  }
967  else {
968  CERR("[create::Create] ", "Stasis sensor not supported!");
969  return false;
970  }
971  }
972 
974  return totalLeftDist;
975  }
976 
978  return totalRightDist;
979  }
980 
982  return measuredLeftVel;
983  }
984 
986  return measuredRightVel;
987  }
988 
990  return requestedLeftVel;
991  }
992 
994  return requestedRightVel;
995  }
996 
998  if (data->isValidPacketID(ID_OI_MODE)) {
1000  }
1001  return mode;
1002  }
1003 
1005  return pose;
1006  }
1007 
1009  return vel;
1010  }
1011 
1012  uint64_t Create::getNumCorruptPackets() const {
1013  return serial->getNumCorruptPackets();
1014  }
1015 
1016  uint64_t Create::getTotalPackets() const {
1017  return serial->getTotalPackets();
1018  }
1019 
1020 } // end namespace
uint64_t getTotalPackets() const
Get the total number of serial packets received (including corrupt packets) since first connecting to...
Definition: create.cpp:1016
ChargingState
Definition: types.h:216
bool setSideMotor(const float &power)
Set the power to the side brush motor.
Definition: create.cpp:481
void init()
Definition: create.cpp:20
static const float PI
Definition: util.h:49
uint8_t getIROmni() const
Get value of 8-bit IR character currently being received by omnidirectional sensor.
Definition: create.cpp:666
float totalLeftDist
Definition: create.h:79
create::Vel vel
Definition: create.h:75
uint8_t dockLED
Definition: create.h:67
uint8_t powerLEDIntensity
Definition: create.h:70
float y
Definition: types.h:277
static const float IN_PLACE_RADIUS
Definition: util.h:48
float totalRightDist
Definition: create.h:80
float getMeasuredRightWheelVel() const
Get the measured velocity of the right wheel.
Definition: create.cpp:985
bool setVacuumMotor(const float &power)
Set the power to the vacuum motor.
Definition: create.cpp:485
bool isWheeldrop() const
Definition: create.cpp:590
bool firstOnData
Definition: create.h:81
bool isLightBumperFrontLeft() const
Definition: create.cpp:853
bool setDigitsASCII(const uint8_t &digit1, const uint8_t &digit2, const uint8_t &digit3, const uint8_t &digit4) const
Set the four 7-segment display digits from left to right with ASCII codes. Any code out side the acce...
Definition: create.cpp:542
float requestedRightVel
Definition: create.h:89
bool isLeftBumper() const
Definition: create.cpp:600
float yaw
Definition: types.h:278
create::ChargingState getChargingState() const
Get the current charging state.
Definition: create.cpp:696
bool driveWheels(const float &leftWheel, const float &rightWheel)
Set the velocities for the left and right wheels.
Definition: create.cpp:382
bool dock() const
Starts the docking behaviour. Changes mode to MODE_PASSIVE.
Definition: create.cpp:344
uint32_t prevTicksRight
Definition: create.h:78
create::Pose pose
Definition: create.h:74
int8_t getTemperature() const
Get the temperature of battery.
Definition: create.cpp:813
bool isHourButtonPressed() const
Get state of &#39;hour&#39; button.
Definition: create.cpp:753
bool isClockButtonPressed() const
Not supported by any firmware!
Definition: create.cpp:720
uint16_t getLightSignalFrontLeft() const
Get the signal strength from the front-left light sensor.
Definition: create.cpp:913
static timestamp_t getTimestamp()
Definition: util.h:64
bool isLightBumperCenterRight() const
Definition: create.cpp:873
float getRequestedLeftWheelVel() const
Get the requested velocity of the left wheel. This value is bounded at the maximum velocity of the ro...
Definition: create.cpp:989
#define BOUND(val, min, max)
Definition: create.cpp:12
uint8_t spotLED
Definition: create.h:66
unsigned long long timestamp_t
Definition: util.h:58
bool setDate(const create::DayOfWeek &day, const uint8_t &hour, const uint8_t &min) const
Sets the internal clock of Create.
Definition: create.cpp:348
Opcode
Definition: types.h:154
float getRightWheelDistance() const
Get the total distance the right wheel has moved.
Definition: create.cpp:977
create::Pose getPose() const
Get the estimated pose of Create based on wheel encoders.
Definition: create.cpp:1004
boost::shared_ptr< create::Serial > serial
Definition: create.h:99
Definition: create.h:46
uint8_t getDirtDetect() const
Get level of the dirt detect sensor.
Definition: create.cpp:656
uint8_t powerLED
Definition: create.h:69
float getRequestedRightWheelVel() const
Get the requested velocity of the right wheel. This value is bounded at the maximum velocity of the r...
Definition: create.cpp:993
bool enableDockLED(const bool &enable)
Set the green "dock" LED on/off.
Definition: create.cpp:516
bool setPowerLED(const uint8_t &power, const uint8_t &intensity=255)
Set the center power LED.
Definition: create.cpp:532
bool isLightBumperFrontRight() const
Definition: create.cpp:883
float getBatteryCharge() const
Get battery&#39;s remaining charge.
Definition: create.cpp:823
uint8_t getIRRight() const
Get value of 8-bit IR character currently being received by right sensor.
Definition: create.cpp:686
float getCurrent() const
Get current flowing in/out of battery. A positive current implies Create is charging.
Definition: create.cpp:803
bool driveWheelsPwm(const float &leftWheel, const float &rightWheel)
Set the direct for the left and right wheels.
Definition: create.cpp:430
ProtocolVersion getVersion() const
Definition: types.cpp:27
CreateMode mode
Definition: create.h:72
Represents a robot pose.
Definition: types.h:275
bool isVirtualWall() const
Definition: create.cpp:646
bool playSong(const uint8_t &songNumber) const
Play a previously created song. This command will not work if a song was not already defined with the...
Definition: create.cpp:583
#define GET_DATA(id)
Definition: create.cpp:10
bool isMovingForward() const
Definition: create.cpp:963
Matrix addMatrices(const Matrix &A, const Matrix &B) const
Definition: create.cpp:68
float measuredRightVel
Definition: create.h:87
std::vector< float > covariance
3x3 covariance matrix in row-major order.
Definition: types.h:283
create::Vel getVel() const
Get the estimated velocity of Create based on wheel encoders.
Definition: create.cpp:1008
uint64_t getNumCorruptPackets() const
Get the number of corrupt serial packets since first connecting to Create. This value is ideally zero...
Definition: create.cpp:1012
int main(int argc, char **argv)
uint16_t getLightSignalCenterLeft() const
Get the signal strength from the center-left light sensor.
Definition: create.cpp:923
float getMaxVelocity() const
Definition: types.cpp:39
static const float V_3_TICKS_PER_REV
Definition: util.h:44
uint8_t sideMotorPower
Definition: create.h:61
#define CERR(prefix, msg)
Definition: util.h:38
bool isLightBumperLeft() const
Definition: create.cpp:843
bool clean(const create::CleanMode &mode=CLEAN_DEFAULT)
Starts a cleaning mode. Changes mode to MODE_PASSIVE.
Definition: create.cpp:340
float getWheelDiameter() const
Definition: types.cpp:43
uint8_t checkLED
Definition: create.h:68
bool isScheduleButtonPressed() const
Not supported by any firmware!
Definition: create.cpp:732
bool enableCheckRobotLED(const bool &enable)
Set the orange "check Create" LED on/off.
Definition: create.cpp:524
bool driveRadius(const float &velocity, const float &radius)
Set the average wheel velocity and turning radius of Create.
Definition: create.cpp:358
static const uint32_t V_3_MAX_ENCODER_TICKS
Definition: util.h:45
bool enableSpotLED(const bool &enable)
Set the green "spot" LED on/off.
Definition: create.cpp:508
bool setMainMotor(const float &power)
Set the power to the main brush motor.
Definition: create.cpp:477
bool isMinButtonPressed() const
Get state of &#39;min&#39; button.
Definition: create.cpp:763
bool isCleanButtonPressed() const
Get state of &#39;clean&#39; button (&#39;play&#39; button on Create 1).
Definition: create.cpp:709
bool drive(const float &xVel, const float &angularVel)
Set the forward and angular velocity of Create.
Definition: create.cpp:451
bool isDockButtonPressed() const
Get state of &#39;dock&#39; button (&#39;advance&#39; button on Create 1).
Definition: create.cpp:773
boost::shared_ptr< create::Data > data
Definition: create.h:98
float getMeasuredLeftWheelVel() const
Get the measured velocity of the left wheel.
Definition: create.cpp:981
boost::numeric::ublas::matrix< float > Matrix
Definition: create.h:49
bool enableDebrisLED(const bool &enable)
Set the blue "debris" LED on/off.
Definition: create.cpp:500
#define BOUND_CONST(val, min, max)
Definition: create.cpp:11
float getVoltage() const
Get battery voltage.
Definition: create.cpp:793
uint16_t getLightSignalLeft() const
Get the signal strength from the left light sensor.
Definition: create.cpp:903
uint8_t vacuumMotorPower
Definition: create.h:62
float x
Definition: types.h:276
bool updateLEDs()
Definition: create.cpp:489
static const float MAX_RADIUS
Definition: util.h:46
bool isRightBumper() const
Definition: create.cpp:610
bool isDayButtonPressed() const
Get state of &#39;day&#39; button.
Definition: create.cpp:743
bool willFloatOverflow(const float a, const float b)
Definition: util.h:70
bool isWall() const
Definition: create.cpp:620
RobotModel model
Definition: create.h:58
static const float EPS
Definition: util.h:51
uint16_t getLightSignalCenterRight() const
Get the signal strength from the center-right light sensor.
Definition: create.cpp:953
static const float STRAIGHT_RADIUS
Definition: util.h:47
#define COUT(prefix, msg)
Definition: util.h:37
bool isSpotButtonPressed() const
Get state of &#39;spot&#39; button.
Definition: create.cpp:783
uint32_t prevTicksLeft
Definition: create.h:77
CleanMode
Definition: types.h:210
uint8_t debrisLED
Definition: create.h:65
float measuredLeftVel
Definition: create.h:86
Create(RobotModel model=RobotModel::CREATE_2)
Default constructor.
Definition: create.cpp:55
uint16_t getLightSignalRight() const
Get the signal strength from the right light sensor.
Definition: create.cpp:933
float getBatteryCapacity() const
Get estimated battery charge capacity.
Definition: create.cpp:833
float requestedLeftVel
Definition: create.h:88
bool connect(const std::string &port, const int &baud)
Make a serial connection to Create.
Definition: create.cpp:272
uint8_t mainMotorPower
Definition: create.h:60
uint8_t getIRLeft() const
Get value of 8-bit IR character currently being received by left sensor.
Definition: create.cpp:676
util::timestamp_t prevOnDataTime
Definition: create.h:82
bool isCliff() const
Definition: create.cpp:630
float normalizeAngle(const float &angle)
Definition: util.h:53
bool setAllMotors(const float &mainPower, const float &sidePower, const float &vacuumPower)
Set the power of all motors.
Definition: create.cpp:458
Matrix poseCovar
Definition: create.h:84
void disconnect()
Disconnect from serial.
Definition: create.cpp:293
void onData()
Definition: create.cpp:92
CreateMode
Definition: types.h:202
DayOfWeek
Definition: types.h:225
float getAxleLength() const
Definition: types.cpp:31
float getLeftWheelDistance() const
Get the total distance the left wheel has moved.
Definition: create.cpp:973
bool setMode(const create::CreateMode &mode)
Change Create mode.
Definition: create.cpp:304
create::CreateMode getMode()
Get the current mode reported by Create.
Definition: create.cpp:997
~Create()
Attempts to disconnect from serial.
Definition: create.cpp:64
bool isLightBumperRight() const
Definition: create.cpp:893
bool isLightBumperCenterLeft() const
Definition: create.cpp:863
uint16_t getLightSignalFrontRight() const
Get the signal strength from the front-right light sensor.
Definition: create.cpp:943
bool defineSong(const uint8_t &songNumber, const uint8_t &songLength, const uint8_t *notes, const float *durations) const
Defines a song from the provided notes and labels it with a song number.
Definition: create.cpp:560


libcreate
Author(s): Jacob Perron
autogenerated on Sat Jun 8 2019 17:58:17