1 #include <boost/bind.hpp> 2 #include <boost/make_shared.hpp> 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)) 16 namespace ublas = boost::numeric::ublas;
49 serial = boost::make_shared<SerialQuery>(
data);
51 serial = boost::make_shared<SerialStream>(
data);
61 serial->connect(dev, baud);
72 assert(rows == B.size1());
73 assert(cols == B.size2());
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);
82 C(i, j) = (a < 0.0) ? std::numeric_limits<float>::min() : std::numeric_limits<float>::max();
106 float deltaDist, deltaX, deltaY, deltaYaw, leftWheelDist, rightWheelDist, wheelDistDiff;
114 std::memcpy(&distance, &distanceRaw,
sizeof(distance));
115 deltaDist = distance / 1000.0;
119 std::memcpy(&angleField, &angleRaw,
sizeof(angleField));
123 wheelDistDiff = 2.0 * angleField / 1000.0;
124 leftWheelDist = deltaDist - (wheelDistDiff / 2.0);
125 rightWheelDist = deltaDist + (wheelDistDiff / 2.0);
140 deltaYaw = angleField * (
util::PI / 180.0);
142 leftWheelDist = deltaDist - (wheelDistDiff / 2.0);
143 rightWheelDist = deltaDist + (wheelDistDiff / 2.0);
151 prevTicksLeft = totalTicksLeft;
152 prevTicksRight = totalTicksRight;
167 deltaDist = (rightWheelDist + leftWheelDist) / 2.0;
169 wheelDistDiff = rightWheelDist - leftWheelDist;
178 deltaX = deltaDist * cos(
pose.
yaw);
179 deltaY = deltaDist * sin(
pose.
yaw);
181 float turnRadius = (
model.
getAxleLength() / 2.0) * (leftWheelDist + rightWheelDist) / wheelDistDiff;
183 deltaY = -turnRadius * (cos(
pose.
yaw + deltaYaw) - cos(
pose.
yaw));
190 vel.
x = deltaDist / dt;
203 float cosYawAndHalfDelta = cos(
pose.
yaw + (deltaYaw / 2.0));
204 float sinYawAndHalfDelta = sin(
pose.
yaw + (deltaYaw / 2.0));
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);
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);
220 Matrix FincT = boost::numeric::ublas::trans(Finc);
225 Fp(0, 2) = (-deltaDist) * sinYawAndHalfDelta;
228 Fp(1, 2) = deltaDist * cosYawAndHalfDelta;
232 Matrix FpT = boost::numeric::ublas::trans(Fp);
234 Matrix velCovar = ublas::prod(invCovar, FincT);
235 velCovar = ublas::prod(Finc, velCovar);
248 poseCovarTmp = ublas::prod(Fp, poseCovarTmp);
273 bool timeout =
false;
276 float retryInterval = 5;
280 if (difftime(now, start) > maxWait) {
282 CERR(
"[create::Create] ",
"failed to connect over serial: timeout");
285 usleep(retryInterval * 1000000);
286 COUT(
"[create::Create] ",
"retrying to establish serial connection...");
313 CERR(
"[create::Create] ",
"protocol version 2 does not support turning robot off");
331 CERR(
"[create::Create] ",
"cannot set robot to mode '" << mode <<
"'");
349 if (day < 0 || day > 6 ||
350 hour < 0 || hour > 23 ||
354 uint8_t cmd[4] = {
OC_DATE, day, hour, min };
355 return serial->send(cmd, 4);
363 int16_t vel_mm = roundf(boundedVel * 1000);
364 int16_t radius_mm = roundf(radius * 1000);
367 if (radius_mm != 32768 && radius_mm != 32767 &&
368 radius_mm != -1 && radius_mm != 1) {
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)
379 return serial->send(cmd, 5);
388 int16_t leftCmd = roundf(boundedLeftVel * 1000);
389 int16_t rightCmd = roundf(boundedRightVel * 1000);
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)
397 return serial->send(cmd, 5);
401 if (boundedLeftVel != boundedRightVel) {
403 (boundedLeftVel - boundedRightVel);
410 if (boundedLeftVel == -boundedRightVel || std::abs(roundf(radius * 1000)) <= 1) {
412 vel = boundedRightVel;
414 vel = (std::abs(boundedLeftVel) + std::abs(boundedRightVel)) / 2.0 * ((boundedLeftVel + boundedRightVel) > 0 ? 1.0 : -1.0);
432 static const int16_t PWM_COUNTS = 255;
434 if (leftWheel < -1.0 || leftWheel > 1.0 ||
435 rightWheel < -1.0 || rightWheel > 1.0)
438 int16_t leftPwm = roundf(leftWheel * PWM_COUNTS);
439 int16_t rightPwm = roundf(rightWheel * PWM_COUNTS);
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)
448 return serial->send(cmd, 5);
459 if (main < -1.0 || main > 1.0 ||
460 side < -1.0 || side > 1.0 ||
461 vacuum < -1.0 || vacuum > 1.0)
474 return serial->send(cmd, 4);
497 return serial->send(cmd, 4);
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)
557 return serial->send(cmd, 5);
561 const uint8_t& songLength,
562 const uint8_t* notes,
563 const float* durations)
const {
566 uint8_t cmd[2 * songLength + 3];
571 for (i = 3; i < 2 * songLength + 3; i = i + 2) {
572 if (durations[j] < 0 || durations[j] >= 4)
574 duration = durations[j] * 64;
576 cmd[i + 1] = duration;
580 return serial->send(cmd, 2 * songLength + 3);
584 if (songNumber < 0 || songNumber > 4)
586 uint8_t cmd[2] = {
OC_PLAY, songNumber };
587 return serial->send(cmd, 2);
595 CERR(
"[create::Create] ",
"Wheeldrop sensor not supported!");
605 CERR(
"[create::Create] ",
"Left bumper not supported!");
615 CERR(
"[create::Create] ",
"Right bumper not supported!");
625 CERR(
"[create::Create] ",
"Wall sensor not supported!");
641 CERR(
"[create::Create] ",
"Cliff sensors not supported!");
651 CERR(
"[create::Create] ",
"Virtual Wall sensor not supported!");
661 CERR(
"[create::Create] ",
"Dirt detector not supported!");
671 CERR(
"[create::Create] ",
"Omni IR sensor not supported!");
681 CERR(
"[create::Create] ",
"Left IR sensor not supported!");
691 CERR(
"[create::Create] ",
"Right IR sensor not supported!");
699 assert(chargeState >= 0);
700 assert(chargeState <= 5);
704 CERR(
"[create::Create] ",
"Charging state not supported!");
714 CERR(
"[create::Create] ",
"Buttons not supported!");
721 CERR(
"[create::Create] ",
"Clock button is not supported!");
726 CERR(
"[create::Create] ",
"Buttons not supported!");
733 CERR(
"[create::Create] ",
"Schedule button is not supported!");
738 CERR(
"[create::Create] ",
"Buttons not supported!");
748 CERR(
"[create::Create] ",
"Buttons not supported!");
758 CERR(
"[create::Create] ",
"Buttons not supported!");
768 CERR(
"[create::Create] ",
"Buttons not supported!");
778 CERR(
"[create::Create] ",
"Buttons not supported!");
788 CERR(
"[create::Create] ",
"Buttons not supported!");
798 CERR(
"[create::Create] ",
"Voltage sensor not supported!");
808 CERR(
"[create::Create] ",
"Current sensor not supported!");
818 CERR(
"[create::Create] ",
"Temperature sensor not supported!");
828 CERR(
"[create::Create] ",
"Battery charge not supported!");
838 CERR(
"[create::Create] ",
"Battery capacity not supported!");
848 CERR(
"[create::Create] ",
"Light sensors not supported!");
858 CERR(
"[create::Create] ",
"Light sensors not supported!");
868 CERR(
"[create::Create] ",
"Light sensors not supported!");
878 CERR(
"[create::Create] ",
"Light sensors not supported!");
888 CERR(
"[create::Create] ",
"Light sensors not supported!");
898 CERR(
"[create::Create] ",
"Light sensors not supported!");
908 CERR(
"[create::Create] ",
"Light sensors not supported!");
918 CERR(
"[create::Create] ",
"Light sensors not supported!");
928 CERR(
"[create::Create] ",
"Light sensors not supported!");
938 CERR(
"[create::Create] ",
"Light sensors not supported!");
948 CERR(
"[create::Create] ",
"Light sensors not supported!");
958 CERR(
"[create::Create] ",
"Light sensors not supported!");
968 CERR(
"[create::Create] ",
"Stasis sensor not supported!");
1013 return serial->getNumCorruptPackets();
1017 return serial->getTotalPackets();
uint64_t getTotalPackets() const
Get the total number of serial packets received (including corrupt packets) since first connecting to...
bool setSideMotor(const float &power)
Set the power to the side brush motor.
uint8_t getIROmni() const
Get value of 8-bit IR character currently being received by omnidirectional sensor.
uint8_t powerLEDIntensity
static const float IN_PLACE_RADIUS
float getMeasuredRightWheelVel() const
Get the measured velocity of the right wheel.
bool setVacuumMotor(const float &power)
Set the power to the vacuum motor.
bool isLightBumperFrontLeft() const
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...
bool isLeftBumper() const
create::ChargingState getChargingState() const
Get the current charging state.
bool driveWheels(const float &leftWheel, const float &rightWheel)
Set the velocities for the left and right wheels.
bool dock() const
Starts the docking behaviour. Changes mode to MODE_PASSIVE.
int8_t getTemperature() const
Get the temperature of battery.
bool isHourButtonPressed() const
Get state of 'hour' button.
bool isClockButtonPressed() const
Not supported by any firmware!
uint16_t getLightSignalFrontLeft() const
Get the signal strength from the front-left light sensor.
static timestamp_t getTimestamp()
bool isLightBumperCenterRight() const
float getRequestedLeftWheelVel() const
Get the requested velocity of the left wheel. This value is bounded at the maximum velocity of the ro...
#define BOUND(val, min, max)
unsigned long long timestamp_t
bool setDate(const create::DayOfWeek &day, const uint8_t &hour, const uint8_t &min) const
Sets the internal clock of Create.
float getRightWheelDistance() const
Get the total distance the right wheel has moved.
create::Pose getPose() const
Get the estimated pose of Create based on wheel encoders.
boost::shared_ptr< create::Serial > serial
uint8_t getDirtDetect() const
Get level of the dirt detect sensor.
float getRequestedRightWheelVel() const
Get the requested velocity of the right wheel. This value is bounded at the maximum velocity of the r...
bool enableDockLED(const bool &enable)
Set the green "dock" LED on/off.
bool setPowerLED(const uint8_t &power, const uint8_t &intensity=255)
Set the center power LED.
bool isLightBumperFrontRight() const
float getBatteryCharge() const
Get battery's remaining charge.
uint8_t getIRRight() const
Get value of 8-bit IR character currently being received by right sensor.
float getCurrent() const
Get current flowing in/out of battery. A positive current implies Create is charging.
bool driveWheelsPwm(const float &leftWheel, const float &rightWheel)
Set the direct for the left and right wheels.
ProtocolVersion getVersion() const
bool isVirtualWall() const
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...
bool isMovingForward() const
Matrix addMatrices(const Matrix &A, const Matrix &B) const
std::vector< float > covariance
3x3 covariance matrix in row-major order.
create::Vel getVel() const
Get the estimated velocity of Create based on wheel encoders.
uint64_t getNumCorruptPackets() const
Get the number of corrupt serial packets since first connecting to Create. This value is ideally zero...
int main(int argc, char **argv)
uint16_t getLightSignalCenterLeft() const
Get the signal strength from the center-left light sensor.
float getMaxVelocity() const
static const float V_3_TICKS_PER_REV
#define CERR(prefix, msg)
bool isLightBumperLeft() const
bool clean(const create::CleanMode &mode=CLEAN_DEFAULT)
Starts a cleaning mode. Changes mode to MODE_PASSIVE.
float getWheelDiameter() const
bool isScheduleButtonPressed() const
Not supported by any firmware!
bool enableCheckRobotLED(const bool &enable)
Set the orange "check Create" LED on/off.
bool driveRadius(const float &velocity, const float &radius)
Set the average wheel velocity and turning radius of Create.
static const uint32_t V_3_MAX_ENCODER_TICKS
bool enableSpotLED(const bool &enable)
Set the green "spot" LED on/off.
bool setMainMotor(const float &power)
Set the power to the main brush motor.
bool isMinButtonPressed() const
Get state of 'min' button.
bool isCleanButtonPressed() const
Get state of 'clean' button ('play' button on Create 1).
bool drive(const float &xVel, const float &angularVel)
Set the forward and angular velocity of Create.
bool isDockButtonPressed() const
Get state of 'dock' button ('advance' button on Create 1).
boost::shared_ptr< create::Data > data
float getMeasuredLeftWheelVel() const
Get the measured velocity of the left wheel.
boost::numeric::ublas::matrix< float > Matrix
bool enableDebrisLED(const bool &enable)
Set the blue "debris" LED on/off.
#define BOUND_CONST(val, min, max)
float getVoltage() const
Get battery voltage.
uint16_t getLightSignalLeft() const
Get the signal strength from the left light sensor.
static const float MAX_RADIUS
bool isRightBumper() const
bool isDayButtonPressed() const
Get state of 'day' button.
bool willFloatOverflow(const float a, const float b)
uint16_t getLightSignalCenterRight() const
Get the signal strength from the center-right light sensor.
static const float STRAIGHT_RADIUS
#define COUT(prefix, msg)
bool isSpotButtonPressed() const
Get state of 'spot' button.
Create(RobotModel model=RobotModel::CREATE_2)
Default constructor.
uint16_t getLightSignalRight() const
Get the signal strength from the right light sensor.
float getBatteryCapacity() const
Get estimated battery charge capacity.
bool connect(const std::string &port, const int &baud)
Make a serial connection to Create.
uint8_t getIRLeft() const
Get value of 8-bit IR character currently being received by left sensor.
util::timestamp_t prevOnDataTime
float normalizeAngle(const float &angle)
bool setAllMotors(const float &mainPower, const float &sidePower, const float &vacuumPower)
Set the power of all motors.
void disconnect()
Disconnect from serial.
float getAxleLength() const
float getLeftWheelDistance() const
Get the total distance the left wheel has moved.
bool setMode(const create::CreateMode &mode)
Change Create mode.
create::CreateMode getMode()
Get the current mode reported by Create.
~Create()
Attempts to disconnect from serial.
bool isLightBumperRight() const
bool isLightBumperCenterLeft() const
uint16_t getLightSignalFrontRight() const
Get the signal strength from the front-right light sensor.
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.