diff options
| author | Dawsyn Schraiber <[email protected]> | 2024-06-13 14:30:58 -0400 |
|---|---|---|
| committer | GitHub <[email protected]> | 2024-06-13 14:30:58 -0400 |
| commit | 58b4bc754bbb9f5197119cd0c124e49c05acff46 (patch) | |
| tree | 8a65e23756374626e2c9cb997af9d8ed6f892390 /include/unused | |
| parent | 8fbd08fe29bbc2246a78b481b219c241f62ff420 (diff) | |
| download | active-drag-system-58b4bc754bbb9f5197119cd0c124e49c05acff46.tar.gz active-drag-system-58b4bc754bbb9f5197119cd0c124e49c05acff46.tar.bz2 active-drag-system-58b4bc754bbb9f5197119cd0c124e49c05acff46.zip | |
Where to begin…. (#13)
+/- Reworked collection of altimeter related functions into altimeter class
+/- Reworked bno055 class to be imu class with minimal functionality
\- Removed external Kalman filter implementations in favor of own in house version
\- Removed any/unused files
\+ Added buffer logger for when sitting on pad for extended period of time in effort to prevent filling of flash chip
\+ Added heartbeat LED for alive status
Diffstat (limited to 'include/unused')
| -rw-r--r-- | include/unused/actuationPlan.hpp | 36 | ||||
| -rw-r--r-- | include/unused/actuator.hpp | 30 | ||||
| -rw-r--r-- | include/unused/ads.hpp | 66 | ||||
| -rw-r--r-- | include/unused/logger.hpp | 83 | ||||
| -rw-r--r-- | include/unused/motor.hpp | 36 | ||||
| -rw-r--r-- | include/unused/rocketUtils.hpp | 121 | ||||
| -rw-r--r-- | include/unused/sensorAltimeter.hpp | 165 | ||||
| -rw-r--r-- | include/unused/sensorI2C.hpp | 105 | ||||
| -rw-r--r-- | include/unused/sensorIMU.hpp | 312 | ||||
| -rw-r--r-- | include/unused/surfaceFitModel.hpp | 32 |
10 files changed, 0 insertions, 986 deletions
diff --git a/include/unused/actuationPlan.hpp b/include/unused/actuationPlan.hpp deleted file mode 100644 index 8d1ef26..0000000 --- a/include/unused/actuationPlan.hpp +++ /dev/null @@ -1,36 +0,0 @@ -#pragma once -#include <algorithm> -#include <ctime> -#include "surfaceFitModel.hpp" -#include "rocketUtils.hpp" -#include "sensorIMU.hpp" -#include "sensorAltimeter.hpp" - -class ActuationPlan { - - private: - SurfaceFitModel sFitModel; - - public: - - /** - * @brief Construct a new Actuation Plan object - * - */ - ActuationPlan(); - - /** - * @brief Construct a new Actuation Plan object - * - * @param sFitModel - */ - ActuationPlan(SurfaceFitModel sFitModel); - - /** - * @brief Run the Fin Actuation Plan. - * Adjusts the fin angle values depending on the current vehicle state during the launch - * - * @param rocket Provides current rocket status and hold updated fin angle value. - */ - void runPlan(Vehicle& rocket); -};
\ No newline at end of file diff --git a/include/unused/actuator.hpp b/include/unused/actuator.hpp deleted file mode 100644 index e7c4120..0000000 --- a/include/unused/actuator.hpp +++ /dev/null @@ -1,30 +0,0 @@ -#pragma once - - -class Actuator { - - private: - - - public: - - /** - * @brief Initialize the actuator. - * - * @param data Data for initializing the actuator - * - * @return true Initialization Success - * @return false Initialization Failure - */ - virtual bool init(void* data) = 0; - - /** - * @brief Pass data to the actuator. - * - * @param data Data to sent to the actuator - * - * @return true Actuator write Success - * @return false Actuator write Failure - */ - virtual bool writeData(void* data) = 0; -};
\ No newline at end of file diff --git a/include/unused/ads.hpp b/include/unused/ads.hpp deleted file mode 100644 index b16c4fb..0000000 --- a/include/unused/ads.hpp +++ /dev/null @@ -1,66 +0,0 @@ -#pragma once -#include <iostream> -#include <exception> -#include <stdexcept> -#include <chrono> -#include <thread> -#include "kalmanfilter.hpp" -#include "logger.hpp" -#include "actuationPlan.hpp" -#include "rocketUtils.hpp" -#include "sensorIMU.hpp" -#include "sensorAltimeter.hpp" -#include "motor.hpp" -#include "eigen3/Eigen/Dense" - -using namespace Eigen; - -class ADS { - - private: - - KalmanFilter kf; - ActuationPlan plan; - - IMUSensor imu; - AltimeterSensor altimeter; - Motor motor; - Vehicle rocket; - - /** - * @brief Logs a summary of all pertinent current rocket data - * (e.g. Altitude, Velocity, Acceleration) - */ - virtual void logSummary(); - - /** - * @brief Performs a routine to calculate the average altitude - * while the vehicle is waiting on the pad. - */ - virtual void updateOnPadAltitude(); - - /** - * @brief Update the vehicle with the current sensor (IMU & Altimeter) readings - */ - virtual void updateSensorData(); - - /** - * @brief Update the rocket state based on its current telemetry readings. - * Also Log pertinent telemetry and rocket state data - */ - virtual void updateRocketState(); - - public: - - /** - * @brief Construct a new ADS object - * - * @param plan The Actuation Plan for the Rocket - */ - ADS(ActuationPlan plan); - - /** - * @brief Run the full active drag system from launch to landing. - */ - virtual void run(); -};
\ No newline at end of file diff --git a/include/unused/logger.hpp b/include/unused/logger.hpp deleted file mode 100644 index 90fa05a..0000000 --- a/include/unused/logger.hpp +++ /dev/null @@ -1,83 +0,0 @@ -#pragma once -#include <iostream> -#include <fstream> -#include <ctime> - -class Logger { - - private: - std::fstream file; - std::string filename; - time_t t; - tm* now; - bool file_open; - - std::string infoTag = "-> [INFO]: "; - std::string errorTag = "-> [ERROR]: "; - std::string months[12] = {"Jan", "Feb", "Mar", "Apr", "May", "Jun", "Jul", "Aug", "Sept", "Oct", "Nov", "Dec"}; - std::string days[7] = {"Sun", "Mon", "Tues", "Wed", "Thur", "Frid", "Sat"}; - - /** - * @brief Create formatted current-date tag - * - * @return string - */ - std::string getDate(); - - /** - * @brief Create formatted current-time tag - * - * @return string - */ - std::string getTime(); - - - public: - - /** - * @brief - * - */ - static Logger& Get(); - - /** - * @brief Open a Log File for writing - * - * @param _filename Name of file to open - * @return true Successful Open - * @return false Unsuccessful Open - */ - bool openLog(std::string _filename); - - /** - * @brief Close the Log File - * - */ - void closeLog(); - - /** - * @brief Write data to Log file - * - * @param data Data to log - * @return true Data Successfully Logged - * @return false Data Logging Unsuccessful - */ - bool log(std::string data); - - /** - * @brief Write error data to Log file - * - * @param data Error Data to log - * @return true Data Successfully Logged - * @return false Data Logging Unsuccessful - */ - bool logErr(std::string data); - - /** - * @brief Print Log Data to Terminal - * - * @return true Successful Print - * @return false Unsuccessful Print - */ - bool printLog(); -};
\ No newline at end of file diff --git a/include/unused/motor.hpp b/include/unused/motor.hpp deleted file mode 100644 index cb95b6a..0000000 --- a/include/unused/motor.hpp +++ /dev/null @@ -1,36 +0,0 @@ -#pragma once -#include "actuator.hpp" -#include "logger.hpp" -#include "rocketUtils.hpp" - -class Motor : public Actuator { - - private: - - - public: - - /** - * @brief Construct a new Motor object - * - */ - Motor(); - - /** - * @brief Initialize the motor. - * - * @param data Data for initializing the motor - * @return true Initialization Success - * @return false Initialization Failure - */ - virtual bool init(void* data) override; - - /** - * @brief Write data to the motor. - * - * @param data Data to be writen to the motor - * @return true Motor write Success - * @return false Motor write Failure - */ - virtual bool writeData(void* data) override; -};
\ No newline at end of file diff --git a/include/unused/rocketUtils.hpp b/include/unused/rocketUtils.hpp deleted file mode 100644 index 65b9cea..0000000 --- a/include/unused/rocketUtils.hpp +++ /dev/null @@ -1,121 +0,0 @@ -#pragma once -#include <iostream> -#include <vector> -#include <ctime> -#include <vector> -#include <iomanip> -#include <sstream> -#include <fstream> - -// Deployment angle limits -#define MAX_ANGLE 100 -#define MIN_ANGLE 120 - -// Altimeter initialization count limit -#define COUNT_LIMIT 50 - -// Constants -#define G_0 9.8066 - -// Threshold limits -#define BOOST_ACCEL_THRESH 3 -#define BOOST_HEIGHT_THRESH 20 -#define GLIDE_ACCEL_THRESH 0.5 - -#define ALTI_DEPL_THRESHOLD 0.5 -#define RATE_ALTI_DEPL 1/50 -#define FSM_DONE_SURFACE_ALTITUDE 200 -#define APOGEE_FSM_CHANGE 3 - -#define INIT_DEPLOYMENT 0 - -#define TIME_BO 8 -#define TIME_APO 25 -#define TIME_END 120 - -#define PAD_PRESSURE 102250 - -#define DUTY_MAX 14.5 -#define DUTY_MIN 3 - -#define LAUNCH_DATE "4-15-2023" -#define LOG_FILENAME "DataLog_" LAUNCH_DATE ".txt" - -#define LED_GAP_TIME 0.5 -#define LED_ONE_PATH "/sys/class/leds/beaglebone:green:usr1" -#define LED_BRIGHTNESS_FILE "brightness" -#define LED_FILENAME LED_ONE_PATH LED_BRIGHTNESS_FILE - -#define TEST_MODE false - - -enum VehicleState {ON_PAD, BOOST, GLIDE, APOGEE, DONE}; -extern std::string state_for_log[5]; - -struct Vehicle { - - int status; - - std::vector<double> acceleration; - std::vector<double> linear_acceleration; - - double apogee_altitude; - double previous_altitude; - double current_altitude; - double filtered_altitude; - - double filtered_velocity; - - double deployment_angle; - - bool imuInitFail; - bool imuReadFail; - bool altiInitFail; - bool altiReadFail; - - double ON_PAD_altitude; - bool ON_PAD_fail; - - double duty_span; - - double dt; - - int led_brightness; - - time_t start_time; - time_t fail_time; // For failure termination - time_t liftoff_time; - time_t relog_time; - time_t deploy_time; // NOT INITIALIZED YET - time_t loop_time; - time_t led_time; -}; - -/** - * @brief Convert fin deployment percentage to fin rotation angle - * - * @param percentage Fin deployment percentage - * @return double - */ -double deploy_percentage_to_angle(double percentage); - -/** - * @brief Set the decimal precision of the given data, and return it - * as a formatted string with a prefix containing a relevant description of the data. - * - * @param prefix Identifying or clarifying information about the loggef data - * @param data Data to Log - * @param precision The decimal precision value for the data - * - * @return A string with the formatted data. - */ -std::string format_data(std::string prefix, double data, int precision); - -/** - * @brief Blink Beaglebone LED 1 - * - * @param vehicle Holds settings pertinent to the Beaglebone LED - * @return true Successful Blink - * @return false Unsuccessful Blink - */ -bool led_out(Vehicle *vehicle); diff --git a/include/unused/sensorAltimeter.hpp b/include/unused/sensorAltimeter.hpp deleted file mode 100644 index aa3a3cd..0000000 --- a/include/unused/sensorAltimeter.hpp +++ /dev/null @@ -1,165 +0,0 @@ -#pragma once -#include "sensorI2C.hpp" -#include <string> - -/* -Header file for driver for MPL3115a2 breakout, based heavily on https://github.com/adafruit/Adafruit_MPL3115A2_Library/tree/master -Based on register declarations found https://cdn-shop.adafruit.com/datasheets/1893_datasheet.pdf -Designed using subclass for I2C handler for Beaglebone Black -*/ - -class AltimeterSensor : public sensorI2C { - - - private: - double internalTemperature = 0; - double internalAltitude = 0; - - //ENUMS COPIED DIRECTLY FROM ADAFRUIT IMPLEMENTATION - /** MPL3115A2 registers **/ - enum { - MPL3115A2_REGISTER_STATUS = (0x00), - - MPL3115A2_REGISTER_PRESSURE_MSB = (0x01), - MPL3115A2_REGISTER_PRESSURE_CSB = (0x02), - MPL3115A2_REGISTER_PRESSURE_LSB = (0x03), - - MPL3115A2_REGISTER_TEMP_MSB = (0x04), - MPL3115A2_REGISTER_TEMP_LSB = (0x05), - - MPL3115A2_REGISTER_DR_STATUS = (0x06), - - MPL3115A2_OUT_P_DELTA_MSB = (0x07), - MPL3115A2_OUT_P_DELTA_CSB = (0x08), - MPL3115A2_OUT_P_DELTA_LSB = (0x09), - - MPL3115A2_OUT_T_DELTA_MSB = (0x0A), - MPL3115A2_OUT_T_DELTA_LSB = (0x0B), - - MPL3115A2_WHOAMI = (0x0C), - //This is hard-coded in the device from the factory - MPL3115A2_WHOAMI_EXPECTED = (0xC4), - - MPL3115A2_BAR_IN_MSB = (0x14), - MPL3115A2_BAR_IN_LSB = (0x15), - - MPL3115A2_OFF_H = (0x2D), - }; - - /** MPL3115A2 status register BITS **/ - enum { - MPL3115A2_REGISTER_STATUS_TDR = 0x02, - MPL3115A2_REGISTER_STATUS_PDR = 0x04, - MPL3115A2_REGISTER_STATUS_PTDR = 0x08, - }; - - /** MPL3115A2 PT DATA register BITS **/ - enum { - MPL3115A2_PT_DATA_CFG = 0x13, - MPL3115A2_PT_DATA_CFG_TDEFE = 0x01, - MPL3115A2_PT_DATA_CFG_PDEFE = 0x02, - MPL3115A2_PT_DATA_CFG_DREM = 0x04, - }; - - /** MPL3115A2 control registers **/ - enum { - MPL3115A2_CTRL_REG1 = (0x26), - MPL3115A2_CTRL_REG2 = (0x27), - MPL3115A2_CTRL_REG3 = (0x28), - MPL3115A2_CTRL_REG4 = (0x29), - MPL3115A2_CTRL_REG5 = (0x2A), - }; - - /** MPL3115A2 control register BITS **/ - enum { - MPL3115A2_CTRL_REG1_SBYB = 0x01, - MPL3115A2_CTRL_REG1_OST = 0x02, - MPL3115A2_CTRL_REG1_RST = 0x04, - MPL3115A2_CTRL_REG1_RAW = 0x40, - MPL3115A2_CTRL_REG1_ALT = 0x80, - MPL3115A2_CTRL_REG1_BAR = 0x00, - }; - - /** MPL3115A2 oversample values **/ - enum { - MPL3115A2_CTRL_REG1_OS1 = 0x00, - MPL3115A2_CTRL_REG1_OS2 = 0x08, - MPL3115A2_CTRL_REG1_OS4 = 0x10, - MPL3115A2_CTRL_REG1_OS8 = 0x18, - MPL3115A2_CTRL_REG1_OS16 = 0x20, - MPL3115A2_CTRL_REG1_OS32 = 0x28, - MPL3115A2_CTRL_REG1_OS64 = 0x30, - MPL3115A2_CTRL_REG1_OS128 = 0x38, - }; - - /** MPL3115A2 measurement modes **/ - typedef enum { - MPL3115A2_BAROMETER = 0, - MPL3115A2_ALTIMETER, - } mpl3115a2_mode_t; - - /** MPL3115A2 measurement types **/ - typedef enum { - MPL3115A2_PRESSURE, - MPL3115A2_ALTITUDE, - MPL3115A2_TEMPERATURE, - } mpl3115a2_meas_t; - - //This never actually gets used, and I can't find anything in the datasheet about it?? - #define MPL3115A2_REGISTER_STARTCONVERSION (0x12) ///< start conversion - - //Store current operating mode, sent to device during startup procedure - //This is why an enum is used rather than raw #define statements - mpl3115a2_mode_t currentMode; - - //Struct for storing ctrl register contents, copied from adafruit implementation - typedef union { - struct { - uint8_t SBYB : 1; - uint8_t OST : 1; - uint8_t RST : 1; - uint8_t OS : 3; - uint8_t RAW : 1; - uint8_t ALT : 1; - } bit; - uint8_t reg; - } CTRL_REG_1_STRUCT; - //Create instance of this register config to use during device startup and operation - CTRL_REG_1_STRUCT ctrl_reg1; - - public: - - /** - * @brief Construct a new Altimeter Sensor object - * - */ - AltimeterSensor(std::string I2C_FILE); - - /** - * @brief Initialize the Altimeter - * - * @param data Data for initializing the sensor - * @return true Initialization Success - * @return false Initialization Failure - */ - bool init() override; - - //Data getters and setters - // double getPressure(); - double getAltitude(); - double getTemperature(); - double setSeaLevelPressure(double pressure); - - //Data and mode handlers - //Use altimeter mode by default as this is what rocket logger wants - void setMode(mpl3115a2_mode_t mode = MPL3115A2_ALTIMETER); - void requestOneShotReading(); - bool isNewDataAvailable(); - void updateCurrentDataBuffer(); - - -}; - - - - diff --git a/include/unused/sensorI2C.hpp b/include/unused/sensorI2C.hpp deleted file mode 100644 index bd497a5..0000000 --- a/include/unused/sensorI2C.hpp +++ /dev/null @@ -1,105 +0,0 @@ -#pragma once - -#include <stdio.h> -#include <fcntl.h> -#include <unistd.h> -#include <sys/ioctl.h> -#include <linux/i2c.h> -#include <linux/i2c-dev.h> -#include <cstdint> -#include <string> - -class sensorI2C { - - - //Predominantly used for I2C handler functions; implement high-level functions in sensor classes - //Implemented as a combination of Jazz' implementation and Derek Malloy's code - public: - - //Initial single byte write, used at beginning of read operation - //Returns 0 if successful, -1 if not - int initialWrite(unsigned char registerAddress) { - unsigned char *convertedAddressBuffer = new unsigned char[1]; - convertedAddressBuffer[0] = registerAddress; - //Expect 1 byte response from 1 byte write - if (write(i2c_bus, convertedAddressBuffer, 1) != 1) { - fprintf(stderr, "ERROR DOING INITIAL READ TRANSACTION WRITE TO REGISTER %x FOR DEVICE %x\n", registerAddress, deviceAddress); - return 0; - } - return 1; - } - - int writeRegister(unsigned char registerAddress, unsigned char value) { - //initialWrite() not used here because it's easier to just pack it into one buffer for file writing - unsigned char writeBuffer[2]; - writeBuffer[0] = registerAddress; - writeBuffer[1] = value; - - //Expect 2 byte output - if (write(i2c_bus, writeBuffer, 2) != 2) { - //These error messages are kind of obtuse but I'd rather have too much information than not enough - fprintf(stderr, "ERROR WRITING %x TO REGISTER %x ON DEVICE %x\n", value, registerAddress, deviceAddress); - return -1; - } - return 0; - } - - //Could probably be uint8_t but Derek Malloy does it with unsigned chars and that's what worked during testing so I don't want to touch it - unsigned char readSingleRegister(unsigned char registerAddress) { - printf("reg addr: %X\n", registerAddress); - - initialWrite(registerAddress); - unsigned char* readBuffer = new unsigned char[1]; - if (read(i2c_bus, readBuffer, 1) != 1){ - fprintf(stderr, "FAILED TO READ VALUE FROM REGISTER %x ON DEVICE %x\n", registerAddress, deviceAddress); - return -1; - } - printf("readBuffer: %X\n", readBuffer[0]); - return readBuffer[0]; - } - - unsigned char* readMultipleRegisters(unsigned char startingRegisterAddress, int numberOfRegisters) { - initialWrite(startingRegisterAddress); - unsigned char* readBuffer = new unsigned char[numberOfRegisters]; - if (read(i2c_bus, readBuffer, numberOfRegisters) != numberOfRegisters) { - fprintf(stderr, "ERROR TRYING TO READ %d REGISTERS STARTING AT ADDRESS %x ON DEVICE %x\n", - numberOfRegisters, startingRegisterAddress, deviceAddress); - } - return readBuffer; - } - - - //Intakes device address and file - //Private because IT'S ASSUMED PROGRAMMER WILL CALL THIS METHOD DURING INIT() ROUTINE - int setupI2C(std::string I2C_FILE) { - // Open i2c driver file - i2c_bus = open("/dev/i2c-2", O_RDWR); - if(i2c_bus < 0){ - fprintf(stderr, "FAILED TO OPEN I2C BUS USING FILE %s\n", "/dev/i2c-2"); - close(i2c_bus); - return -1; - } - - // Identify slave device address (MODIFIED FROM INITIAL IMPLEMENTATION, USES INTERNAL deviceAddress INSTEAD OF PARAMETER) - if(ioctl(i2c_bus, I2C_SLAVE, deviceAddress) < 0){ - fprintf(stderr, "FAILED TO CONNECT TO DEVICE AT ADDRESS %x VIA I2C\n", deviceAddress); - close(i2c_bus); - return -1; - } - return 0; - } - - /** - * @brief Initialize the sensor. - * - * @param data Data for initializing the sensor - * - * @return true Initialization Success - * @return false Initialization Failure - */ - virtual bool init() = 0; - - unsigned char deviceAddress; - int i2c_bus; - std::string I2C_FILE; -}; diff --git a/include/unused/sensorIMU.hpp b/include/unused/sensorIMU.hpp deleted file mode 100644 index caddbe4..0000000 --- a/include/unused/sensorIMU.hpp +++ /dev/null @@ -1,312 +0,0 @@ -#pragma once -#include <vector> -#include "sensorI2C.hpp" -#include "logger.hpp" -#include "rocketUtils.hpp" -#include "imumath.h" -#include <string> - -struct IMUData { - std::vector<double> acceleration[3]; - std::vector<double> linear_acceleration[3]; -}; - -//Register addresses and data structs copied from Adafruit implementation -/** BNO055 Address A **/ -#define BNO055_ADDRESS_A (0x28) -/** BNO055 Address B **/ -#define BNO055_ADDRESS_B (0x29) -/** BNO055 ID **/ -#define BNO055_ID (0xA0) - -/** Offsets registers **/ -#define NUM_BNO055_OFFSET_REGISTERS (22) - -/** A structure to represent offsets **/ -typedef struct { - int16_t accel_offset_x; /**< x acceleration offset */ - int16_t accel_offset_y; /**< y acceleration offset */ - int16_t accel_offset_z; /**< z acceleration offset */ - - int16_t mag_offset_x; /**< x magnetometer offset */ - int16_t mag_offset_y; /**< y magnetometer offset */ - int16_t mag_offset_z; /**< z magnetometer offset */ - - int16_t gyro_offset_x; /**< x gyroscrope offset */ - int16_t gyro_offset_y; /**< y gyroscrope offset */ - int16_t gyro_offset_z; /**< z gyroscrope offset */ - - int16_t accel_radius; /**< acceleration radius */ - - int16_t mag_radius; /**< magnetometer radius */ -} adafruit_bno055_offsets_t; - -/** Operation mode settings **/ -typedef enum { - 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_IMUPLUS = 0X08, - OPERATION_MODE_COMPASS = 0X09, - OPERATION_MODE_M4G = 0X0A, - OPERATION_MODE_NDOF_FMC_OFF = 0X0B, - OPERATION_MODE_NDOF = 0X0C -} adafruit_bno055_opmode_t; -class IMUSensor : public sensorI2C { - - private: - deviceAddress = BNO055_ADDRESS_A; - - adafruit_bno055_opmode_t default_mode = OPERATION_MODE_NDOF; - /** BNO055 Registers **/ - typedef enum { - /* Page id register definition */ - BNO055_PAGE_ID_ADDR = 0X07, - - /* PAGE0 REGISTER DEFINITION START*/ - 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, - - /* Accel data register */ - BNO055_ACCEL_DATA_X_LSB_ADDR = 0X08, - BNO055_ACCEL_DATA_X_MSB_ADDR = 0X09, - 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, - - /* Mag data register */ - 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, - - /* Gyro data registers */ - 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_GYRO_DATA_Z_LSB_ADDR = 0X18, - BNO055_GYRO_DATA_Z_MSB_ADDR = 0X19, - - /* Euler data registers */ - 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, - - /* Quaternion data registers */ - 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, - - /* Linear acceleration data registers */ - BNO055_LINEAR_ACCEL_DATA_X_LSB_ADDR = 0X28, - BNO055_LINEAR_ACCEL_DATA_X_MSB_ADDR = 0X29, - 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, - - /* Gravity data registers */ - 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, - - /* Temperature data register */ - BNO055_TEMP_ADDR = 0X34, - - /* Status registers */ - BNO055_CALIB_STAT_ADDR = 0X35, - BNO055_SELFTEST_RESULT_ADDR = 0X36, - BNO055_INTR_STAT_ADDR = 0X37, - - BNO055_SYS_CLK_STAT_ADDR = 0X38, - BNO055_SYS_STAT_ADDR = 0X39, - BNO055_SYS_ERR_ADDR = 0X3A, - - /* Unit selection register */ - BNO055_UNIT_SEL_ADDR = 0X3B, - - /* Mode registers */ - BNO055_OPR_MODE_ADDR = 0X3D, - BNO055_PWR_MODE_ADDR = 0X3E, - - BNO055_SYS_TRIGGER_ADDR = 0X3F, - BNO055_TEMP_SOURCE_ADDR = 0X40, - - /* Axis remap registers */ - BNO055_AXIS_MAP_CONFIG_ADDR = 0X41, - BNO055_AXIS_MAP_SIGN_ADDR = 0X42, - - /* SIC registers */ - 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_2_MSB_ADDR = 0X48, - BNO055_SIC_MATRIX_3_LSB_ADDR = 0X49, - 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, - - /* Accelerometer Offset registers */ - ACCEL_OFFSET_X_LSB_ADDR = 0X55, - ACCEL_OFFSET_X_MSB_ADDR = 0X56, - ACCEL_OFFSET_Y_LSB_ADDR = 0X57, - ACCEL_OFFSET_Y_MSB_ADDR = 0X58, - ACCEL_OFFSET_Z_LSB_ADDR = 0X59, - ACCEL_OFFSET_Z_MSB_ADDR = 0X5A, - - /* Magnetometer Offset registers */ - 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, - - /* Gyroscope Offset register s*/ - 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, - - /* Radius registers */ - ACCEL_RADIUS_LSB_ADDR = 0X67, - ACCEL_RADIUS_MSB_ADDR = 0X68, - MAG_RADIUS_LSB_ADDR = 0X69, - MAG_RADIUS_MSB_ADDR = 0X6A - } adafruit_bno055_reg_t; - - /** BNO055 power settings */ - typedef enum { - POWER_MODE_NORMAL = 0X00, - POWER_MODE_LOWPOWER = 0X01, - POWER_MODE_SUSPEND = 0X02 - } adafruit_bno055_powermode_t; - - /** Remap settings **/ - typedef enum { - REMAP_CONFIG_P0 = 0x21, - REMAP_CONFIG_P1 = 0x24, // default - REMAP_CONFIG_P2 = 0x24, - REMAP_CONFIG_P3 = 0x21, - REMAP_CONFIG_P4 = 0x24, - REMAP_CONFIG_P5 = 0x21, - REMAP_CONFIG_P6 = 0x21, - REMAP_CONFIG_P7 = 0x24 - } adafruit_bno055_axis_remap_config_t; - - /** Remap Signs **/ - typedef enum { - REMAP_SIGN_P0 = 0x04, - REMAP_SIGN_P1 = 0x00, // default - REMAP_SIGN_P2 = 0x06, - REMAP_SIGN_P3 = 0x02, - REMAP_SIGN_P4 = 0x03, - REMAP_SIGN_P5 = 0x01, - REMAP_SIGN_P6 = 0x07, - REMAP_SIGN_P7 = 0x05 - } adafruit_bno055_axis_remap_sign_t; - - /** A structure to represent revisions **/ - typedef struct { - uint8_t accel_rev; /**< acceleration rev */ - uint8_t mag_rev; /**< magnetometer rev */ - uint8_t gyro_rev; /**< gyroscrope rev */ - uint16_t sw_rev; /**< SW rev */ - uint8_t bl_rev; /**< bootloader rev */ - } adafruit_bno055_rev_info_t; - - /** Vector Mappings **/ - typedef enum { - 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 - } adafruit_vector_type_t; - - int32_t _sensorID; - adafruit_bno055_opmode_t currentMode; - - public: - /** - * @brief Construct a new IMUSensor object - * - */ - IMUSensor(std::string I2C_FILE); - - /** - * @brief Inititlize the IMU - * - * @param data Data for initializing the sensor - * @return true Initialization Success - * @return false Initialization Failure - */ - bool init() override; - - //Data handlers, copied from adafruit implementation (not all of them) - void setModeTemp(adafruit_bno055_opmode_t mode); - void setModeHard(adafruit_bno055_opmode_t mode); - adafruit_bno055_opmode_t getMode(); - - imu::Vector<3> getVector(adafruit_vector_type_t vector_type); - imu::Quaternion getQuat(); - int8_t getTemp(); - - //Configuration and status getters/setters - void setAxisRemap(adafruit_bno055_axis_remap_config_t remapcode); - void setAxisSign(adafruit_bno055_axis_remap_sign_t remapsign); - void getSystemStatus(uint8_t *system_status, uint8_t *self_test_result, - uint8_t *system_error); - void getCalibration(uint8_t *sys, uint8_t *gyro, uint8_t *accel, - uint8_t *mag); - - /* Functions to deal with raw calibration data */ - bool getSensorOffsets(uint8_t *calibData); - bool getSensorOffsets(adafruit_bno055_offsets_t &offsets_type); - void setSensorOffsets(const uint8_t *calibData); - void setSensorOffsets(const adafruit_bno055_offsets_t &offsets_type); - bool isFullyCalibrated(); - - /* Power managments functions */ - void enterSuspendMode(); - void enterNormalMode(); - -};
\ No newline at end of file diff --git a/include/unused/surfaceFitModel.hpp b/include/unused/surfaceFitModel.hpp deleted file mode 100644 index 303633f..0000000 --- a/include/unused/surfaceFitModel.hpp +++ /dev/null @@ -1,32 +0,0 @@ -#pragma once -#include <cmath> -#include "eigen3/Eigen/Dense" - - -using namespace Eigen; - -#define X_DEGREE 4 // Highest x-degree of current Surface Fit Model -#define Y_DEGREE 3 // Highest y-degree of current Surface Fit Model - -class SurfaceFitModel { - - private: - MatrixXd p; // Polynomial values - - public: - - /** - * @brief Construct a new Surface Fit Model object - * - */ - SurfaceFitModel(); - - /** - * @brief - * - * @param x - * @param y - * @return double - */ - double getFit(double x, double y); -}; |
