Go to the documentation of this file.
    6 #include "mraa/common.hpp" 
    7 #include "mraa/uart.hpp" 
   17 #define CMD_ENABLE          0x01 
   18 #define CMD_DISABLE         0x02 
   19 #define CMD_SETTIMEOUT      0x03 
   20 #define CMD_SETPWMMAX       0x04 
   21 #define CMD_SENDRPM         0x05 
   22 #define CMD_SENDPOS         0x06 
   23 #define CMD_INVERTENC       0x07 
   24 #define CMD_LOWVOLTAGECHECK 0x08 
   25 #define CMD_STALLCHECK      0x09 
   26 #define CMD_IMURAWDATA      0x0A 
   27 #define CMD_FUSEIMUWEIGHT   0x0B 
   28 #define CMD_UARTTIMEOUT     0x0C 
   29 #define CMD_IMUCALIBRATE    0x0D 
   30 #define CMD_IMUFIXZAXIS     0x0E 
   33 #define CMD_SETPWM          0x10 
   34 #define CMD_SETRPM          0x11 
   39 #define CMD_CTL_KP          0x20 
   40 #define CMD_CTL_KI          0x21 
   41 #define CMD_CTL_KD          0x22 
   42 #define CMD_CTL_ANTIWINDUP  0x23 
   43 #define CMD_CTL_INPUTFILTER 0x24 
   44 #define CMD_CTL_ENCLOWPASS  0x25 
   47 #define CMD_GEARRATIO       0x30 // Ratio of motor gears 
   48 #define CMD_TICKSPERREV     0x31 // Ticks per motor revolution ((raising + falling edges) x 2 channels) 
   50 #define CMD_AUX1            0x40 // Enable/Disable auxilary power output 1 
   51 #define CMD_AUX2            0x41 // Enable/Disable auxilary power output 2 
   52 #define CMD_LIGHTS_OFF      0x42 // Switch lights off 
   53 #define CMD_DIM_LIGHT       0x43 // Dimmed headlight 
   54 #define CMD_HIGH_BEAM       0x44 // High beam headlight 
   55 #define CMD_FLASH_ALL       0x45 // Flash lights 
   56 #define CMD_FLASH_LEFT      0x46 // Flash lights 
   57 #define CMD_FLASH_RIGHT     0x47 // Flash lights 
   58 #define CMD_PULSATION       0x48 // Pulsation 
   59 #define CMD_ROTATION        0x49 // Rotation light, e.g. police light in blue 
   60 #define CMD_RUNNING         0x4A // Running light 
  156    bool setKp(
float kp);
 
  163    bool setKi(
float ki);
 
  170    bool setKd(
float kd);
 
  198    bool setPWM(int8_t pwm[4]);
 
  205    bool setRPM(
float rpm[4]);
 
  211    const std::vector<float> 
getRPM();
 
  301    std::vector<float> 
_q;
 
  313 #endif //__IOTSHIELD_H 
  
bool setControlFrequency(uint32_t freq)
bool setLowPassSetPoint(float weight)
bool setIMURawFormat(bool rawdata)
const float getTemperature()
bool setTicksPerRev(float ticksPerRev)
const std::vector< float > getAngularRate()
std::vector< float > _angularRate
std::vector< float > _rpm
const std::vector< float > getRPM()
Interface class to IOTShield via UART.
const std::vector< float > getRangeMeasurements()
bool fixIMUZAxis(bool fix)
std::vector< float > _ranges
bool setTimeout(float timeout)
bool setGearRatio(float gearRatio)
std::vector< float > _acceleration
bool setRPM(float rpm[4])
bool setDriftWeight(float weight)
const std::vector< float > getAcceleration()
bool setPWM(int8_t pwm[4])
bool setLowPassEncoder(float weight)
const std::vector< float > getOrientation()
bool setLighting(eLighting light, unsigned char rgb[3])
iotbot
Author(s): Stefan May (EduArt Robotik)
autogenerated on Wed May 24 2023 02:13:39