diff options
| author | Dawsyn Schraiber <[email protected]> | 2024-05-09 02:05:35 -0400 |
|---|---|---|
| committer | GitHub <[email protected]> | 2024-05-09 02:05:35 -0400 |
| commit | 93acde052369568beaefb0d99629d8797f5c191f (patch) | |
| tree | a3fb96ddad2d289aa7f8bf410c60cf6289bca7a1 /src/AltEst/filters.h | |
| parent | 5f68c7a1b5c8dec82d4a2e1e12443a41b5196b1d (diff) | |
| download | active-drag-system-93acde052369568beaefb0d99629d8797f5c191f.tar.gz active-drag-system-93acde052369568beaefb0d99629d8797f5c191f.tar.bz2 active-drag-system-93acde052369568beaefb0d99629d8797f5c191f.zip | |
Raspberry Pi Pico (#12)
* Adding a 90% completed, compilable but untested ADS
* Made basic changes to actuator & sensor. Also added motor class
* Removed unnecessary .cpp files
* Updated sensor & actuator classes, finished ads, added variable time step to kalman filter, set up all tests for future assertions
* Relocated 'main' to 'active-drag-system.cpp'. Added more info to README
* Removed main.cpp
* Added more details to README
* Changed some function parameters from pass-by-pointer to pass-by-reference. Also removed the std namespace
* Started writing the test cases
* Updated the .gitignore file
* Removed some files that should be gitignored
* Up to date with Jazz's pull request
* Test Launch Branch Created; PRU Servo Control with Test Program
* Added I2C device class and register IDs for MPL [INCOMPLETE SENSOR IMPLEMENTATION]
Needs actual data getting function implementation for both sensors and register IDs for BNO, will implement shortly.
* Partial implementation of MPL sensor
Added startup method, still needs fleshed out data getters and setters and finished I2C implementation. MOST LIKELY WILL HAVE COMPILATION ISSUES.
* *Hypothetically* complete MPL implementation
NEEDS HARDWARE TESTING
* IMU Header and init() method implementation
Needs like, all data handling still lol
* Hypothetically functional (Definitely won't compile)
* We ball?
* Conversion to Raspberry Pi Pico Build System; Removed Beaglebone
specific code; Simple blinking example in ADS source file; builds for
Pico W
* Rearranged build so dependent upon cmake file already existing in pico-sdk; current executable prints current altitude, velocity, and time taken to read and calculate said values; ~320 us to do so
* Altimeter interrupt callback for Pad to Boost State; dummy templates for other callbacks with comments describing potential implementation details
* Altimeter interrupts relatively finished; need to test with vacuum chamber to verify behavior
* Established interrupt pins as pullup and active-low; adjusted callback functions to properly use function pointers; still need to verify interrupt system with vacuum chamber
* Removed weird artifact in .gitignore, adjust CMakeLists to auto pull pico sdk, added Dockerfile
* added Docker dev container file
* modified CMakeLists to auto pull sdk if not already downloaded, add build.sh script, fixed Dockerfile
* added bno055 support
* changed bno055 lin accel struct to use float instead of double
* added bno055 support not tested, but compiles, fixed CMakLists to before I messed with it
* added absolute quaternion output from bno055
* Added Euler and aboslute linear accelration
* Flash implementation for data logging; each log entry is 32 bytes long
* added base pwm functions and started on apogee detection
* State machine verified functional with logging capabilities; currently on same core
* Ooops missed double define, renamed LOOP_HZ to LOOP_PERIOD; State machine functional after merge still
* Simple test program to see servo PWM range; logging with semaphores for safe multithreading
* Kalman filters generously provided from various sources for temporary replacement; minimum deployment 30 percent; state machine functionality restored; multithreading logging verified; altimeter broke and replaced
* Stop logging on END state; provide deployment function with AGL instead of ASL altitude
* Various minimal changes; Flash size from 1MB to 8MB; M1939 to M2500T burn time; pin assignments for new PCB; External Status LED to Internal Status LED
---------
Co-authored-by: Jazz Jackson <[email protected]>
Co-authored-by: Cian Capacci <[email protected]>
Co-authored-by: Gregory Wainer <[email protected]>
Diffstat (limited to 'src/AltEst/filters.h')
| -rw-r--r-- | src/AltEst/filters.h | 65 |
1 files changed, 65 insertions, 0 deletions
diff --git a/src/AltEst/filters.h b/src/AltEst/filters.h new file mode 100644 index 0000000..2e316a3 --- /dev/null +++ b/src/AltEst/filters.h @@ -0,0 +1,65 @@ +/* + filters.h: Filter class declarations + */ + +#pragma once + +//#include <cmath> +#include <math.h> +#include <stdint.h> + +#include "algebra.h" + +class KalmanFilter { + private: + float currentState[3] = {0, 0, 1}; + float currErrorCovariance[3][3] = {{100, 0, 0},{0, 100, 0},{0, 0, 100}}; + float H[3][3] = {{9.81, 0, 0}, {0, 9.81, 0}, {0, 0, 9.81}}; + float previousAccelSensor[3] = {0, 0, 0}; + float ca; + float sigmaGyro; + float sigmaAccel; + + void getPredictionCovariance(float covariance[3][3], float previousState[3], float deltat); + + void getMeasurementCovariance(float covariance[3][3]); + + void predictState(float predictedState[3], float gyro[3], float deltat); + + void predictErrorCovariance(float covariance[3][3], float gyro[3], float deltat); + + void updateGain(float gain[3][3], float errorCovariance[3][3]); + + void updateState(float updatedState[3], float predictedState[3], float gain[3][3], float accel[3]); + + void updateErrorCovariance(float covariance[3][3], float errorCovariance[3][3], float gain[3][3]); + + public: + + KalmanFilter(float ca, float sigmaGyro, float sigmaAccel); + + float estimate(float gyro[3], float accel[3], float deltat); + +}; // Class KalmanFilter + +class ComplementaryFilter { + + private: + + // filter gain + float gain[2]; + // Zero-velocity update + float accelThreshold; + static const uint8_t ZUPT_SIZE = 12; + uint8_t ZUPTIdx; + float ZUPT[ZUPT_SIZE]; + + float ApplyZUPT(float accel, float vel); + + public: + + ComplementaryFilter(float sigmaAccel, float sigmaBaro, float accelThreshold); + + void estimate(float * velocity, float * altitude, float baroAltitude, + float pastAltitude, float pastVelocity, float accel, float deltat); +}; // Class ComplementaryFilter |
