Public Member Functions | Protected Attributes | Private Types | Private Member Functions | Private Attributes
create::Create Class Reference

#include <create.h>

List of all members.

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::Datadata
boost::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 ()
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

Detailed Description

Definition at line 47 of file create.h.


Member Typedef Documentation

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

Definition at line 49 of file create.h.


Member Enumeration Documentation

enum create::Create::CreateLED [private]
Enumerator:
LED_DEBRIS 
LED_SPOT 
LED_DOCK 
LED_CHECK 

Definition at line 51 of file create.h.


Constructor & Destructor Documentation

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.

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.

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.

Definition at line 59 of file create.cpp.

Attempts to disconnect from serial.

Definition at line 64 of file create.cpp.


Member Function Documentation

Create::Matrix create::Create::addMatrices ( const Matrix A,
const Matrix B 
) const [private]

Definition at line 68 of file create.cpp.

Starts a cleaning mode. Changes mode to MODE_PASSIVE.

Returns:
true if successful, false otherwise

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.

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

Definition at line 269 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 138 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 536 of file create.cpp.

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.

Returns:
true if successful, false otherwise

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.

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

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.

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 355 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 379 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 500 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 476 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 492 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 484 of file create.cpp.

Get estimated battery charge capacity.

Returns:
in amp-hours

Definition at line 809 of file create.cpp.

Get battery's remaining charge.

Returns:
value in amp-hours

Definition at line 799 of file create.cpp.

Get the current charging state.

Returns:
charging state.

Definition at line 672 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 779 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 632 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 652 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 642 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 662 of file create.cpp.

Get the total distance the left wheel has moved.

Returns:
distance in meters.

Definition at line 949 of file create.cpp.

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

Returns:
value in range [0, 4095]

Definition at line 899 of file create.cpp.

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

Returns:
value in range [0, 4095]

Definition at line 929 of file create.cpp.

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

Returns:
value in range [0, 4095]

Definition at line 889 of file create.cpp.

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

Returns:
value in range [0, 4095]

Definition at line 919 of file create.cpp.

Get the signal strength from the left light sensor.

Returns:
value in range [0, 4095]

Definition at line 879 of file create.cpp.

Get the signal strength from the right light sensor.

Returns:
value in range [0, 4095]

Definition at line 909 of file create.cpp.

Get the current mode reported by Create.

Returns:
mode.

Definition at line 965 of file create.cpp.

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 980 of file create.cpp.

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 972 of file create.cpp.

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 957 of file create.cpp.

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 961 of file create.cpp.

Get the total distance the right wheel has moved.

Returns:
distance in meters.

Definition at line 953 of file create.cpp.

Get the temperature of battery.

Returns:
value in Celsius

Definition at line 789 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 984 of file create.cpp.

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 976 of file create.cpp.

float create::Create::getVoltage ( ) const

Get battery voltage.

Returns:
value in volts

Definition at line 769 of file create.cpp.

void create::Create::init ( ) [private]

Definition at line 20 of file create.cpp.

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

Returns:
true if button is pressed, false otherwise.

Definition at line 685 of file create.cpp.

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

Definition at line 606 of file create.cpp.

Not supported by any firmware!

Definition at line 696 of file create.cpp.

Get state of 'day' button.

Returns:
true if button is pressed, false otherwise.

Definition at line 719 of file create.cpp.

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

Returns:
true if button is pressed, false otherwise.

Definition at line 749 of file create.cpp.

Get state of 'hour' button.

Returns:
true if button is pressed, false otherwise.

Definition at line 729 of file create.cpp.

Returns:
true if left bumper is pressed, false otherwise.

Definition at line 576 of file create.cpp.

Returns:
true if center left light sensor detects an obstacle, false otherwise.

Definition at line 839 of file create.cpp.

Returns:
true if center right light sensor detects an obstacle, false otherwise.

Definition at line 849 of file create.cpp.

Returns:
true if front left light sensor detects an obstacle, false otherwise.

Definition at line 829 of file create.cpp.

Returns:
true if front right light sensor detects an obstacle, false otherwise.

Definition at line 859 of file create.cpp.

Returns:
true if farthest left light sensor detects an obstacle, false otherwise.

Definition at line 819 of file create.cpp.

Returns:
true if farthest right light sensor detects an obstacle, false otherwise.

Definition at line 869 of file create.cpp.

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

Get state of 'min' button.

Returns:
true if button is pressed, false otherwise.

Definition at line 739 of file create.cpp.

Returns:
true if Create is moving forward, false otherwise.

Definition at line 939 of file create.cpp.

Returns:
true if right bumper is pressed, false otherwise.

Definition at line 586 of file create.cpp.

Not supported by any firmware!

Definition at line 708 of file create.cpp.

Todo:
Not implemented yet (https://github.com/AutonomyLab/libcreate/issues/8)
Returns:
true if side brush motor is overcurrent.

Get state of 'spot' button.

Returns:
true if button is pressed, false otherwise.

Definition at line 759 of file create.cpp.

Returns:
true if there is a virtual wall signal is being received.

Definition at line 622 of file create.cpp.

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

Definition at line 596 of file create.cpp.

Returns:
true if a left or right wheeldrop is detected, false otherwise.

Definition at line 566 of file create.cpp.

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

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

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.

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

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

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.

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 518 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 453 of file create.cpp.

Change Create mode.

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

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.

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

Definition at line 508 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 457 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 461 of file create.cpp.

bool create::Create::updateLEDs ( ) [private]

Definition at line 465 of file create.cpp.


Member Data Documentation

uint8_t create::Create::checkLED [private]

Definition at line 68 of file create.h.

boost::shared_ptr<create::Data> create::Create::data [protected]

Definition at line 96 of file create.h.

uint8_t create::Create::debrisLED [private]

Definition at line 65 of file create.h.

uint8_t create::Create::dockLED [private]

Definition at line 67 of file create.h.

Definition at line 81 of file create.h.

uint8_t create::Create::mainMotorPower [private]

Definition at line 60 of file create.h.

Definition at line 72 of file create.h.

Definition at line 58 of file create.h.

Definition at line 74 of file create.h.

Definition at line 84 of file create.h.

uint8_t create::Create::powerLED [private]

Definition at line 69 of file create.h.

Definition at line 70 of file create.h.

Definition at line 82 of file create.h.

uint32_t create::Create::prevTicksLeft [private]

Definition at line 77 of file create.h.

uint32_t create::Create::prevTicksRight [private]

Definition at line 78 of file create.h.

Definition at line 86 of file create.h.

Definition at line 87 of file create.h.

boost::shared_ptr<create::Serial> create::Create::serial [protected]

Definition at line 97 of file create.h.

uint8_t create::Create::sideMotorPower [private]

Definition at line 61 of file create.h.

uint8_t create::Create::spotLED [private]

Definition at line 66 of file create.h.

Definition at line 79 of file create.h.

Definition at line 80 of file create.h.

Definition at line 62 of file create.h.

Definition at line 75 of file create.h.


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


libcreate
Author(s): Jacob Perron
autogenerated on Sat Nov 26 2016 03:41:46