Public Member Functions | Protected Attributes | Private Types | Private Member Functions | Private Attributes | List of all members
create::Create Class Reference

#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::Datadata
 
std::shared_ptr< create::Serialserial
 

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
 

Detailed Description

Definition at line 49 of file create.h.

Member Typedef Documentation

typedef boost::numeric::ublas::matrix<float> create::Create::Matrix
private

Definition at line 51 of file create.h.

Member Enumeration Documentation

Enumerator
LED_DEBRIS 
LED_SPOT 
LED_DOCK 
LED_CHECK 

Definition at line 53 of file create.h.

Constructor & Destructor Documentation

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.

Parameters
modelthe type of the robot. See RobotModel to determine the value for your robot.
install_signal_handlerif 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.

Parameters
portof your computer that is connected to Create.
baudrate to communicate with Create. Typically, 115200 for Create 2 and 57600 for Create 1.
modeltype of robot. See RobotModel to determine the value for your robot.
install_signal_handlerif 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.

Member Function Documentation

Create::Matrix create::Create::addMatrices ( const Matrix A,
const Matrix B 
) const
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.

Returns
true if successful, false otherwise

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.

Returns
true if a successful connection is established, false otherwise.

Definition at line 293 of file create.cpp.

bool create::Create::connected ( ) const
inline

Check if serial connection is active.

Returns
true if successfully connected, false otherwise.

Definition at line 148 of file create.h.

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.

Parameters
songNumbercan be one of four possible song slots, [0, 4]
songLengthis the number of notes, maximum 16. length(notes) = length(durations) = songLength should be true.
notesis a sequence of notes. Each note is in the range [31, 127]. Anything outside this range is considered a rest note.
durationsfor each note in fractions of a second from the range [0, 4)
Returns
true if successful, false otherwise

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.

Returns
true if successful, false otherwise

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.

Parameters
xVelin m/s
angularVelin rads/s
Returns
true if successful, false otherwise

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.

Parameters
velocityis in m/s bounded between [-0.5, 0.5]
radiusin 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
Returns
true if successful, false otherwise

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.

Parameters
leftWheelvelocity in m/s.
rightWheelveloctiy in m/s.
Returns
true if successful, false otherwise

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.

Parameters
leftWheelpwm in the range [-1, 1]
rightWheelpwm in the range [-1, 1]
Returns
true if successful, false otherwise

Definition at line 451 of file create.cpp.

bool create::Create::enableCheckRobotLED ( const bool &  enable)

Set the orange "check Create" LED on/off.

Parameters
enable
Returns
true if successful, false otherwise

Definition at line 554 of file create.cpp.

bool create::Create::enableDebrisLED ( const bool &  enable)

Set the blue "debris" LED on/off.

Parameters
enable
Returns
true if successful, false otherwise

Definition at line 530 of file create.cpp.

bool create::Create::enableDockLED ( const bool &  enable)

Set the green "dock" LED on/off.

Parameters
enable
Returns
true if successful, false otherwise

Definition at line 546 of file create.cpp.

bool create::Create::enableSpotLED ( const bool &  enable)

Set the green "spot" LED on/off.

Parameters
enable
Returns
true if successful, false otherwise

Definition at line 538 of file create.cpp.

float create::Create::getBatteryCapacity ( ) const

Get estimated battery charge capacity.

Returns
in amp-hours

Definition at line 926 of file create.cpp.

float create::Create::getBatteryCharge ( ) const

Get battery's remaining charge.

Returns
value in amp-hours

Definition at line 916 of file create.cpp.

ChargingState create::Create::getChargingState ( ) const

Get the current charging state.

Returns
charging state.

Definition at line 790 of file create.cpp.

float create::Create::getCurrent ( ) const

Get current flowing in/out of battery. A positive current implies Create is charging.

Returns
value in amps

Definition at line 896 of file create.cpp.

uint8_t create::Create::getDirtDetect ( ) const

Get level of the dirt detect sensor.

Returns
value in range [0, 255]

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.

Returns
value in range [0, 255]

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.

Returns
value in range [0, 255]

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.

Returns
value in range [0, 255]

Definition at line 780 of file create.cpp.

float create::Create::getLeftWheelDistance ( ) const

Get the total distance the left wheel has moved.

Returns
distance in meters.

Definition at line 1096 of file create.cpp.

uint16_t create::Create::getLightSignalCenterLeft ( ) const

Get the signal strength from the center-left light sensor.

Returns
value in range [0, 4095]

Definition at line 1016 of file create.cpp.

uint16_t create::Create::getLightSignalCenterRight ( ) const

Get the signal strength from the center-right light sensor.

Returns
value in range [0, 4095]

Definition at line 1046 of file create.cpp.

uint16_t create::Create::getLightSignalFrontLeft ( ) const

Get the signal strength from the front-left light sensor.

Returns
value in range [0, 4095]

Definition at line 1006 of file create.cpp.

uint16_t create::Create::getLightSignalFrontRight ( ) const

Get the signal strength from the front-right light sensor.

Returns
value in range [0, 4095]

Definition at line 1036 of file create.cpp.

uint16_t create::Create::getLightSignalLeft ( ) const

Get the signal strength from the left light sensor.

Returns
value in range [0, 4095]

Definition at line 996 of file create.cpp.

uint16_t create::Create::getLightSignalRight ( ) const

Get the signal strength from the right light sensor.

Returns
value in range [0, 4095]

Definition at line 1026 of file create.cpp.

float create::Create::getMeasuredLeftWheelVel ( ) const

Get the measured velocity of the left wheel.

Returns
velocity in m/s

Definition at line 1104 of file create.cpp.

float create::Create::getMeasuredRightWheelVel ( ) const

Get the measured velocity of the right wheel.

Returns
velocity in m/s

Definition at line 1108 of file create.cpp.

create::CreateMode create::Create::getMode ( )

Get the current mode reported by Create.

Returns
mode.

Definition at line 1120 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.

Returns
number of corrupt packets.

Definition at line 1135 of file create.cpp.

Pose create::Create::getPose ( ) const

Get the estimated pose of Create based on wheel encoders.

Returns
pose (x-y position in meters and yaw angle in Radians)

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.

Returns
requested velocity in m/s.

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.

Returns
requested velocity in m/s.

Definition at line 1116 of file create.cpp.

float create::Create::getRightWheelDistance ( ) const

Get the total distance the right wheel has moved.

Returns
distance in meters.

Definition at line 1100 of file create.cpp.

int8_t create::Create::getTemperature ( ) const

Get the temperature of battery.

Returns
value in Celsius

Definition at line 906 of file create.cpp.

uint64_t create::Create::getTotalPackets ( ) const

Get the total number of serial packets received (including corrupt packets) since first connecting to Create.

Returns
total number of serial packets.

Definition at line 1139 of file create.cpp.

Vel create::Create::getVel ( ) const

Get the estimated velocity of Create based on wheel encoders.

Returns
velocity (x and y in m/s and angular velocity in Radians/s)

Definition at line 1131 of file create.cpp.

float create::Create::getVoltage ( ) const

Get battery voltage.

Returns
value in volts

Definition at line 886 of file create.cpp.

void create::Create::init ( bool  install_signal_handler)
private

Definition at line 17 of file create.cpp.

bool create::Create::isCleanButtonPressed ( ) const

Get state of 'clean' button ('play' button on Create 1).

Returns
true if button is pressed, false otherwise.

Definition at line 802 of file create.cpp.

bool create::Create::isCliff ( ) const
Returns
true if there are any cliff detections, false otherwise.

Definition at line 684 of file create.cpp.

bool create::Create::isCliffFrontLeft ( ) const
Returns
true if the front left sensor detects a cliff, false otherwise.

Definition at line 710 of file create.cpp.

bool create::Create::isCliffFrontRight ( ) const
Returns
true if the front right sensor detects a cliff, false otherwise.

Definition at line 730 of file create.cpp.

bool create::Create::isCliffLeft ( ) const
Returns
true if the left sensor detects a cliff, false otherwise.

Definition at line 700 of file create.cpp.

bool create::Create::isCliffRight ( ) const
Returns
true if the right sensor detects a cliff, false otherwise.

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.

Returns
true if button is pressed, false otherwise.

Definition at line 836 of file create.cpp.

bool create::Create::isDockButtonPressed ( ) const

Get state of 'dock' button ('advance' button on Create 1).

Returns
true if button is pressed, false otherwise.

Definition at line 866 of file create.cpp.

bool create::Create::isHourButtonPressed ( ) const

Get state of 'hour' button.

Returns
true if button is pressed, false otherwise.

Definition at line 846 of file create.cpp.

bool create::Create::isLeftBumper ( ) const
Returns
true if left bumper is pressed, false otherwise.

Definition at line 654 of file create.cpp.

bool create::Create::isLeftWheeldrop ( ) const
Returns
true if a left wheeldrop is detected, false otherwise.

Definition at line 634 of file create.cpp.

bool create::Create::isLightBumperCenterLeft ( ) const
Returns
true if center left light sensor detects an obstacle, false otherwise.

Definition at line 956 of file create.cpp.

bool create::Create::isLightBumperCenterRight ( ) const
Returns
true if center right light sensor detects an obstacle, false otherwise.

Definition at line 966 of file create.cpp.

bool create::Create::isLightBumperFrontLeft ( ) const
Returns
true if front left light sensor detects an obstacle, false otherwise.

Definition at line 946 of file create.cpp.

bool create::Create::isLightBumperFrontRight ( ) const
Returns
true if front right light sensor detects an obstacle, false otherwise.

Definition at line 976 of file create.cpp.

bool create::Create::isLightBumperLeft ( ) const
Returns
true if farthest left light sensor detects an obstacle, false otherwise.

Definition at line 936 of file create.cpp.

bool create::Create::isLightBumperRight ( ) const
Returns
true if farthest right light sensor detects an obstacle, false otherwise.

Definition at line 986 of file create.cpp.

bool create::Create::isMainBrushOvercurrent ( ) const
Todo:
Not implemented yet (https://github.com/AutonomyLab/libcreate/issues/8)
Returns
true if main brush motor is overcurrent.

Definition at line 1076 of file create.cpp.

bool create::Create::isMinButtonPressed ( ) const

Get state of 'min' button.

Returns
true if button is pressed, false otherwise.

Definition at line 856 of file create.cpp.

bool create::Create::isMovingForward ( ) const
Returns
true if Create is moving forward, false otherwise.

Definition at line 1056 of file create.cpp.

bool create::Create::isRightBumper ( ) const
Returns
true if right bumper is pressed, false otherwise.

Definition at line 664 of file create.cpp.

bool create::Create::isRightWheeldrop ( ) const
Returns
true if a right wheeldrop is detected, false otherwise.

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
Todo:
Not implemented yet (https://github.com/AutonomyLab/libcreate/issues/8)
Returns
true if side brush motor is overcurrent.

Definition at line 1066 of file create.cpp.

bool create::Create::isSpotButtonPressed ( ) const

Get state of 'spot' button.

Returns
true if button is pressed, false otherwise.

Definition at line 876 of file create.cpp.

bool create::Create::isVirtualWall ( ) const
Returns
true if there is a virtual wall signal is being received.

Definition at line 740 of file create.cpp.

bool create::Create::isWall ( ) const
Returns
true if wall is seen to right of Create, false otherwise.

Definition at line 674 of file create.cpp.

bool create::Create::isWheeldrop ( ) const
Returns
true if a left or right wheeldrop is detected, false otherwise.

Definition at line 624 of file create.cpp.

bool create::Create::isWheelOvercurrent ( ) const
Todo:
Not implemented yet (https://github.com/AutonomyLab/libcreate/issues/8)
Returns
true if drive motors are overcurrent.

Definition at line 1086 of file create.cpp.

void create::Create::onData ( )
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.

Parameters
songNumberis one of four stored songs in the range [0, 4]
Returns
true if successful, false otherwise

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.

Parameters
mainPowerin the range [-1, 1]
sidePowerin the range [-1, 1]
vacuumPowerin the range [0, 1]
Returns
true if successful, false otherwise

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.

Parameters
dayin range [0, 6]
hourin range [0, 23]
minin range [0, 59]
Returns
true if successful, false otherwise

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.

Todo:
This function is not yet implemented refer to https://github.com/AutonomyLab/libcreate/issues/7
Parameters
segmentsto 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
   
Returns
true if successful, false otherwise
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.

Parameters
digit1is left most digit with ascii range [32, 126]
digit2is second to left digit with ascii range [32, 126]
digit3is second to right digit with ascii range [32, 126]
digit4is right most digit with ascii range [32, 126]
Returns
true if successful, false otherwise

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.

Parameters
dtHistoryLengthnumber 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.

Parameters
poweris in the range [-1, 1]
Returns
true if successful, false otherwise

Definition at line 507 of file create.cpp.

bool create::Create::setMode ( const create::CreateMode mode)

Change Create mode.

Parameters
modeto change Create to.
Returns
true if successful, false otherwise

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.

Parameters
powerin range [0, 255] where 0 = green and 255 = red
intensityin range [0, 255]
Returns
true if successful, false otherwise

Definition at line 562 of file create.cpp.

bool create::Create::setSideMotor ( const float &  power)

Set the power to the side brush motor.

Parameters
poweris in the range [-1, 1]
Returns
true if successful, false otherwise

Definition at line 511 of file create.cpp.

bool create::Create::setVacuumMotor ( const float &  power)

Set the power to the vacuum motor.

Parameters
poweris in the range [0, 1]
Returns
true if successful, false otherwise

Definition at line 515 of file create.cpp.

bool create::Create::updateLEDs ( )
private

Definition at line 519 of file create.cpp.

Member Data Documentation

uint8_t create::Create::checkLED
private

Definition at line 70 of file create.h.

std::shared_ptr<create::Data> create::Create::data
protected

Definition at line 102 of file create.h.

uint8_t create::Create::debrisLED
private

Definition at line 67 of file create.h.

uint8_t create::Create::dockLED
private

Definition at line 69 of file create.h.

std::deque<float> create::Create::dtHistory
private

Definition at line 85 of file create.h.

uint8_t create::Create::dtHistoryLength
private

Definition at line 86 of file create.h.

bool create::Create::firstOnData
private

Definition at line 83 of file create.h.

uint8_t create::Create::mainMotorPower
private

Definition at line 62 of file create.h.

float create::Create::measuredLeftVel
private

Definition at line 90 of file create.h.

float create::Create::measuredRightVel
private

Definition at line 91 of file create.h.

CreateMode create::Create::mode
private

Definition at line 74 of file create.h.

RobotModel create::Create::model
private

Definition at line 60 of file create.h.

create::Pose create::Create::pose
private

Definition at line 76 of file create.h.

Matrix create::Create::poseCovar
private

Definition at line 88 of file create.h.

uint8_t create::Create::powerLED
private

Definition at line 71 of file create.h.

uint8_t create::Create::powerLEDIntensity
private

Definition at line 72 of file create.h.

std::chrono::time_point<std::chrono::steady_clock> create::Create::prevOnDataTime
private

Definition at line 84 of file create.h.

uint32_t create::Create::prevTicksLeft
private

Definition at line 79 of file create.h.

uint32_t create::Create::prevTicksRight
private

Definition at line 80 of file create.h.

float create::Create::requestedLeftVel
private

Definition at line 92 of file create.h.

float create::Create::requestedRightVel
private

Definition at line 93 of file create.h.

std::shared_ptr<create::Serial> create::Create::serial
protected

Definition at line 103 of file create.h.

uint8_t create::Create::sideMotorPower
private

Definition at line 63 of file create.h.

uint8_t create::Create::spotLED
private

Definition at line 68 of file create.h.

float create::Create::totalLeftDist
private

Definition at line 81 of file create.h.

float create::Create::totalRightDist
private

Definition at line 82 of file create.h.

uint8_t create::Create::vacuumMotorPower
private

Definition at line 64 of file create.h.

create::Vel create::Create::vel
private

Definition at line 77 of file create.h.


The documentation for this class was generated from the following files:


libcreate
Author(s): Jacob Perron
autogenerated on Sat May 8 2021 03:02:37