#include <create.h>
Public Member Functions | |
bool | clean (const create::CleanMode &mode=CLEAN_DEFAULT) |
Starts a cleaning mode. Changes mode to MODE_PASSIVE. | |
bool | connect (const std::string &port, const int &baud) |
Make a serial connection to Create. | |
bool | connected () const |
Check if serial connection is active. | |
Create (RobotModel model=RobotModel::CREATE_2) | |
Default constructor. | |
Create (const std::string &port, const int &baud, RobotModel model=RobotModel::CREATE_2) | |
Attempts to establish serial connection to Create. | |
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. | |
void | disconnect () |
Disconnect from serial. | |
bool | dock () const |
Starts the docking behaviour. Changes mode to MODE_PASSIVE. | |
bool | drive (const float &xVel, const float &angularVel) |
Set the forward and angular velocity of Create. | |
bool | driveRadius (const float &velocity, const float &radius) |
Set the average wheel velocity and turning radius of Create. | |
bool | driveWheels (const float &leftWheel, const float &rightWheel) |
Set the velocities for the left and right wheels. | |
bool | enableCheckRobotLED (const bool &enable) |
Set the orange "check Create" LED on/off. | |
bool | enableDebrisLED (const bool &enable) |
Set the blue "debris" LED on/off. | |
bool | enableDockLED (const bool &enable) |
Set the green "dock" LED on/off. | |
bool | enableSpotLED (const bool &enable) |
Set the green "spot" LED on/off. | |
float | getBatteryCapacity () const |
Get estimated battery charge capacity. | |
float | getBatteryCharge () const |
Get battery's remaining charge. | |
create::ChargingState | getChargingState () const |
Get the current charging state. | |
float | getCurrent () const |
Get current flowing in/out of battery. A positive current implies Create is charging. | |
uint8_t | getDirtDetect () const |
Get level of the dirt detect sensor. | |
uint8_t | getIRLeft () const |
Get value of 8-bit IR character currently being received by left sensor. | |
uint8_t | getIROmni () const |
Get value of 8-bit IR character currently being received by omnidirectional sensor. | |
uint8_t | getIRRight () const |
Get value of 8-bit IR character currently being received by right sensor. | |
float | getLeftWheelDistance () const |
Get the total distance the left wheel has moved. | |
uint16_t | getLightSignalCenterLeft () const |
Get the signal strength from the center-left light sensor. | |
uint16_t | getLightSignalCenterRight () const |
Get the signal strength from the center-right light sensor. | |
uint16_t | getLightSignalFrontLeft () const |
Get the signal strength from the front-left light sensor. | |
uint16_t | getLightSignalFrontRight () const |
Get the signal strength from the front-right light sensor. | |
uint16_t | getLightSignalLeft () const |
Get the signal strength from the left light sensor. | |
uint16_t | getLightSignalRight () const |
Get the signal strength from the right light sensor. | |
create::CreateMode | getMode () |
Get the current mode reported by Create. | |
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. | |
create::Pose | getPose () const |
Get the estimated pose of Create based on wheel encoders. | |
float | getRequestedLeftWheelVel () const |
Get the requested velocity of the left wheel. This value is bounded at the maximum velocity of the robot model. | |
float | getRequestedRightWheelVel () const |
Get the requested velocity of the right wheel. This value is bounded at the maximum velocity of the robot model. | |
float | getRightWheelDistance () const |
Get the total distance the right wheel has moved. | |
int8_t | getTemperature () const |
Get the temperature of battery. | |
uint64_t | getTotalPackets () const |
Get the total number of serial packets received (including corrupt packets) since first connecting to Create. | |
create::Vel | getVel () const |
Get the estimated velocity of Create based on wheel encoders. | |
float | getVoltage () const |
Get battery voltage. | |
bool | isCleanButtonPressed () const |
Get state of 'clean' button ('play' button on Create 1). | |
bool | isCliff () const |
bool | isClockButtonPressed () const |
Not supported by any firmware! | |
bool | isDayButtonPressed () const |
Get state of 'day' button. | |
bool | isDockButtonPressed () const |
Get state of 'dock' button ('advance' button on Create 1). | |
bool | isHourButtonPressed () const |
Get state of 'hour' button. | |
bool | isLeftBumper () 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. | |
bool | isMovingForward () const |
bool | isRightBumper () const |
bool | isScheduleButtonPressed () const |
Not supported by any firmware! | |
bool | isSideBrushOvercurrent () const |
bool | isSpotButtonPressed () const |
Get state of 'spot' button. | |
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. | |
bool | setAllMotors (const float &mainPower, const float &sidePower, const float &vacuumPower) |
Set the power of all motors. | |
bool | setDate (const create::DayOfWeek &day, const uint8_t &hour, const uint8_t &min) const |
Sets the internal clock of Create. | |
bool | setDigits (const std::vector< bool > &segments) const |
Set the four 7-segment display digits from left to right. | |
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. | |
bool | setMainMotor (const float &power) |
Set the power to the main brush motor. | |
bool | setMode (const create::CreateMode &mode) |
Change Create mode. | |
bool | setPowerLED (const uint8_t &power, const uint8_t &intensity=255) |
Set the center power LED. | |
bool | setSideMotor (const float &power) |
Set the power to the side brush motor. | |
bool | setVacuumMotor (const float &power) |
Set the power to the vacuum motor. | |
~Create () | |
Attempts to disconnect from serial. | |
Protected Attributes | |
boost::shared_ptr< create::Data > | data |
boost::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 () |
void | onData () |
bool | updateLEDs () |
Private Attributes | |
uint8_t | checkLED |
uint8_t | debrisLED |
uint8_t | dockLED |
bool | firstOnData |
uint8_t | mainMotorPower |
CreateMode | mode |
RobotModel | model |
create::Pose | pose |
Matrix | poseCovar |
uint8_t | powerLED |
uint8_t | powerLEDIntensity |
util::timestamp_t | 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 |
typedef boost::numeric::ublas::matrix<float> create::Create::Matrix [private] |
enum create::Create::CreateLED [private] |
create::Create::Create | ( | RobotModel | model = RobotModel::CREATE_2 | ) |
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. |
Definition at line 55 of file create.cpp.
create::Create::Create | ( | const std::string & | port, |
const int & | baud, | ||
RobotModel | model = RobotModel::CREATE_2 |
||
) |
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. |
Definition at line 59 of file create.cpp.
Attempts to disconnect from serial.
Definition at line 64 of file create.cpp.
Create::Matrix create::Create::addMatrices | ( | const Matrix & | A, |
const Matrix & | B | ||
) | const [private] |
Definition at line 68 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 337 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 269 of file create.cpp.
bool create::Create::connected | ( | ) | const [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 536 of file create.cpp.
void create::Create::disconnect | ( | ) |
Disconnect from serial.
Definition at line 290 of file create.cpp.
bool create::Create::dock | ( | ) | const |
Starts the docking behaviour. Changes mode to MODE_PASSIVE.
Definition at line 341 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 427 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 355 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 379 of file create.cpp.
bool create::Create::enableCheckRobotLED | ( | const bool & | enable | ) |
Set the orange "check Create" LED on/off.
enable |
Definition at line 500 of file create.cpp.
bool create::Create::enableDebrisLED | ( | const bool & | enable | ) |
Set the blue "debris" LED on/off.
enable |
Definition at line 476 of file create.cpp.
bool create::Create::enableDockLED | ( | const bool & | enable | ) |
Set the green "dock" LED on/off.
enable |
Definition at line 492 of file create.cpp.
bool create::Create::enableSpotLED | ( | const bool & | enable | ) |
Set the green "spot" LED on/off.
enable |
Definition at line 484 of file create.cpp.
float create::Create::getBatteryCapacity | ( | ) | const |
Get estimated battery charge capacity.
Definition at line 809 of file create.cpp.
float create::Create::getBatteryCharge | ( | ) | const |
Get battery's remaining charge.
Definition at line 799 of file create.cpp.
float create::Create::getCurrent | ( | ) | const |
Get current flowing in/out of battery. A positive current implies Create is charging.
Definition at line 779 of file create.cpp.
uint8_t create::Create::getDirtDetect | ( | ) | const |
Get level of the dirt detect sensor.
Definition at line 632 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 652 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 642 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 662 of file create.cpp.
float create::Create::getLeftWheelDistance | ( | ) | const |
Get the total distance the left wheel has moved.
Definition at line 949 of file create.cpp.
uint16_t create::Create::getLightSignalCenterLeft | ( | ) | const |
Get the signal strength from the center-left light sensor.
Definition at line 899 of file create.cpp.
uint16_t create::Create::getLightSignalCenterRight | ( | ) | const |
Get the signal strength from the center-right light sensor.
Definition at line 929 of file create.cpp.
uint16_t create::Create::getLightSignalFrontLeft | ( | ) | const |
Get the signal strength from the front-left light sensor.
Definition at line 889 of file create.cpp.
uint16_t create::Create::getLightSignalFrontRight | ( | ) | const |
Get the signal strength from the front-right light sensor.
Definition at line 919 of file create.cpp.
uint16_t create::Create::getLightSignalLeft | ( | ) | const |
Get the signal strength from the left light sensor.
Definition at line 879 of file create.cpp.
uint16_t create::Create::getLightSignalRight | ( | ) | const |
Get the signal strength from the right light sensor.
Definition at line 909 of file create.cpp.
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 980 of file create.cpp.
Pose create::Create::getPose | ( | ) | const |
Get the estimated pose of Create based on wheel encoders.
Definition at line 972 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 957 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 961 of file create.cpp.
float create::Create::getRightWheelDistance | ( | ) | const |
Get the total distance the right wheel has moved.
Definition at line 953 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 984 of file create.cpp.
Vel create::Create::getVel | ( | ) | const |
Get the estimated velocity of Create based on wheel encoders.
Definition at line 976 of file create.cpp.
float create::Create::getVoltage | ( | ) | const |
void create::Create::init | ( | ) | [private] |
Definition at line 20 of file create.cpp.
bool create::Create::isCleanButtonPressed | ( | ) | const |
Get state of 'clean' button ('play' button on Create 1).
Definition at line 685 of file create.cpp.
bool create::Create::isCliff | ( | ) | const |
Definition at line 606 of file create.cpp.
bool create::Create::isClockButtonPressed | ( | ) | const |
Not supported by any firmware!
Definition at line 696 of file create.cpp.
bool create::Create::isDayButtonPressed | ( | ) | const |
Get state of 'day' button.
Definition at line 719 of file create.cpp.
bool create::Create::isDockButtonPressed | ( | ) | const |
Get state of 'dock' button ('advance' button on Create 1).
Definition at line 749 of file create.cpp.
bool create::Create::isHourButtonPressed | ( | ) | const |
Get state of 'hour' button.
Definition at line 729 of file create.cpp.
bool create::Create::isLeftBumper | ( | ) | const |
Definition at line 576 of file create.cpp.
bool create::Create::isLightBumperCenterLeft | ( | ) | const |
Definition at line 839 of file create.cpp.
bool create::Create::isLightBumperCenterRight | ( | ) | const |
Definition at line 849 of file create.cpp.
bool create::Create::isLightBumperFrontLeft | ( | ) | const |
Definition at line 829 of file create.cpp.
bool create::Create::isLightBumperFrontRight | ( | ) | const |
Definition at line 859 of file create.cpp.
bool create::Create::isLightBumperLeft | ( | ) | const |
Definition at line 819 of file create.cpp.
bool create::Create::isLightBumperRight | ( | ) | const |
Definition at line 869 of file create.cpp.
bool create::Create::isMainBrushOvercurrent | ( | ) | const |
bool create::Create::isMinButtonPressed | ( | ) | const |
Get state of 'min' button.
Definition at line 739 of file create.cpp.
bool create::Create::isMovingForward | ( | ) | const |
Definition at line 939 of file create.cpp.
bool create::Create::isRightBumper | ( | ) | const |
Definition at line 586 of file create.cpp.
bool create::Create::isScheduleButtonPressed | ( | ) | const |
Not supported by any firmware!
Definition at line 708 of file create.cpp.
bool create::Create::isSideBrushOvercurrent | ( | ) | const |
bool create::Create::isSpotButtonPressed | ( | ) | const |
Get state of 'spot' button.
Definition at line 759 of file create.cpp.
bool create::Create::isVirtualWall | ( | ) | const |
Definition at line 622 of file create.cpp.
bool create::Create::isWall | ( | ) | const |
Definition at line 596 of file create.cpp.
bool create::Create::isWheeldrop | ( | ) | const |
Definition at line 566 of file create.cpp.
bool create::Create::isWheelOvercurrent | ( | ) | const |
void create::Create::onData | ( | ) | [private] |
Definition at line 92 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 559 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 434 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 345 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 518 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 453 of file create.cpp.
bool create::Create::setMode | ( | const create::CreateMode & | mode | ) |
Change Create mode.
mode | to change Create to. |
Definition at line 301 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 508 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 457 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 461 of file create.cpp.
bool create::Create::updateLEDs | ( | ) | [private] |
Definition at line 465 of file create.cpp.
uint8_t create::Create::checkLED [private] |
boost::shared_ptr<create::Data> create::Create::data [protected] |
uint8_t create::Create::debrisLED [private] |
uint8_t create::Create::dockLED [private] |
bool create::Create::firstOnData [private] |
uint8_t create::Create::mainMotorPower [private] |
CreateMode create::Create::mode [private] |
RobotModel create::Create::model [private] |
create::Pose create::Create::pose [private] |
Matrix create::Create::poseCovar [private] |
uint8_t create::Create::powerLED [private] |
uint8_t create::Create::powerLEDIntensity [private] |
uint32_t create::Create::prevTicksLeft [private] |
uint32_t create::Create::prevTicksRight [private] |
float create::Create::requestedLeftVel [private] |
float create::Create::requestedRightVel [private] |
boost::shared_ptr<create::Serial> create::Create::serial [protected] |
uint8_t create::Create::sideMotorPower [private] |
uint8_t create::Create::spotLED [private] |
float create::Create::totalLeftDist [private] |
float create::Create::totalRightDist [private] |
uint8_t create::Create::vacuumMotorPower [private] |
create::Vel create::Create::vel [private] |