these macros were also defined in NuttX in clock.h
@ -115,7 +115,7 @@ bool AP_Baro_BMP280::_init()
_dev->get_semaphore()->give();
// request 50Hz update
_dev->register_periodic_callback(20 * USEC_PER_MSEC, FUNCTOR_BIND_MEMBER(&AP_Baro_BMP280::_timer, void));
_dev->register_periodic_callback(20 * AP_USEC_PER_MSEC, FUNCTOR_BIND_MEMBER(&AP_Baro_BMP280::_timer, void));
return true;
}
@ -144,7 +144,7 @@ bool AP_Baro_MS56XX::_init()
/* Request 100Hz update */
_dev->register_periodic_callback(10 * USEC_PER_MSEC,
_dev->register_periodic_callback(10 * AP_USEC_PER_MSEC,
FUNCTOR_BIND_MEMBER(&AP_Baro_MS56XX::_timer, void));