API

class A1335

Public Functions

A1335(int32_t *i2c_base, vector<uint8_t> &deviceIDs)

Constructor.

Parameters
  • i2c_base: i2c base (cf hps_0.h )
  • deviceIDs: active device ids

~A1335()
bool readAngleData(vector<A1335State> &states)

Reads the angle data.

Return
success
Parameters
  • states: will be filled with angle data

string decodeFlag(int type, uint16_t code)

Decodes a status flag.

Return
human readable string
Parameters
  • type: the type
  • code: thsi code

Private Functions

bool writeMemoryCheck(uint8_t deviceaddress, uint8_t eeaddress, uint8_t *wdata)
bool clearStatusRegisters(uint8_t deviceaddress)
bool checkDefaultSettings(A1335State *state)
bool readDeviceState(uint8_t deviceaddress, A1335State *state)
bool searchAddressSpace()

Private Members

vector<uint8_t> deviceIDs
const uint8_t start_register = 0x20
const uint8_t num_registers = 6
const uint8_t start_register2 = 0x34
const uint8_t num_registers2 = 2
const uint8_t expected_registers[8][2] = { {0b00000000, 0b00000000}, {0b10000000, 0b00010001}, {0b10100000, 0b00000000}, {0b10110000, 0b00000000}, {0b11110000, 0b00000000}, {0b11100000, 0b00000000}, {0b11000000, 0b00000000}, {0b11010000, 0b00000000} }

Content of the registers that should be on every chip Starts on ANG register (0x20:21)

const uint8_t expected_registers_mask[8][2] = { {0b11000000, 0b00000000}, {0b11110001, 0b11111111}, {0b11111100, 0b11111111}, {0b11111111, 0b11111111}, {0b11110000, 0b00000000}, {0b11110000, 0b00000000}, {0b11110100, 0b01111111}, {0b11111111, 0b11111111} }

1 marks the bits that belong to the expected values (to check the expected content)

const vector<const char *> angle_flags = { "NEW ", "ERR " }
const vector<const char *> status_flags = { "ERR ", "NEW ", "Soft_Rst ", "PwON_Rst " }
const vector<const char *> error_flags = { "MagLow ", "MagHigh ", "UnderVolt ", "OverVolt ", "AngleLow ", "AngleHigh ", "ProcError ", "NoRunMode ", "(CRC_Err) ", "(INTFErr) ", "(XOV) ", "XERR " }
const vector<const char *> xerror_flags = { "SelfTest ", "MemAddr ", "Execute ", "ResetCond ", "WTD_Timer ", "WTD_Halt ", "EEPR_Hard ", "SRAM_Hard ", "Temp_Err ", "AngleWarn ", "EEPR_Soft ", "SRAM_Soft " }
I2C *i2c
uint8_t deviceID
string str
struct A1335State

Public Members

uint8_t address
bool isOK
float angle
uint8_t angle_flags
uint8_t status_flags
uint16_t err_flags
uint16_t xerr_flags
float temp
float fieldStrength
uint8_t rawData[8][2]
class Adafruit_BNO055 : public Adafruit_Sensor

Public Types

enum adafruit_bno055_reg_t

Values:

BNO055_PAGE_ID_ADDR = 0X07
BNO055_CHIP_ID_ADDR = 0x00
BNO055_ACCEL_REV_ID_ADDR = 0x01
BNO055_MAG_REV_ID_ADDR = 0x02
BNO055_GYRO_REV_ID_ADDR = 0x03
BNO055_SW_REV_ID_LSB_ADDR = 0x04
BNO055_SW_REV_ID_MSB_ADDR = 0x05
BNO055_BL_REV_ID_ADDR = 0X06
BNO055_ACCEL_DATA_Y_LSB_ADDR = 0X0A
BNO055_ACCEL_DATA_Y_MSB_ADDR = 0X0B
BNO055_ACCEL_DATA_Z_LSB_ADDR = 0X0C
BNO055_ACCEL_DATA_Z_MSB_ADDR = 0X0D
BNO055_MAG_DATA_X_LSB_ADDR = 0X0E
BNO055_MAG_DATA_X_MSB_ADDR = 0X0F
BNO055_MAG_DATA_Y_LSB_ADDR = 0X10
BNO055_MAG_DATA_Y_MSB_ADDR = 0X11
BNO055_MAG_DATA_Z_LSB_ADDR = 0X12
BNO055_MAG_DATA_Z_MSB_ADDR = 0X13
BNO055_GYRO_DATA_X_LSB_ADDR = 0X14
BNO055_GYRO_DATA_X_MSB_ADDR = 0X15
BNO055_GYRO_DATA_Y_LSB_ADDR = 0X16
BNO055_GYRO_DATA_Y_MSB_ADDR = 0X17
BNO055_EULER_H_LSB_ADDR = 0X1A
BNO055_EULER_H_MSB_ADDR = 0X1B
BNO055_EULER_R_LSB_ADDR = 0X1C
BNO055_EULER_R_MSB_ADDR = 0X1D
BNO055_EULER_P_LSB_ADDR = 0X1E
BNO055_EULER_P_MSB_ADDR = 0X1F
BNO055_QUATERNION_DATA_W_LSB_ADDR = 0X20
BNO055_QUATERNION_DATA_W_MSB_ADDR = 0X21
BNO055_QUATERNION_DATA_X_LSB_ADDR = 0X22
BNO055_QUATERNION_DATA_X_MSB_ADDR = 0X23
BNO055_QUATERNION_DATA_Y_LSB_ADDR = 0X24
BNO055_QUATERNION_DATA_Y_MSB_ADDR = 0X25
BNO055_QUATERNION_DATA_Z_LSB_ADDR = 0X26
BNO055_QUATERNION_DATA_Z_MSB_ADDR = 0X27
BNO055_LINEAR_ACCEL_DATA_Y_LSB_ADDR = 0X2A
BNO055_LINEAR_ACCEL_DATA_Y_MSB_ADDR = 0X2B
BNO055_LINEAR_ACCEL_DATA_Z_LSB_ADDR = 0X2C
BNO055_LINEAR_ACCEL_DATA_Z_MSB_ADDR = 0X2D
BNO055_GRAVITY_DATA_X_LSB_ADDR = 0X2E
BNO055_GRAVITY_DATA_X_MSB_ADDR = 0X2F
BNO055_GRAVITY_DATA_Y_LSB_ADDR = 0X30
BNO055_GRAVITY_DATA_Y_MSB_ADDR = 0X31
BNO055_GRAVITY_DATA_Z_LSB_ADDR = 0X32
BNO055_GRAVITY_DATA_Z_MSB_ADDR = 0X33
BNO055_TEMP_ADDR = 0X34
BNO055_CALIB_STAT_ADDR = 0X35
BNO055_SELFTEST_RESULT_ADDR = 0X36
BNO055_INTR_STAT_ADDR = 0X37
BNO055_SYS_ERR_ADDR = 0X3A
BNO055_UNIT_SEL_ADDR = 0X3B
BNO055_DATA_SELECT_ADDR = 0X3C
BNO055_OPR_MODE_ADDR = 0X3D
BNO055_PWR_MODE_ADDR = 0X3E
BNO055_SYS_TRIGGER_ADDR = 0X3F
BNO055_TEMP_SOURCE_ADDR = 0X40
BNO055_AXIS_MAP_CONFIG_ADDR = 0X41
BNO055_AXIS_MAP_SIGN_ADDR = 0X42
BNO055_SIC_MATRIX_0_LSB_ADDR = 0X43
BNO055_SIC_MATRIX_0_MSB_ADDR = 0X44
BNO055_SIC_MATRIX_1_LSB_ADDR = 0X45
BNO055_SIC_MATRIX_1_MSB_ADDR = 0X46
BNO055_SIC_MATRIX_2_LSB_ADDR = 0X47
BNO055_SIC_MATRIX_3_MSB_ADDR = 0X4A
BNO055_SIC_MATRIX_4_LSB_ADDR = 0X4B
BNO055_SIC_MATRIX_4_MSB_ADDR = 0X4C
BNO055_SIC_MATRIX_5_LSB_ADDR = 0X4D
BNO055_SIC_MATRIX_5_MSB_ADDR = 0X4E
BNO055_SIC_MATRIX_6_LSB_ADDR = 0X4F
BNO055_SIC_MATRIX_6_MSB_ADDR = 0X50
BNO055_SIC_MATRIX_7_LSB_ADDR = 0X51
BNO055_SIC_MATRIX_7_MSB_ADDR = 0X52
BNO055_SIC_MATRIX_8_LSB_ADDR = 0X53
BNO055_SIC_MATRIX_8_MSB_ADDR = 0X54
ACCEL_OFFSET_X_LSB_ADDR = 0X55
ACCEL_OFFSET_X_MSB_ADDR = 0X56
ACCEL_OFFSET_Y_LSB_ADDR = 0X57
ACCEL_OFFSET_Z_MSB_ADDR = 0X5A
MAG_OFFSET_X_LSB_ADDR = 0X5B
MAG_OFFSET_X_MSB_ADDR = 0X5C
MAG_OFFSET_Y_LSB_ADDR = 0X5D
MAG_OFFSET_Y_MSB_ADDR = 0X5E
MAG_OFFSET_Z_LSB_ADDR = 0X5F
MAG_OFFSET_Z_MSB_ADDR = 0X60
GYRO_OFFSET_X_LSB_ADDR = 0X61
GYRO_OFFSET_X_MSB_ADDR = 0X62
GYRO_OFFSET_Y_LSB_ADDR = 0X63
GYRO_OFFSET_Y_MSB_ADDR = 0X64
GYRO_OFFSET_Z_LSB_ADDR = 0X65
GYRO_OFFSET_Z_MSB_ADDR = 0X66
ACCEL_RADIUS_LSB_ADDR = 0X67
MAG_RADIUS_MSB_ADDR = 0X6A
enum adafruit_bno055_powermode_t

Values:

POWER_MODE_NORMAL = 0X00
POWER_MODE_LOWPOWER = 0X01
POWER_MODE_SUSPEND = 0X02
enum adafruit_bno055_opmode_t

Values:

OPERATION_MODE_CONFIG = 0X00
OPERATION_MODE_ACCONLY = 0X01
OPERATION_MODE_MAGONLY = 0X02
OPERATION_MODE_GYRONLY = 0X03
OPERATION_MODE_ACCMAG = 0X04
OPERATION_MODE_ACCGYRO = 0X05
OPERATION_MODE_MAGGYRO = 0X06
OPERATION_MODE_AMG = 0X07
OPERATION_MODE_M4G = 0X0A
OPERATION_MODE_NDOF_FMC_OFF = 0X0B
OPERATION_MODE_NDOF = 0X0C
enum adafruit_bno055_axis_remap_config_t

Values:

REMAP_CONFIG_P0 = 0x21
REMAP_CONFIG_P1 = 0x24
REMAP_CONFIG_P2 = 0x24
REMAP_CONFIG_P3 = 0x21
REMAP_CONFIG_P4 = 0x24
REMAP_CONFIG_P5 = 0x21
REMAP_CONFIG_P6 = 0x21
REMAP_CONFIG_P7 = 0x24
enum adafruit_bno055_axis_remap_sign_t

Values:

REMAP_SIGN_P0 = 0x04
REMAP_SIGN_P1 = 0x00
REMAP_SIGN_P2 = 0x06
REMAP_SIGN_P3 = 0x02
REMAP_SIGN_P4 = 0x03
REMAP_SIGN_P5 = 0x01
REMAP_SIGN_P6 = 0x07
REMAP_SIGN_P7 = 0x05
enum adafruit_vector_type_t

Values:

VECTOR_ACCELEROMETER = BNO055_ACCEL_DATA_X_LSB_ADDR
VECTOR_MAGNETOMETER = BNO055_MAG_DATA_X_LSB_ADDR
VECTOR_GYROSCOPE = BNO055_GYRO_DATA_X_LSB_ADDR
VECTOR_EULER = BNO055_EULER_H_LSB_ADDR
VECTOR_LINEARACCEL = BNO055_LINEAR_ACCEL_DATA_X_LSB_ADDR
VECTOR_GRAVITY = BNO055_GRAVITY_DATA_X_LSB_ADDR

Public Functions

Adafruit_BNO055(int32_t sensorID = -1, uint8_t address = BNO055_ADDRESS_A, void *h2p_lw_i2c_addr = nullptr)

Instantiates a new Adafruit_BNO055 class.

~Adafruit_BNO055()
bool begin(adafruit_bno055_opmode_t mode = OPERATION_MODE_NDOF)

Sets up the HW.

void setMode(adafruit_bno055_opmode_t mode)

Puts the chip in the specified operating mode.

void getRevInfo(adafruit_bno055_rev_info_t *info)

Gets the chip revision numbers.

void displayRevInfo(void)
void setExtCrystalUse(bool usextal)

Use the external 32.768KHz crystal.

void getSystemStatus(uint8_t *system_status, uint8_t *self_test_result, uint8_t *system_error)

Gets the latest system status info.

void displaySystemStatus(void)
void getCalibration(uint8_t *system, uint8_t *gyro, uint8_t *accel, uint8_t *mag)

Gets current calibration state. Each value should be a uint8_t pointer and it will be set to 0 if not calibrated and 3 if fully calibrated.

imu::Vector<3> getVector(adafruit_vector_type_t vector_type)

Gets a vector reading from the specified source.

imu::Quaternion getQuat(void)

Gets a quaternion reading from the specified source.

int8_t getTemp(void)

Gets the temperature in degrees celsius.

bool getEvent(sensors_event_t *event)

Reads the sensor and returns the data as a sensors_event_t.

void getSensor(sensor_t *sensor)

Provides the sensor_t data for this sensor.

bool getSensorOffsets(uint8_t *calibData)

Reads the sensor’s offset registers into a byte array.

bool getSensorOffsets(adafruit_bno055_offsets_t &offsets_type)

Reads the sensor’s offset registers into an offset struct.

void setSensorOffsets(const uint8_t *calibData)

Writes an array of calibration values to the sensor’s offset registers.

void setSensorOffsets(const adafruit_bno055_offsets_t &offsets_type)

Writes to the sensor’s offset registers from an offset struct.

bool isFullyCalibrated(void)

Private Functions

byte read8(adafruit_bno055_reg_t reg)

Reads an 8 bit value over I2C.

bool readLen(adafruit_bno055_reg_t reg, byte *buffer, uint8_t len)

Reads the specified number of bytes over I2C.

bool write8(adafruit_bno055_reg_t reg, byte value)

Writes an 8 bit value over I2C.

Private Members

uint8_t _address
int32_t _sensorID
adafruit_bno055_opmode_t _mode
I2C *i2c
high_resolution_clock::time_point t0
high_resolution_clock::time_point t1
struct adafruit_bno055_offsets_t

Public Members

uint16_t accel_offset_x
uint16_t accel_offset_y
uint16_t accel_offset_z
uint16_t gyro_offset_x
uint16_t gyro_offset_y
uint16_t gyro_offset_z
uint16_t mag_offset_x
uint16_t mag_offset_y
uint16_t mag_offset_z
uint16_t accel_radius
uint16_t mag_radius
struct adafruit_bno055_rev_info_t

Public Members

uint8_t accel_rev
uint8_t mag_rev
uint8_t gyro_rev
uint16_t sw_rev
uint8_t bl_rev
class Adafruit_LSM9DS1

Public Types

enum lsm9ds1AccGyroRegisters_t

Values:

LSM9DS1_REGISTER_WHO_AM_I_XG = 0x0F
LSM9DS1_REGISTER_CTRL_REG1_G = 0x10
LSM9DS1_REGISTER_CTRL_REG2_G = 0x11
LSM9DS1_REGISTER_CTRL_REG3_G = 0x12
LSM9DS1_REGISTER_TEMP_OUT_L = 0x15
LSM9DS1_REGISTER_TEMP_OUT_H = 0x16
LSM9DS1_REGISTER_STATUS_REG = 0x17
LSM9DS1_REGISTER_OUT_Y_L_G = 0x1A
LSM9DS1_REGISTER_OUT_Y_H_G = 0x1B
LSM9DS1_REGISTER_OUT_Z_L_G = 0x1C
LSM9DS1_REGISTER_OUT_Z_H_G = 0x1D
LSM9DS1_REGISTER_CTRL_REG4 = 0x1E
LSM9DS1_REGISTER_CTRL_REG5_XL = 0x1F
LSM9DS1_REGISTER_CTRL_REG6_XL = 0x20
LSM9DS1_REGISTER_CTRL_REG7_XL = 0x21
LSM9DS1_REGISTER_CTRL_REG8 = 0x22
LSM9DS1_REGISTER_CTRL_REG9 = 0x23
LSM9DS1_REGISTER_CTRL_REG10 = 0x24
LSM9DS1_REGISTER_OUT_Y_L_XL = 0x2A
LSM9DS1_REGISTER_OUT_Y_H_XL = 0x2B
LSM9DS1_REGISTER_OUT_Z_L_XL = 0x2C
LSM9DS1_REGISTER_OUT_Z_H_XL = 0x2D
enum lsm9ds1MagRegisters_t

Values:

LSM9DS1_REGISTER_WHO_AM_I_M = 0x0F
LSM9DS1_REGISTER_CTRL_REG1_M = 0x20
LSM9DS1_REGISTER_CTRL_REG2_M = 0x21
LSM9DS1_REGISTER_CTRL_REG3_M = 0x22
LSM9DS1_REGISTER_CTRL_REG4_M = 0x23
LSM9DS1_REGISTER_CTRL_REG5_M = 0x24
LSM9DS1_REGISTER_STATUS_REG_M = 0x27
LSM9DS1_REGISTER_OUT_Y_L_M = 0x2A
LSM9DS1_REGISTER_OUT_Y_H_M = 0x2B
LSM9DS1_REGISTER_OUT_Z_L_M = 0x2C
LSM9DS1_REGISTER_OUT_Z_H_M = 0x2D
LSM9DS1_REGISTER_CFG_M = 0x30
LSM9DS1_REGISTER_INT_SRC_M = 0x31
enum lsm9ds1AccelRange_t

Values:

LSM9DS1_ACCELRANGE_2G = (0b00 << 3)
LSM9DS1_ACCELRANGE_16G = (0b01 << 3)
LSM9DS1_ACCELRANGE_4G = (0b10 << 3)
LSM9DS1_ACCELRANGE_8G = (0b11 << 3)
enum lm9ds1AccelDataRate_t

Values:

LSM9DS1_ACCELDATARATE_POWERDOWN = (0b0000 << 4)
LSM9DS1_ACCELDATARATE_3_125HZ = (0b0001 << 4)
LSM9DS1_ACCELDATARATE_6_25HZ = (0b0010 << 4)
LSM9DS1_ACCELDATARATE_12_5HZ = (0b0011 << 4)
LSM9DS1_ACCELDATARATE_25HZ = (0b0100 << 4)
LSM9DS1_ACCELDATARATE_50HZ = (0b0101 << 4)
LSM9DS1_ACCELDATARATE_100HZ = (0b0110 << 4)
LSM9DS1_ACCELDATARATE_200HZ = (0b0111 << 4)
LSM9DS1_ACCELDATARATE_400HZ = (0b1000 << 4)
LSM9DS1_ACCELDATARATE_800HZ = (0b1001 << 4)
LSM9DS1_ACCELDATARATE_1600HZ = (0b1010 << 4)
enum lsm9ds1MagGain_t

Values:

LSM9DS1_MAGGAIN_4GAUSS = (0b00 << 5)
LSM9DS1_MAGGAIN_8GAUSS = (0b01 << 5)
LSM9DS1_MAGGAIN_12GAUSS = (0b10 << 5)
LSM9DS1_MAGGAIN_16GAUSS = (0b11 << 5)
enum lsm9ds1MagDataRate_t

Values:

LSM9DS1_MAGDATARATE_3_125HZ = (0b000 << 2)
LSM9DS1_MAGDATARATE_6_25HZ = (0b001 << 2)
LSM9DS1_MAGDATARATE_12_5HZ = (0b010 << 2)
LSM9DS1_MAGDATARATE_25HZ = (0b011 << 2)
LSM9DS1_MAGDATARATE_50HZ = (0b100 << 2)
LSM9DS1_MAGDATARATE_100HZ = (0b101 << 2)
enum lsm9ds1GyroScale_t

Values:

LSM9DS1_GYROSCALE_245DPS = (0b00 << 4)
LSM9DS1_GYROSCALE_500DPS = (0b01 << 4)
LSM9DS1_GYROSCALE_2000DPS = (0b11 << 4)
typedef struct Adafruit_LSM9DS1::vector_s lsm9ds1Vector_t

Public Functions

Adafruit_LSM9DS1(int32_t sensorID = 0)
Adafruit_LSM9DS1(int32_t sensorID = 0, void *i2c_base_address = nullptr)
void initI2C(int32_t sensorID)
bool begin(void)
void read(void)
void readAccel(void)
void readMag(void)
void readGyro(void)
void readTemp(void)
void setupAccel(lsm9ds1AccelRange_t range)
void setupMag(lsm9ds1MagGain_t gain)
void setupGyro(lsm9ds1GyroScale_t scale)
void write8(byte address, byte reg, byte value)
byte read8(byte address, byte reg)
byte readBuffer(byte address, byte reg, byte len, uint8_t *buffer)
uint8_t spixfer(uint8_t data)
bool getEvent(sensors_event_t *accel, sensors_event_t *mag, sensors_event_t *gyro, sensors_event_t *temp)

Gets the most recent accel sensor event.

void getSensor(sensor_t *accel, sensor_t *mag, sensor_t *gyro, sensor_t *temp)

Gets the sensor_t data.

Sensor &getAccel(void)
Sensor &getMag(void)
Sensor &getGyro(void)
Sensor &getTemp(void)

Public Members

lsm9ds1Vector_t accelData
lsm9ds1Vector_t magData
lsm9ds1Vector_t gyroData
int16_t temperature

Private Functions

void getAccelEvent(sensors_event_t *event, uint32_t timestamp)
void getMagEvent(sensors_event_t *event, uint32_t timestamp)
void getGyroEvent(sensors_event_t *event, uint32_t timestamp)
void getTempEvent(sensors_event_t *event, uint32_t timestamp)
void getAccelSensor(sensor_t *sensor)
void getMagSensor(sensor_t *sensor)
void getGyroSensor(sensor_t *sensor)
void getTempSensor(sensor_t *sensor)

Private Members

bool _i2c
int8_t _csm
int8_t _csxg
int8_t _mosi
int8_t _miso
int8_t _clk
float _accel_mg_lsb
float _mag_mgauss_lsb
float _gyro_dps_digit
int32_t _lsm9dso_sensorid_accel
int32_t _lsm9dso_sensorid_mag
int32_t _lsm9dso_sensorid_gyro
int32_t _lsm9dso_sensorid_temp
Sensor _accelSensor
Sensor _magSensor
Sensor _gyroSensor
Sensor _tempSensor
I2C *i2c
high_resolution_clock::time_point t0
high_resolution_clock::time_point t1
class Adafruit_Sensor

Subclassed by Adafruit_BNO055, Adafruit_LSM9DS1::Sensor

Public Functions

Adafruit_Sensor()
virtual ~Adafruit_Sensor()
virtual void enableAutoRange(bool enabled)
virtual bool getEvent(sensors_event_t *) = 0
virtual void getSensor(sensor_t *) = 0

Private Members

bool _autoRange
class AM4096

Public Functions

AM4096(int32_t *baseAddr)

Constructor.

Parameters
  • baseAddr: fpga i2C base address

AM4096(int32_t *baseAddr, vector<int> &i2cAddrs)

Constructor.

Parameters
  • baseAddr: fpga i2C base address
  • i2cAddrs: vector of device ids

~AM4096()
void readAbsAngle(vector<uint32_t> &absAngles)

Reads the absolute angles of all devices.

Parameters
  • absAngles: the angles

bool readAbsAngle(uint8_t i2cAddr, uint32_t &absAngle)

Reads the ansolute angle of a device.

Return
dataOK
Parameters
  • i2cAddr: the device id
  • absAngle: the angle

void readRelAngle(vector<uint32_t> &relAngles)

Reads the relative angles of all devices.

Parameters
  • relAngles: the angles

bool readRelAngle(uint8_t i2cAddr, uint32_t &relAngle)

Reads the relative angle of a device.

Return
dataOK
Parameters
  • i2cAddr: the device id
  • relAngle: the angle

void readMagnetStatus(vector<bool> &magnetTooFar, vector<bool> &magnetTooClose)

Reads the magnet status of all devices.

Parameters
  • magnetTooFar:
  • magnetTooClose:

void readMagnetStatus(vector<unsigned char> &magnetTooFar, vector<unsigned char> &magnetTooClose)
void readMagnetStatus(uint8_t i2cAddr, bool &magnetTooFar, bool &magnetTooClose)

Reads the magnet status of a device.

Parameters
  • i2cAddr: the device id
  • magnetTooFar:
  • magnetTooClose:

void readAgcGain(vector<uint8_t> &agcGain)

Reads AGC gain (magnet “power”) of all devices.

Parameters
  • agcGain: the gains

void readAgcGain(uint8_t i2cAddr, uint8_t &agcGain)

Reads AGC gain (magnet “power”)

Parameters
  • i2cAddr: address
  • agcGain: the gain

void readTacho(vector<uint32_t> &tacho)

Reads tacho of all devices.

Parameters
  • tacho: tacho values

bool readTacho(uint8_t i2cAddr, uint32_t &tacho)

Reads tacho, returns.

Return
tacho overflow.
Parameters
  • i2cAddr: address
  • tacho: tacho value

Public Members

vector<int> i2cAddrs

Private Members

void *h2p_lw_i2c_addr
I2C *i2c
class ArmControl

Public Functions

ArmControl(int32_t *myo_base)
~ArmControl()
void handCommandCB(const roboy_middleware_msgs::HandCommand::ConstPtr &msg)

Callback for hand command.

Parameters
  • msg: hand command

void fingerCommandCB(const roboy_middleware_msgs::FingerCommand::ConstPtr &msg)

Callback for finger command.

Parameters
  • msg: finger command

Private Members

ros::NodeHandlePtr nh
ros::Subscriber handCommand_sub
ros::Subscriber fingerCommand_sub
ros::Publisher armStatus_pub
bool keep_publishing = true
int32_t *myo_base
int elbow_agonist = 1
int elbow_antagonist = 0
vector<uint8_t> handDeviceIDs
uint8_t id = 0
bool elbow_joint_controller_active = true
float elbow_joint_angle = 0
string hand
class CRC32
#include <CRC32.h>

A class for calculating the CRC32 checksum from arbitrary data.

See
http://forum.arduino.cc/index.php?topic=91179.0

Public Functions

CRC32()

Initialize an empty CRC32 checksum.

void reset()

Reset the checksum claculation.

void update(const uint8_t &data)

Update the current checksum caclulation with the given data.

Parameters
  • data: The data to add to the checksum.

template<typename Type>
void update(const Type &data)

Update the current checksum caclulation with the given data.

Template Parameters
  • Type: The data type to read.
Parameters
  • data: The data to add to the checksum.

template<typename Type>
void update(const Type *data, size_t size)

Update the current checksum caclulation with the given data.

Template Parameters
  • Type: The data type to read.
Parameters
  • data: The array to add to the checksum.
  • size: Size of the array to add.

uint32_t finalize() const

Return
the caclulated checksum.

Public Static Functions

template<typename Type>
static uint32_t calculate(const Type *data, size_t size)

Calculate the checksum of an arbitrary data array.

Return
the calculated checksum.
Template Parameters
  • Type: The data type to read.
Parameters
  • data: A pointer to the data to add to the checksum.
  • size: The size of the data to add to the checksum.

Private Members

uint32_t _state = ~0L

The internal checksum state.

class I2C

Public Functions

I2C(void *baseAddr)

Constructor.

Parameters
  • baseAddr: i2c base address (cf hps_0.h)

void write(uint8_t i2cAddr, uint32_t data, uint8_t number_of_bytes)

Writes up to three bytes to an address.

Parameters
  • i2cAddr: device address
  • data: (reg<<24|data[0]<<16|data[1]<<8|data[2])
  • number_of_bytes: length(data)+1 for register

void read(uint8_t i2cAddr, uint8_t reg, uint8_t number_of_bytes, vector<uint8_t> &data)

Reads up to number of bytes from i2c slave.

Parameters
  • i2cAddr: i2c slave address
  • reg: start register
  • number_of_bytes: hwo many bytes should be read
  • data: will be filled with the read data

void read_continuous(uint8_t i2cAddr, uint8_t number_of_bytes, vector<uint8_t> &data)

Reads up to number of bytes from i2c slave, without start register (behaviour depends on slave device)

Parameters
  • i2cAddr: i2c slave address
  • number_of_bytes: hwo many bytes should be read
  • data: will be filled with the read data

bool ack_error()

Queries for acknowledge error.

Return
error/no error

bool checkAddressSpace(uint8_t fromDeviceID, uint8_t toDeviceID, vector<uint8_t> &activeDevices)

Scans the provided address range for active devices.

Return
true if at least one active device was found
Parameters
  • fromDeviceID: start address
  • toDeviceID: end address
  • activeDevices: will be filled with active device addresses

Public Members

const uint8_t ADDR = 0
const uint8_t DATA = 1
const uint8_t RW = 2
const uint8_t ENA = 3
const uint8_t NUMBER_OF_BYTES = 4
const uint8_t GPIO_CONTROL = 5
const uint8_t READ_ONLY = 6
const uint8_t RESET_TLV = 7
const uint8_t BUSY = 4
const uint8_t ACK_ERROR = 5
const uint8_t FIFO_SIZE = 6
const uint8_t WRITE = 0
const uint8_t READ = 1

Private Members

void *h2p_lw_i2c_addr
class MyoControl

Public Functions

MyoControl(vector<int32_t *> &myo_base)

Constructor.

Parameters
  • myo_base: vector of myo base addresses (cf hps_0.h)

MyoControl(vector<int32_t *> &myo_base, int32_t *adc_base)

Alternative Constructor.

Parameters
  • myo_base: vector of myo base addresses (cf hps_0.h)
  • adc_base: adc base address (cf hps_0.h)

~MyoControl()
void changeControl(int motor, int mode, control_Parameters_t &params, int32_t setPoint)

Changes the controller of a motor.

Parameters
  • motor: for this motor
  • mode: choose from Position, Velocity or Displacement
  • params: with these controller parameters
  • setPoint: new setPoint

void changeControl(int motor, int mode, control_Parameters_t &params)

Changes the controller of a motor.

Parameters
  • motor: for this motor
  • mode: choose from Position, Velocity or Displacement
  • params: with these controller parameters

void changeControl(int motor, int mode)

Changes the controller of a motor with the saved controller parameters.

Parameters
  • motor: for this motor
  • mode: choose from Position, Velocity or Displacement

void changeControl(int mode)

Changes the controller of ALL motors with the saved controller parameters.

Parameters
  • mode: choose from Position, Velocity or Displacement

void changeControlParameters(int motor, control_Parameters_t &params)

Changes the controller parameters of a motor.

Parameters
  • motor: for this motor
  • params: with these controller parameters

void reset()

Resets all myo controllers.

bool setSPIactive(int motor, bool active)

Sets the spi state for the interface of a motor.

Parameters
  • motor:
  • active:
  • active/not: active

void getPIDcontrollerParams(int &Pgain, int &Igain, int &Dgain, int &forwardGain, int &deadband, int &setPoint, int &outputDivider, int motor)

Get the parameters for the PID controller of a motor.

Parameters
  • motor: for this motor

void setPIDcontrollerParams(uint16_t Pgain, uint16_t Igain, uint16_t Dgain, uint16_t forwardGain, uint16_t deadband, int motor, int mode)

Get the parameters for the PID controller of a motor.

Parameters
  • motor: for this motor

uint16_t getControlMode(int motor)

Gets the current control_mode of a motor.

Parameters
  • motor: for this motor

int32_t getMotorAngle(int motor)

Gets the motor angle of a myo brick.

Return
angle in ticks
Parameters
  • motor:

int32_t getMotorAnglePrev(int motor)

Gets the motor angle of a myo brick.

Return
angle in ticks
Parameters
  • motor:

int32_t getRawMotorAngle(int motor)

Gets the raw motor angle of a myo brick.

Return
angle in ticks
Parameters
  • motor:

int32_t getRelativeMotorAngle(int motor)

Gets the raw motor angle of a myo brick.

Return
angle in ticks
Parameters
  • motor:

int32_t getMotorAngleOffset(int motor)

Gets the raw motor angle of a myo brick.

Return
angle in ticks
Parameters
  • motor:

int32_t getRevolutionCounter(int motor)

Gets the motor angle revolution counter of a myo brick.

Return
angle in ticks
Parameters
  • motor:

bool getPowerSense()

Get the power sense.

Return
true (power on), false (power off)

int16_t getPWM(int motor)

Gets the current pwm of a motor.

Parameters
  • motor: for this motor

int32_t getPosition(int motor)

Gets the current position of a motor in radians.

Parameters
  • motor: for this motor

int32_t getVelocity(int motor)

Gets the current velocity of a motor in radians/seconds.

Parameters
  • motor: for this motor

int32_t getDisplacement(int motor)

Gets the displacement in encoder ticks.

Parameters
  • motor: for this motor

void setPosition(int motor, int32_t setPoint)

Sets the position of a motor in radians.

Parameters
  • motor: for this motor

void setVelocity(int motor, int32_t setPoint)

Sets the current velocity of a motor in radians/seconds.

Parameters
  • motor: for this motor

void setDisplacement(int motor, int16_t setPoint)

Set the displacement in encoder ticks.

Parameters
  • motor: for this motor

bool configureMyoBricks(vector<uint8_t> &motorIDs, vector<uint8_t> &deviceIDs, vector<int32_t> &encoderMultiplier, vector<int32_t> &gearBoxRatio)

Configures motors to be handled as myoBricks.

Parameters
  • motorIDs: these are the ids of the motors
  • deviceIDs: these are the i2c addresses of the motor angle sensors (A1335)
  • encoderMultiplier: this multiplies the output of the optical encoder
  • gearBoxRatio: the ratio of the gear box for each myoBrick

int16_t getCurrent(int motor)

Gets the current in Ampere.

Parameters
  • motor: for this motor

void getDefaultControlParams(control_Parameters_t *params, int control_mode)

Fills the given params with default values for the corresponding control mode.

Parameters
  • params: pointer to control struct
  • control_mode: Position, Velocity, Force

void allToPosition(int32_t pos)

Changes the control mode for all motors to Position.

Parameters
  • pos: new setPoint

void allToVelocity(int32_t vel)

Changes the control mode for all motors to Velocity.

Parameters
  • pos: new setPoint

void allToDisplacement(int16_t displacement)

Changes the control mode for all motors to Displacement.

Parameters
  • force: new setPoint

void zeroWeight(int load_cell = 0)

Zeros the weight for a load cell.

Parameters
  • load_cell: for this load cell

uint32_t readADC(int load_cell)

Returns the current adc of the load cell.

Return
the adc value
Parameters
  • load_cell: for this load cell

float getWeight(int load_cell)

Returns the current weight according to adc_weight_parameters of a load_cell.

Return
the load
Parameters
  • load_cell: for this load cell

float getWeight(int load_cell, uint32_t &adc_value)

Returns the current weight according to adc_weight_parameters of a load_cell.

Return
the load
Parameters
  • load_cell: for this load cell
  • the: adc value

float recordTrajectories(float samplingTime, float recordTime, map<int, vector<float>> &trajectories, vector<int> &idList, vector<int> &controlmode, string name)

records positions of motors in Displacement mode

Parameters
  • samplingTime:
  • recordTime:
  • trajectories: will be filled with positions
  • idList: record these motors
  • controlmode: in this mode
  • name: filename

float startRecordTrajectories(float samplingTime, map<int, vector<float>> &trajectories, vector<int> &idList, string name)

starts recording positions of motors in Displacement mode

Parameters
  • samplingTime:
  • trajectories: will be filled with positions
  • idList: record these motors
  • name: filename

void stopRecordTrajectories()

stops recording a trajectory and writes to file

bool playTrajectory(const char *file)

Plays back a trajectory.

Return
success
Parameters
  • file:

void setPredisplacement(int value)

Sets predisplacement for recording trajectories (50 by default)

Parameters
  • value:

void setReplay(bool status)

Enables/disables replaying trajectory.

Parameters
  • replay:

void estimateSpringParameters(int motor, int degree, vector<float> &coeffs, int timeout, uint numberOfDataPoints, float displacement_min, float displacement_max, vector<double> &load, vector<double> &displacement)

Estimates the spring parameters of a motor by pulling with variable forces keeping track of displacement and weight, it will either timeout or stop when the requested number of samples was reached.

Parameters
  • motor: for this motor
  • degree: the degree for the polynomial regression
  • coeffs: these are the result from the polynomial regression
  • timeout: in milliseconds
  • numberOfDataPoints: how many samples do you wanne collect
  • displacement_min: the minimal displacement to be sampled from
  • displacement_min: the maximal displacement to be sampled from
  • load: will be filled with the load cell data
  • displacement: will be filled with the displacement

void estimateMotorAngleLinearisationParameters(int motor, int degree, vector<float> &coeffs, int timeout, uint numberOfDataPoints, float delta_revolution_negative, float delta_revolution_positive, vector<double> &motor_angle, vector<double> &motor_encoder)

Estimates the linearisation parameters of a myobrick by turning the motor and measuring the positions from the motor angle sensor.

The optical encoder data is then used to estimate linearisation parameters

Parameters
  • motor: for this motor
  • degree: the degree for the polynomial regression
  • coeffs: these are the result from the polynomial regression
  • timeout: in milliseconds
  • numberOfDataPoints: how many samples do you wanne collect
  • delta_revolution_negative: value to turn the motor to into negative direction in degrees
  • delta_revolution_positive: value to turn the motor to into negative direction in degrees
  • motor_angle: will be filled with the a1339 motor_angle data (values between 0-4095)
  • motor_encoder: will be filled with positions from the optical encoder (values between 0-4095)

void polynomialRegression(int degree, vector<double> &x, vector<double> &y, vector<float> &coeffs)

Performs polynomial regression (http://www.bragitoff.com/2015/09/c-program-for-polynomial-fit-least-squares/)

Parameters
  • degree: (e.g. 2 -> a * x^0 + b * x^1 + c * x^2)
  • coeffs: the estimated coefficients
  • X: the x-data
  • Y: the y-data

void gpioControl(bool power)

Public Members

int myo_base_of_motor[NUMBER_OF_MOTORS_PER_FPGA]
int motor_offset[NUMBER_OF_MOTORS_PER_FPGA]
map<int, map<int, control_Parameters_t>> control_params
vector<uint8_t> myo_bricks
vector<int32_t> myo_bricks_gearbox_ratio
vector<int32_t> myo_bricks_encoder_multiplier
int32_t *adc_base
float weight_offset = 0
float adc_weight_parameters[2] = {-89.6187, 0.1133}
uint numberOfMotors
const string trajectories_folder = "/home/root/trajectories/"
const string behaviors_folder = "/home/root/behaviors/"

Private Members

Timer timer
vector<int32_t *> myo_base
int iter = 0
bool recording = false
bool replay = true
int predisplacement = 100
class PerformMovementAction

Public Functions

PerformMovementAction(boost::shared_ptr<MyoControl> myoControl, string name)
void executeCB(const roboy_control_msgs::PerformMovementGoalConstPtr &goal)

Protected Attributes

ros::NodeHandle nh_
boost::shared_ptr<MyoControl> myoControl
string action_name
actionlib::SimpleActionServer<roboy_control_msgs::PerformMovementAction> performMovement_as
roboy_control_msgs::PerformMovementFeedback feedback
roboy_control_msgs::PerformMovementResult result
class PerformMovementsAction

Public Functions

PerformMovementsAction(boost::shared_ptr<MyoControl> myoControl, string name)
void executeCB(const roboy_control_msgs::PerformMovementsGoalConstPtr &goal)

Protected Attributes

ros::NodeHandle nh_
boost::shared_ptr<MyoControl> myoControl
string action_name
actionlib::SimpleActionServer<roboy_control_msgs::PerformMovementsAction> performMovements_as
roboy_control_msgs::PerformMovementsFeedback feedback
roboy_control_msgs::PerformMovementsResult result
class RoboyPlexus

Public Functions

RoboyPlexus(MyoControlPtr myoControl, vector<int32_t *> &myo_base, vector<int32_t *> &i2c_base = DEFAULT_POINTER_VECTOR, int32_t *darkroom_base = nullptr, vector<int32_t *> &darkroom_ootx_addr = DEFAULT_POINTER_VECTOR, int32_t *adc_base = nullptr, int32_t *switches_base = nullptr)
~RoboyPlexus()
string getBodyPart()
void motorStatusPublisher()

Publishes information about motors.

Public Members

uint8_t data[33]
uint16_t fw_version
uint32_t ID
uint16_t fcal_0_phase
uint16_t fcal_1_phase
uint16_t fcal_0_tilt
uint16_t fcal_1_tilt
uint8_t unlock_count
uint8_t hw_version
uint16_t fcal_0_curve
uint16_t fcal_1_curve
int8_t accel_dir_x
int8_t accel_dir_y
int8_t accel_dir_z
uint16_t fcal_0_gibphase
uint16_t fcal_1_gibphase
uint16_t fcal_0_gibmag
uint16_t fcal_1_gibmag
uint8_t mode
uint8_t faults
struct RoboyPlexus::[anonymous]::[anonymous] frame

Private Functions

void gsensorPublisher()

Publishes IMU data.

void adcPublisher()

Publishes ADC values.

void testBenchPublisher()

Publishes sensor values measured in the test rig.

void darkRoomPublisher()

Publishes lighthouse sensor values.

void darkRoomOOTXPublisher()

Publishes decoded lighthouse ootx data.

void motorAnglePublisher()

Publishes motor angles.

void magneticShoulderJointPublisher()

Publishes 3d magnetic information about shoulder joint.

void motorCommandCB(const roboy_middleware_msgs::MotorCommand::ConstPtr &msg)

Callback for motor command.

Parameters
  • msg: motor command

void motorAnglePID()

Motor Angle PID controller.

bool HandPower(std_srvs::SetBool::Request &req, std_srvs::SetBool::Response &res)

Service for turning on/off hand.

Return
success
Parameters
  • req:
  • res:

bool MotorConfigService(roboy_middleware_msgs::MotorConfigService::Request &req, roboy_middleware_msgs::MotorConfigService::Response &res)

Service for changing motor PID parameters.

Return
success
Parameters
  • req: PID parameters
  • res: success

bool ControlModeService(roboy_middleware_msgs::ControlMode::Request &req, roboy_middleware_msgs::ControlMode::Response &res)

Service for changing the control mode of motors, perviously set PID parameters are restored.

Return
success
Parameters
  • req: control mode
  • res:

bool MotorCalibrationService(roboy_middleware_msgs::MotorCalibrationService::Request &req, roboy_middleware_msgs::MotorCalibrationService::Response &res)

Service for motor spring calibration, samples the spring space for a requested amount of time and estimates spring coefficients.

Return
Parameters
  • req:
  • res:

bool MyoBrickCalibrationService(roboy_middleware_msgs::MyoBrickCalibrationService::Request &req, roboy_middleware_msgs::MyoBrickCalibrationService::Response &res)

Service for calibrating the motor angle sensor.

Return
Parameters
  • req:
  • res:

bool EmergencyStopService(std_srvs::SetBool::Request &req, std_srvs::SetBool::Response &res)

Emergency stop service, zeros all PID gains, causing all motors to stop, PID parameters and control mode are restored on release.

Return
Parameters
  • req:
  • res:

bool SystemCheckService(roboy_middleware_msgs::SystemCheck::Request &req, roboy_middleware_msgs::SystemCheck::Response &res)

Service for system check.

Return
Parameters
  • req:
  • res:

void StartRecordTrajectoryCB(const roboy_control_msgs::StartRecordTrajectory::ConstPtr &msg)

Motor setpoints trajectory recording callback.

Return
Parameters
  • msg:

void StopRecordTrajectoryCB(const std_msgs::Empty::ConstPtr &msg)

Callback stops recording the trajectory.

Return
Parameters
  • msg:

void SaveBehaviorCB(const roboy_control_msgs::Behavior &msg)

Callback saves behavior.

Parameters
  • msg:

void PredisplacementCB(const std_msgs::Int32 &msg)

Callback updates the displacement for recording trajectories.

Parameters
  • msg:

void EnablePlaybackCB(const std_msgs::Bool::ConstPtr &msg)

Stops replaying the trajectory.

Parameters
  • msg:

bool ListExistingItemsService(roboy_control_msgs::ListItems::Request &req, roboy_control_msgs::ListItems::Response &res)

Service return a list of files in the requested folder.

Return
Parameters
  • req:
  • res:

bool ExpandBehaviorService(roboy_control_msgs::ListItems::Request &req, roboy_control_msgs::ListItems::Response &res)

Service returns the list of actions in the requested behavior.

Return
Parameters
  • req:
  • res:

bool SetDisplacementForAll(roboy_middleware_msgs::SetInt16::Request &req, roboy_middleware_msgs::SetInt16::Request &res)

Service sets displacement for all motors.

Return
Parameters
  • req:
  • res:

uint8_t rev(uint8_t b)

Reverses the bit order of a byte, eg.

0b00001011 -> 0b11010000

Return
reversed byte
Parameters
  • b: input byte

uint32_t reverse(uint32_t b)

Reverses the bit order of each byte in a 4 byte uint32_t.

Return
reversed uint32_t
Parameters
  • b: input

bool ADXL345_REG_WRITE(int file, uint8_t address, uint8_t value)
bool ADXL345_REG_READ(int file, uint8_t address, uint8_t *value)
bool ADXL345_REG_MULTI_READ(int file, uint8_t readaddr, uint8_t readdata[], uint8_t len)
bool ADXL345_Init(int file)
bool ADXL345_IsDataReady(int file)
bool ADXL345_XYZ_Read(int file, uint16_t szData16[3])
bool ADXL345_IdRead(int file, uint8_t *pId)
bool executeAction(string actions)
bool executeActions(vector<string> actions)
vector<string> expandBehavior(string name)

Private Members

ros::NodeHandlePtr nh
boost::shared_ptr<ros::AsyncSpinner> spinner
ros::Subscriber motorCommand_sub
ros::Subscriber startRecordTrajectory_sub
ros::Subscriber stopRecordTrajectory_sub
ros::Subscriber saveBehavior_sub
ros::Subscriber enablePlayback_sub
ros::Subscriber predisplacement_sub
ros::Publisher motorStatus_pub
ros::Publisher darkroom_pub
ros::Publisher darkroom_ootx_pub
ros::Publisher darkroom_status_pub
ros::Publisher adc_pub
ros::Publisher gsensor_pub
ros::Publisher motorAngle_pub
ros::Publisher magneticSensor_pub
ros::Publisher testbench_pub
ros::ServiceServer motorConfig_srv
ros::ServiceServer controlMode_srv
ros::ServiceServer emergencyStop_srv
ros::ServiceServer motorCalibration_srv
ros::ServiceServer replayTrajectory_srv
ros::ServiceServer executeActions_srv
ros::ServiceServer executeBehavior_srv
ros::ServiceServer handPower_srv
ros::ServiceServer setDisplacementForAll_srv
ros::ServiceServer listExistingTrajectories_srv
ros::ServiceServer listExistingBehaviors_srv
ros::ServiceServer expandBehavior_srv
ros::ServiceServer soliGetData_srv
ros::ServiceServer soli_srv
ros::ServiceServer soliGetFrameFormat_srv
ros::ServiceServer soliSetFrameFormat_srv
ros::ServiceServer soliGetAdcSamplerate_srv
ros::ServiceServer soliSetAdcSamplerate_srv
ros::ServiceServer soliGetChirpDuration_srv
ros::ServiceServer soliSetFMCWConfiguration_srv
ros::ServiceServer soliGetFMCWConfiguration_srv
ros::ServiceServer soliGetFrameInfo_srv
ros::ServiceServer myobrick_calibration_srv
map<int, int> setPoint_backup
map<int, map<int, control_Parameters_t>> control_params_backup
map<int, int> control_mode
map<int, int> control_mode_backup
map<int, int> rotationCounter
map<int, float> motorAngles
boost::shared_ptr<MyoControl> myoControl
boost::shared_ptr<A1335> a1335
boost::shared_ptr<std::thread> adcThread
boost::shared_ptr<std::thread> darkRoomThread
boost::shared_ptr<std::thread> darkRoomOOTXThread
boost::shared_ptr<std::thread> motorStatusThread
boost::shared_ptr<std::thread> gsensor_thread
boost::shared_ptr<std::thread> motorAngleThread
boost::shared_ptr<std::thread> jointAngleThread
boost::shared_ptr<std::thread> magneticsShoulderThread
boost::shared_ptr<std::thread> testbenchThread
bool keep_publishing = true
int32_t *darkroom_base
int32_t *adc_base
int32_t *switches_base
vector<int32_t *> myo_base
vector<int32_t *> i2c_base
vector<int32_t *> darkroom_ootx_addr
bool emergency_stop = false
vector<boost::shared_ptr<A1335>> motorAngle
vector<boost::shared_ptr<A1335>> jointAngle
int file
const char *filename = "/dev/i2c-0"
uint8_t id
bool bSuccess
const int mg_per_digi = 4
uint16_t szXYZ[3]
int cnt = 0
int max_cnt = 0
union RoboyPlexus::[anonymous] ootx
uint32_t ootx_sensor_channel = 0
string ethaddr
vector<boost::shared_ptr<TLV493D_FPGA>> tlv493D0
string body_part
vector<string> body_parts
class Sensor : public Adafruit_Sensor

Public Functions

Sensor()
Sensor(const Sensor &copy)
Sensor(Adafruit_LSM9DS1 *parent, lsm9ds1_read_func readFunc, lsm9ds1_get_event_func eventFunc, lsm9ds1_get_sensor_func sensorFunc)
virtual bool getEvent(sensors_event_t *event)
virtual void getSensor(sensor_t *sensor)

Private Members

Adafruit_LSM9DS1 *_parent
lsm9ds1_read_func _readFunc
lsm9ds1_get_event_func _eventFunc
lsm9ds1_get_sensor_func _sensorFunc
struct sensor_t
#include <Adafruit_Sensor.h>

struct sensor_s is used to describe basic information about a specific sensor.

Public Members

char name[12]

sensor name

int32_t version

version of the hardware + driver

int32_t sensor_id

unique sensor identifier

int32_t type

this sensor’s type (ex.

SENSOR_TYPE_LIGHT)

float max_value

maximum value of this sensor’s value in SI units

float min_value

minimum value of this sensor’s value in SI units

float resolution

smallest difference between two values reported by this sensor

int32_t min_delay

min delay in microseconds between events.

zero = not a constant rate

struct sensors_color_t
#include <Adafruit_Sensor.h>

struct sensors_color_s is used to return color data in a common format.

Public Members

float c[3]
float r

Red component.

float g

Green component.

float b

Blue component.

union sensors_color_t::[anonymous] [anonymous]
uint32_t rgba

24-bit RGBA value

struct sensors_event_t
#include <Adafruit_Sensor.h>

struct sensor_event_s is used to provide a single sensor event in a common format.

Public Members

int32_t version

must be sizeof(struct sensors_event_t)

int32_t sensor_id

unique sensor identifier

int32_t type

sensor type

int32_t reserved0

reserved

int32_t timestamp

time is in milliseconds

float data[4]
sensors_vec_t acceleration

acceleration values are in meter per second per second (m/s^2)

sensors_vec_t magnetic

magnetic vector values are in micro-Tesla (uT)

sensors_vec_t orientation

orientation values are in degrees

sensors_vec_t gyro

gyroscope values are in rad/s

float temperature

temperature is in degrees centigrade (Celsius)

float distance

distance in centimeters

float light

light in SI lux units

float pressure

pressure in hectopascal (hPa)

float relative_humidity

relative humidity in percent

float current

current in milliamps (mA)

float voltage

voltage in volts (V)

sensors_color_t color

color in RGB component values

union sensors_event_t::[anonymous] [anonymous]
struct sensors_vec_t
#include <Adafruit_Sensor.h>

struct sensors_vec_s is used to return a vector in a common format.

Public Members

float v[3]
float x
float y
float z
float roll

Rotation around the longitudinal axis (the plane body, ‘X axis’).

Roll is positive and increasing when moving downward. -90°<=roll<=90°

float pitch

Rotation around the lateral axis (the wing span, ‘Y axis’).

Pitch is positive and increasing when moving upwards. -180°<=pitch<=180°)

float heading

Angle between the longitudinal axis (the plane body) and magnetic north, measured clockwise when viewing from the top of the device.

0-359°

union sensors_vec_t::[anonymous] [anonymous]
int8_t status
uint8_t reserved[3]
class TLV493D

Public Functions

TLV493D(int32_t *i2c_base)
~TLV493D()
bool initTLV(uint8_t &deviceaddress, int devicepin)
void reset()
float convertToMilliTesla(uint8_t MSB, uint8_t LSB)
void readAllRegisters(int deviceaddress, vector<uint8_t> &reg, bool print = true)
bool read(float &fx, float &fy, float &fz)

Public Members

boost::shared_ptr<I2C> i2c
int32_t *i2c_base

Private Functions

bool checkParity(uint32_t val)

checks the parity of 32 bit val

Return
true if odd, false if even
Parameters
  • val:

Private Members

vector<uint8_t> deviceAddress
uint8_t gpioreg = 0
uint8_t frameCounter = 0
class TLV493D_FPGA

Public Functions

TLV493D_FPGA(int32_t *i2c_base)
~TLV493D_FPGA()
float convertToMilliTesla(int32_t data)
bool read(float &fx, float &fy, float &fz)

Public Members

int32_t *tlv_base
struct vector_s

Public Members

float x
float y
float z
namespace std
namespace chrono
file A1335.hpp
#include “roboy_plexus/i2c.hpp”#include <iostream>#include <ros/ros.h>

Defines

FLAGS_STRLEN
ANGLES_FLAGS
STATUS_FLAGS
ERROR_FLAGS
XERROR_FLAGS

Typedefs

typedef boost::shared_ptr<A1335> A1335Ptr
file Adafruit_BNO055.hpp
#include <cstdint>#include “i2c.hpp”#include “roboy_plexus/Adafruit_Sensor.h”#include “roboy_plexus/utility/imumaths.h”#include <chrono>

Defines

IOWR_32DIRECT(base, offset, data)
BNO055_ADDRESS_A
BNO055_ADDRESS_B
BNO055_ID
NUM_BNO055_OFFSET_REGISTERS

Typedefs

typedef uint8_t byte
file Adafruit_LSM9DS1.hpp
#include “i2c.hpp”#include “roboy_plexus/Adafruit_Sensor.h”#include <cstring>

Defines

LSM9DS1_ADDRESS_ACCELGYRO
LSM9DS1_ADDRESS_MAG
LSM9DS1_XG_ID
LSM9DS1_MAG_ID
LSM9DS1_ACCEL_MG_LSB_2G
LSM9DS1_ACCEL_MG_LSB_4G
LSM9DS1_ACCEL_MG_LSB_8G
LSM9DS1_ACCEL_MG_LSB_16G
LSM9DS1_MAG_MGAUSS_4GAUSS
LSM9DS1_MAG_MGAUSS_8GAUSS
LSM9DS1_MAG_MGAUSS_12GAUSS
LSM9DS1_MAG_MGAUSS_16GAUSS
LSM9DS1_GYRO_DPS_DIGIT_245DPS
LSM9DS1_GYRO_DPS_DIGIT_500DPS
LSM9DS1_GYRO_DPS_DIGIT_2000DPS
LSM9DS1_TEMP_LSB_DEGREE_CELSIUS
MAGTYPE
XGTYPE

Typedefs

typedef void (Adafruit_LSM9DS1::*lsm9ds1_read_func)(void)
typedef void (Adafruit_LSM9DS1::*lsm9ds1_get_event_func)(sensors_event_t *, uint32_t)
typedef void (Adafruit_LSM9DS1::*lsm9ds1_get_sensor_func)(sensor_t *)
file Adafruit_Sensor.h
#include <cstdint>#include <chrono>

Defines

SENSORS_GRAVITY_EARTH

Earth’s gravity in m/s^2.

SENSORS_GRAVITY_MOON

The moon’s gravity in m/s^2.

SENSORS_GRAVITY_SUN

The sun’s gravity in m/s^2.

SENSORS_GRAVITY_STANDARD
SENSORS_MAGFIELD_EARTH_MAX

Maximum magnetic field on Earth’s surface.

SENSORS_MAGFIELD_EARTH_MIN

Minimum magnetic field on Earth’s surface.

SENSORS_PRESSURE_SEALEVELHPA

Average sea level pressure is 1013.25 hPa.

SENSORS_DPS_TO_RADS

Degrees/s to rad/s multiplier.

SENSORS_GAUSS_TO_MICROTESLA

Gauss to micro-Tesla multiplier.

Typedefs

typedef uint8_t byte

Enums

enum sensors_type_t

Sensor types.

Values:

SENSOR_TYPE_ACCELEROMETER = (1)

Gravity + linear acceleration.

SENSOR_TYPE_MAGNETIC_FIELD = (2)
SENSOR_TYPE_ORIENTATION = (3)
SENSOR_TYPE_GYROSCOPE = (4)
SENSOR_TYPE_LIGHT = (5)
SENSOR_TYPE_PRESSURE = (6)
SENSOR_TYPE_PROXIMITY = (8)
SENSOR_TYPE_GRAVITY = (9)
SENSOR_TYPE_LINEAR_ACCELERATION = (10)

Acceleration not including gravity.

SENSOR_TYPE_ROTATION_VECTOR = (11)
SENSOR_TYPE_RELATIVE_HUMIDITY = (12)
SENSOR_TYPE_AMBIENT_TEMPERATURE = (13)
SENSOR_TYPE_VOLTAGE = (15)
SENSOR_TYPE_CURRENT = (16)
SENSOR_TYPE_COLOR = (17)
file ADXL345.h
#include “hwlib.h”#include <cstdint>

Defines

XL345_RATE_3200
XL345_RATE_1600
XL345_RATE_800
XL345_RATE_400
XL345_RATE_200
XL345_RATE_100
XL345_RATE_50
XL345_RATE_25
XL345_RATE_12_5
XL345_RATE_6_25
XL345_RATE_3_125
XL345_RATE_1_563
XL345_RATE__782
XL345_RATE__39
XL345_RATE__195
XL345_RATE__098
XL345_RANGE_2G
XL345_RANGE_4G
XL345_RANGE_8G
XL345_RANGE_16G
XL345_DATA_JUST_RIGHT
XL345_DATA_JUST_LEFT
XL345_10BIT
XL345_FULL_RESOLUTION
XL345_INT_LOW
XL345_INT_HIGH
XL345_SPI3WIRE
XL345_SPI4WIRE
XL345_SELFTEST
XL345_OVERRUN
XL345_WATERMARK
XL345_FREEFALL
XL345_INACTIVITY
XL345_ACTIVITY
XL345_DOUBLETAP
XL345_SINGLETAP
XL345_DATAREADY
XL345_WAKEUP_8HZ
XL345_WAKEUP_4HZ
XL345_WAKEUP_2HZ
XL345_WAKEUP_1HZ
XL345_SLEEP
XL345_MEASURE
XL345_STANDBY
XL345_AUTO_SLEEP
XL345_ACT_INACT_SERIAL
XL345_ACT_INACT_CONCURRENT
ADXL345_REG_DEVID
ADXL345_REG_POWER_CTL
ADXL345_REG_DATA_FORMAT
ADXL345_REG_FIFO_CTL
ADXL345_REG_BW_RATE
ADXL345_REG_INT_ENALBE
ADXL345_REG_INT_MAP
ADXL345_REG_INT_SOURCE
ADXL345_REG_DATA_FORMAT
ADXL345_REG_DATAX0
ADXL345_REG_DATAX1
ADXL345_REG_DATAY0
ADXL345_REG_DATAY1
ADXL345_REG_DATAZ0
ADXL345_REG_DATAZ1
file am4096.hpp
#include <bitset>#include <iostream>#include <vector>#include <ros/ros.h>#include <roboy_plexus/i2c.hpp>
file armControl.hpp
#include <ros/ros.h>#include <thread>#include <roboy_middleware_msgs/FingerCommand.h>#include <roboy_middleware_msgs/ArmStatus.h>#include <roboy_middleware_msgs/HandCommand.h>#include <roboy_middleware_msgs/JointController.h>#include <roboy_control_msgs/SetMode.h>#include <std_msgs/Float32.h>#include <std_srvs/SetBool.h>#include “roboy_plexus/myoControl.hpp”

Defines

THUMB
INDEXFINGER
MIDDLEFINGER
RINGLITTLEFINGER
OPEN
CLOSE

Typedefs

typedef boost::shared_ptr<ArmControl> ArmControlPtr
file controlActions.hpp
#include <ros/ros.h>#include <ros/spinner.h>#include <ros/callback_queue.h>#include <actionlib/server/simple_action_server.h>#include <roboy_control_msgs/PerformMovementAction.h>#include <roboy_control_msgs/PerformMovementsAction.h>#include <actionlib_tutorials/FibonacciAction.h>#include <roboy_plexus/myoControl.hpp>
file CRC32.h
#include <cstdint>#include <cstddef>
file hps_0.h

Defines

I2C_3_COMPONENT_TYPE
I2C_3_COMPONENT_NAME
I2C_3_BASE
I2C_3_SPAN
I2C_3_END
I2C_1_COMPONENT_TYPE
I2C_1_COMPONENT_NAME
I2C_1_BASE
I2C_1_SPAN
I2C_1_END
I2C_2_COMPONENT_TYPE
I2C_2_COMPONENT_NAME
I2C_2_BASE
I2C_2_SPAN
I2C_2_END
I2C_0_COMPONENT_TYPE
I2C_0_COMPONENT_NAME
I2C_0_BASE
I2C_0_SPAN
I2C_0_END
PIO_0_COMPONENT_TYPE
PIO_0_COMPONENT_NAME
PIO_0_BASE
PIO_0_SPAN
PIO_0_END
PIO_0_BIT_CLEARING_EDGE_REGISTER
PIO_0_BIT_MODIFYING_OUTPUT_REGISTER
PIO_0_CAPTURE
PIO_0_DATA_WIDTH
PIO_0_DO_TEST_BENCH_WIRING
PIO_0_DRIVEN_SIM_VALUE
PIO_0_EDGE_TYPE
PIO_0_FREQ
PIO_0_HAS_IN
PIO_0_HAS_OUT
PIO_0_HAS_TRI
PIO_0_IRQ_TYPE
PIO_0_RESET_VALUE
SWITCHES_COMPONENT_TYPE
SWITCHES_COMPONENT_NAME
SWITCHES_BASE
SWITCHES_SPAN
SWITCHES_END
SWITCHES_BIT_CLEARING_EDGE_REGISTER
SWITCHES_BIT_MODIFYING_OUTPUT_REGISTER
SWITCHES_CAPTURE
SWITCHES_DATA_WIDTH
SWITCHES_DO_TEST_BENCH_WIRING
SWITCHES_DRIVEN_SIM_VALUE
SWITCHES_EDGE_TYPE
SWITCHES_FREQ
SWITCHES_HAS_IN
SWITCHES_HAS_OUT
SWITCHES_HAS_TRI
SWITCHES_IRQ_TYPE
SWITCHES_RESET_VALUE
LED_COMPONENT_TYPE
LED_COMPONENT_NAME
LED_BASE
LED_SPAN
LED_END
LED_BIT_CLEARING_EDGE_REGISTER
LED_BIT_MODIFYING_OUTPUT_REGISTER
LED_CAPTURE
LED_DATA_WIDTH
LED_DO_TEST_BENCH_WIRING
LED_DRIVEN_SIM_VALUE
LED_EDGE_TYPE
LED_FREQ
LED_HAS_IN
LED_HAS_OUT
LED_HAS_TRI
LED_IRQ_TYPE
LED_RESET_VALUE
ADC_LTC2308_0_COMPONENT_TYPE
ADC_LTC2308_0_COMPONENT_NAME
ADC_LTC2308_0_BASE
ADC_LTC2308_0_SPAN
ADC_LTC2308_0_END
SYSID_QSYS_COMPONENT_TYPE
SYSID_QSYS_COMPONENT_NAME
SYSID_QSYS_BASE
SYSID_QSYS_SPAN
SYSID_QSYS_END
SYSID_QSYS_ID
SYSID_QSYS_TIMESTAMP
JTAG_UART_COMPONENT_TYPE
JTAG_UART_COMPONENT_NAME
JTAG_UART_BASE
JTAG_UART_SPAN
JTAG_UART_END
JTAG_UART_IRQ
JTAG_UART_READ_DEPTH
JTAG_UART_READ_THRESHOLD
JTAG_UART_WRITE_DEPTH
JTAG_UART_WRITE_THRESHOLD
PWM_0_COMPONENT_TYPE
PWM_0_COMPONENT_NAME
PWM_0_BASE
PWM_0_SPAN
PWM_0_END
MYOCONTROL_2_COMPONENT_TYPE
MYOCONTROL_2_COMPONENT_NAME
MYOCONTROL_2_BASE
MYOCONTROL_2_SPAN
MYOCONTROL_2_END
MYOCONTROL_0_COMPONENT_TYPE
MYOCONTROL_0_COMPONENT_NAME
MYOCONTROL_0_BASE
MYOCONTROL_0_SPAN
MYOCONTROL_0_END
MYOCONTROL_1_COMPONENT_TYPE
MYOCONTROL_1_COMPONENT_NAME
MYOCONTROL_1_BASE
MYOCONTROL_1_SPAN
MYOCONTROL_1_END
file i2c.hpp
#include <ros/ros.h>#include <stdio.h>#include <unistd.h>#include <cstdint>#include <fcntl.h>#include “hwlib.h”#include “hps_0.h”#include <vector>

Defines

IORD(base, reg)
IOWR(base, reg, data)
IORD_8DIRECT(base, offset)
IORD_16DIRECT(base, offset)
IORD_32DIRECT(base, offset)
IOWR_8DIRECT(base, offset, data)
IOWR_16DIRECT(base, offset, data)
file myoControl.hpp
#include <vector>#include <map>#include <iostream>#include <math.h>#include <chrono>#include <fstream>#include <unistd.h>#include <tinyxml.h>#include <string>#include <sstream>#include <common_utilities/CommonDefinitions.h>#include <roboy_plexus/timer.hpp>#include <ros/ros.h>

Defines

MOTORS_PER_MYOCONTROL
IORD(base, reg)
IOWR(base, reg, data)
MYO_READ_Kp(base, motor)
MYO_READ_Ki(base, motor)
MYO_READ_Kd(base, motor)
MYO_READ_sp(base, motor)
MYO_READ_forwardGain(base, motor)
MYO_READ_outputPosMax(base, motor)
MYO_READ_outputNegMax(base, motor)
MYO_READ_IntegralPosMax(base, motor)
MYO_READ_IntegralNegMax(base, motor)
MYO_READ_deadBand(base, motor)
MYO_READ_control(base, motor)
MYO_READ_position(base, motor)
MYO_READ_velocity(base, motor)
MYO_READ_current(base, motor)
MYO_READ_displacement(base, motor)
MYO_READ_pwmRef(base, motor)
MYO_READ_update_frequency(base)
MYO_READ_power_sense(base)
MYO_READ_gpio(base)
MYO_READ_myo_brick_motor_angle(base, motor)
MYO_READ_myo_brick(base)
MYO_READ_myo_brick_device_id(base, motor)
MYO_READ_myo_brick_gear_box_ratio(base, motor)
MYO_READ_myo_brick_encoder_multiplier(base, motor)
MYO_READ_outputDivider(base, motor)
MYO_READ_myo_brick_i2c_ack_error(base, motor)
MYO_READ_elbow_joint_angle_error(base)
MYO_READ_elbow_Kp_joint_angle(base)
MYO_READ_elbow_Kd_joint_angle(base)
MYO_READ_elbow_agonist(base)
MYO_READ_elbow_antagonist(base)
MYO_READ_elbow_joint_angle_setpoint(base)
MYO_READ_elbow_joint_angle_device_id(base)
MYO_READ_elbow_joint_angle(base)
MYO_READ_elbow_joint_angle_offset(base)
MYO_READ_elbow_joint_control_result(base)
MYO_READ_elbow_joint_pretension(base)
MYO_READ_elbow_joint_deadband(base)
MYO_READ_hand_control(base)
MYO_READ_arm_board_device_id(base, motor)
MYO_READ_motor0(base, board)
MYO_READ_motor1(base, board)
MYO_READ_motor2(base, board)
MYO_READ_motor3(base, board)
MYO_READ_motor4(base, board)
MYO_READ_arm_board_ack_error(base)
MYO_READ_elbow_smooth_distance(base)
MYO_READ_wrist_joint_angle_error(base)
MYO_READ_wrist_Kp_joint_angle(base)
MYO_READ_wrist_Kd_joint_angle(base)
MYO_READ_wrist_agonist(base)
MYO_READ_wrist_antagonist(base)
MYO_READ_wrist_joint_angle_setpoint(base)
MYO_READ_wrist_joint_angle_device_id(base)
MYO_READ_wrist_joint_angle(base)
MYO_READ_wrist_joint_angle_offset(base)
MYO_READ_wrist_joint_control_result(base)
MYO_READ_wrist_joint_pretension(base)
MYO_READ_wrist_joint_deadband(base)
MYO_READ_wrist_smooth_distance(base)
MYO_READ_myo_brick_motor_raw_angle(base, motor)
MYO_READ_myo_brick_motor_raw_angle_prev(base, motor)
MYO_READ_myo_brick_motor_offset_angle(base, motor)
MYO_READ_myo_brick_motor_relative_angle(base, motor)
MYO_READ_myo_brick_motor_angle_revolution_counter(base, motor)
MYO_WRITE_Kp(base, motor, data)
MYO_WRITE_Ki(base, motor, data)
MYO_WRITE_Kd(base, motor, data)
MYO_WRITE_sp(base, motor, data)
MYO_WRITE_forwardGain(base, motor, data)
MYO_WRITE_outputPosMax(base, motor, data)
MYO_WRITE_outputNegMax(base, motor, data)
MYO_WRITE_IntegralPosMax(base, motor, data)
MYO_WRITE_IntegralNegMax(base, motor, data)
MYO_WRITE_deadBand(base, motor, data)
MYO_WRITE_control(base, motor, data)
MYO_WRITE_reset_myo_control(base, data)
MYO_WRITE_spi_activated(base, data)
MYO_WRITE_reset_controller(base, motor)
MYO_WRITE_update_frequency(base, data)
MYO_WRITE_gpio(base, data)
MYO_WRITE_myo_brick(base, data)
MYO_WRITE_myo_brick_device_id(base, motor, data)
MYO_WRITE_myo_brick_gear_box_ratio(base, motor, data)
MYO_WRITE_myo_brick_encoder_multiplier(base, motor, data)
MYO_WRITE_outputDivider(base, motor, data)
MYO_WRITE_elbow_joint_control(base, data)
MYO_WRITE_elbow_joint_angle_device_id(base, data)
MYO_WRITE_elbow_agonist(base, motor)
MYO_WRITE_elbow_antagonist(base, motor)
MYO_WRITE_elbow_Kp_joint_angle(base, data)
MYO_WRITE_elbow_Kd_joint_angle(base, data)
MYO_WRITE_elbow_joint_angle_offset(base, data)
MYO_WRITE_elbow_joint_pretension(base, data)
MYO_WRITE_elbow_joint_deadband(base, data)
MYO_WRITE_elbow_joint_angle_setpoint(base, data)
MYO_WRITE_hand_control(base, data)
MYO_WRITE_arm_board_device_id(base, board, data)
MYO_WRITE_motor0(base, board, data)
MYO_WRITE_motor1(base, board, data)
MYO_WRITE_motor2(base, board, data)
MYO_WRITE_motor3(base, board, data)
MYO_WRITE_motor4(base, board, data)
MYO_WRITE_elbow_smooth_distance(base, data)
MYO_WRITE_wrist_joint_control(base, data)
MYO_WRITE_wrist_joint_angle_device_id(base, data)
MYO_WRITE_wrist_agonist(base, motor)
MYO_WRITE_wrist_antagonist(base, motor)
MYO_WRITE_wrist_Kp_joint_angle(base, data)
MYO_WRITE_wrist_Kd_joint_angle(base, data)
MYO_WRITE_wrist_joint_angle_offset(base, data)
MYO_WRITE_wrist_joint_pretension(base, data)
MYO_WRITE_wrist_joint_deadband(base, data)
MYO_WRITE_wrist_joint_angle_setpoint(base, data)
MYO_WRITE_wrist_smooth_distance(base, data)
NUMBER_OF_ADC_SAMPLES
MOTOR_BOARD_COMMUNICATION_FREQUENCY

Typedefs

typedef boost::shared_ptr<MyoControl> MyoControlPtr
file roboyPlexus.hpp
#include <ros/ros.h>#include <vector>#include <roboy_plexus/myoControl.hpp>#include “roboy_plexus/controlActions.hpp”#include <roboy_plexus/am4096.hpp>#include <roboy_plexus/Adafruit_LSM9DS1.hpp>#include <roboy_plexus/A1335.hpp>#include <roboy_middleware_msgs/ADCvalue.h>#include <roboy_middleware_msgs/ControlMode.h>#include <roboy_middleware_msgs/DarkRoom.h>#include <roboy_middleware_msgs/DarkRoomOOTX.h>#include <roboy_middleware_msgs/DarkRoomStatus.h>#include <roboy_middleware_msgs/MagneticSensor.h>#include <roboy_middleware_msgs/MotorAngle.h>#include <roboy_middleware_msgs/MotorCalibrationService.h>#include <roboy_middleware_msgs/MotorCommand.h>#include <roboy_middleware_msgs/MotorStatus.h>#include <roboy_middleware_msgs/MotorConfigService.h>#include <roboy_middleware_msgs/MyoBrickCalibrationService.h>#include <roboy_middleware_msgs/SetInt16.h>#include <roboy_control_msgs/Behavior.h>#include <roboy_control_msgs/StartRecordTrajectory.h>#include <roboy_middleware_msgs/SystemCheck.h>#include <roboy_control_msgs/ListItems.h>#include <std_srvs/SetBool.h>#include <std_msgs/Bool.h>#include <std_msgs/Float32MultiArray.h>#include <std_msgs/Empty.h>#include <std_msgs/Int32.h>#include <std_msgs/Float32.h>#include <sensor_msgs/Imu.h>#include <thread>#include <map>#include <chrono>#include <algorithm>#include <roboy_plexus/ADXL345.h>#include <linux/i2c-dev.h>#include <sys/ioctl.h>#include “hwlib.h”#include “roboy_plexus/half.hpp”#include “roboy_plexus/CRC32.h”#include <bitset>#include “roboy_plexus/tlv493d_fpga.hpp”#include <sys/types.h>#include <dirent.h>#include <sys/stat.h>#include <common_utilities/CommonDefinitions.h>

Defines

NUM_SENSORS
NUMBER_OF_LOADCELLS

Variables

vector<int32_t *> DEFAULT_POINTER_VECTOR
vector<int32_t> DEFAULT_VECTOR
vector<vector<int32_t>> DEFAULT_VECTOR_VECTOR
file tlv493d.hpp
#include <stdint.h>#include “i2c.hpp”#include <vector>#include <ros/ros.h>

Defines

bitRead(byte, pos)
BYTE_TO_BINARY_PATTERN
BYTE_TO_BINARY(byte)
file tlv493d_fpga.hpp
#include <stdint.h>#include <vector>#include <ros/ros.h>

Defines

IORD(base, reg)
IOWR(base, reg, data)
file A1335.cpp
#include “roboy_plexus/A1335.hpp”
file Adafruit_BNO055.cpp
#include <math.h>#include <limits.h>#include <roboy_plexus/Adafruit_Sensor.h>#include “roboy_plexus/Adafruit_BNO055.hpp”
file Adafruit_LSM9DS1.cpp
#include “roboy_plexus/Adafruit_LSM9DS1.hpp”
file am4096.cpp
#include <roboy_plexus/am4096.hpp>
file armControl.cpp
#include “roboy_plexus/armControl.hpp”
file controlActions.cpp
#include “roboy_plexus/controlActions.hpp”
file CRC32.cpp
#include “roboy_plexus/CRC32.h”

Defines

FLASH_PROGMEM
FLASH_READ_DWORD(x)

Variables

const uint32_t crc32_table [] FLASH_PROGMEM= { 0x00000000, 0x1db71064, 0x3b6e20c8, 0x26d930ac, 0x76dc4190, 0x6b6b51f4, 0x4db26158, 0x5005713c, 0xedb88320, 0xf00f9344, 0xd6d6a3e8, 0xcb61b38c, 0x9b64c2b0, 0x86d3d2d4, 0xa00ae278, 0xbdbdf21c}
file i2c.cpp
#include “roboy_plexus/i2c.hpp”
file main.cpp
#include <stdio.h>#include <unistd.h>#include <fcntl.h>#include <sys/mman.h>#include <signal.h>#include <stdlib.h>#include “hwlib.h”#include “socal/hps.h”#include “roboy_plexus/hps_0.h”#include “roboy_plexus/roboyPlexus.hpp”

Defines

ALT_LWFPGASLVS_OFST
HW_REGS_BASE
HW_REGS_SPAN
HW_REGS_MASK

Functions

void SigintHandler(int sig)
int main(int argc, char *argv[])

Variables

int32_t *h2p_lw_sysid_addr
int32_t *h2p_lw_led_addr
int32_t *h2p_lw_adc_addr
int32_t *h2p_lw_switches_addr
int32_t *h2p_lw_darkroom_addr
int32_t *h2p_lw_a1339_addr
vector<int32_t *> h2p_lw_darkroom_ootx_addr
vector<int32_t *> h2p_lw_myo_addr
vector<int32_t *> h2p_lw_i2c_addr
MyoControlPtr myoControl
file myoControl.cpp
#include “roboy_plexus/myoControl.hpp”
file roboyPlexus.cpp
#include <roboy_plexus/roboyPlexus.hpp>
file ROS_MASTER_URI_receiver.cpp
#include <ros/ros.h>#include <common_utilities/UDPSocket.hpp>

Functions

int main(int argc, char *argv[])

Variables

const char* key= "The path of the righteous man is beset on all sides by the inequities of the " "selfish and the tyranny of evil men. Blessed is he who, in the name of " "charity and good will, shepherds the weak through the valley of the darkness. " "For he is truly his brother's keeper and the finder of lost children. And I " "will strike down upon thee with great vengeance and furious anger those who " "attempt to poison and destroy my brothers. And you will know I am the Lord " "when I lay my vengeance upon you0"
file tlv493d.cpp
#include “roboy_plexus/tlv493d.hpp”
file tlv493d_fpga.cpp
#include “roboy_plexus/tlv493d_fpga.hpp”
file UDPSocket.cpp
#include <ifaddrs.h>#include “common_utilities/UDPSocket.hpp”
group test

This is the first group.

dir /home/docs/checkouts/readthedocs.org/user_builds/roboy-plexus/checkouts/latest/include
dir /home/docs/checkouts/readthedocs.org/user_builds/roboy-plexus/checkouts/latest/include/roboy_plexus
dir /home/docs/checkouts/readthedocs.org/user_builds/roboy-plexus/checkouts/latest/src