summaryrefslogtreecommitdiff
path: root/src/unused/ads.cpp
diff options
context:
space:
mode:
authorDawsyn Schraiber <[email protected]>2024-05-09 02:05:35 -0400
committerGitHub <[email protected]>2024-05-09 02:05:35 -0400
commit93acde052369568beaefb0d99629d8797f5c191f (patch)
treea3fb96ddad2d289aa7f8bf410c60cf6289bca7a1 /src/unused/ads.cpp
parent5f68c7a1b5c8dec82d4a2e1e12443a41b5196b1d (diff)
downloadactive-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/unused/ads.cpp')
-rw-r--r--src/unused/ads.cpp286
1 files changed, 286 insertions, 0 deletions
diff --git a/src/unused/ads.cpp b/src/unused/ads.cpp
new file mode 100644
index 0000000..5484970
--- /dev/null
+++ b/src/unused/ads.cpp
@@ -0,0 +1,286 @@
+#include "../include/ads.hpp"
+
+
+// Private----------------------------------------------------------------------
+void ADS::logSummary() {
+
+ std::string output_string = "" + state_for_log[rocket.status];
+
+ if (!rocket.altiInitFail && !rocket.altiReadFail) {
+
+ output_string += format_data(" ", rocket.filtered_altitude, 3);
+ }
+
+ output_string += format_data(" ", rocket.deployment_angle, 2);
+
+ if (!rocket.imuInitFail && !rocket.imuReadFail) {
+
+ output_string += format_data(" ", rocket.acceleration[2], 2);
+ output_string += format_data(" ", rocket.filtered_velocity, 2);
+ }
+
+ Logger::Get().log(output_string);
+}
+
+
+void ADS::updateOnPadAltitude() {
+
+ std::this_thread::sleep_for(std::chrono::milliseconds(1000));
+
+ double avg_alt = 0;
+ double alt_read_count = 0;
+
+ while (alt_read_count < COUNT_LIMIT) {
+
+ altimeter.getData(&rocket.current_altitude);
+ alt_read_count++;
+ avg_alt = (avg_alt * (alt_read_count - 1) + rocket.current_altitude) / alt_read_count;
+ }
+
+ Logger::Get().log(format_data("pad altitude initialization complete - ", avg_alt, 3));
+ rocket.ON_PAD_altitude = avg_alt;
+}
+
+
+void ADS::updateSensorData() {
+
+ if (!rocket.imuInitFail) {
+
+ try {
+ imu.getData((void*)&rocket);
+ }
+
+ catch (...) {
+ std::exception_ptr e = std::current_exception();
+ Logger::Get().logErr(e.__cxa_exception_type()->name());
+ rocket.imuReadFail = true;
+ }
+ }
+
+ rocket.previous_altitude = rocket.current_altitude; // Why was this placed here????
+
+ if (!rocket.altiInitFail) {
+
+ try {
+ altimeter.getData((void*)&rocket.current_altitude);
+ if (rocket.ON_PAD_fail) {
+ rocket.ON_PAD_altitude = rocket.current_altitude;
+ rocket.ON_PAD_fail = false;
+ }
+
+ rocket.altiReadFail = false;
+ }
+
+ catch (...) {
+ std::exception_ptr e = std::current_exception();
+ Logger::Get().logErr(e.__cxa_exception_type()->name());
+ rocket.altiReadFail = true;
+ }
+ }
+}
+
+
+void ADS::updateRocketState() {
+
+ // Filter sensor data
+ VectorXf control_input(1);
+ VectorXf measurement(1);
+ control_input << rocket.acceleration[2];
+ measurement << rocket.current_altitude;
+ VectorXf filtered = kf.run(control_input, measurement, rocket.dt);
+ rocket.filtered_altitude = filtered(0);
+ rocket.filtered_velocity = filtered(1);
+
+ if (rocket.apogee_altitude < rocket.filtered_altitude) {
+ rocket.apogee_altitude = rocket.filtered_altitude;
+ }
+
+ // (VEHICLE ON PAD)
+ if (rocket.status == ON_PAD) {
+
+ // If launch detected
+ if (rocket.acceleration[2] >= BOOST_ACCEL_THRESH * G_0
+ && rocket.filtered_altitude >= BOOST_HEIGHT_THRESH + rocket.ON_PAD_altitude) {
+ Logger::Get().log(format_data("LOM at -- ", (double)(rocket.liftoff_time - rocket.start_time), 3));
+ }
+
+ if (TEST_MODE && time(nullptr) - rocket.start_time >= 15) {
+ Logger::Get().log(format_data("TEST LOM at -- ", (double)(rocket.liftoff_time - rocket.start_time), 3));
+ }
+
+ if (time(nullptr) - rocket.relog_time > 2*60*60
+ && rocket.status == ON_PAD) {
+ std::cout << "OverWR Success" << std::endl;
+ }
+ }
+
+ // (VEHICLE BOOSTING)
+ else if (rocket.status == BOOST) {
+
+ if (rocket.acceleration[2] <= GLIDE_ACCEL_THRESH * G_0
+ || time(nullptr) - rocket.liftoff_time >= TIME_BO) {
+ rocket.status = GLIDE;
+ }
+
+ }
+
+ // (VEHICLE IN GLIDE)
+ else if (rocket.status == GLIDE) {
+
+ if (rocket.filtered_altitude < rocket.apogee_altitude - APOGEE_FSM_CHANGE
+ || time(nullptr) - rocket.liftoff_time >= TIME_BO + TIME_APO) {
+ rocket.status = APOGEE;
+ Logger::Get().log(format_data("APO: ", (double)(rocket.apogee_altitude), 2));
+ }
+ }
+
+ // (VEHICLE AT APOGEE)
+ else if (rocket.status == APOGEE) {
+
+ if (rocket.filtered_altitude <= FSM_DONE_SURFACE_ALTITUDE + rocket.ON_PAD_altitude) {
+ rocket.status = DONE;
+ return;
+ }
+ }
+}
+
+
+// Public----------------------------------------------------------------------
+ADS::ADS(ActuationPlan plan) : plan(plan) {
+
+ rocket.status = ON_PAD;
+
+ rocket.apogee_altitude = 0;
+ rocket.previous_altitude = 0;
+ rocket.current_altitude = 0;
+ rocket.filtered_altitude = 0;
+
+ rocket.filtered_velocity = 0;
+
+ rocket.duty_span = DUTY_MAX - DUTY_MIN;
+ rocket.deployment_angle = deploy_percentage_to_angle(INIT_DEPLOYMENT);
+
+ rocket.dt = 0.1;
+
+ rocket.imuInitFail = false;
+ rocket.imuReadFail = false;
+ rocket.altiInitFail = false;
+ rocket.altiReadFail = false;
+
+ rocket.ON_PAD_altitude = 0;
+ rocket.ON_PAD_fail = false;
+
+ rocket.start_time = time(nullptr);
+ rocket.fail_time = rocket.start_time;
+ rocket.relog_time = rocket.start_time;
+ rocket.led_time = rocket.start_time;
+
+ imu = IMUSensor();
+ altimeter = AltimeterSensor();
+ motor = Motor();
+ kf = KalmanFilter(2, 1, 1, rocket.dt);
+
+ Logger::Get().openLog(LOG_FILENAME);
+
+ motor.init(&rocket);
+
+ imu.init(nullptr);
+ altimeter.init(nullptr);
+
+ if (TEST_MODE) {
+
+ Logger::Get().log("TEST Record Start --");
+ }
+}
+
+
+
+void ADS::run() {
+
+ if (!rocket.altiInitFail) {
+ try {
+ updateOnPadAltitude();
+ }
+
+ catch (...) {
+ std::exception_ptr e = std::current_exception();
+ Logger::Get().logErr(e.__cxa_exception_type()->name());
+ rocket.ON_PAD_fail = true;
+ }
+ }
+
+ rocket.loop_time = time(nullptr);
+ while (rocket.status != DONE) {
+
+ updateSensorData();
+
+ if (!rocket.imuInitFail && !rocket.altiInitFail) {
+
+ updateRocketState();
+
+ // Run the Actuation Plan----------------------------------
+ plan.runPlan(rocket);
+
+ if (rocket.imuReadFail || rocket.altiReadFail) {
+
+ if (rocket.imuReadFail) {
+ imu.init(nullptr); // Restart
+ Logger::Get().log("Altimeter reset attempt");
+ }
+
+ if (rocket.altiReadFail) {
+ altimeter.init(nullptr); // Restart
+ Logger::Get().log("IMU reset attempt");
+ }
+ }
+ }
+
+ // Altimeter or IMU setup failed. Attempt to reinitialize
+ else {
+
+ if (time(nullptr) - rocket.fail_time >= TIME_END) {
+ rocket.status = DONE;
+ }
+
+ if (rocket.altiInitFail || rocket.altiReadFail) {
+ imu.init(nullptr); // Restart
+ Logger::Get().log("Altimeter reset attempt");
+ }
+
+ if (rocket.imuInitFail || rocket.imuReadFail) {
+ altimeter.init(nullptr); // Restart
+ Logger::Get().log("IMU reset attempt");
+ }
+
+ rocket.deployment_angle = deploy_percentage_to_angle(INIT_DEPLOYMENT);
+ }
+
+ // Actuate Servos
+ motor.writeData(&rocket);
+
+ logSummary();
+
+ // Blink Beaglebone LED 1
+ if (time(nullptr) - rocket.led_time > LED_GAP_TIME) {
+ led_out(&rocket);
+ }
+
+ std::this_thread::sleep_for(std::chrono::milliseconds(1));
+ rocket.dt = time(nullptr) - rocket.loop_time;
+ rocket.loop_time = time(nullptr);
+ }
+
+ Logger::Get().closeLog();
+ std::cout << "Done" << std::endl;
+}
+
+
+
+
+
+
+
+
+
+
+