create.h
Go to the documentation of this file.
00001 
00032 #ifndef CREATE_H
00033 #define CREATE_H
00034 
00035 #include <boost/shared_ptr.hpp>
00036 #include <boost/numeric/ublas/matrix.hpp>
00037 #include <string>
00038 #include <unistd.h>
00039 
00040 #include "create/serial_stream.h"
00041 #include "create/serial_query.h"
00042 #include "create/data.h"
00043 #include "create/types.h"
00044 #include "create/util.h"
00045 
00046 namespace create {
00047   class Create {
00048     private:
00049       typedef boost::numeric::ublas::matrix<float> Matrix;
00050 
00051       enum CreateLED {
00052         LED_DEBRIS = 1,
00053         LED_SPOT = 2,
00054         LED_DOCK = 4,
00055         LED_CHECK = 8
00056       };
00057 
00058       RobotModel model;
00059 
00060       uint8_t mainMotorPower;
00061       uint8_t sideMotorPower;
00062       uint8_t vacuumMotorPower;
00063 
00064       // LEDs
00065       uint8_t debrisLED;
00066       uint8_t spotLED;
00067       uint8_t dockLED;
00068       uint8_t checkLED;
00069       uint8_t powerLED;
00070       uint8_t powerLEDIntensity;
00071 
00072       CreateMode mode;
00073 
00074       create::Pose pose;
00075       create::Vel vel;
00076 
00077       uint32_t prevTicksLeft;
00078       uint32_t prevTicksRight;
00079       float totalLeftDist;
00080       float totalRightDist;
00081       bool firstOnData;
00082       util::timestamp_t prevOnDataTime;
00083 
00084       Matrix poseCovar;
00085 
00086       float requestedLeftVel;
00087       float requestedRightVel;
00088 
00089       void init();
00090       // Add two matrices and handle overflow case
00091       Matrix addMatrices(const Matrix &A, const Matrix &B) const;
00092       void onData();
00093       bool updateLEDs();
00094 
00095     protected:
00096       boost::shared_ptr<create::Data> data;
00097       boost::shared_ptr<create::Serial> serial;
00098 
00099     public:
00107       Create(RobotModel model = RobotModel::CREATE_2);
00108 
00117       Create(const std::string& port, const int& baud, RobotModel model = RobotModel::CREATE_2);
00118 
00122       ~Create();
00123 
00131       bool connect(const std::string& port, const int& baud);
00132 
00138       inline bool connected() const { return serial->connected(); };
00139 
00143       void disconnect();
00144 
00150       bool setMode(const create::CreateMode& mode);
00151 
00157       bool clean(const create::CleanMode& mode = CLEAN_DEFAULT);
00158 
00164       bool dock() const;
00165 
00173       bool setDate(const create::DayOfWeek& day, const uint8_t& hour, const uint8_t& min) const;
00174 
00184       bool driveRadius(const float& velocity, const float& radius);
00185 
00192       bool driveWheels(const float& leftWheel, const float& rightWheel);
00193 
00200       bool drive(const float& xVel, const float& angularVel);
00201 
00207       bool setSideMotor(const float& power);
00208 
00214       bool setMainMotor(const float& power);
00215 
00221       bool setVacuumMotor(const float& power);
00222 
00230       bool setAllMotors(const float& mainPower, const float& sidePower, const float& vacuumPower);
00231 
00237       bool enableDebrisLED(const bool& enable);
00238 
00244       bool enableSpotLED(const bool& enable);
00245 
00251       bool enableDockLED(const bool& enable);
00252 
00258       bool enableCheckRobotLED(const bool& enable);
00259 
00266       bool setPowerLED(const uint8_t& power, const uint8_t& intensity = 255);
00267 
00285       bool setDigits(const std::vector<bool>& segments) const;
00286 
00296       bool setDigitsASCII(const uint8_t& digit1, const uint8_t& digit2,
00297                           const uint8_t& digit3, const uint8_t& digit4) const;
00298 
00309       bool defineSong(const uint8_t& songNumber,
00310                       const uint8_t& songLength,
00311                       const uint8_t* notes,
00312                       const float* durations) const;
00313 
00320       bool playSong(const uint8_t& songNumber) const;
00321 
00325       bool isWheeldrop() const;
00326 
00330       bool isLeftBumper() const;
00331 
00335       bool isRightBumper() const;
00336 
00340       bool isWall() const;
00341 
00345       bool isCliff() const;
00346 
00350       bool isVirtualWall() const;
00351 
00356       bool isWheelOvercurrent() const;
00357 
00362       bool isMainBrushOvercurrent() const;
00363 
00368       bool isSideBrushOvercurrent() const;
00369 
00374       uint8_t getDirtDetect() const;
00375 
00380       uint8_t getIROmni() const;
00381 
00387       uint8_t getIRLeft() const;
00388 
00393       uint8_t getIRRight() const;
00394 
00399       bool isCleanButtonPressed() const;
00400 
00404       bool isClockButtonPressed() const;
00405 
00409       bool isScheduleButtonPressed() const;
00410 
00415       bool isDayButtonPressed() const;
00416 
00421       bool isHourButtonPressed() const;
00422 
00427       bool isMinButtonPressed() const;
00428 
00433       bool isDockButtonPressed() const;
00434 
00439       bool isSpotButtonPressed() const;
00440 
00445       float getVoltage() const;
00446 
00452       float getCurrent() const;
00453 
00458       int8_t getTemperature() const;
00459 
00464       float getBatteryCharge() const;
00465 
00470       float getBatteryCapacity() const;
00471 
00475       bool isLightBumperLeft() const;
00476 
00480       bool isLightBumperFrontLeft() const;
00481 
00485       bool isLightBumperCenterLeft() const;
00486 
00490       bool isLightBumperRight() const;
00491 
00495       bool isLightBumperFrontRight() const;
00496 
00500       bool isLightBumperCenterRight() const;
00501 
00506       uint16_t getLightSignalLeft() const;
00507 
00512       uint16_t getLightSignalFrontLeft() const;
00513 
00518       uint16_t getLightSignalCenterLeft() const;
00519 
00524       uint16_t getLightSignalRight() const;
00525 
00530       uint16_t getLightSignalFrontRight() const;
00531 
00536       uint16_t getLightSignalCenterRight() const;
00537 
00541       bool isMovingForward() const;
00542 
00547       float getLeftWheelDistance() const;
00548 
00553       float getRightWheelDistance() const;
00554 
00560       float getRequestedLeftWheelVel() const;
00561 
00567       float getRequestedRightWheelVel() const;
00568 
00573       create::ChargingState getChargingState() const;
00574 
00579       create::CreateMode getMode();
00580 
00585       create::Pose getPose() const;
00586 
00591       create::Vel getVel() const;
00592 
00599       uint64_t getNumCorruptPackets() const;
00600 
00605       uint64_t getTotalPackets() const;
00606   };  // end Create class
00607 
00608 }  // namespace create
00609 #endif  // CREATE_DRIVER_H


libcreate
Author(s): Jacob Perron
autogenerated on Sat Nov 26 2016 03:41:46