mirror of https://github.com/ArduPilot/ardupilot
parent
303030c524
commit
0dd6415052
|
@ -76,6 +76,7 @@ void AP_Stats::flush()
|
||||||
void AP_Stats::update_flighttime()
|
void AP_Stats::update_flighttime()
|
||||||
{
|
{
|
||||||
if (_flying_ms) {
|
if (_flying_ms) {
|
||||||
|
WITH_SEMAPHORE(sem);
|
||||||
const uint32_t now = AP_HAL::millis();
|
const uint32_t now = AP_HAL::millis();
|
||||||
const uint32_t delta = (now - _flying_ms)/1000;
|
const uint32_t delta = (now - _flying_ms)/1000;
|
||||||
flttime += delta;
|
flttime += delta;
|
||||||
|
@ -93,6 +94,7 @@ void AP_Stats::update_runtime()
|
||||||
|
|
||||||
void AP_Stats::update()
|
void AP_Stats::update()
|
||||||
{
|
{
|
||||||
|
WITH_SEMAPHORE(sem);
|
||||||
const uint32_t now_ms = AP_HAL::millis();
|
const uint32_t now_ms = AP_HAL::millis();
|
||||||
if (now_ms - last_flush_ms > flush_interval_ms) {
|
if (now_ms - last_flush_ms > flush_interval_ms) {
|
||||||
update_flighttime();
|
update_flighttime();
|
||||||
|
|
|
@ -67,7 +67,7 @@ private:
|
||||||
|
|
||||||
void update_flighttime();
|
void update_flighttime();
|
||||||
void update_runtime();
|
void update_runtime();
|
||||||
|
HAL_Semaphore_Recursive sem;
|
||||||
};
|
};
|
||||||
|
|
||||||
namespace AP {
|
namespace AP {
|
||||||
|
|
Loading…
Reference in New Issue