IOTShield.h
Go to the documentation of this file.
1 #ifndef __IOTSHIELD_H
2 #define __IOTSHIELD_H
3 
4 #include <vector>
5 #if _WITH_MRAA
6 #include "mraa/common.hpp"
7 #include "mraa/uart.hpp"
8 #else
9 #include <stdint.h>
10 #include <string.h>
11 #endif
12 
13 namespace iotbot
14 {
15 
16 // Common parameters
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
31 
32 // Operating commands
33 #define CMD_SETPWM 0x10
34 #define CMD_SETRPM 0x11
35 #define CMD_FREQ 0x12
36 #define CMD_SYNC 0x13
37 
38 // Closed/Open loop controller parameters
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
45 
46 // Platform parameters
47 #define CMD_GEARRATIO 0x30 // Ratio of motor gears
48 #define CMD_TICKSPERREV 0x31 // Ticks per motor revolution ((raising + falling edges) x 2 channels)
49 
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
61 
71 
78 class IOTShield
79 {
80 public:
84  IOTShield();
85 
89  ~IOTShield();
90 
95  bool enable();
96 
101  bool disable();
102 
108  bool setIMURawFormat(bool rawdata);
109 
115  bool fixIMUZAxis(bool fix);
116 
121  bool setTimeout(float timeout);
122 
129  bool setDriftWeight(float weight);
130 
135  bool calibrateIMU();
136 
142  bool setGearRatio(float gearRatio);
143 
149  bool setTicksPerRev(float ticksPerRev);
150 
156  bool setKp(float kp);
157 
163  bool setKi(float ki);
164 
170  bool setKd(float kd);
171 
177  bool setControlFrequency(uint32_t freq);
178 
184  bool setLowPassSetPoint(float weight);
185 
191  bool setLowPassEncoder(float weight);
192 
198  bool setPWM(int8_t pwm[4]);
199 
205  bool setRPM(float rpm[4]);
206 
211  const std::vector<float> getRPM();
212 
219  bool setLighting(eLighting light, unsigned char rgb[3]);
220 
226  bool setAUX1(bool on);
227 
233  bool setAUX2(bool on);
234 
239  float getSystemVoltage();
240 
245  float getLoadCurrent();
246 
251  const std::vector<float> getRangeMeasurements();
252 
257  const std::vector<float> getAcceleration();
258 
263  const std::vector<float> getAngularRate();
264 
269  const std::vector<float> getOrientation();
270 
275  const float getTemperature();
276 
277 private:
278 
279  void sendReceive();
280 
281 #if _WITH_MRAA
282  mraa::Uart* _uart;
283 #endif
284 
285  char _txBuf[11];
286 
287  char _rxBuf[32];
288 
290 
292 
293  std::vector<float> _rpm;
294 
295  std::vector<float> _ranges;
296 
297  std::vector<float> _acceleration;
298 
299  std::vector<float> _angularRate;
300 
301  std::vector<float> _q;
302 
303  double _timeCom;
304 
305  bool _rawdata;
306 
308 
309 };
310 
311 } // namespace
312 
313 #endif //__IOTSHIELD_H
iotbot::IOTShield::setControlFrequency
bool setControlFrequency(uint32_t freq)
Definition: IOTShield.cpp:201
iotbot::IOTShield::_temperature
float _temperature
Definition: IOTShield.h:307
iotbot::flashRight
@ flashRight
Definition: IOTShield.h:67
iotbot::IOTShield::setLowPassSetPoint
bool setLowPassSetPoint(float weight)
Definition: IOTShield.cpp:210
iotbot::warningLight
@ warningLight
Definition: IOTShield.h:65
CMD_DIM_LIGHT
#define CMD_DIM_LIGHT
Definition: IOTShield.h:53
iotbot::IOTShield::setKd
bool setKd(float kd)
Definition: IOTShield.cpp:192
iotbot::IOTShield::_rxBuf
char _rxBuf[32]
Definition: IOTShield.h:287
iotbot::flashLeft
@ flashLeft
Definition: IOTShield.h:66
iotbot::IOTShield::setIMURawFormat
bool setIMURawFormat(bool rawdata)
Definition: IOTShield.cpp:92
iotbot::IOTShield::_q
std::vector< float > _q
Definition: IOTShield.h:301
iotbot::IOTShield::IOTShield
IOTShield()
Definition: IOTShield.cpp:32
iotbot::IOTShield::setKp
bool setKp(float kp)
Definition: IOTShield.cpp:174
iotbot::IOTShield::getTemperature
const float getTemperature()
Definition: IOTShield.cpp:320
iotbot::IOTShield::setAUX1
bool setAUX1(bool on)
Definition: IOTShield.cpp:266
iotbot::IOTShield::setTicksPerRev
bool setTicksPerRev(float ticksPerRev)
Definition: IOTShield.cpp:165
iotbot::IOTShield::disable
bool disable()
Definition: IOTShield.cpp:83
iotbot::IOTShield::getAngularRate
const std::vector< float > getAngularRate()
Definition: IOTShield.cpp:310
iotbot::IOTShield::_angularRate
std::vector< float > _angularRate
Definition: IOTShield.h:299
iotbot::IOTShield::getLoadCurrent
float getLoadCurrent()
Definition: IOTShield.cpp:295
iotbot::IOTShield::_rpm
std::vector< float > _rpm
Definition: IOTShield.h:293
iotbot::IOTShield::getRPM
const std::vector< float > getRPM()
Definition: IOTShield.cpp:249
iotbot::IOTShield::_txBuf
char _txBuf[11]
Definition: IOTShield.h:285
iotbot::eLighting
eLighting
Definition: IOTShield.h:62
iotbot::lightsOff
@ lightsOff
Definition: IOTShield.h:62
iotbot::IOTShield
Interface class to IOTShield via UART.
Definition: IOTShield.h:78
iotbot::beamLight
@ beamLight
Definition: IOTShield.h:64
iotbot::IOTShield::getRangeMeasurements
const std::vector< float > getRangeMeasurements()
Definition: IOTShield.cpp:300
CMD_RUNNING
#define CMD_RUNNING
Definition: IOTShield.h:60
iotbot
Definition: IOTBot.cpp:6
iotbot::IOTShield::setKi
bool setKi(float ki)
Definition: IOTShield.cpp:183
iotbot::IOTShield::enable
bool enable()
Definition: IOTShield.cpp:74
iotbot::IOTShield::fixIMUZAxis
bool fixIMUZAxis(bool fix)
Definition: IOTShield.cpp:121
CMD_ROTATION
#define CMD_ROTATION
Definition: IOTShield.h:59
iotbot::IOTShield::_ranges
std::vector< float > _ranges
Definition: IOTShield.h:295
iotbot::IOTShield::calibrateIMU
bool calibrateIMU()
Definition: IOTShield.cpp:148
iotbot::IOTShield::setAUX2
bool setAUX2(bool on)
Definition: IOTShield.cpp:278
iotbot::IOTShield::setTimeout
bool setTimeout(float timeout)
Definition: IOTShield.cpp:130
iotbot::IOTShield::setGearRatio
bool setGearRatio(float gearRatio)
Definition: IOTShield.cpp:156
iotbot::IOTShield::sendReceive
void sendReceive()
Definition: IOTShield.cpp:325
iotbot::IOTShield::_acceleration
std::vector< float > _acceleration
Definition: IOTShield.h:297
iotbot::IOTShield::setRPM
bool setRPM(float rpm[4])
Definition: IOTShield.cpp:237
iotbot::IOTShield::setDriftWeight
bool setDriftWeight(float weight)
Definition: IOTShield.cpp:139
iotbot::IOTShield::getAcceleration
const std::vector< float > getAcceleration()
Definition: IOTShield.cpp:305
iotbot::IOTShield::_rawdata
bool _rawdata
Definition: IOTShield.h:305
iotbot::IOTShield::getSystemVoltage
float getSystemVoltage()
Definition: IOTShield.cpp:290
iotbot::IOTShield::setPWM
bool setPWM(int8_t pwm[4])
Definition: IOTShield.cpp:228
CMD_FLASH_LEFT
#define CMD_FLASH_LEFT
Definition: IOTShield.h:56
CMD_LIGHTS_OFF
#define CMD_LIGHTS_OFF
Definition: IOTShield.h:52
iotbot::IOTShield::~IOTShield
~IOTShield()
Definition: IOTShield.cpp:67
iotbot::IOTShield::setLowPassEncoder
bool setLowPassEncoder(float weight)
Definition: IOTShield.cpp:219
iotbot::IOTShield::getOrientation
const std::vector< float > getOrientation()
Definition: IOTShield.cpp:315
iotbot::pulsation
@ pulsation
Definition: IOTShield.h:68
iotbot::rotation
@ rotation
Definition: IOTShield.h:69
CMD_FLASH_RIGHT
#define CMD_FLASH_RIGHT
Definition: IOTShield.h:57
iotbot::IOTShield::_timeCom
double _timeCom
Definition: IOTShield.h:303
iotbot::IOTShield::setLighting
bool setLighting(eLighting light, unsigned char rgb[3])
Definition: IOTShield.cpp:254
iotbot::IOTShield::_loadCurrent
float _loadCurrent
Definition: IOTShield.h:291
iotbot::dimLight
@ dimLight
Definition: IOTShield.h:63
iotbot::IOTShield::_systemVoltage
float _systemVoltage
Definition: IOTShield.h:289
CMD_PULSATION
#define CMD_PULSATION
Definition: IOTShield.h:58
CMD_FLASH_ALL
#define CMD_FLASH_ALL
Definition: IOTShield.h:55
CMD_HIGH_BEAM
#define CMD_HIGH_BEAM
Definition: IOTShield.h:54
iotbot::running
@ running
Definition: IOTShield.h:70


iotbot
Author(s): Stefan May (EduArt Robotik)
autogenerated on Wed May 24 2023 02:13:39