mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_Scheduler: added get_last_loop_time_s()
this gives compatibility with previous G_Dt in copter
This commit is contained in:
parent
f436901517
commit
491715bec7
@ -213,8 +213,11 @@ void AP_Scheduler::loop()
|
||||
|
||||
const uint32_t sample_time_us = AP_HAL::micros();
|
||||
|
||||
if (loop_timer_start_us == 0) {
|
||||
loop_timer_start_us = sample_time_us;
|
||||
if (_loop_timer_start_us == 0) {
|
||||
_loop_timer_start_us = sample_time_us;
|
||||
_last_loop_time_s = get_loop_period_s();
|
||||
} else {
|
||||
_last_loop_time_s = (sample_time_us - _loop_timer_start_us) * 1.0e-6;
|
||||
}
|
||||
|
||||
// Execute the fast loop
|
||||
@ -241,9 +244,9 @@ void AP_Scheduler::loop()
|
||||
#endif
|
||||
|
||||
// check loop time
|
||||
perf_info.check_loop_time(sample_time_us - loop_timer_start_us);
|
||||
perf_info.check_loop_time(sample_time_us - _loop_timer_start_us);
|
||||
|
||||
loop_timer_start_us = sample_time_us;
|
||||
_loop_timer_start_us = sample_time_us;
|
||||
}
|
||||
|
||||
void AP_Scheduler::update_logging()
|
||||
|
@ -131,6 +131,11 @@ public:
|
||||
float get_filtered_loop_time(void) const {
|
||||
return perf_info.get_filtered_time();
|
||||
}
|
||||
|
||||
// get the time in seconds that the last loop took
|
||||
float get_last_loop_time_s(void) const {
|
||||
return _last_loop_time_s;
|
||||
}
|
||||
|
||||
static const struct AP_Param::GroupInfo var_info[];
|
||||
|
||||
@ -185,8 +190,11 @@ private:
|
||||
uint8_t _spare_ticks;
|
||||
|
||||
// start of loop timing
|
||||
uint32_t loop_timer_start_us;
|
||||
uint32_t _loop_timer_start_us;
|
||||
|
||||
// time of last loop in seconds
|
||||
uint32_t _last_loop_time_s;
|
||||
|
||||
// performance counters
|
||||
AP_HAL::Util::perf_counter_t *_perf_counters;
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user