create.h
Go to the documentation of this file.
1 
32 #ifndef CREATE_H
33 #define CREATE_H
34 
35 #include <boost/numeric/ublas/matrix.hpp>
36 #include <chrono>
37 #include <memory>
38 #include <string>
39 #include <unistd.h>
40 #include <deque>
41 
42 #include "create/serial_stream.h"
43 #include "create/serial_query.h"
44 #include "create/data.h"
45 #include "create/types.h"
46 #include "create/util.h"
47 
48 namespace create {
49  class Create {
50  private:
51  typedef boost::numeric::ublas::matrix<float> Matrix;
52 
53  enum CreateLED {
55  LED_SPOT = 2,
56  LED_DOCK = 4,
58  };
59 
61 
62  uint8_t mainMotorPower;
63  uint8_t sideMotorPower;
65 
66  // LEDs
67  uint8_t debrisLED;
68  uint8_t spotLED;
69  uint8_t dockLED;
70  uint8_t checkLED;
71  uint8_t powerLED;
73 
75 
78 
79  uint32_t prevTicksLeft;
80  uint32_t prevTicksRight;
84  std::chrono::time_point<std::chrono::steady_clock> prevOnDataTime;
85  std::deque<float> dtHistory;
86  uint8_t dtHistoryLength;
87 
88  Matrix poseCovar;
89 
94 
95  void init(bool install_signal_handler);
96  // Add two matrices and handle overflow case
97  Matrix addMatrices(const Matrix &A, const Matrix &B) const;
98  void onData();
99  bool updateLEDs();
100 
101  protected:
102  std::shared_ptr<create::Data> data;
103  std::shared_ptr<create::Serial> serial;
104 
105  public:
115  Create(RobotModel model = RobotModel::CREATE_2, bool install_signal_handler = true);
116 
127  Create(const std::string& port, const int& baud, RobotModel model = RobotModel::CREATE_2, bool install_signal_handler = true);
128 
132  ~Create();
133 
141  bool connect(const std::string& port, const int& baud);
142 
148  inline bool connected() const { return serial->connected(); };
149 
153  void disconnect();
154 
160  bool setMode(const create::CreateMode& mode);
161 
167  bool clean(const create::CleanMode& mode = CLEAN_DEFAULT);
168 
174  bool dock() const;
175 
183  bool setDate(const create::DayOfWeek& day, const uint8_t& hour, const uint8_t& min) const;
184 
194  bool driveRadius(const float& velocity, const float& radius);
195 
202  bool driveWheels(const float& leftWheel, const float& rightWheel);
203 
210  bool driveWheelsPwm(const float& leftWheel, const float& rightWheel);
211 
218  bool drive(const float& xVel, const float& angularVel);
219 
225  bool setSideMotor(const float& power);
226 
232  bool setMainMotor(const float& power);
233 
239  bool setVacuumMotor(const float& power);
240 
248  bool setAllMotors(const float& mainPower, const float& sidePower, const float& vacuumPower);
249 
255  bool enableDebrisLED(const bool& enable);
256 
262  bool enableSpotLED(const bool& enable);
263 
269  bool enableDockLED(const bool& enable);
270 
276  bool enableCheckRobotLED(const bool& enable);
277 
284  bool setPowerLED(const uint8_t& power, const uint8_t& intensity = 255);
285 
305  bool setDigits(const std::vector<bool>& segments) const;
306 
316  bool setDigitsASCII(const uint8_t& digit1, const uint8_t& digit2,
317  const uint8_t& digit3, const uint8_t& digit4) const;
318 
329  bool defineSong(const uint8_t& songNumber,
330  const uint8_t& songLength,
331  const uint8_t* notes,
332  const float* durations) const;
333 
340  bool playSong(const uint8_t& songNumber) const;
341 
348  void setDtHistoryLength(const uint8_t& dtHistoryLength);
349 
353  bool isWheeldrop() const;
354 
358  bool isLeftWheeldrop() const;
359 
363  bool isRightWheeldrop() const;
364 
368  bool isLeftBumper() const;
369 
373  bool isRightBumper() const;
374 
378  bool isWall() const;
379 
383  bool isCliff() const;
384 
388  bool isCliffLeft() const;
389 
393  bool isCliffFrontLeft() const;
394 
398  bool isCliffRight() const;
399 
403  bool isCliffFrontRight() const;
404 
408  bool isVirtualWall() const;
409 
414  bool isWheelOvercurrent() const;
415 
420  bool isMainBrushOvercurrent() const;
421 
426  bool isSideBrushOvercurrent() const;
427 
432  uint8_t getDirtDetect() const;
433 
438  uint8_t getIROmni() const;
439 
445  uint8_t getIRLeft() const;
446 
451  uint8_t getIRRight() const;
452 
457  bool isCleanButtonPressed() const;
458 
462  bool isClockButtonPressed() const;
463 
467  bool isScheduleButtonPressed() const;
468 
473  bool isDayButtonPressed() const;
474 
479  bool isHourButtonPressed() const;
480 
485  bool isMinButtonPressed() const;
486 
491  bool isDockButtonPressed() const;
492 
497  bool isSpotButtonPressed() const;
498 
503  float getVoltage() const;
504 
510  float getCurrent() const;
511 
516  int8_t getTemperature() const;
517 
522  float getBatteryCharge() const;
523 
528  float getBatteryCapacity() const;
529 
533  bool isLightBumperLeft() const;
534 
538  bool isLightBumperFrontLeft() const;
539 
543  bool isLightBumperCenterLeft() const;
544 
548  bool isLightBumperRight() const;
549 
553  bool isLightBumperFrontRight() const;
554 
558  bool isLightBumperCenterRight() const;
559 
564  uint16_t getLightSignalLeft() const;
565 
570  uint16_t getLightSignalFrontLeft() const;
571 
576  uint16_t getLightSignalCenterLeft() const;
577 
582  uint16_t getLightSignalRight() const;
583 
588  uint16_t getLightSignalFrontRight() const;
589 
594  uint16_t getLightSignalCenterRight() const;
595 
599  bool isMovingForward() const;
600 
605  float getLeftWheelDistance() const;
606 
611  float getRightWheelDistance() const;
612 
617  float getMeasuredLeftWheelVel() const;
618 
623  float getMeasuredRightWheelVel() const;
624 
630  float getRequestedLeftWheelVel() const;
631 
637  float getRequestedRightWheelVel() const;
638 
644 
650 
655  create::Pose getPose() const;
656 
661  create::Vel getVel() const;
662 
669  uint64_t getNumCorruptPackets() const;
670 
675  uint64_t getTotalPackets() const;
676  }; // end Create class
677 
678 } // namespace create
679 #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:1139
ChargingState
Definition: types.h:216
bool setSideMotor(const float &power)
Set the power to the side brush motor.
Definition: create.cpp:511
uint8_t getIROmni() const
Get value of 8-bit IR character currently being received by omnidirectional sensor.
Definition: create.cpp:760
float totalLeftDist
Definition: create.h:81
create::Vel vel
Definition: create.h:77
uint8_t dockLED
Definition: create.h:69
uint8_t powerLEDIntensity
Definition: create.h:72
bool isLeftWheeldrop() const
Definition: create.cpp:634
float totalRightDist
Definition: create.h:82
float getMeasuredRightWheelVel() const
Get the measured velocity of the right wheel.
Definition: create.cpp:1108
bool setVacuumMotor(const float &power)
Set the power to the vacuum motor.
Definition: create.cpp:515
bool isWheeldrop() const
Definition: create.cpp:624
bool isWheelOvercurrent() const
Definition: create.cpp:1086
bool firstOnData
Definition: create.h:83
bool isLightBumperFrontLeft() const
Definition: create.cpp:946
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:572
float requestedRightVel
Definition: create.h:93
bool isCliffRight() const
Definition: create.cpp:720
bool isLeftBumper() const
Definition: create.cpp:654
create::ChargingState getChargingState() const
Get the current charging state.
Definition: create.cpp:790
bool driveWheels(const float &leftWheel, const float &rightWheel)
Set the velocities for the left and right wheels.
Definition: create.cpp:403
bool dock() const
Starts the docking behaviour. Changes mode to MODE_PASSIVE.
Definition: create.cpp:365
uint32_t prevTicksRight
Definition: create.h:80
create::Pose pose
Definition: create.h:76
int8_t getTemperature() const
Get the temperature of battery.
Definition: create.cpp:906
bool isHourButtonPressed() const
Get state of &#39;hour&#39; button.
Definition: create.cpp:846
uint8_t dtHistoryLength
Definition: create.h:86
bool isClockButtonPressed() const
Not supported by any firmware!
Definition: create.cpp:813
uint16_t getLightSignalFrontLeft() const
Get the signal strength from the front-left light sensor.
Definition: create.cpp:1006
bool isLightBumperCenterRight() const
Definition: create.cpp:966
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:1112
uint8_t spotLED
Definition: create.h:68
void setDtHistoryLength(const uint8_t &dtHistoryLength)
Set dtHistoryLength parameter. Used to configure the size of the buffer for calculating average time ...
Definition: create.cpp:620
bool setDate(const create::DayOfWeek &day, const uint8_t &hour, const uint8_t &min) const
Sets the internal clock of Create.
Definition: create.cpp:369
float getRightWheelDistance() const
Get the total distance the right wheel has moved.
Definition: create.cpp:1100
create::Pose getPose() const
Get the estimated pose of Create based on wheel encoders.
Definition: create.cpp:1127
Definition: create.h:48
uint8_t getDirtDetect() const
Get level of the dirt detect sensor.
Definition: create.cpp:750
uint8_t powerLED
Definition: create.h:71
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:1116
bool enableDockLED(const bool &enable)
Set the green "dock" LED on/off.
Definition: create.cpp:546
bool setPowerLED(const uint8_t &power, const uint8_t &intensity=255)
Set the center power LED.
Definition: create.cpp:562
bool isLightBumperFrontRight() const
Definition: create.cpp:976
float getBatteryCharge() const
Get battery&#39;s remaining charge.
Definition: create.cpp:916
uint8_t getIRRight() const
Get value of 8-bit IR character currently being received by right sensor.
Definition: create.cpp:780
void init(bool install_signal_handler)
Definition: create.cpp:17
float getCurrent() const
Get current flowing in/out of battery. A positive current implies Create is charging.
Definition: create.cpp:896
bool driveWheelsPwm(const float &leftWheel, const float &rightWheel)
Set the direct for the left and right wheels.
Definition: create.cpp:451
CreateMode mode
Definition: create.h:74
std::shared_ptr< create::Data > data
Definition: create.h:102
Represents a robot pose.
Definition: types.h:275
bool isVirtualWall() const
Definition: create.cpp:740
bool isCliffFrontRight() const
Definition: create.cpp:730
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:613
bool connected() const
Check if serial connection is active.
Definition: create.h:148
bool isMovingForward() const
Definition: create.cpp:1056
Matrix addMatrices(const Matrix &A, const Matrix &B) const
Definition: create.cpp:69
float measuredRightVel
Definition: create.h:91
create::Vel getVel() const
Get the estimated velocity of Create based on wheel encoders.
Definition: create.cpp:1131
uint64_t getNumCorruptPackets() const
Get the number of corrupt serial packets since first connecting to Create. This value is ideally zero...
Definition: create.cpp:1135
uint16_t getLightSignalCenterLeft() const
Get the signal strength from the center-left light sensor.
Definition: create.cpp:1016
uint8_t sideMotorPower
Definition: create.h:63
std::shared_ptr< create::Serial > serial
Definition: create.h:103
bool isLightBumperLeft() const
Definition: create.cpp:936
bool clean(const create::CleanMode &mode=CLEAN_DEFAULT)
Starts a cleaning mode. Changes mode to MODE_PASSIVE.
Definition: create.cpp:361
uint8_t checkLED
Definition: create.h:70
Create(RobotModel model=RobotModel::CREATE_2, bool install_signal_handler=true)
Default constructor.
Definition: create.cpp:54
bool isScheduleButtonPressed() const
Not supported by any firmware!
Definition: create.cpp:825
bool enableCheckRobotLED(const bool &enable)
Set the orange "check Create" LED on/off.
Definition: create.cpp:554
bool driveRadius(const float &velocity, const float &radius)
Set the average wheel velocity and turning radius of Create.
Definition: create.cpp:379
bool enableSpotLED(const bool &enable)
Set the green "spot" LED on/off.
Definition: create.cpp:538
bool setMainMotor(const float &power)
Set the power to the main brush motor.
Definition: create.cpp:507
bool isMinButtonPressed() const
Get state of &#39;min&#39; button.
Definition: create.cpp:856
bool isCleanButtonPressed() const
Get state of &#39;clean&#39; button (&#39;play&#39; button on Create 1).
Definition: create.cpp:802
bool drive(const float &xVel, const float &angularVel)
Set the forward and angular velocity of Create.
Definition: create.cpp:472
bool isDockButtonPressed() const
Get state of &#39;dock&#39; button (&#39;advance&#39; button on Create 1).
Definition: create.cpp:866
float getMeasuredLeftWheelVel() const
Get the measured velocity of the left wheel.
Definition: create.cpp:1104
boost::numeric::ublas::matrix< float > Matrix
Definition: create.h:51
bool enableDebrisLED(const bool &enable)
Set the blue "debris" LED on/off.
Definition: create.cpp:530
float getVoltage() const
Get battery voltage.
Definition: create.cpp:886
uint16_t getLightSignalLeft() const
Get the signal strength from the left light sensor.
Definition: create.cpp:996
uint8_t vacuumMotorPower
Definition: create.h:64
bool isMainBrushOvercurrent() const
Definition: create.cpp:1076
bool updateLEDs()
Definition: create.cpp:519
bool isRightWheeldrop() const
Definition: create.cpp:644
bool isRightBumper() const
Definition: create.cpp:664
bool isDayButtonPressed() const
Get state of &#39;day&#39; button.
Definition: create.cpp:836
bool isWall() const
Definition: create.cpp:674
RobotModel model
Definition: create.h:60
std::chrono::time_point< std::chrono::steady_clock > prevOnDataTime
Definition: create.h:84
uint16_t getLightSignalCenterRight() const
Get the signal strength from the center-right light sensor.
Definition: create.cpp:1046
bool isSpotButtonPressed() const
Get state of &#39;spot&#39; button.
Definition: create.cpp:876
uint32_t prevTicksLeft
Definition: create.h:79
CleanMode
Definition: types.h:210
uint8_t debrisLED
Definition: create.h:67
bool isCliffFrontLeft() const
Definition: create.cpp:710
float measuredLeftVel
Definition: create.h:90
uint16_t getLightSignalRight() const
Get the signal strength from the right light sensor.
Definition: create.cpp:1026
bool isSideBrushOvercurrent() const
Definition: create.cpp:1066
float getBatteryCapacity() const
Get estimated battery charge capacity.
Definition: create.cpp:926
bool isCliffLeft() const
Definition: create.cpp:700
float requestedLeftVel
Definition: create.h:92
bool connect(const std::string &port, const int &baud)
Make a serial connection to Create.
Definition: create.cpp:293
uint8_t mainMotorPower
Definition: create.h:62
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:770
bool isCliff() const
Definition: create.cpp:684
bool setAllMotors(const float &mainPower, const float &sidePower, const float &vacuumPower)
Set the power of all motors.
Definition: create.cpp:479
Matrix poseCovar
Definition: create.h:88
void disconnect()
Disconnect from serial.
Definition: create.cpp:314
void onData()
Definition: create.cpp:93
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:1096
bool setMode(const create::CreateMode &mode)
Change Create mode.
Definition: create.cpp:325
create::CreateMode getMode()
Get the current mode reported by Create.
Definition: create.cpp:1120
~Create()
Attempts to disconnect from serial.
Definition: create.cpp:65
std::deque< float > dtHistory
Definition: create.h:85
bool isLightBumperRight() const
Definition: create.cpp:986
bool isLightBumperCenterLeft() const
Definition: create.cpp:956
uint16_t getLightSignalFrontRight() const
Get the signal strength from the front-right light sensor.
Definition: create.cpp:1036
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:590


libcreate
Author(s): Jacob Perron
autogenerated on Sat May 8 2021 03:02:37