35 #include <boost/shared_ptr.hpp> 36 #include <boost/numeric/ublas/matrix.hpp> 49 typedef boost::numeric::ublas::matrix<float>
Matrix;
93 Matrix
addMatrices(
const Matrix &A,
const Matrix &B)
const;
98 boost::shared_ptr<create::Data>
data;
99 boost::shared_ptr<create::Serial>
serial;
133 bool connect(
const std::string& port,
const int& baud);
140 inline bool connected()
const {
return serial->connected(); };
186 bool driveRadius(
const float& velocity,
const float& radius);
194 bool driveWheels(
const float& leftWheel,
const float& rightWheel);
202 bool driveWheelsPwm(
const float& leftWheel,
const float& rightWheel);
210 bool drive(
const float& xVel,
const float& angularVel);
240 bool setAllMotors(
const float& mainPower,
const float& sidePower,
const float& vacuumPower);
276 bool setPowerLED(
const uint8_t& power,
const uint8_t& intensity = 255);
297 bool setDigits(
const std::vector<bool>& segments)
const;
309 const uint8_t& digit3,
const uint8_t& digit4)
const;
322 const uint8_t& songLength,
323 const uint8_t* notes,
324 const float* durations)
const;
332 bool playSong(
const uint8_t& songNumber)
const;
633 #endif // CREATE_DRIVER_H uint64_t getTotalPackets() const
Get the total number of serial packets received (including corrupt packets) since first connecting to...
bool setSideMotor(const float &power)
Set the power to the side brush motor.
uint8_t getIROmni() const
Get value of 8-bit IR character currently being received by omnidirectional sensor.
uint8_t powerLEDIntensity
float getMeasuredRightWheelVel() const
Get the measured velocity of the right wheel.
bool setVacuumMotor(const float &power)
Set the power to the vacuum motor.
bool isWheelOvercurrent() const
bool isLightBumperFrontLeft() const
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...
bool isLeftBumper() const
create::ChargingState getChargingState() const
Get the current charging state.
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.
int8_t getTemperature() const
Get the temperature of battery.
bool isHourButtonPressed() const
Get state of 'hour' button.
bool isClockButtonPressed() const
Not supported by any firmware!
uint16_t getLightSignalFrontLeft() const
Get the signal strength from the front-left light sensor.
bool isLightBumperCenterRight() const
float getRequestedLeftWheelVel() const
Get the requested velocity of the left wheel. This value is bounded at the maximum velocity of the ro...
unsigned long long timestamp_t
bool setDate(const create::DayOfWeek &day, const uint8_t &hour, const uint8_t &min) const
Sets the internal clock of Create.
float getRightWheelDistance() const
Get the total distance the right wheel has moved.
create::Pose getPose() const
Get the estimated pose of Create based on wheel encoders.
boost::shared_ptr< create::Serial > serial
uint8_t getDirtDetect() const
Get level of the dirt detect sensor.
float getRequestedRightWheelVel() const
Get the requested velocity of the right wheel. This value is bounded at the maximum velocity of the r...
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.
bool isLightBumperFrontRight() const
float getBatteryCharge() const
Get battery's remaining charge.
uint8_t getIRRight() const
Get value of 8-bit IR character currently being received by right sensor.
float getCurrent() const
Get current flowing in/out of battery. A positive current implies Create is charging.
bool driveWheelsPwm(const float &leftWheel, const float &rightWheel)
Set the direct for the left and right wheels.
bool isVirtualWall() const
bool setDigits(const std::vector< bool > &segments) const
Set the four 7-segment display digits from left to right.
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 connected() const
Check if serial connection is active.
bool isMovingForward() const
Matrix addMatrices(const Matrix &A, const Matrix &B) const
create::Vel getVel() const
Get the estimated velocity of Create based on wheel encoders.
uint64_t getNumCorruptPackets() const
Get the number of corrupt serial packets since first connecting to Create. This value is ideally zero...
uint16_t getLightSignalCenterLeft() const
Get the signal strength from the center-left light sensor.
bool isLightBumperLeft() const
bool clean(const create::CleanMode &mode=CLEAN_DEFAULT)
Starts a cleaning mode. Changes mode to MODE_PASSIVE.
bool isScheduleButtonPressed() const
Not supported by any firmware!
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.
bool isMinButtonPressed() const
Get state of 'min' button.
bool isCleanButtonPressed() const
Get state of 'clean' button ('play' button on Create 1).
bool drive(const float &xVel, const float &angularVel)
Set the forward and angular velocity of Create.
bool isDockButtonPressed() const
Get state of 'dock' button ('advance' button on Create 1).
boost::shared_ptr< create::Data > data
float getMeasuredLeftWheelVel() const
Get the measured velocity of the left wheel.
boost::numeric::ublas::matrix< float > Matrix
bool enableDebrisLED(const bool &enable)
Set the blue "debris" LED on/off.
float getVoltage() const
Get battery voltage.
uint16_t getLightSignalLeft() const
Get the signal strength from the left light sensor.
bool isMainBrushOvercurrent() const
bool isRightBumper() const
bool isDayButtonPressed() const
Get state of 'day' button.
uint16_t getLightSignalCenterRight() const
Get the signal strength from the center-right light sensor.
bool isSpotButtonPressed() const
Get state of 'spot' button.
Create(RobotModel model=RobotModel::CREATE_2)
Default constructor.
uint16_t getLightSignalRight() const
Get the signal strength from the right light sensor.
bool isSideBrushOvercurrent() const
float getBatteryCapacity() const
Get estimated battery charge capacity.
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.
uint8_t getIRLeft() const
Get value of 8-bit IR character currently being received by left sensor.
util::timestamp_t prevOnDataTime
bool setAllMotors(const float &mainPower, const float &sidePower, const float &vacuumPower)
Set the power of all motors.
void disconnect()
Disconnect from serial.
float getLeftWheelDistance() const
Get the total distance the left wheel has moved.
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.
bool isLightBumperRight() const
bool isLightBumperCenterLeft() const
uint16_t getLightSignalFrontRight() const
Get the signal strength from the front-right light sensor.
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.