Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

create recovery timer mechanism #101

Merged
merged 12 commits into from
Jun 8, 2024
Merged
Show file tree
Hide file tree
Changes from 2 commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
13 changes: 10 additions & 3 deletions boards/recovery/src/data_manager.rs
Original file line number Diff line number Diff line change
@@ -1,10 +1,12 @@
use crate::app::{fire_drogue, fire_main};
use crate::state_machine::RocketStates;
use atsamd_hal::timer::TimerCounter2;

Check warning on line 3 in boards/recovery/src/data_manager.rs

View workflow job for this annotation

GitHub Actions / clippy

unused import: `atsamd_hal::timer::TimerCounter2`

warning: unused import: `atsamd_hal::timer::TimerCounter2` --> boards/recovery/src/data_manager.rs:3:5 | 3 | use atsamd_hal::timer::TimerCounter2; | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ | = note: `#[warn(unused_imports)]` on by default
NoahSprenger marked this conversation as resolved.
Show resolved Hide resolved
use common_arm::{spawn, HydraError};
use defmt::info;
use heapless::HistoryBuffer;
use messages::sensor::{Air, EkfNav1, EkfNav2, EkfQuat, GpsVel, Imu1, Imu2, UtcTime};
use messages::Message;
use crate::app::recovery_counter_tick;

const MAIN_HEIGHT: f32 = 876.0; // meters ASL
const HEIGHT_MIN: f32 = 600.0; // meters ASL
Expand All @@ -18,6 +20,7 @@
pub gps_vel: Option<GpsVel>,
pub historical_barometer_altitude: HistoryBuffer<(f32, u32), 8>,
pub current_state: Option<RocketStates>,
pub recovery_counter: u8,
NoahSprenger marked this conversation as resolved.
Show resolved Hide resolved
}

impl DataManager {
Expand All @@ -32,6 +35,7 @@
gps_vel: None,
historical_barometer_altitude,
current_state: None,
recovery_counter: 0
}
}
/// Returns true if the rocket is descending
Expand Down Expand Up @@ -79,7 +83,7 @@
None => false,
}
}
pub fn is_landed(&self) -> bool {
pub fn is_landed(&mut self) -> bool {
if self.historical_barometer_altitude.len() < 8 {
return false;
}
Expand All @@ -99,10 +103,13 @@
match avg_sum / 7.0 {
// inclusive range
x if (-0.25..=0.25).contains(&x) => {
return true;
if (self.recovery_counter >= 15) {
NoahSprenger marked this conversation as resolved.
Show resolved Hide resolved
return true;
}
spawn!(recovery_counter_tick);

Check warning on line 109 in boards/recovery/src/data_manager.rs

View workflow job for this annotation

GitHub Actions / clippy

unnecessary parentheses around `if` condition

warning: unnecessary parentheses around `if` condition --> boards/recovery/src/data_manager.rs:109:28 | 109 | if (self.recovery_counter >= 15) { | ^ ^ | = note: `#[warn(unused_parens)]` on by default help: remove these parentheses | 109 - if (self.recovery_counter >= 15) { 109 + if self.recovery_counter >= 15 { |
NoahSprenger marked this conversation as resolved.
Show resolved Hide resolved
}
_ => {
// continue
self.recovery_counter = 0;
}
}
}
Expand Down
32 changes: 31 additions & 1 deletion boards/recovery/src/main.rs
Original file line number Diff line number Diff line change
Expand Up @@ -49,6 +49,7 @@
led_green: Pin<PB16, PushPullOutput>,
led_red: Pin<PB17, PushPullOutput>,
state_machine: StateMachine,
recovery_timer: hal::timer::TimerCounter2,
NoahSprenger marked this conversation as resolved.
Show resolved Hide resolved
}

#[monotonic(binds = SysTick, default = true)]
Expand Down Expand Up @@ -78,7 +79,7 @@

// SAFETY: Misusing the PAC API can break the system.
// This is safe because we only steal the MCLK.
let (_, _, _, _mclk) = unsafe { clocks.pac.steal() };
let (_, _, _, mut mclk) = unsafe { clocks.pac.steal() };

/* CAN config */
let (pclk_can, gclk0) = Pclk::enable(tokens.pclks.can0, gclk0);
Expand All @@ -104,6 +105,12 @@
/* State Machine config */
let state_machine = StateMachine::new();

/* Recovery Timer config */
let (pclk_tc2tc3, gclk0) = Pclk::enable(tokens.pclks.tc2_tc3, gclk0);
let timerclk: hal::clock::v1::Tc2Tc3Clock = pclk_tc2tc3.into();
let mut recovery_timer = hal::timer::TimerCounter2::tc2_(&timerclk, peripherals.TC2, &mut mclk);
recovery_timer.enable_interrupt();
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

We don't want to enable interrupts here, just create the timer object.


NoahSprenger marked this conversation as resolved.
Show resolved Hide resolved
/* Spawn tasks */
run_sm::spawn().ok();
state_send::spawn().ok();
Expand All @@ -125,6 +132,7 @@
led_green,
led_red,
state_machine,
recovery_timer,
},
init::Monotonics(mono),
)
Expand All @@ -133,9 +141,31 @@
/// Idle task for when no other tasks are running.
#[idle]
fn idle(_: idle::Context) -> ! {
loop {}

Check warning on line 144 in boards/recovery/src/main.rs

View workflow job for this annotation

GitHub Actions / clippy

empty `loop {}` wastes CPU cycles

warning: empty `loop {}` wastes CPU cycles --> boards/recovery/src/main.rs:144:9 | 144 | loop {} | ^^^^^^^ | = help: you should either use `panic!()` or add a call pausing or sleeping the thread to the loop body = help: for further information visit https://rust-lang.github.io/rust-clippy/master/index.html#empty_loop = note: `#[warn(clippy::empty_loop)]` on by default
}

// handle recovery counter
// start a counter
#[task(local = [recovery_timer])]
fn recovery_counter_tick(mut cx: recovery_counter_tick::Context) {

Check warning on line 150 in boards/recovery/src/main.rs

View workflow job for this annotation

GitHub Actions / clippy

variable does not need to be mutable

warning: variable does not need to be mutable --> boards/recovery/src/main.rs:150:30 | 150 | fn recovery_counter_tick(mut cx: recovery_counter_tick::Context) { | ----^^ | | | help: remove this `mut` | = note: `#[warn(unused_mut)]` on by default
NoahSprenger marked this conversation as resolved.
Show resolved Hide resolved
let timer = cx.local.recovery_timer;
// should probably check if timer is already running
NoahSprenger marked this conversation as resolved.
Show resolved Hide resolved
// to avoid resetting it

let duration_mins = atsamd_hal::fugit::MinutesDurationU32::minutes(1);
// timer requires specific duration format
let timer_duration: atsamd_hal::fugit::Duration<u32, 1, 1000000000> = duration_mins.convert();
timer.start(timer_duration);
}

// interrupt handler for when counter is finished
#[task(binds=TC2, shared=[data_manager])]
fn recovery_counter_finish(mut cx: recovery_counter_finish::Context) {
NoahSprenger marked this conversation as resolved.
Show resolved Hide resolved
cx.shared.data_manager.lock(|data| {
data.recovery_counter += 1;
});
}

#[task(priority = 3, local = [fired: bool = false], shared=[gpio, &em])]
fn fire_drogue(mut cx: fire_drogue::Context) {
cx.shared.em.run(|| {
Expand Down
Loading