mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-26 10:38:28 -04:00
AP_Parachute: use millis/micros/panic functions
This commit is contained in:
parent
5b06924779
commit
d186704724
@ -74,7 +74,7 @@ void AP_Parachute::release()
|
||||
|
||||
// set release time to current system time
|
||||
if (_release_time == 0) {
|
||||
_release_time = hal.scheduler->millis();
|
||||
_release_time = AP_HAL::millis();
|
||||
}
|
||||
|
||||
// update AP_Notify
|
||||
@ -90,7 +90,7 @@ void AP_Parachute::update()
|
||||
}
|
||||
|
||||
// calc time since release
|
||||
uint32_t time_diff = hal.scheduler->millis() - _release_time;
|
||||
uint32_t time_diff = AP_HAL::millis() - _release_time;
|
||||
|
||||
// check if we should release parachute
|
||||
if ((_release_time != 0) && !_release_in_progress) {
|
||||
|
Loading…
Reference in New Issue
Block a user