Public Member Functions | Private Member Functions | Private Attributes | List of all members
iotbot::IOTShield Class Reference

Interface class to IOTShield via UART. More...

#include <IOTShield.h>

Public Member Functions

bool calibrateIMU ()
 
bool disable ()
 
bool enable ()
 
bool fixIMUZAxis (bool fix)
 
const std::vector< float > getAcceleration ()
 
const std::vector< float > getAngularRate ()
 
float getLoadCurrent ()
 
const std::vector< float > getOrientation ()
 
const std::vector< float > getRangeMeasurements ()
 
const std::vector< float > getRPM ()
 
float getSystemVoltage ()
 
const float getTemperature ()
 
 IOTShield ()
 
bool setAUX1 (bool on)
 
bool setAUX2 (bool on)
 
bool setControlFrequency (uint32_t freq)
 
bool setDriftWeight (float weight)
 
bool setGearRatio (float gearRatio)
 
bool setIMURawFormat (bool rawdata)
 
bool setKd (float kd)
 
bool setKi (float ki)
 
bool setKp (float kp)
 
bool setLighting (eLighting light, unsigned char rgb[3])
 
bool setLowPassEncoder (float weight)
 
bool setLowPassSetPoint (float weight)
 
bool setPWM (int8_t pwm[4])
 
bool setRPM (float rpm[4])
 
bool setTicksPerRev (float ticksPerRev)
 
bool setTimeout (float timeout)
 
 ~IOTShield ()
 

Private Member Functions

void sendReceive ()
 

Private Attributes

std::vector< float > _acceleration
 
std::vector< float > _angularRate
 
float _loadCurrent
 
std::vector< float > _q
 
std::vector< float > _ranges
 
bool _rawdata
 
std::vector< float > _rpm
 
char _rxBuf [32]
 
float _systemVoltage
 
float _temperature
 
double _timeCom
 
char _txBuf [11]
 

Detailed Description

Interface class to IOTShield via UART.

Author
Stefan May
Date
04.07.2021

Definition at line 78 of file IOTShield.h.

Constructor & Destructor Documentation

◆ IOTShield()

iotbot::IOTShield::IOTShield ( )

Default Constructor

Definition at line 32 of file IOTShield.cpp.

◆ ~IOTShield()

iotbot::IOTShield::~IOTShield ( )

Destructor

Definition at line 67 of file IOTShield.cpp.

Member Function Documentation

◆ calibrateIMU()

bool iotbot::IOTShield::calibrateIMU ( )

Trigger IMU calibration (takes about 1 second). The platform needs to stand still during this procedure.

Returns
success

Definition at line 148 of file IOTShield.cpp.

◆ disable()

bool iotbot::IOTShield::disable ( )

Disable shield (no motion can be performed after disabling)

Returns
success

Definition at line 83 of file IOTShield.cpp.

◆ enable()

bool iotbot::IOTShield::enable ( )

Enable shield (must be done before steering)

Returns
success

Definition at line 74 of file IOTShield.cpp.

◆ fixIMUZAxis()

bool iotbot::IOTShield::fixIMUZAxis ( bool  fix)

Fix IMU z-axis

Parameters
[in]fixtrue: fix z-axis, false: enable z-axis (yaw angle estimation)
Returns
success

Definition at line 121 of file IOTShield.cpp.

◆ getAcceleration()

const std::vector< float > iotbot::IOTShield::getAcceleration ( )

Get linear acceleration in g (multiple of 9,81 m/s^2) return 3-dimensional measurement vector

Definition at line 305 of file IOTShield.cpp.

◆ getAngularRate()

const std::vector< float > iotbot::IOTShield::getAngularRate ( )

Get angular rate in degrees per second return 3-dimensional measurement vector

Definition at line 310 of file IOTShield.cpp.

◆ getLoadCurrent()

float iotbot::IOTShield::getLoadCurrent ( )

Get load current (consumed by IOT2050 and drives)

Returns
load current [A]

Definition at line 295 of file IOTShield.cpp.

◆ getOrientation()

const std::vector< float > iotbot::IOTShield::getOrientation ( )

Get fused IMU data (accelerometer and gyroscope) return orientation as quaternion (w x y z)

Definition at line 315 of file IOTShield.cpp.

◆ getRangeMeasurements()

const std::vector< float > iotbot::IOTShield::getRangeMeasurements ( )

Get time-of-flight measurements

Returns
ToF measurements

Definition at line 300 of file IOTShield.cpp.

◆ getRPM()

const std::vector< float > iotbot::IOTShield::getRPM ( )

Get actual revolutions per minute

Returns
revolutions per minutes

Definition at line 249 of file IOTShield.cpp.

◆ getSystemVoltage()

float iotbot::IOTShield::getSystemVoltage ( )

Get system voltage

Returns
system voltage [V]

Definition at line 290 of file IOTShield.cpp.

◆ getTemperature()

const float iotbot::IOTShield::getTemperature ( )

Get onboard temperature measurement. return temperature

Definition at line 320 of file IOTShield.cpp.

◆ sendReceive()

void iotbot::IOTShield::sendReceive ( )
private

Definition at line 325 of file IOTShield.cpp.

◆ setAUX1()

bool iotbot::IOTShield::setAUX1 ( bool  on)

Switch on/off auxiliary output (channel 1)

Parameters
[in]onon/off state
Returns
success

Definition at line 266 of file IOTShield.cpp.

◆ setAUX2()

bool iotbot::IOTShield::setAUX2 ( bool  on)

Switch on/off auxiliary output (channel 2)

Parameters
[in]onon/off state
Returns
success

Definition at line 278 of file IOTShield.cpp.

◆ setControlFrequency()

bool iotbot::IOTShield::setControlFrequency ( uint32_t  freq)

Set frequency of bridge driver for motor control. param[in] freq frequency in HZ in range [1000, 1000000] return success

Definition at line 201 of file IOTShield.cpp.

◆ setDriftWeight()

bool iotbot::IOTShield::setDriftWeight ( float  weight)

Set weight of drift parameter. Gyro data is used for fast orientation changes, while the accelerometer comensates drift for 2 of the degrees of freedom.

Parameters
[in]weighta larger weight increases the belief in the accelerometer values [0; 1], default: 0.03f. return success

Definition at line 139 of file IOTShield.cpp.

◆ setGearRatio()

bool iotbot::IOTShield::setGearRatio ( float  gearRatio)

Set ration of motor gears

Parameters
[in]gearRatiogear ratio
Returns
success

Definition at line 156 of file IOTShield.cpp.

◆ setIMURawFormat()

bool iotbot::IOTShield::setIMURawFormat ( bool  rawdata)

Enable/Disable IMU rawdata transmission.

Parameters
[in]rawdatatrue: raw data is transmitted (default), false: fused data as quaternion is transmitted.
Returns
success

Definition at line 92 of file IOTShield.cpp.

◆ setKd()

bool iotbot::IOTShield::setKd ( float  kd)

Set differentiating coefficient of closed loop controller

Parameters
[in]kddifferentiating coefficient
Returns
success

Definition at line 192 of file IOTShield.cpp.

◆ setKi()

bool iotbot::IOTShield::setKi ( float  ki)

Set integration coefficient of closed loop controller

Parameters
[in]kiintegration coefficient
Returns
success

Definition at line 183 of file IOTShield.cpp.

◆ setKp()

bool iotbot::IOTShield::setKp ( float  kp)

Set proportional coefficient of closed loop controller

Parameters
[in]kpproportional weight
Returns
success

Definition at line 174 of file IOTShield.cpp.

◆ setLighting()

bool iotbot::IOTShield::setLighting ( eLighting  light,
unsigned char  rgb[3] 
)

Set lighting effects

Parameters
[in]lightlighting effect
[in]rgbcolor triple for lighting effect return success

Definition at line 254 of file IOTShield.cpp.

◆ setLowPassEncoder()

bool iotbot::IOTShield::setLowPassEncoder ( float  weight)

Set low pass coefficient of encoder measurements. New values are weighted with this value.

Parameters
[in]weightlow pass coefficient of encoder measurements
Returns
success

Definition at line 219 of file IOTShield.cpp.

◆ setLowPassSetPoint()

bool iotbot::IOTShield::setLowPassSetPoint ( float  weight)

Set low pass coefficient of set point. New values are weighted with this value.

Parameters
[in]weightlow pass coefficient of set point
Returns
success

Definition at line 210 of file IOTShield.cpp.

◆ setPWM()

bool iotbot::IOTShield::setPWM ( int8_t  pwm[4])

Set PWM of motors

Parameters
[in]pulsewidth modulation of motors
Returns
success

Definition at line 228 of file IOTShield.cpp.

◆ setRPM()

bool iotbot::IOTShield::setRPM ( float  rpm[4])

Set command variable of closed loop controllers for motor control

Parameters
[in]rpmrevolutions per minute
Returns
success

Definition at line 237 of file IOTShield.cpp.

◆ setTicksPerRev()

bool iotbot::IOTShield::setTicksPerRev ( float  ticksPerRev)

Set ticks per revolution of encoders

Parameters
[in]ticksPerRevticks per revoluation (raising and falling edges)
Returns
success

Definition at line 165 of file IOTShield.cpp.

◆ setTimeout()

bool iotbot::IOTShield::setTimeout ( float  timeout)

Set time without UART communication until an enable state will be removed.

Parameters

Definition at line 130 of file IOTShield.cpp.

Member Data Documentation

◆ _acceleration

std::vector<float> iotbot::IOTShield::_acceleration
private

Definition at line 297 of file IOTShield.h.

◆ _angularRate

std::vector<float> iotbot::IOTShield::_angularRate
private

Definition at line 299 of file IOTShield.h.

◆ _loadCurrent

float iotbot::IOTShield::_loadCurrent
private

Definition at line 291 of file IOTShield.h.

◆ _q

std::vector<float> iotbot::IOTShield::_q
private

Definition at line 301 of file IOTShield.h.

◆ _ranges

std::vector<float> iotbot::IOTShield::_ranges
private

Definition at line 295 of file IOTShield.h.

◆ _rawdata

bool iotbot::IOTShield::_rawdata
private

Definition at line 305 of file IOTShield.h.

◆ _rpm

std::vector<float> iotbot::IOTShield::_rpm
private

Definition at line 293 of file IOTShield.h.

◆ _rxBuf

char iotbot::IOTShield::_rxBuf[32]
private

Definition at line 287 of file IOTShield.h.

◆ _systemVoltage

float iotbot::IOTShield::_systemVoltage
private

Definition at line 289 of file IOTShield.h.

◆ _temperature

float iotbot::IOTShield::_temperature
private

Definition at line 307 of file IOTShield.h.

◆ _timeCom

double iotbot::IOTShield::_timeCom
private

Definition at line 303 of file IOTShield.h.

◆ _txBuf

char iotbot::IOTShield::_txBuf[11]
private

Definition at line 285 of file IOTShield.h.


The documentation for this class was generated from the following files:


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