35 #include <boost/numeric/ublas/matrix.hpp> 51 typedef boost::numeric::ublas::matrix<float>
Matrix;
95 void init(
bool install_signal_handler);
97 Matrix
addMatrices(
const Matrix &A,
const Matrix &B)
const;
106 std::shared_ptr<create::Data>
data;
145 bool connect(
const std::string& port,
const int& baud);
152 inline bool connected()
const {
return serial->connected(); };
198 bool driveRadius(
const float& velocity,
const float& radius);
206 bool driveWheels(
const float& leftWheel,
const float& rightWheel);
214 bool driveWheelsPwm(
const float& leftWheel,
const float& rightWheel);
222 bool drive(
const float& xVel,
const float& angularVel);
252 bool setAllMotors(
const float& mainPower,
const float& sidePower,
const float& vacuumPower);
288 bool setPowerLED(
const uint8_t& power,
const uint8_t& intensity = 255);
309 bool setDigits(
const std::vector<bool>& segments)
const;
321 const uint8_t& digit3,
const uint8_t& digit4)
const;
334 const uint8_t& songLength,
335 const uint8_t* notes,
336 const float* durations)
const;
344 bool playSong(
const uint8_t& songNumber)
const;
697 #endif // CREATE_DRIVER_H bool isDockButtonPressed() const
Get state of 'dock' button ('advance' button on Create 1).
bool setSideMotor(const float &power)
Set the power to the side brush motor.
bool isLightBumperLeft() const
bool isSpotButtonPressed() const
Get state of 'spot' button.
uint16_t getLightSignalLeft() const
Get the signal strength from the left light sensor.
uint16_t getLightSignalCenterRight() const
Get the signal strength from the center-right light sensor.
bool modeReportWorkaround
uint8_t powerLEDIntensity
bool isCliffFrontLeft() const
bool setVacuumMotor(const float &power)
Set the power to the vacuum motor.
bool isSideBrushOvercurrent() const
uint16_t getLightSignalRight() const
Get the signal strength from the right light sensor.
bool isHourButtonPressed() const
Get state of 'hour' button.
bool isScheduleButtonPressed() const
Not supported by any firmware!
bool isVirtualWall() const
float getVoltage() const
Get battery voltage.
bool setDate(const create::DayOfWeek &day, const uint8_t &hour, const uint8_t &min) const
Sets the internal clock of Create.
bool driveWheels(const float &leftWheel, const float &rightWheel)
Set the velocities for the left and right wheels.
bool dock() const
Starts the docking behaviour. Changes mode to MODE_PASSIVE.
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 acce...
float getBatteryCapacity() const
Get estimated battery charge capacity.
bool isRightWheeldrop() const
void setDtHistoryLength(const uint8_t &dtHistoryLength)
Set dtHistoryLength parameter. Used to configure the size of the buffer for calculating average time ...
bool isMovingForward() const
bool isCleanButtonPressed() const
Get state of 'clean' button ('play' button on Create 1).
bool isLightBumperCenterRight() const
bool getModeReportWorkaround() const
bool isLeftBumper() const
bool enableDockLED(const bool &enable)
Set the green "dock" LED on/off.
bool setPowerLED(const uint8_t &power, const uint8_t &intensity=255)
Set the center power LED.
void init(bool install_signal_handler)
bool driveWheelsPwm(const float &leftWheel, const float &rightWheel)
Set the direct for the left and right wheels.
std::shared_ptr< create::Data > data
uint16_t getLightSignalFrontRight() const
Get the signal strength from the front-right light sensor.
std::shared_ptr< create::Serial > serial
float getRequestedRightWheelVel() const
Get the requested velocity of the right wheel. This value is bounded at the maximum velocity of the r...
bool clean(const create::CleanMode &mode=CLEAN_DEFAULT)
Starts a cleaning mode. Changes mode to MODE_PASSIVE.
uint16_t getLightSignalCenterLeft() const
Get the signal strength from the center-left light sensor.
float getLeftWheelDistance() const
Get the total distance the left wheel has moved.
Create(RobotModel model=RobotModel::CREATE_2, bool install_signal_handler=true)
Default constructor.
bool connected() const
Check if serial connection is active.
bool enableCheckRobotLED(const bool &enable)
Set the orange "check Create" LED on/off.
bool driveRadius(const float &velocity, const float &radius)
Set the average wheel velocity and turning radius of Create.
bool enableSpotLED(const bool &enable)
Set the green "spot" LED on/off.
bool setMainMotor(const float &power)
Set the power to the main brush motor.
uint64_t getNumCorruptPackets() const
Get the number of corrupt serial packets since first connecting to Create. This value is ideally zero...
float getCurrent() const
Get current flowing in/out of battery. A positive current implies Create is charging.
bool isMainBrushOvercurrent() const
bool drive(const float &xVel, const float &angularVel)
Set the forward and angular velocity of Create.
bool isLeftWheeldrop() const
uint8_t getIROmni() const
Get value of 8-bit IR character currently being received by omnidirectional sensor.
bool isLightBumperFrontRight() const
boost::numeric::ublas::matrix< float > Matrix
bool enableDebrisLED(const bool &enable)
Set the blue "debris" LED on/off.
uint64_t getTotalPackets() const
Get the total number of serial packets received (including corrupt packets) since first connecting to...
bool isWheelOvercurrent() const
bool isClockButtonPressed() const
Not supported by any firmware!
float getMeasuredLeftWheelVel() const
Get the measured velocity of the left wheel.
create::ChargingState getChargingState() const
Get the current charging state.
bool setDigits(const std::vector< bool > &segments) const
Set the four 7-segment display digits from left to right.
bool isRightBumper() const
float getRightWheelDistance() const
Get the total distance the right wheel has moved.
std::chrono::time_point< std::chrono::steady_clock > prevOnDataTime
bool isLightBumperRight() const
void setModeReportWorkaround(const bool &enable)
Enable or disable the mode reporting workaround. Some Roomba 6xx robots incorrectly report the OI mod...
bool isMinButtonPressed() const
Get state of 'min' button.
int8_t getTemperature() const
Get the temperature of battery.
bool isCliffRight() const
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.
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...
bool connect(const std::string &port, const int &baud)
Make a serial connection to Create.
static RobotModel CREATE_2
Compatible with Create 2 or Roomba 600 series and greater.
bool isLightBumperFrontLeft() const
bool setAllMotors(const float &mainPower, const float &sidePower, const float &vacuumPower)
Set the power of all motors.
float getMeasuredRightWheelVel() const
Get the measured velocity of the right wheel.
bool isLightBumperCenterLeft() const
void disconnect()
Disconnect from serial.
bool isCliffFrontRight() const
uint8_t getIRRight() const
Get value of 8-bit IR character currently being received by right sensor.
uint16_t getLightSignalFrontLeft() const
Get the signal strength from the front-left light sensor.
create::Vel getVel() const
Get the estimated velocity of Create based on wheel encoders.
create::Pose getPose() const
Get the estimated pose of Create based on wheel encoders.
bool setMode(const create::CreateMode &mode)
Change Create mode.
create::CreateMode getMode()
Get the current mode reported by Create.
~Create()
Attempts to disconnect from serial.
uint8_t getDirtDetect() const
Get level of the dirt detect sensor.
std::deque< float > dtHistory
float getBatteryCharge() const
Get battery's remaining charge.
uint8_t getIRLeft() const
Get value of 8-bit IR character currently being received by left sensor.
float getRequestedLeftWheelVel() const
Get the requested velocity of the left wheel. This value is bounded at the maximum velocity of the ro...
bool isDayButtonPressed() const
Get state of 'day' button.
Matrix addMatrices(const Matrix &A, const Matrix &B) const