create.h
Go to the documentation of this file.
1 
32 #ifndef CREATE_H
33 #define CREATE_H
34 
35 #include <boost/shared_ptr.hpp>
36 #include <boost/numeric/ublas/matrix.hpp>
37 #include <string>
38 #include <unistd.h>
39 
40 #include "create/serial_stream.h"
41 #include "create/serial_query.h"
42 #include "create/data.h"
43 #include "create/types.h"
44 #include "create/util.h"
45 
46 namespace create {
47  class Create {
48  private:
49  typedef boost::numeric::ublas::matrix<float> Matrix;
50 
51  enum CreateLED {
53  LED_SPOT = 2,
54  LED_DOCK = 4,
56  };
57 
59 
60  uint8_t mainMotorPower;
61  uint8_t sideMotorPower;
63 
64  // LEDs
65  uint8_t debrisLED;
66  uint8_t spotLED;
67  uint8_t dockLED;
68  uint8_t checkLED;
69  uint8_t powerLED;
71 
73 
76 
77  uint32_t prevTicksLeft;
78  uint32_t prevTicksRight;
83 
84  Matrix poseCovar;
85 
90 
91  void init();
92  // Add two matrices and handle overflow case
93  Matrix addMatrices(const Matrix &A, const Matrix &B) const;
94  void onData();
95  bool updateLEDs();
96 
97  protected:
98  boost::shared_ptr<create::Data> data;
99  boost::shared_ptr<create::Serial> serial;
100 
101  public:
110 
119  Create(const std::string& port, const int& baud, RobotModel model = RobotModel::CREATE_2);
120 
124  ~Create();
125 
133  bool connect(const std::string& port, const int& baud);
134 
140  inline bool connected() const { return serial->connected(); };
141 
145  void disconnect();
146 
152  bool setMode(const create::CreateMode& mode);
153 
159  bool clean(const create::CleanMode& mode = CLEAN_DEFAULT);
160 
166  bool dock() const;
167 
175  bool setDate(const create::DayOfWeek& day, const uint8_t& hour, const uint8_t& min) const;
176 
186  bool driveRadius(const float& velocity, const float& radius);
187 
194  bool driveWheels(const float& leftWheel, const float& rightWheel);
195 
202  bool driveWheelsPwm(const float& leftWheel, const float& rightWheel);
203 
210  bool drive(const float& xVel, const float& angularVel);
211 
217  bool setSideMotor(const float& power);
218 
224  bool setMainMotor(const float& power);
225 
231  bool setVacuumMotor(const float& power);
232 
240  bool setAllMotors(const float& mainPower, const float& sidePower, const float& vacuumPower);
241 
247  bool enableDebrisLED(const bool& enable);
248 
254  bool enableSpotLED(const bool& enable);
255 
261  bool enableDockLED(const bool& enable);
262 
268  bool enableCheckRobotLED(const bool& enable);
269 
276  bool setPowerLED(const uint8_t& power, const uint8_t& intensity = 255);
277 
297  bool setDigits(const std::vector<bool>& segments) const;
298 
308  bool setDigitsASCII(const uint8_t& digit1, const uint8_t& digit2,
309  const uint8_t& digit3, const uint8_t& digit4) const;
310 
321  bool defineSong(const uint8_t& songNumber,
322  const uint8_t& songLength,
323  const uint8_t* notes,
324  const float* durations) const;
325 
332  bool playSong(const uint8_t& songNumber) const;
333 
337  bool isWheeldrop() const;
338 
342  bool isLeftBumper() const;
343 
347  bool isRightBumper() const;
348 
352  bool isWall() const;
353 
357  bool isCliff() const;
358 
362  bool isVirtualWall() const;
363 
368  bool isWheelOvercurrent() const;
369 
374  bool isMainBrushOvercurrent() const;
375 
380  bool isSideBrushOvercurrent() const;
381 
386  uint8_t getDirtDetect() const;
387 
392  uint8_t getIROmni() const;
393 
399  uint8_t getIRLeft() const;
400 
405  uint8_t getIRRight() const;
406 
411  bool isCleanButtonPressed() const;
412 
416  bool isClockButtonPressed() const;
417 
421  bool isScheduleButtonPressed() const;
422 
427  bool isDayButtonPressed() const;
428 
433  bool isHourButtonPressed() const;
434 
439  bool isMinButtonPressed() const;
440 
445  bool isDockButtonPressed() const;
446 
451  bool isSpotButtonPressed() const;
452 
457  float getVoltage() const;
458 
464  float getCurrent() const;
465 
470  int8_t getTemperature() const;
471 
476  float getBatteryCharge() const;
477 
482  float getBatteryCapacity() const;
483 
487  bool isLightBumperLeft() const;
488 
492  bool isLightBumperFrontLeft() const;
493 
497  bool isLightBumperCenterLeft() const;
498 
502  bool isLightBumperRight() const;
503 
507  bool isLightBumperFrontRight() const;
508 
512  bool isLightBumperCenterRight() const;
513 
518  uint16_t getLightSignalLeft() const;
519 
524  uint16_t getLightSignalFrontLeft() const;
525 
530  uint16_t getLightSignalCenterLeft() const;
531 
536  uint16_t getLightSignalRight() const;
537 
542  uint16_t getLightSignalFrontRight() const;
543 
548  uint16_t getLightSignalCenterRight() const;
549 
553  bool isMovingForward() const;
554 
559  float getLeftWheelDistance() const;
560 
565  float getRightWheelDistance() const;
566 
571  float getMeasuredLeftWheelVel() const;
572 
577  float getMeasuredRightWheelVel() const;
578 
584  float getRequestedLeftWheelVel() const;
585 
591  float getRequestedRightWheelVel() const;
592 
598 
604 
609  create::Pose getPose() const;
610 
615  create::Vel getVel() const;
616 
623  uint64_t getNumCorruptPackets() const;
624 
629  uint64_t getTotalPackets() const;
630  }; // end Create class
631 
632 } // namespace create
633 #endif // CREATE_DRIVER_H
uint64_t getTotalPackets() const
Get the total number of serial packets received (including corrupt packets) since first connecting to...
Definition: create.cpp:1016
ChargingState
Definition: types.h:216
bool setSideMotor(const float &power)
Set the power to the side brush motor.
Definition: create.cpp:481
void init()
Definition: create.cpp:20
uint8_t getIROmni() const
Get value of 8-bit IR character currently being received by omnidirectional sensor.
Definition: create.cpp:666
float totalLeftDist
Definition: create.h:79
create::Vel vel
Definition: create.h:75
uint8_t dockLED
Definition: create.h:67
uint8_t powerLEDIntensity
Definition: create.h:70
float totalRightDist
Definition: create.h:80
float getMeasuredRightWheelVel() const
Get the measured velocity of the right wheel.
Definition: create.cpp:985
bool setVacuumMotor(const float &power)
Set the power to the vacuum motor.
Definition: create.cpp:485
bool isWheeldrop() const
Definition: create.cpp:590
bool isWheelOvercurrent() const
bool firstOnData
Definition: create.h:81
bool isLightBumperFrontLeft() const
Definition: create.cpp:853
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...
Definition: create.cpp:542
float requestedRightVel
Definition: create.h:89
bool isLeftBumper() const
Definition: create.cpp:600
create::ChargingState getChargingState() const
Get the current charging state.
Definition: create.cpp:696
bool driveWheels(const float &leftWheel, const float &rightWheel)
Set the velocities for the left and right wheels.
Definition: create.cpp:382
bool dock() const
Starts the docking behaviour. Changes mode to MODE_PASSIVE.
Definition: create.cpp:344
uint32_t prevTicksRight
Definition: create.h:78
create::Pose pose
Definition: create.h:74
int8_t getTemperature() const
Get the temperature of battery.
Definition: create.cpp:813
bool isHourButtonPressed() const
Get state of &#39;hour&#39; button.
Definition: create.cpp:753
bool isClockButtonPressed() const
Not supported by any firmware!
Definition: create.cpp:720
uint16_t getLightSignalFrontLeft() const
Get the signal strength from the front-left light sensor.
Definition: create.cpp:913
bool isLightBumperCenterRight() const
Definition: create.cpp:873
float getRequestedLeftWheelVel() const
Get the requested velocity of the left wheel. This value is bounded at the maximum velocity of the ro...
Definition: create.cpp:989
uint8_t spotLED
Definition: create.h:66
unsigned long long timestamp_t
Definition: util.h:58
bool setDate(const create::DayOfWeek &day, const uint8_t &hour, const uint8_t &min) const
Sets the internal clock of Create.
Definition: create.cpp:348
float getRightWheelDistance() const
Get the total distance the right wheel has moved.
Definition: create.cpp:977
create::Pose getPose() const
Get the estimated pose of Create based on wheel encoders.
Definition: create.cpp:1004
boost::shared_ptr< create::Serial > serial
Definition: create.h:99
Definition: create.h:46
uint8_t getDirtDetect() const
Get level of the dirt detect sensor.
Definition: create.cpp:656
uint8_t powerLED
Definition: create.h:69
float getRequestedRightWheelVel() const
Get the requested velocity of the right wheel. This value is bounded at the maximum velocity of the r...
Definition: create.cpp:993
bool enableDockLED(const bool &enable)
Set the green "dock" LED on/off.
Definition: create.cpp:516
bool setPowerLED(const uint8_t &power, const uint8_t &intensity=255)
Set the center power LED.
Definition: create.cpp:532
bool isLightBumperFrontRight() const
Definition: create.cpp:883
float getBatteryCharge() const
Get battery&#39;s remaining charge.
Definition: create.cpp:823
uint8_t getIRRight() const
Get value of 8-bit IR character currently being received by right sensor.
Definition: create.cpp:686
float getCurrent() const
Get current flowing in/out of battery. A positive current implies Create is charging.
Definition: create.cpp:803
bool driveWheelsPwm(const float &leftWheel, const float &rightWheel)
Set the direct for the left and right wheels.
Definition: create.cpp:430
CreateMode mode
Definition: create.h:72
Represents a robot pose.
Definition: types.h:275
bool isVirtualWall() const
Definition: create.cpp:646
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...
Definition: create.cpp:583
bool connected() const
Check if serial connection is active.
Definition: create.h:140
bool isMovingForward() const
Definition: create.cpp:963
Matrix addMatrices(const Matrix &A, const Matrix &B) const
Definition: create.cpp:68
float measuredRightVel
Definition: create.h:87
create::Vel getVel() const
Get the estimated velocity of Create based on wheel encoders.
Definition: create.cpp:1008
uint64_t getNumCorruptPackets() const
Get the number of corrupt serial packets since first connecting to Create. This value is ideally zero...
Definition: create.cpp:1012
uint16_t getLightSignalCenterLeft() const
Get the signal strength from the center-left light sensor.
Definition: create.cpp:923
uint8_t sideMotorPower
Definition: create.h:61
bool isLightBumperLeft() const
Definition: create.cpp:843
bool clean(const create::CleanMode &mode=CLEAN_DEFAULT)
Starts a cleaning mode. Changes mode to MODE_PASSIVE.
Definition: create.cpp:340
uint8_t checkLED
Definition: create.h:68
bool isScheduleButtonPressed() const
Not supported by any firmware!
Definition: create.cpp:732
bool enableCheckRobotLED(const bool &enable)
Set the orange "check Create" LED on/off.
Definition: create.cpp:524
bool driveRadius(const float &velocity, const float &radius)
Set the average wheel velocity and turning radius of Create.
Definition: create.cpp:358
bool enableSpotLED(const bool &enable)
Set the green "spot" LED on/off.
Definition: create.cpp:508
bool setMainMotor(const float &power)
Set the power to the main brush motor.
Definition: create.cpp:477
bool isMinButtonPressed() const
Get state of &#39;min&#39; button.
Definition: create.cpp:763
bool isCleanButtonPressed() const
Get state of &#39;clean&#39; button (&#39;play&#39; button on Create 1).
Definition: create.cpp:709
bool drive(const float &xVel, const float &angularVel)
Set the forward and angular velocity of Create.
Definition: create.cpp:451
bool isDockButtonPressed() const
Get state of &#39;dock&#39; button (&#39;advance&#39; button on Create 1).
Definition: create.cpp:773
boost::shared_ptr< create::Data > data
Definition: create.h:98
float getMeasuredLeftWheelVel() const
Get the measured velocity of the left wheel.
Definition: create.cpp:981
boost::numeric::ublas::matrix< float > Matrix
Definition: create.h:49
bool enableDebrisLED(const bool &enable)
Set the blue "debris" LED on/off.
Definition: create.cpp:500
float getVoltage() const
Get battery voltage.
Definition: create.cpp:793
uint16_t getLightSignalLeft() const
Get the signal strength from the left light sensor.
Definition: create.cpp:903
uint8_t vacuumMotorPower
Definition: create.h:62
bool isMainBrushOvercurrent() const
bool updateLEDs()
Definition: create.cpp:489
bool isRightBumper() const
Definition: create.cpp:610
bool isDayButtonPressed() const
Get state of &#39;day&#39; button.
Definition: create.cpp:743
bool isWall() const
Definition: create.cpp:620
RobotModel model
Definition: create.h:58
uint16_t getLightSignalCenterRight() const
Get the signal strength from the center-right light sensor.
Definition: create.cpp:953
bool isSpotButtonPressed() const
Get state of &#39;spot&#39; button.
Definition: create.cpp:783
uint32_t prevTicksLeft
Definition: create.h:77
CleanMode
Definition: types.h:210
uint8_t debrisLED
Definition: create.h:65
float measuredLeftVel
Definition: create.h:86
Create(RobotModel model=RobotModel::CREATE_2)
Default constructor.
Definition: create.cpp:55
uint16_t getLightSignalRight() const
Get the signal strength from the right light sensor.
Definition: create.cpp:933
bool isSideBrushOvercurrent() const
float getBatteryCapacity() const
Get estimated battery charge capacity.
Definition: create.cpp:833
float requestedLeftVel
Definition: create.h:88
bool connect(const std::string &port, const int &baud)
Make a serial connection to Create.
Definition: create.cpp:272
uint8_t mainMotorPower
Definition: create.h:60
static RobotModel CREATE_2
Compatible with Create 2 or Roomba 600 series and greater.
Definition: types.h:73
uint8_t getIRLeft() const
Get value of 8-bit IR character currently being received by left sensor.
Definition: create.cpp:676
util::timestamp_t prevOnDataTime
Definition: create.h:82
bool isCliff() const
Definition: create.cpp:630
bool setAllMotors(const float &mainPower, const float &sidePower, const float &vacuumPower)
Set the power of all motors.
Definition: create.cpp:458
Matrix poseCovar
Definition: create.h:84
void disconnect()
Disconnect from serial.
Definition: create.cpp:293
void onData()
Definition: create.cpp:92
CreateMode
Definition: types.h:202
DayOfWeek
Definition: types.h:225
float getLeftWheelDistance() const
Get the total distance the left wheel has moved.
Definition: create.cpp:973
bool setMode(const create::CreateMode &mode)
Change Create mode.
Definition: create.cpp:304
create::CreateMode getMode()
Get the current mode reported by Create.
Definition: create.cpp:997
~Create()
Attempts to disconnect from serial.
Definition: create.cpp:64
bool isLightBumperRight() const
Definition: create.cpp:893
bool isLightBumperCenterLeft() const
Definition: create.cpp:863
uint16_t getLightSignalFrontRight() const
Get the signal strength from the front-right light sensor.
Definition: create.cpp:943
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.
Definition: create.cpp:560


libcreate
Author(s): Jacob Perron
autogenerated on Sat Jun 8 2019 17:58:17