Program Listing for File create.h

Return to documentation for file (/tmp/ws/src/libcreate/include/create/create.h)

#ifndef CREATE_H
#define CREATE_H

#include <boost/numeric/ublas/matrix.hpp>
#include <chrono>
#include <memory>
#include <string>
#include <unistd.h>
#include <deque>

#include "create/serial_stream.h"
#include "create/serial_query.h"
#include "create/data.h"
#include "create/types.h"
#include "create/util.h"

namespace create {
  class Create {
    private:
      typedef boost::numeric::ublas::matrix<float> Matrix;

      enum CreateLED {
        LED_DEBRIS = 1,
        LED_SPOT = 2,
        LED_DOCK = 4,
        LED_CHECK = 8
      };

      RobotModel model;

      uint8_t mainMotorPower;
      uint8_t sideMotorPower;
      uint8_t vacuumMotorPower;

      // LEDs
      uint8_t debrisLED;
      uint8_t spotLED;
      uint8_t dockLED;
      uint8_t checkLED;
      uint8_t powerLED;
      uint8_t powerLEDIntensity;

      CreateMode mode;

      create::Pose pose;
      create::Vel vel;

      uint32_t prevTicksLeft;
      uint32_t prevTicksRight;
      float totalLeftDist;
      float totalRightDist;
      bool firstOnData;
      std::chrono::time_point<std::chrono::steady_clock> prevOnDataTime;
      std::deque<float> dtHistory;
      uint8_t dtHistoryLength;

      Matrix poseCovar;

      float measuredLeftVel;
      float measuredRightVel;
      float requestedLeftVel;
      float requestedRightVel;

      void init(bool install_signal_handler);
      // Add two matrices and handle overflow case
      Matrix addMatrices(const Matrix &A, const Matrix &B) const;
      void onData();
      bool updateLEDs();

      // Flag to enable/disable the workaround for some 6xx incorrectly reporting OI mode
      // https://github.com/AutonomyLab/create_robot/issues/64
      bool modeReportWorkaround;

    protected:
      std::shared_ptr<create::Data> data;
      std::shared_ptr<create::Serial> serial;

    public:
      Create(RobotModel model = RobotModel::CREATE_2, bool install_signal_handler = true);

      Create(const std::string& port, const int& baud, RobotModel model = RobotModel::CREATE_2, bool install_signal_handler = true);

      ~Create();

      bool connect(const std::string& port, const int& baud);

      inline bool connected() const { return serial->connected(); };

      void disconnect();

      bool setMode(const create::CreateMode& mode);

      bool clean(const create::CleanMode& mode = CLEAN_DEFAULT);

      bool dock() const;

      bool setDate(const create::DayOfWeek& day, const uint8_t& hour, const uint8_t& min) const;

      bool driveRadius(const float& velocity, const float& radius);

      bool driveWheels(const float& leftWheel, const float& rightWheel);

      bool driveWheelsPwm(const float& leftWheel, const float& rightWheel);

      bool drive(const float& xVel, const float& angularVel);

      bool setSideMotor(const float& power);

      bool setMainMotor(const float& power);

      bool setVacuumMotor(const float& power);

      bool setAllMotors(const float& mainPower, const float& sidePower, const float& vacuumPower);

      bool enableDebrisLED(const bool& enable);

      bool enableSpotLED(const bool& enable);

      bool enableDockLED(const bool& enable);

      bool enableCheckRobotLED(const bool& enable);

      bool setPowerLED(const uint8_t& power, const uint8_t& intensity = 255);

      bool setDigits(const std::vector<bool>& segments) const;

      bool setDigitsASCII(const uint8_t& digit1, const uint8_t& digit2,
                          const uint8_t& digit3, const uint8_t& digit4) const;

      bool defineSong(const uint8_t& songNumber,
                      const uint8_t& songLength,
                      const uint8_t* notes,
                      const float* durations) const;

      bool playSong(const uint8_t& songNumber) const;

      void setDtHistoryLength(const uint8_t& dtHistoryLength);

      bool isWheeldrop() const;

      bool isLeftWheeldrop() const;

      bool isRightWheeldrop() const;

      bool isLeftBumper() const;

      bool isRightBumper() const;

      bool isWall() const;

      bool isCliff() const;

      bool isCliffLeft() const;

      bool isCliffFrontLeft() const;

      bool isCliffRight() const;

      bool isCliffFrontRight() const;

      bool isVirtualWall() const;

      bool isWheelOvercurrent() const;

      bool isMainBrushOvercurrent() const;

      bool isSideBrushOvercurrent() const;

      uint8_t getDirtDetect() const;

      uint8_t getIROmni() const;

      uint8_t getIRLeft() const;

      uint8_t getIRRight() const;

      bool isCleanButtonPressed() const;

      bool isClockButtonPressed() const;

      bool isScheduleButtonPressed() const;

      bool isDayButtonPressed() const;

      bool isHourButtonPressed() const;

      bool isMinButtonPressed() const;

      bool isDockButtonPressed() const;

      bool isSpotButtonPressed() const;

      float getVoltage() const;

      float getCurrent() const;

      int8_t getTemperature() const;

      float getBatteryCharge() const;

      float getBatteryCapacity() const;

      bool isLightBumperLeft() const;

      bool isLightBumperFrontLeft() const;

      bool isLightBumperCenterLeft() const;

      bool isLightBumperRight() const;

      bool isLightBumperFrontRight() const;

      bool isLightBumperCenterRight() const;

      uint16_t getLightSignalLeft() const;

      uint16_t getLightSignalFrontLeft() const;

      uint16_t getLightSignalCenterLeft() const;

      uint16_t getLightSignalRight() const;

      uint16_t getLightSignalFrontRight() const;

      uint16_t getLightSignalCenterRight() const;

      bool isMovingForward() const;

      float getLeftWheelDistance() const;

      float getRightWheelDistance() const;

      float getMeasuredLeftWheelVel() const;

      float getMeasuredRightWheelVel() const;

      float getRequestedLeftWheelVel() const;

      float getRequestedRightWheelVel() const;

      create::ChargingState getChargingState() const;

      create::CreateMode getMode();

      create::Pose getPose() const;

      create::Vel getVel() const;

      uint64_t getNumCorruptPackets() const;

      uint64_t getTotalPackets() const;

      void setModeReportWorkaround(const bool& enable);

      bool getModeReportWorkaround() const;

  };  // end Create class

}  // namespace create
#endif  // CREATE_DRIVER_H