#include <create.h>
Public Member Functions | |
bool | clean (const create::CleanMode &mode=CLEAN_DEFAULT) |
Starts a cleaning mode. Changes mode to MODE_PASSIVE. More... | |
bool | connect (const std::string &port, const int &baud) |
Make a serial connection to Create. More... | |
bool | connected () const |
Check if serial connection is active. More... | |
Create (RobotModel model=RobotModel::CREATE_2, bool install_signal_handler=true) | |
Default constructor. More... | |
Create (const std::string &port, const int &baud, RobotModel model=RobotModel::CREATE_2, bool install_signal_handler=true) | |
Attempts to establish serial connection to Create. More... | |
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. More... | |
void | disconnect () |
Disconnect from serial. More... | |
bool | dock () const |
Starts the docking behaviour. Changes mode to MODE_PASSIVE. More... | |
bool | drive (const float &xVel, const float &angularVel) |
Set the forward and angular velocity of Create. More... | |
bool | driveRadius (const float &velocity, const float &radius) |
Set the average wheel velocity and turning radius of Create. More... | |
bool | driveWheels (const float &leftWheel, const float &rightWheel) |
Set the velocities for the left and right wheels. More... | |
bool | driveWheelsPwm (const float &leftWheel, const float &rightWheel) |
Set the direct for the left and right wheels. More... | |
bool | enableCheckRobotLED (const bool &enable) |
Set the orange "check Create" LED on/off. More... | |
bool | enableDebrisLED (const bool &enable) |
Set the blue "debris" LED on/off. More... | |
bool | enableDockLED (const bool &enable) |
Set the green "dock" LED on/off. More... | |
bool | enableSpotLED (const bool &enable) |
Set the green "spot" LED on/off. More... | |
float | getBatteryCapacity () const |
Get estimated battery charge capacity. More... | |
float | getBatteryCharge () const |
Get battery's remaining charge. More... | |
create::ChargingState | getChargingState () const |
Get the current charging state. More... | |
float | getCurrent () const |
Get current flowing in/out of battery. A positive current implies Create is charging. More... | |
uint8_t | getDirtDetect () const |
Get level of the dirt detect sensor. More... | |
uint8_t | getIRLeft () const |
Get value of 8-bit IR character currently being received by left sensor. More... | |
uint8_t | getIROmni () const |
Get value of 8-bit IR character currently being received by omnidirectional sensor. More... | |
uint8_t | getIRRight () const |
Get value of 8-bit IR character currently being received by right sensor. More... | |
float | getLeftWheelDistance () const |
Get the total distance the left wheel has moved. More... | |
uint16_t | getLightSignalCenterLeft () const |
Get the signal strength from the center-left light sensor. More... | |
uint16_t | getLightSignalCenterRight () const |
Get the signal strength from the center-right light sensor. More... | |
uint16_t | getLightSignalFrontLeft () const |
Get the signal strength from the front-left light sensor. More... | |
uint16_t | getLightSignalFrontRight () const |
Get the signal strength from the front-right light sensor. More... | |
uint16_t | getLightSignalLeft () const |
Get the signal strength from the left light sensor. More... | |
uint16_t | getLightSignalRight () const |
Get the signal strength from the right light sensor. More... | |
float | getMeasuredLeftWheelVel () const |
Get the measured velocity of the left wheel. More... | |
float | getMeasuredRightWheelVel () const |
Get the measured velocity of the right wheel. More... | |
create::CreateMode | getMode () |
Get the current mode reported by Create. More... | |
uint64_t | getNumCorruptPackets () const |
Get the number of corrupt serial packets since first connecting to Create. This value is ideally zero. If the number is consistently increasing then chances are some sensor information is not being updated. More... | |
create::Pose | getPose () const |
Get the estimated pose of Create based on wheel encoders. More... | |
float | getRequestedLeftWheelVel () const |
Get the requested velocity of the left wheel. This value is bounded at the maximum velocity of the robot model. More... | |
float | getRequestedRightWheelVel () const |
Get the requested velocity of the right wheel. This value is bounded at the maximum velocity of the robot model. More... | |
float | getRightWheelDistance () const |
Get the total distance the right wheel has moved. More... | |
int8_t | getTemperature () const |
Get the temperature of battery. More... | |
uint64_t | getTotalPackets () const |
Get the total number of serial packets received (including corrupt packets) since first connecting to Create. More... | |
create::Vel | getVel () const |
Get the estimated velocity of Create based on wheel encoders. More... | |
float | getVoltage () const |
Get battery voltage. More... | |
bool | isCleanButtonPressed () const |
Get state of 'clean' button ('play' button on Create 1). More... | |
bool | isCliff () const |
bool | isCliffFrontLeft () const |
bool | isCliffFrontRight () const |
bool | isCliffLeft () const |
bool | isCliffRight () const |
bool | isClockButtonPressed () const |
Not supported by any firmware! More... | |
bool | isDayButtonPressed () const |
Get state of 'day' button. More... | |
bool | isDockButtonPressed () const |
Get state of 'dock' button ('advance' button on Create 1). More... | |
bool | isHourButtonPressed () const |
Get state of 'hour' button. More... | |
bool | isLeftBumper () const |
bool | isLeftWheeldrop () const |
bool | isLightBumperCenterLeft () const |
bool | isLightBumperCenterRight () const |
bool | isLightBumperFrontLeft () const |
bool | isLightBumperFrontRight () const |
bool | isLightBumperLeft () const |
bool | isLightBumperRight () const |
bool | isMainBrushOvercurrent () const |
bool | isMinButtonPressed () const |
Get state of 'min' button. More... | |
bool | isMovingForward () const |
bool | isRightBumper () const |
bool | isRightWheeldrop () const |
bool | isScheduleButtonPressed () const |
Not supported by any firmware! More... | |
bool | isSideBrushOvercurrent () const |
bool | isSpotButtonPressed () const |
Get state of 'spot' button. More... | |
bool | isVirtualWall () const |
bool | isWall () const |
bool | isWheeldrop () const |
bool | isWheelOvercurrent () 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 specified song number. More... | |
bool | setAllMotors (const float &mainPower, const float &sidePower, const float &vacuumPower) |
Set the power of all motors. More... | |
bool | setDate (const create::DayOfWeek &day, const uint8_t &hour, const uint8_t &min) const |
Sets the internal clock of Create. More... | |
bool | setDigits (const std::vector< bool > &segments) const |
Set the four 7-segment display digits from left to right. More... | |
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 accepted ascii ranges results in blank display. More... | |
void | setDtHistoryLength (const uint8_t &dtHistoryLength) |
Set dtHistoryLength parameter. Used to configure the size of the buffer for calculating average time delta (dt). between onData calls, which in turn is used for velocity calculation. More... | |
bool | setMainMotor (const float &power) |
Set the power to the main brush motor. More... | |
bool | setMode (const create::CreateMode &mode) |
Change Create mode. More... | |
bool | setPowerLED (const uint8_t &power, const uint8_t &intensity=255) |
Set the center power LED. More... | |
bool | setSideMotor (const float &power) |
Set the power to the side brush motor. More... | |
bool | setVacuumMotor (const float &power) |
Set the power to the vacuum motor. More... | |
~Create () | |
Attempts to disconnect from serial. More... | |
Protected Attributes | |
std::shared_ptr< create::Data > | data |
std::shared_ptr< create::Serial > | serial |
Private Types | |
enum | CreateLED { LED_DEBRIS = 1, LED_SPOT = 2, LED_DOCK = 4, LED_CHECK = 8 } |
typedef boost::numeric::ublas::matrix< float > | Matrix |
Private Member Functions | |
Matrix | addMatrices (const Matrix &A, const Matrix &B) const |
void | init (bool install_signal_handler) |
void | onData () |
bool | updateLEDs () |
Private Attributes | |
uint8_t | checkLED |
uint8_t | debrisLED |
uint8_t | dockLED |
std::deque< float > | dtHistory |
uint8_t | dtHistoryLength |
bool | firstOnData |
uint8_t | mainMotorPower |
float | measuredLeftVel |
float | measuredRightVel |
CreateMode | mode |
RobotModel | model |
create::Pose | pose |
Matrix | poseCovar |
uint8_t | powerLED |
uint8_t | powerLEDIntensity |
std::chrono::time_point< std::chrono::steady_clock > | prevOnDataTime |
uint32_t | prevTicksLeft |
uint32_t | prevTicksRight |
float | requestedLeftVel |
float | requestedRightVel |
uint8_t | sideMotorPower |
uint8_t | spotLED |
float | totalLeftDist |
float | totalRightDist |
uint8_t | vacuumMotorPower |
create::Vel | vel |
|
private |
|
private |
create::Create::Create | ( | RobotModel | model = RobotModel::CREATE_2 , |
bool | install_signal_handler = true |
||
) |
Default constructor.
Calling this constructor Does not attempt to establish a serial connection to the robot.
model | the type of the robot. See RobotModel to determine the value for your robot. |
install_signal_handler | if true, then register a signal handler to disconnect from the robot on SIGINT or SIGTERM. |
Definition at line 54 of file create.cpp.
create::Create::Create | ( | const std::string & | port, |
const int & | baud, | ||
RobotModel | model = RobotModel::CREATE_2 , |
||
bool | install_signal_handler = true |
||
) |
Attempts to establish serial connection to Create.
port | of your computer that is connected to Create. |
baud | rate to communicate with Create. Typically, 115200 for Create 2 and 57600 for Create 1. |
model | type of robot. See RobotModel to determine the value for your robot. |
install_signal_handler | if true, then register a signal handler to disconnect from the robot on SIGINT or SIGTERM. |
Definition at line 58 of file create.cpp.
create::Create::~Create | ( | ) |
Attempts to disconnect from serial.
Definition at line 65 of file create.cpp.
|
private |
Definition at line 69 of file create.cpp.
bool create::Create::clean | ( | const create::CleanMode & | mode = CLEAN_DEFAULT | ) |
Starts a cleaning mode. Changes mode to MODE_PASSIVE.
Definition at line 361 of file create.cpp.
bool create::Create::connect | ( | const std::string & | port, |
const int & | baud | ||
) |
Make a serial connection to Create.
This is the first thing that should be done after instantiated this class.
Definition at line 293 of file create.cpp.
|
inline |
bool create::Create::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.
songNumber | can be one of four possible song slots, [0, 4] |
songLength | is the number of notes, maximum 16. length(notes) = length(durations) = songLength should be true. |
notes | is a sequence of notes. Each note is in the range [31, 127]. Anything outside this range is considered a rest note. |
durations | for each note in fractions of a second from the range [0, 4) |
Definition at line 590 of file create.cpp.
void create::Create::disconnect | ( | ) |
Disconnect from serial.
Definition at line 314 of file create.cpp.
bool create::Create::dock | ( | ) | const |
Starts the docking behaviour. Changes mode to MODE_PASSIVE.
Definition at line 365 of file create.cpp.
bool create::Create::drive | ( | const float & | xVel, |
const float & | angularVel | ||
) |
Set the forward and angular velocity of Create.
xVel | in m/s |
angularVel | in rads/s |
Definition at line 472 of file create.cpp.
bool create::Create::driveRadius | ( | const float & | velocity, |
const float & | radius | ||
) |
Set the average wheel velocity and turning radius of Create.
velocity | is in m/s bounded between [-0.5, 0.5] |
radius | in meters. Special cases: drive straight = CREATE_2_STRAIGHT_RADIUS, turn in place counter-clockwise = CREATE_2_IN_PLACE_RADIUS, turn in place clockwise = -CREATE_2_IN_PLACE_RADIUS |
Definition at line 379 of file create.cpp.
bool create::Create::driveWheels | ( | const float & | leftWheel, |
const float & | rightWheel | ||
) |
Set the velocities for the left and right wheels.
leftWheel | velocity in m/s. |
rightWheel | veloctiy in m/s. |
Definition at line 403 of file create.cpp.
bool create::Create::driveWheelsPwm | ( | const float & | leftWheel, |
const float & | rightWheel | ||
) |
Set the direct for the left and right wheels.
leftWheel | pwm in the range [-1, 1] |
rightWheel | pwm in the range [-1, 1] |
Definition at line 451 of file create.cpp.
bool create::Create::enableCheckRobotLED | ( | const bool & | enable | ) |
Set the orange "check Create" LED on/off.
enable |
Definition at line 554 of file create.cpp.
bool create::Create::enableDebrisLED | ( | const bool & | enable | ) |
Set the blue "debris" LED on/off.
enable |
Definition at line 530 of file create.cpp.
bool create::Create::enableDockLED | ( | const bool & | enable | ) |
Set the green "dock" LED on/off.
enable |
Definition at line 546 of file create.cpp.
bool create::Create::enableSpotLED | ( | const bool & | enable | ) |
Set the green "spot" LED on/off.
enable |
Definition at line 538 of file create.cpp.
float create::Create::getBatteryCapacity | ( | ) | const |
Get estimated battery charge capacity.
Definition at line 926 of file create.cpp.
float create::Create::getBatteryCharge | ( | ) | const |
Get battery's remaining charge.
Definition at line 916 of file create.cpp.
ChargingState create::Create::getChargingState | ( | ) | const |
float create::Create::getCurrent | ( | ) | const |
Get current flowing in/out of battery. A positive current implies Create is charging.
Definition at line 896 of file create.cpp.
uint8_t create::Create::getDirtDetect | ( | ) | const |
Get level of the dirt detect sensor.
Definition at line 750 of file create.cpp.
uint8_t create::Create::getIRLeft | ( | ) | const |
Get value of 8-bit IR character currently being received by left sensor.
Definition at line 770 of file create.cpp.
uint8_t create::Create::getIROmni | ( | ) | const |
Get value of 8-bit IR character currently being received by omnidirectional sensor.
Definition at line 760 of file create.cpp.
uint8_t create::Create::getIRRight | ( | ) | const |
Get value of 8-bit IR character currently being received by right sensor.
Definition at line 780 of file create.cpp.
float create::Create::getLeftWheelDistance | ( | ) | const |
Get the total distance the left wheel has moved.
Definition at line 1096 of file create.cpp.
uint16_t create::Create::getLightSignalCenterLeft | ( | ) | const |
Get the signal strength from the center-left light sensor.
Definition at line 1016 of file create.cpp.
uint16_t create::Create::getLightSignalCenterRight | ( | ) | const |
Get the signal strength from the center-right light sensor.
Definition at line 1046 of file create.cpp.
uint16_t create::Create::getLightSignalFrontLeft | ( | ) | const |
Get the signal strength from the front-left light sensor.
Definition at line 1006 of file create.cpp.
uint16_t create::Create::getLightSignalFrontRight | ( | ) | const |
Get the signal strength from the front-right light sensor.
Definition at line 1036 of file create.cpp.
uint16_t create::Create::getLightSignalLeft | ( | ) | const |
Get the signal strength from the left light sensor.
Definition at line 996 of file create.cpp.
uint16_t create::Create::getLightSignalRight | ( | ) | const |
Get the signal strength from the right light sensor.
Definition at line 1026 of file create.cpp.
float create::Create::getMeasuredLeftWheelVel | ( | ) | const |
Get the measured velocity of the left wheel.
Definition at line 1104 of file create.cpp.
float create::Create::getMeasuredRightWheelVel | ( | ) | const |
Get the measured velocity of the right wheel.
Definition at line 1108 of file create.cpp.
create::CreateMode create::Create::getMode | ( | ) |
uint64_t create::Create::getNumCorruptPackets | ( | ) | const |
Get the number of corrupt serial packets since first connecting to Create. This value is ideally zero. If the number is consistently increasing then chances are some sensor information is not being updated.
Definition at line 1135 of file create.cpp.
Pose create::Create::getPose | ( | ) | const |
Get the estimated pose of Create based on wheel encoders.
Definition at line 1127 of file create.cpp.
float create::Create::getRequestedLeftWheelVel | ( | ) | const |
Get the requested velocity of the left wheel. This value is bounded at the maximum velocity of the robot model.
Definition at line 1112 of file create.cpp.
float create::Create::getRequestedRightWheelVel | ( | ) | const |
Get the requested velocity of the right wheel. This value is bounded at the maximum velocity of the robot model.
Definition at line 1116 of file create.cpp.
float create::Create::getRightWheelDistance | ( | ) | const |
Get the total distance the right wheel has moved.
Definition at line 1100 of file create.cpp.
int8_t create::Create::getTemperature | ( | ) | const |
uint64_t create::Create::getTotalPackets | ( | ) | const |
Get the total number of serial packets received (including corrupt packets) since first connecting to Create.
Definition at line 1139 of file create.cpp.
Vel create::Create::getVel | ( | ) | const |
Get the estimated velocity of Create based on wheel encoders.
Definition at line 1131 of file create.cpp.
float create::Create::getVoltage | ( | ) | const |
|
private |
Definition at line 17 of file create.cpp.
bool create::Create::isCleanButtonPressed | ( | ) | const |
Get state of 'clean' button ('play' button on Create 1).
Definition at line 802 of file create.cpp.
bool create::Create::isCliff | ( | ) | const |
Definition at line 684 of file create.cpp.
bool create::Create::isCliffFrontLeft | ( | ) | const |
Definition at line 710 of file create.cpp.
bool create::Create::isCliffFrontRight | ( | ) | const |
Definition at line 730 of file create.cpp.
bool create::Create::isCliffLeft | ( | ) | const |
Definition at line 700 of file create.cpp.
bool create::Create::isCliffRight | ( | ) | const |
Definition at line 720 of file create.cpp.
bool create::Create::isClockButtonPressed | ( | ) | const |
Not supported by any firmware!
Definition at line 813 of file create.cpp.
bool create::Create::isDayButtonPressed | ( | ) | const |
Get state of 'day' button.
Definition at line 836 of file create.cpp.
bool create::Create::isDockButtonPressed | ( | ) | const |
Get state of 'dock' button ('advance' button on Create 1).
Definition at line 866 of file create.cpp.
bool create::Create::isHourButtonPressed | ( | ) | const |
Get state of 'hour' button.
Definition at line 846 of file create.cpp.
bool create::Create::isLeftBumper | ( | ) | const |
Definition at line 654 of file create.cpp.
bool create::Create::isLeftWheeldrop | ( | ) | const |
Definition at line 634 of file create.cpp.
bool create::Create::isLightBumperCenterLeft | ( | ) | const |
Definition at line 956 of file create.cpp.
bool create::Create::isLightBumperCenterRight | ( | ) | const |
Definition at line 966 of file create.cpp.
bool create::Create::isLightBumperFrontLeft | ( | ) | const |
Definition at line 946 of file create.cpp.
bool create::Create::isLightBumperFrontRight | ( | ) | const |
Definition at line 976 of file create.cpp.
bool create::Create::isLightBumperLeft | ( | ) | const |
Definition at line 936 of file create.cpp.
bool create::Create::isLightBumperRight | ( | ) | const |
Definition at line 986 of file create.cpp.
bool create::Create::isMainBrushOvercurrent | ( | ) | const |
Definition at line 1076 of file create.cpp.
bool create::Create::isMinButtonPressed | ( | ) | const |
Get state of 'min' button.
Definition at line 856 of file create.cpp.
bool create::Create::isMovingForward | ( | ) | const |
Definition at line 1056 of file create.cpp.
bool create::Create::isRightBumper | ( | ) | const |
Definition at line 664 of file create.cpp.
bool create::Create::isRightWheeldrop | ( | ) | const |
Definition at line 644 of file create.cpp.
bool create::Create::isScheduleButtonPressed | ( | ) | const |
Not supported by any firmware!
Definition at line 825 of file create.cpp.
bool create::Create::isSideBrushOvercurrent | ( | ) | const |
Definition at line 1066 of file create.cpp.
bool create::Create::isSpotButtonPressed | ( | ) | const |
Get state of 'spot' button.
Definition at line 876 of file create.cpp.
bool create::Create::isVirtualWall | ( | ) | const |
Definition at line 740 of file create.cpp.
bool create::Create::isWall | ( | ) | const |
Definition at line 674 of file create.cpp.
bool create::Create::isWheeldrop | ( | ) | const |
Definition at line 624 of file create.cpp.
bool create::Create::isWheelOvercurrent | ( | ) | const |
Definition at line 1086 of file create.cpp.
|
private |
Definition at line 93 of file create.cpp.
bool create::Create::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 specified song number.
songNumber | is one of four stored songs in the range [0, 4] |
Definition at line 613 of file create.cpp.
bool create::Create::setAllMotors | ( | const float & | mainPower, |
const float & | sidePower, | ||
const float & | vacuumPower | ||
) |
Set the power of all motors.
mainPower | in the range [-1, 1] |
sidePower | in the range [-1, 1] |
vacuumPower | in the range [0, 1] |
Definition at line 479 of file create.cpp.
bool create::Create::setDate | ( | const create::DayOfWeek & | day, |
const uint8_t & | hour, | ||
const uint8_t & | min | ||
) | const |
Sets the internal clock of Create.
day | in range [0, 6] |
hour | in range [0, 23] |
min | in range [0, 59] |
Definition at line 369 of file create.cpp.
bool create::Create::setDigits | ( | const std::vector< bool > & | segments | ) | const |
Set the four 7-segment display digits from left to right.
segments | to enable (true) or disable (false). The size of segments should be less than 29. The ordering of segments is left to right, top to bottom for each digit: |
0 7 14 21 |‾‾‾| |‾‾‾| |‾‾‾| |‾‾‾| 1 |___| 2 8 |___| 9 15 |___| 16 22 |___| 23 | 3 | | 10| | 17| | 24| 4 |___| 5 11|___| 12 18 |___| 19 25 |___| 26 6 13 20 27
bool create::Create::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 accepted ascii ranges results in blank display.
digit1 | is left most digit with ascii range [32, 126] |
digit2 | is second to left digit with ascii range [32, 126] |
digit3 | is second to right digit with ascii range [32, 126] |
digit4 | is right most digit with ascii range [32, 126] |
Definition at line 572 of file create.cpp.
void create::Create::setDtHistoryLength | ( | const uint8_t & | dtHistoryLength | ) |
Set dtHistoryLength parameter. Used to configure the size of the buffer for calculating average time delta (dt). between onData calls, which in turn is used for velocity calculation.
dtHistoryLength | number of historical samples to use for calculating average dt. |
Definition at line 620 of file create.cpp.
bool create::Create::setMainMotor | ( | const float & | power | ) |
Set the power to the main brush motor.
power | is in the range [-1, 1] |
Definition at line 507 of file create.cpp.
bool create::Create::setMode | ( | const create::CreateMode & | mode | ) |
Change Create mode.
mode | to change Create to. |
Definition at line 325 of file create.cpp.
bool create::Create::setPowerLED | ( | const uint8_t & | power, |
const uint8_t & | intensity = 255 |
||
) |
Set the center power LED.
power | in range [0, 255] where 0 = green and 255 = red |
intensity | in range [0, 255] |
Definition at line 562 of file create.cpp.
bool create::Create::setSideMotor | ( | const float & | power | ) |
Set the power to the side brush motor.
power | is in the range [-1, 1] |
Definition at line 511 of file create.cpp.
bool create::Create::setVacuumMotor | ( | const float & | power | ) |
Set the power to the vacuum motor.
power | is in the range [0, 1] |
Definition at line 515 of file create.cpp.
|
private |
Definition at line 519 of file create.cpp.
|
protected |
|
private |
|
private |
|
private |
|
private |
|
protected |
|
private |