Class Create
Defined in File create.h
Class Documentation
-
class Create
Public Functions
-
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:
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.
-
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:
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.
-
~Create()
Attempts to disconnect from serial.
-
bool 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.
-
inline bool connected() const
Check if serial connection is active.
- Returns:
true if successfully connected, false otherwise.
-
void disconnect()
Disconnect from serial.
-
bool setMode(const create::CreateMode &mode)
Change Create mode.
- Parameters:
mode – to change Create to.
- Returns:
true if successful, false otherwise
-
bool clean(const create::CleanMode &mode = CLEAN_DEFAULT)
Starts a cleaning mode. Changes mode to MODE_PASSIVE.
- Returns:
true if successful, false otherwise
-
bool dock() const
Starts the docking behaviour. Changes mode to MODE_PASSIVE.
- Returns:
true if successful, false otherwise
-
bool setDate(const create::DayOfWeek &day, const uint8_t &hour, const uint8_t &min) const
Sets the internal clock of Create.
- Parameters:
day – in range [0, 6]
hour – in range [0, 23]
min – in range [0, 59]
- Returns:
true if successful, false otherwise
-
bool driveRadius(const float &velocity, const float &radius)
Set the average wheel velocity and turning radius of Create.
- Parameters:
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
- Returns:
true if successful, false otherwise
-
bool driveWheels(const float &leftWheel, const float &rightWheel)
Set the velocities for the left and right wheels.
- Parameters:
leftWheel – velocity in m/s.
rightWheel – veloctiy in m/s.
- Returns:
true if successful, false otherwise
-
bool driveWheelsPwm(const float &leftWheel, const float &rightWheel)
Set the direct for the left and right wheels.
- Parameters:
leftWheel – pwm in the range [-1, 1]
rightWheel – pwm in the range [-1, 1]
- Returns:
true if successful, false otherwise
-
bool drive(const float &xVel, const float &angularVel)
Set the forward and angular velocity of Create.
- Parameters:
xVel – in m/s
angularVel – in rads/s
- Returns:
true if successful, false otherwise
-
bool setSideMotor(const float &power)
Set the power to the side brush motor.
- Parameters:
power – is in the range [-1, 1]
- Returns:
true if successful, false otherwise
-
bool setMainMotor(const float &power)
Set the power to the main brush motor.
- Parameters:
power – is in the range [-1, 1]
- Returns:
true if successful, false otherwise
-
bool setVacuumMotor(const float &power)
Set the power to the vacuum motor.
- Parameters:
power – is in the range [0, 1]
- Returns:
true if successful, false otherwise
-
bool setAllMotors(const float &mainPower, const float &sidePower, const float &vacuumPower)
Set the power of all motors.
- Parameters:
mainPower – in the range [-1, 1]
sidePower – in the range [-1, 1]
vacuumPower – in the range [0, 1]
- Returns:
true if successful, false otherwise
-
bool enableDebrisLED(const bool &enable)
Set the blue “debris” LED on/off.
- Parameters:
enable –
- Returns:
true if successful, false otherwise
-
bool enableSpotLED(const bool &enable)
Set the green “spot” LED on/off.
- Parameters:
enable –
- Returns:
true if successful, false otherwise
-
bool enableDockLED(const bool &enable)
Set the green “dock” LED on/off.
- Parameters:
enable –
- Returns:
true if successful, false otherwise
-
bool enableCheckRobotLED(const bool &enable)
Set the orange “check Create” LED on/off.
- Parameters:
enable –
- Returns:
true if successful, false otherwise
-
bool setPowerLED(const uint8_t &power, const uint8_t &intensity = 255)
Set the center power LED.
- Parameters:
power – in range [0, 255] where 0 = green and 255 = red
intensity – in range [0, 255]
- Returns:
true if successful, false otherwise
-
bool 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:
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:
- Returns:
true if successful, false otherwise
-
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.
- Parameters:
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]
- Returns:
true if successful, false otherwise
-
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.
- Parameters:
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)
- Returns:
true if successful, false otherwise
-
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.
- Parameters:
songNumber – is one of four stored songs in the range [0, 4]
- Returns:
true if successful, false otherwise
-
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.
- Parameters:
dtHistoryLength – number of historical samples to use for calculating average dt.
-
bool isWheeldrop() const
- Returns:
true if a left or right wheeldrop is detected, false otherwise.
-
bool isLeftWheeldrop() const
- Returns:
true if a left wheeldrop is detected, false otherwise.
-
bool isRightWheeldrop() const
- Returns:
true if a right wheeldrop is detected, false otherwise.
-
bool isLeftBumper() const
- Returns:
true if left bumper is pressed, false otherwise.
-
bool isRightBumper() const
- Returns:
true if right bumper is pressed, false otherwise.
-
bool isCliff() const
- Returns:
true if there are any cliff detections, false otherwise.
-
bool isCliffLeft() const
- Returns:
true if the left sensor detects a cliff, false otherwise.
-
bool isCliffFrontLeft() const
- Returns:
true if the front left sensor detects a cliff, false otherwise.
-
bool isCliffRight() const
- Returns:
true if the right sensor detects a cliff, false otherwise.
-
bool isCliffFrontRight() const
- Returns:
true if the front right sensor detects a cliff, false otherwise.
-
bool isVirtualWall() const
- Returns:
true if there is a virtual wall signal is being received.
-
bool isWheelOvercurrent() const
- Todo:
Not implemented yet (https://github.com/AutonomyLab/libcreate/issues/8)
- Returns:
true if drive motors are overcurrent.
-
bool isMainBrushOvercurrent() const
- Todo:
Not implemented yet (https://github.com/AutonomyLab/libcreate/issues/8)
- Returns:
true if main brush motor is overcurrent.
-
bool isSideBrushOvercurrent() const
- Todo:
Not implemented yet (https://github.com/AutonomyLab/libcreate/issues/8)
- Returns:
true if side brush motor is overcurrent.
-
uint8_t getDirtDetect() const
Get level of the dirt detect sensor.
- Returns:
value in range [0, 255]
-
uint8_t getIROmni() const
Get value of 8-bit IR character currently being received by omnidirectional sensor.
- Returns:
value in range [0, 255]
-
uint8_t getIRLeft() const
Get value of 8-bit IR character currently being received by left sensor.
- Returns:
value in range [0, 255]
-
uint8_t getIRRight() const
Get value of 8-bit IR character currently being received by right sensor.
- Returns:
value in range [0, 255]
-
bool isCleanButtonPressed() const
Get state of ‘clean’ button (‘play’ button on Create 1).
- Returns:
true if button is pressed, false otherwise.
-
bool isClockButtonPressed() const
Not supported by any firmware!
-
bool isScheduleButtonPressed() const
Not supported by any firmware!
-
bool isDayButtonPressed() const
Get state of ‘day’ button.
- Returns:
true if button is pressed, false otherwise.
-
bool isHourButtonPressed() const
Get state of ‘hour’ button.
- Returns:
true if button is pressed, false otherwise.
-
bool isMinButtonPressed() const
Get state of ‘min’ button.
- Returns:
true if button is pressed, false otherwise.
-
bool isDockButtonPressed() const
Get state of ‘dock’ button (‘advance’ button on Create 1).
- Returns:
true if button is pressed, false otherwise.
-
bool isSpotButtonPressed() const
Get state of ‘spot’ button.
- Returns:
true if button is pressed, false otherwise.
-
float getVoltage() const
Get battery voltage.
- Returns:
value in volts
-
float getCurrent() const
Get current flowing in/out of battery. A positive current implies Create is charging.
- Returns:
value in amps
-
int8_t getTemperature() const
Get the temperature of battery.
- Returns:
value in Celsius
-
float getBatteryCharge() const
Get battery’s remaining charge.
- Returns:
value in amp-hours
-
float getBatteryCapacity() const
Get estimated battery charge capacity.
- Returns:
in amp-hours
-
bool isLightBumperLeft() const
- Returns:
true if farthest left light sensor detects an obstacle, false otherwise.
-
bool isLightBumperFrontLeft() const
- Returns:
true if front left light sensor detects an obstacle, false otherwise.
-
bool isLightBumperCenterLeft() const
- Returns:
true if center left light sensor detects an obstacle, false otherwise.
-
bool isLightBumperRight() const
- Returns:
true if farthest right light sensor detects an obstacle, false otherwise.
-
bool isLightBumperFrontRight() const
- Returns:
true if front right light sensor detects an obstacle, false otherwise.
-
bool isLightBumperCenterRight() const
- Returns:
true if center right light sensor detects an obstacle, false otherwise.
-
uint16_t getLightSignalLeft() const
Get the signal strength from the left light sensor.
- Returns:
value in range [0, 4095]
-
uint16_t getLightSignalFrontLeft() const
Get the signal strength from the front-left light sensor.
- Returns:
value in range [0, 4095]
-
uint16_t getLightSignalCenterLeft() const
Get the signal strength from the center-left light sensor.
- Returns:
value in range [0, 4095]
-
uint16_t getLightSignalRight() const
Get the signal strength from the right light sensor.
- Returns:
value in range [0, 4095]
-
uint16_t getLightSignalFrontRight() const
Get the signal strength from the front-right light sensor.
- Returns:
value in range [0, 4095]
-
uint16_t getLightSignalCenterRight() const
Get the signal strength from the center-right light sensor.
- Returns:
value in range [0, 4095]
-
float getLeftWheelDistance() const
Get the total distance the left wheel has moved.
- Returns:
distance in meters.
-
float getRightWheelDistance() const
Get the total distance the right wheel has moved.
- Returns:
distance in meters.
-
float getMeasuredLeftWheelVel() const
Get the measured velocity of the left wheel.
- Returns:
velocity in m/s
-
float getMeasuredRightWheelVel() const
Get the measured velocity of the right wheel.
- Returns:
velocity in m/s
-
float 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.
-
float 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.
-
create::ChargingState getChargingState() const
Get the current charging state.
- Returns:
charging state.
-
create::CreateMode getMode()
Get the current mode reported by Create.
- Returns:
mode.
-
create::Pose getPose() const
Get the estimated pose of Create based on wheel encoders.
- Returns:
pose (x-y position in meters and yaw angle in Radians)
-
create::Vel 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)
-
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.
- Returns:
number of corrupt packets.
-
uint64_t getTotalPackets() const
Get the total number of serial packets received (including corrupt packets) since first connecting to Create.
- Returns:
total number of serial packets.
-
void setModeReportWorkaround(const bool &enable)
Enable or disable the mode reporting workaround. Some Roomba 6xx robots incorrectly report the OI mode in their sensor streams. Enabling the workaround will cause libcreate to decrement the reported OI mode in the sensor stream by 1. See https://github.com/AutonomyLab/create_robot/issues/64.
-
bool getModeReportWorkaround() const
- Returns:
true if the mode reporting workaround is enabled, false otherwise.
-
Create(RobotModel model = RobotModel::CREATE_2, bool install_signal_handler = true)