summaryrefslogtreecommitdiff
path: root/src/sensor
diff options
context:
space:
mode:
Diffstat (limited to 'src/sensor')
-rw-r--r--src/sensor/calibration.cpp96
-rw-r--r--src/sensor/calibration.hpp76
-rw-r--r--src/sensor/registers.hpp136
-rw-r--r--src/sensor/sensor.cpp298
-rw-r--r--src/sensor/sensor.hpp194
5 files changed, 0 insertions, 800 deletions
diff --git a/src/sensor/calibration.cpp b/src/sensor/calibration.cpp
deleted file mode 100644
index 5626388..0000000
--- a/src/sensor/calibration.cpp
+++ /dev/null
@@ -1,96 +0,0 @@
-#include "calibration.hpp"
-
-#include "common/time.hpp"
-#include "utils.hpp"
-
-SensorCalibrator::SensorCalibrator(common::SharedPtr<Sensor> sensor,
- common::SharedPtr<SerialStream> sout)
- : _sensor(sensor), _sout(sout)
-{
-}
-
-bool SensorCalibrator::calibrate(unsigned int throttle_time)
-{
- bool done = false;
- auto start_time = common::time_now();
-
- while (!done)
- {
- if (common::time_now().diff(start_time).millisecs() >= CALIBRATION_TIMEOUT)
- {
- return false;
- }
-
- delay(throttle_time);
-
- auto values = SensorCalibratorValues();
-
- for (unsigned int i = 0U; i < SENSOR_READ_CNT; i++)
- {
- _updateValues(values);
- }
-
- _adjustValues(values);
-
- *_sout << "Accel X: " << values.accel_x << " "
- << "Accel Y: " << values.accel_y << " "
- << "Accel Z: " << values.accel_z << " "
- << "Gyro X: " << values.gyro_x << " "
- << "Gyro Y: " << values.gyro_y << " "
- << "Gyro Z: " << values.gyro_z << endl;
-
- if (_isValuesInRange(values))
- {
- done = true;
- }
-
- _adjustCalibrationWithValues(values);
- }
-
- return true;
-}
-
-void SensorCalibrator::_updateValues(SensorCalibratorValues &values)
-{
- _sensor->read();
-
- values.accel_x -= _sensor->getAccelX();
- values.accel_y -= _sensor->getAccelY();
- values.accel_z -= _sensor->getAccelZ();
-
- values.gyro_x -= _sensor->getGyroX();
- values.gyro_y -= _sensor->getGyroY();
- values.gyro_z -= _sensor->getGyroZ();
-}
-
-void SensorCalibrator::_adjustCalibrationWithValues(const SensorCalibratorValues &values)
-{
- _sensor->accel_cal_x += values.accel_x;
- _sensor->accel_cal_y += values.accel_y;
- _sensor->accel_cal_z += values.accel_z;
-
- _sensor->gyro_cal_x += values.gyro_x;
- _sensor->gyro_cal_y += values.gyro_y;
- _sensor->gyro_cal_z += values.gyro_z;
-}
-
-void SensorCalibrator::_adjustValues(SensorCalibratorValues &values)
-{
- values.accel_x *= SENSOR_VAL_ADJUST;
- values.accel_y *= SENSOR_VAL_ADJUST;
- values.accel_z *= SENSOR_VAL_ADJUST;
-
- values.gyro_x *= SENSOR_VAL_ADJUST;
- values.gyro_y *= SENSOR_VAL_ADJUST;
- values.gyro_z *= SENSOR_VAL_ADJUST;
-}
-
-bool SensorCalibrator::_isValuesInRange(const SensorCalibratorValues &values)
-{
- return (values.accel_x < ACCEL_CAL_X_MAX && values.accel_x > ACCEL_CAL_X_MIN &&
- values.accel_y < ACCEL_CAL_Y_MAX && values.accel_y > ACCEL_CAL_Y_MIN &&
- values.accel_z < ACCEL_CAL_Z_MAX && values.accel_z > ACCEL_CAL_Z_MIN &&
- values.gyro_x < GYRO_CAL_X_MAX && values.gyro_x > GYRO_CAL_X_MIN &&
- values.gyro_y < GYRO_CAL_Y_MAX && values.gyro_y > GYRO_CAL_Y_MIN &&
- values.gyro_z < GYRO_CAL_Z_MAX && values.gyro_z > GYRO_CAL_Z_MIN);
-}
diff --git a/src/sensor/calibration.hpp b/src/sensor/calibration.hpp
deleted file mode 100644
index c85d336..0000000
--- a/src/sensor/calibration.hpp
+++ /dev/null
@@ -1,76 +0,0 @@
-#pragma once
-
-#include "common/memory/shared_ptr.hpp"
-#include "sensor/sensor.hpp"
-#include "serial.hpp"
-
-// Calibration precision
-constexpr double ACCEL_CAL_X_MAX = 0.003;
-constexpr double ACCEL_CAL_X_MIN = -0.003;
-
-constexpr double ACCEL_CAL_Y_MAX = 0.003;
-constexpr double ACCEL_CAL_Y_MIN = -0.003;
-
-constexpr double ACCEL_CAL_Z_MAX = 0.003;
-constexpr double ACCEL_CAL_Z_MIN = -0.003;
-
-constexpr double GYRO_CAL_X_MAX = 0.003;
-constexpr double GYRO_CAL_X_MIN = -0.003;
-
-constexpr double GYRO_CAL_Y_MAX = 0.05;
-constexpr double GYRO_CAL_Y_MIN = -0.05;
-
-constexpr double GYRO_CAL_Z_MAX = 0.04;
-constexpr double GYRO_CAL_Z_MIN = -0.04;
-
-constexpr uint32_t CALIBRATION_TIMEOUT = 120000; // milliseconds
-
-constexpr uint32_t SENSOR_READ_CNT = 20;
-constexpr double SENSOR_VAL_ADJUST = 0.05;
-
-class SensorCalibratorValues
-{
-public:
- double accel_x = 0;
- double accel_y = 0;
- double accel_z = 0;
-
- double gyro_x = 0;
- double gyro_y = 0;
- double gyro_z = 0;
-};
-
-/**
- * Sensor calibrator.
- */
-class SensorCalibrator
-{
-public:
- /**
- * Sensor calibrator.
- *
- * @param sensor A sensor to calibrate
- * @param sout A Serial output stream
- */
- SensorCalibrator(common::SharedPtr<Sensor> sensor,
- common::SharedPtr<SerialStream> sout);
-
- /**
- * Calibrates the sensor.
- *
- * @param throttle_time The sensor's throttle time
- * @returns Whether or not the calibration succeeded. Will return false on
- * timeout.
- */
- bool calibrate(unsigned int throttle_time);
-
-private:
- void _updateValues(SensorCalibratorValues &values);
- void _adjustCalibrationWithValues(const SensorCalibratorValues &values);
-
- static void _adjustValues(SensorCalibratorValues &values);
- static bool _isValuesInRange(const SensorCalibratorValues &values);
-
- common::SharedPtr<Sensor> _sensor;
- common::SharedPtr<SerialStream> _sout;
-};
diff --git a/src/sensor/registers.hpp b/src/sensor/registers.hpp
deleted file mode 100644
index fadb62b..0000000
--- a/src/sensor/registers.hpp
+++ /dev/null
@@ -1,136 +0,0 @@
-#pragma once
-
-#include <stdint.h>
-
-namespace SensorRegisters
-{
- const uint8_t XG_OFFS_TC = 0x00U;
- const uint8_t YG_OFFS_TC = 0x01U;
- const uint8_t ZG_OFFS_TC = 0x02U;
-
- const uint8_t X_FINE_GAIN = 0x03U;
- const uint8_t Y_FINE_GAIN = 0x04U;
- const uint8_t Z_FINE_GAIN = 0x05U;
-
- const uint8_t XA_OFFS_H = 0x06U;
- const uint8_t XA_OFFS_L_TC = 0x07U;
- const uint8_t YA_OFFS_H = 0x08U;
- const uint8_t YA_OFFS_L_TC = 0x09U;
- const uint8_t ZA_OFFS_H = 0x0AU;
- const uint8_t ZA_OFFS_L_TC = 0x0BU;
-
- const uint8_t SELF_TEST_X = 0x0DU;
- const uint8_t SELF_TEST_Y = 0x0EU;
- const uint8_t SELF_TEST_Z = 0x0FU;
- const uint8_t SELF_TEST_A = 0x10U;
-
- const uint8_t XG_OFFS_USRH = 0x13U;
- const uint8_t XG_OFFS_USRL = 0x14U;
- const uint8_t YG_OFFS_USRH = 0x15U;
- const uint8_t YG_OFFS_USRL = 0x16U;
- const uint8_t ZG_OFFS_USRH = 0x17U;
- const uint8_t ZG_OFFS_USRL = 0x18U;
-
- const uint8_t SMPLRT_DIV = 0x19U;
- const uint8_t CONFIG = 0x1AU;
- const uint8_t GYRO_CONFIG = 0x1BU;
- const uint8_t ACCEL_CONFIG = 0x1CU;
-
- const uint8_t FF_THR = 0x1DU;
- const uint8_t FF_DUR = 0x1EU;
- const uint8_t MOT_THR = 0x1FU;
- const uint8_t MOT_DUR = 0x20U;
- const uint8_t ZRMOT_THR = 0x21U;
- const uint8_t ZRMOT_DUR = 0x22U;
- const uint8_t FIFO_EN = 0x23U;
-
- const uint8_t I2C_MST_CTRL = 0x24U;
- const uint8_t I2C_SLV0_ADDR = 0x25U;
- const uint8_t I2C_SLV0_REG = 0x26U;
- const uint8_t I2C_SLV0_CTRL = 0x27U;
- const uint8_t I2C_SLV1_ADDR = 0x28U;
- const uint8_t I2C_SLV1_REG = 0x29U;
- const uint8_t I2C_SLV1_CTRL = 0x2AU;
- const uint8_t I2C_SLV2_ADDR = 0x2BU;
- const uint8_t I2C_SLV2_REG = 0x2CU;
- const uint8_t I2C_SLV2_CTRL = 0x2DU;
- const uint8_t I2C_SLV3_ADDR = 0x2EU;
- const uint8_t I2C_SLV3_REG = 0x2FU;
- const uint8_t I2C_SLV3_CTRL = 0x30U;
- const uint8_t I2C_SLV4_ADDR = 0x31U;
- const uint8_t I2C_SLV4_REG = 0x32U;
- const uint8_t I2C_SLV4_DO = 0x33U;
- const uint8_t I2C_SLV4_CTRL = 0x34U;
- const uint8_t I2C_SLV4_DI = 0x35U;
- const uint8_t I2C_MST_STATUS = 0x36U;
-
- const uint8_t INT_PIN_CFG = 0x37U;
- const uint8_t INT_ENABLE = 0x38U;
- const uint8_t DMP_INT_STATUS = 0x39U;
- const uint8_t INT_STATUS = 0x3AU;
-
- const uint8_t ACCEL_XOUT_H = 0x3BU;
- const uint8_t ACCEL_XOUT_L = 0x3CU;
- const uint8_t ACCEL_YOUT_H = 0x3DU;
- const uint8_t ACCEL_YOUT_L = 0x3EU;
- const uint8_t ACCEL_ZOUT_H = 0x3FU;
- const uint8_t ACCEL_ZOUT_L = 0x40U;
- const uint8_t TEMP_OUT_H = 0x41U;
- const uint8_t TEMP_OUT_L = 0x42U;
- const uint8_t GYRO_XOUT_H = 0x43U;
- const uint8_t GYRO_XOUT_L = 0x44U;
- const uint8_t GYRO_YOUT_H = 0x45U;
- const uint8_t GYRO_YOUT_L = 0x46U;
- const uint8_t GYRO_ZOUT_H = 0x47U;
- const uint8_t GYRO_ZOUT_L = 0x48U;
-
- const uint8_t EXT_SENS_DATA_00 = 0x49U;
- const uint8_t EXT_SENS_DATA_01 = 0x4AU;
- const uint8_t EXT_SENS_DATA_02 = 0x4BU;
- const uint8_t EXT_SENS_DATA_03 = 0x4CU;
- const uint8_t EXT_SENS_DATA_04 = 0x4DU;
- const uint8_t EXT_SENS_DATA_05 = 0x4EU;
- const uint8_t EXT_SENS_DATA_06 = 0x4FU;
- const uint8_t EXT_SENS_DATA_07 = 0x50U;
- const uint8_t EXT_SENS_DATA_08 = 0x51U;
- const uint8_t EXT_SENS_DATA_09 = 0x52U;
- const uint8_t EXT_SENS_DATA_10 = 0x53U;
- const uint8_t EXT_SENS_DATA_11 = 0x54U;
- const uint8_t EXT_SENS_DATA_12 = 0x55U;
- const uint8_t EXT_SENS_DATA_13 = 0x56U;
- const uint8_t EXT_SENS_DATA_14 = 0x57U;
- const uint8_t EXT_SENS_DATA_15 = 0x58U;
- const uint8_t EXT_SENS_DATA_16 = 0x59U;
- const uint8_t EXT_SENS_DATA_17 = 0x5AU;
- const uint8_t EXT_SENS_DATA_18 = 0x5BU;
- const uint8_t EXT_SENS_DATA_19 = 0x5CU;
- const uint8_t EXT_SENS_DATA_20 = 0x5DU;
- const uint8_t EXT_SENS_DATA_21 = 0x5EU;
- const uint8_t EXT_SENS_DATA_22 = 0x5FU;
- const uint8_t EXT_SENS_DATA_23 = 0x60U;
-
- const uint8_t MOT_DETECT_STATUS = 0x61U;
-
- const uint8_t I2C_SLV0_DO = 0x63U;
- const uint8_t I2C_SLV1_DO = 0x64U;
- const uint8_t I2C_SLV2_DO = 0x65U;
- const uint8_t I2C_SLV3_DO = 0x66U;
- const uint8_t I2C_MST_DELAY_CTRL = 0x67U;
-
- const uint8_t SIGNAL_PATH_RESET = 0x68U;
- const uint8_t MOT_DETECT_CTRL = 0x69U;
- const uint8_t USER_CTRL = 0x6AU;
-
- const uint8_t PWR_MGMT_1 = 0x6BU;
- const uint8_t PWR_MGMT_2 = 0x6CU;
- const uint8_t BANK_SEL = 0x6DU;
- const uint8_t MEM_START_ADDR = 0x6EU;
- const uint8_t MEM_R_W = 0x6FU;
-
- const uint8_t DMP_CFG_1 = 0x70U;
- const uint8_t DMP_CFG_2 = 0x71U;
- const uint8_t FIFO_COUNTH = 0x72U;
- const uint8_t FIFO_COUNTL = 0x73U;
- const uint8_t FIFO_R_W = 0x74U;
- const uint8_t WHO_AM_I = 0x75U;
-} // namespace SensorRegisters
diff --git a/src/sensor/sensor.cpp b/src/sensor/sensor.cpp
deleted file mode 100644
index a801270..0000000
--- a/src/sensor/sensor.cpp
+++ /dev/null
@@ -1,298 +0,0 @@
-#include "sensor.hpp"
-
-#include "sensor/registers.hpp"
-
-Sensor::Sensor(uint8_t address, TwoWire wire, unsigned int throttle_time) noexcept
- : _wire(wire),
- _address(address),
- _throttle_enabled(true),
- _throttle_time(throttle_time),
- _last_time(0),
- _status(SensorStatus::OK),
- _accel_to_g_force(RAW_TO_G_FACTOR),
- _ang_rate_to_dps(RAW_TO_DPS_FACTOR)
-{
-}
-
-bool Sensor::begin() noexcept
-{
- _wire.begin();
-
- if (isConnected())
- {
- _wire.beginTransmission(_address);
- _wire.write(SensorRegisters::PWR_MGMT_1);
- _wire.write(SENSOR_WAKEUP);
-
- return (_wire.endTransmission() == 0);
- }
-
- return false;
-}
-
-bool Sensor::isConnected() noexcept
-{
- _wire.beginTransmission(_address);
- return (_wire.endTransmission() == 0);
-}
-
-bool Sensor::read() noexcept
-{
- auto now = common::time_now();
-
- if (_throttle_enabled && now.diff(_last_time).millisecs() < _throttle_time)
- {
- _status = SensorStatus::THROTTLED;
- return false;
- }
-
- _wire.beginTransmission(_address);
- _wire.write(SensorRegisters::ACCEL_XOUT_H);
-
- if (_wire.endTransmission() != 0U)
- {
- _status = SensorStatus::ERR_WRITE;
- return false;
- }
-
- uint8_t response_length = _wire.requestFrom(_address, SensorRegisters::SELF_TEST_Y);
-
- const uint8_t self_test_success = 14U;
-
- if (response_length != self_test_success)
- {
- _status = SensorStatus::ERR_READ;
- return false;
- }
-
- // Accelerometer
- _accel_raw_x = _readHighLow();
- _accel_raw_y = _readHighLow();
- _accel_raw_z = _readHighLow();
-
- // Gyroscope
- _gyro_raw_x = _readHighLow();
- _gyro_raw_y = _readHighLow();
- _gyro_raw_z = _readHighLow();
-
- // Duration interval
- now.update();
- auto duration = now.diff(_last_time).secs();
- _last_time = now;
-
- // Convert raw acceleration to g:s (g-force)
- _accel_raw_x *= _accel_to_g_force;
- _accel_raw_y *= _accel_to_g_force;
- _accel_raw_z *= _accel_to_g_force;
-
- // Error correct raw acceleration
- _accel_raw_x += accel_cal_x;
- _accel_raw_y += accel_cal_y;
- _accel_raw_z += accel_cal_z;
-
- // Prepare for Pitch Roll Yaw
- auto accel_y_pow_two = pow(_accel_raw_y, 2);
- auto accel_z_pow_two = pow(_accel_raw_z, 2);
-
- _accel_x = atan2(_accel_raw_y, _accel_raw_z) * ONE_EIGHTY / PI;
-
- _accel_y =
- atan2(-_accel_raw_x, sqrt(accel_y_pow_two + accel_z_pow_two)) * ONE_EIGHTY / PI;
-
- // Convert raw Gyro to degrees/s
- _gyro_raw_x *= _ang_rate_to_dps;
- _gyro_raw_y *= _ang_rate_to_dps;
- _gyro_raw_z *= _ang_rate_to_dps;
-
- // Error correct raw gyro measurements.
- _gyro_raw_x += gyro_cal_x;
- _gyro_raw_y += gyro_cal_y;
- _gyro_raw_z += gyro_cal_z;
-
- _gyro_x += _gyro_raw_x * duration;
- _gyro_y += _gyro_raw_y * duration;
- _gyro_z += _gyro_raw_z * duration;
-
- _pitch = _gyro_y + _accel_y;
- _roll = _gyro_x + _accel_x;
-
- _yaw = _gyro_z;
-
- return true;
-}
-
-bool Sensor::setAccelSensitivity(uint8_t sensitivity) noexcept
-{
- if (sensitivity > 3)
- {
- sensitivity = 3;
- }
-
- _accel_sensitivity = sensitivity;
-
- auto accel_config = static_cast<int>(getRegister(SensorRegisters::ACCEL_CONFIG));
-
- if (_status != SensorStatus::OK)
- {
- return false;
- }
-
- // No need to write same value
- if (((accel_config >> 3) & 3) != _accel_sensitivity)
- {
- const uint8_t magic = 0xE7U;
-
- accel_config &= magic;
- accel_config |= (_accel_sensitivity << 3U);
-
- if (!setRegister(SensorRegisters::ACCEL_CONFIG,
- static_cast<uint8_t>(accel_config)))
- {
- return false;
- }
- }
-
- // Calculate conversion factor.
- _accel_to_g_force = static_cast<float>(1 << _accel_sensitivity) * RAW_TO_G_FACTOR;
-
- return true;
-}
-
-bool Sensor::setGyroSensitivity(uint8_t sensitivity) noexcept
-{
- if (sensitivity > 3)
- {
- sensitivity = 3;
- }
-
- _gyro_sensitivity = sensitivity;
-
- auto gyro_config = static_cast<int>(getRegister(SensorRegisters::GYRO_CONFIG));
-
- if (_status != SensorStatus::OK)
- {
- return false;
- }
-
- // No need to write same value
- if (((gyro_config >> 3) & 3) != _gyro_sensitivity)
- {
- const uint8_t magic = 0xE7U;
-
- gyro_config &= magic;
- gyro_config |= (_gyro_sensitivity << 3U);
-
- if (!setRegister(SensorRegisters::GYRO_CONFIG, static_cast<uint8_t>(gyro_config)))
- {
- return false;
- }
- }
-
- _ang_rate_to_dps = static_cast<float>(1 << _gyro_sensitivity) * RAW_TO_DPS_FACTOR;
-
- return true;
-}
-
-double Sensor::getAccelX() const noexcept
-{
- return _accel_raw_x;
-}
-
-double Sensor::getAccelY() const noexcept
-{
- return _accel_raw_y;
-}
-
-double Sensor::getAccelZ() const noexcept
-{
- return _accel_raw_z;
-}
-
-double Sensor::getAngleX() const noexcept
-{
- return _accel_x;
-}
-
-double Sensor::getAngleY() const noexcept
-{
- return _accel_y;
-}
-
-double Sensor::getGyroX() const noexcept
-{
- return _gyro_raw_x;
-}
-
-double Sensor::getGyroY() const noexcept
-{
- return _gyro_raw_y;
-}
-
-double Sensor::getGyroZ() const noexcept
-{
- return _gyro_raw_z;
-}
-
-double Sensor::getPitch() const noexcept
-{
- return _pitch;
-}
-
-double Sensor::getRoll() const noexcept
-{
- return _roll;
-}
-
-bool Sensor::setRegister(uint8_t reg, uint8_t value) noexcept
-{
- _wire.beginTransmission(_address);
- _wire.write(reg);
- _wire.write(value);
-
- if (_wire.endTransmission() != 0U)
- {
- _status = SensorStatus::ERR_WRITE;
- return false;
- }
-
- return true;
-}
-
-uint8_t Sensor::getRegister(uint8_t reg) noexcept
-{
- _wire.beginTransmission(_address);
- _wire.write(reg);
-
- if (_wire.endTransmission() != 0U)
- {
- _status = SensorStatus::ERR_WRITE;
- return 0U;
- }
-
- uint8_t response_length = _wire.requestFrom(_address, 1U);
- if (response_length != 1U)
- {
- _status = SensorStatus::ERR_READ;
- return 0U;
- }
-
- return static_cast<uint8_t>(_wire.read());
-}
-
-SensorStatus Sensor::getStatus() noexcept
-{
- SensorStatus status = _status;
- _status = SensorStatus::OK;
-
- return status;
-}
-
-int16_t Sensor::_readHighLow() noexcept
-{
- const auto high = static_cast<int16_t>(_wire.read());
- const auto low = static_cast<int16_t>(_wire.read());
-
- const int8_t bits_in_byte = 8;
-
- return static_cast<int16_t>(high << bits_in_byte | low);
-}
diff --git a/src/sensor/sensor.hpp b/src/sensor/sensor.hpp
deleted file mode 100644
index 1b99f6e..0000000
--- a/src/sensor/sensor.hpp
+++ /dev/null
@@ -1,194 +0,0 @@
-#pragma once
-
-#include "common/time.hpp"
-
-#include <Arduino.h>
-#include <Wire.h>
-
-constexpr uint8_t SENSOR_WAKEUP = 0x00U;
-
-constexpr float RAW_TO_DPS_FACTOR = 1.0 / 131.0;
-constexpr float RAW_TO_G_FACTOR = 1.0 / 16384.0;
-
-constexpr uint32_t ONE_EIGHTY = 180;
-
-enum class SensorStatus
-{
- OK = 0,
- THROTTLED = 1,
- ERR_READ = -1,
- ERR_WRITE = -2,
- ERR_NOT_CONNECTED = -3
-};
-
-/**
- * A GY521 gyro and accelerometer sensor.
- */
-class Sensor
-{
-public:
- /**
- * A GY521 gyro and accelerometer sensor.
- *
- * @param address The address of the sensor
- * @param wire A Wire instance
- * @param throttle_time A minumum time between sensor reads for the sensor to throttle
- */
- Sensor(uint8_t address, TwoWire wire, unsigned int throttle_time) noexcept;
-
- /**
- * Initializes communication with the sensor.
- *
- * @returns Whether or not the sensor can be communicated with.
- */
- bool begin() noexcept;
-
- /**
- * Returns whether or not the sensor is connected.
- */
- bool isConnected() noexcept;
-
- /**
- * Reads from the sensor.
- *
- * @returns Whether or not it succeeded.
- */
- bool read() noexcept;
-
- /**
- * Sets the accelerometer sensitivity.
- *
- * @param sensitivity Accelerometer sensitivity. 0, 1, 2, 3 => 2g 4g 8g 16g
- * @returns Whether or not it succeeded.
- */
- bool setAccelSensitivity(uint8_t sensitivity) noexcept;
-
- /**
- * Sets the gyro sensitivity.
- *
- * @param sensitivity Gyro sensitivity.
- * 0, 1, 2, 3 => 250, 500, 1000, 2000 degrees/s
- * @returns Whether or not it succeeded.
- */
- bool setGyroSensitivity(uint8_t sensitivity) noexcept;
-
- /**
- * Returns the current X axis acceleration in g:s (g-force).
- */
- double getAccelX() const noexcept;
-
- /**
- * Returns the current Y axis acceleration in g:s (g-force).
- */
- double getAccelY() const noexcept;
-
- /**
- * Returns the current Z axis acceleration in g:s (g-force).
- */
- double getAccelZ() const noexcept;
-
- /**
- * Returns the current X angle.
- */
- double getAngleX() const noexcept;
-
- /**
- * Returns the current Y angle.
- */
- double getAngleY() const noexcept;
-
- /**
- * Returns the current X axis in degrees/s.
- */
- double getGyroX() const noexcept;
-
- /**
- * Returns the current Y axis in degrees/s.
- */
- double getGyroY() const noexcept;
-
- /**
- * Returns the current Z axis in degrees/s.
- */
- double getGyroZ() const noexcept;
-
- /**
- * Returns the current pitch angle.
- */
- double getPitch() const noexcept;
-
- /**
- * Returns the current roll angle.
- */
- double getRoll() const noexcept;
-
- /**
- * Sets the value of a key in the sensor's register.
- *
- * @param reg The address of a registry key
- * @param value A new value
- * @returns Whether or not it succeeded.
- */
- bool setRegister(uint8_t reg, uint8_t value) noexcept;
-
- /**
- * Returns the value of a key in the sensor's registry.
- *
- * @param reg The address of a registry key
- */
- uint8_t getRegister(uint8_t reg) noexcept;
-
- /**
- * Returns the last sensor status.
- */
- SensorStatus getStatus() noexcept;
-
- // Accelerometer calibration values
- double accel_cal_x = 0;
- double accel_cal_y = 0;
- double accel_cal_z = 0;
-
- // Gyroscope calibration values
- double gyro_cal_x = 0;
- double gyro_cal_y = 0;
- double gyro_cal_z = 0;
-
-private:
- TwoWire _wire;
-
- uint8_t _address;
-
- bool _throttle_enabled;
- unsigned int _throttle_time;
-
- common::Time _last_time;
-
- SensorStatus _status;
-
- uint8_t _accel_sensitivity = 0U;
- float _accel_to_g_force;
-
- double _accel_raw_x = 0;
- double _accel_raw_y = 0;
- double _accel_raw_z = 0;
-
- double _accel_x = 0;
- double _accel_y = 0;
-
- uint8_t _gyro_sensitivity = 0U;
- float _ang_rate_to_dps;
-
- double _gyro_raw_x = 0;
- double _gyro_raw_y = 0;
- double _gyro_raw_z = 0;
-
- double _gyro_x = 0;
- double _gyro_y = 0;
- double _gyro_z = 0;
-
- double _pitch = 0;
- double _roll = 0;
- double _yaw = 0;
-
- int16_t _readHighLow() noexcept;
-};