mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-21 16:18:29 -04:00
Rover: let AP_Vehicle base class worry about scheduler delay callback
This commit is contained in:
parent
9ef23872e0
commit
09669bdc66
@ -1054,36 +1054,3 @@ uint64_t GCS_MAVLINK_Rover::capabilities() const
|
||||
MAV_PROTOCOL_CAPABILITY_SET_ATTITUDE_TARGET |
|
||||
GCS_MAVLINK::capabilities());
|
||||
}
|
||||
|
||||
/*
|
||||
* a delay() callback that processes MAVLink packets. We set this as the
|
||||
* callback in long running library initialisation routines to allow
|
||||
* MAVLink to process packets while waiting for the initialisation to
|
||||
* complete
|
||||
*/
|
||||
void Rover::mavlink_delay_cb()
|
||||
{
|
||||
static uint32_t last_1hz, last_50hz, last_5s;
|
||||
|
||||
// don't allow potentially expensive logging calls:
|
||||
logger.EnableWrites(false);
|
||||
|
||||
const uint32_t tnow = millis();
|
||||
if (tnow - last_1hz > 1000) {
|
||||
last_1hz = tnow;
|
||||
gcs().send_message(MSG_HEARTBEAT);
|
||||
gcs().send_message(MSG_SYS_STATUS);
|
||||
}
|
||||
if (tnow - last_50hz > 20) {
|
||||
last_50hz = tnow;
|
||||
gcs().update_receive();
|
||||
gcs().update_send();
|
||||
notify.update();
|
||||
}
|
||||
if (tnow - last_5s > 5000) {
|
||||
last_5s = tnow;
|
||||
gcs().send_text(MAV_SEVERITY_INFO, "Initialising APM");
|
||||
}
|
||||
|
||||
logger.EnableWrites(true);
|
||||
}
|
||||
|
@ -429,7 +429,6 @@ private:
|
||||
|
||||
|
||||
public:
|
||||
void mavlink_delay_cb();
|
||||
void failsafe_check();
|
||||
// Motor test
|
||||
void motor_test_output();
|
||||
|
@ -8,11 +8,6 @@ The init_ardupilot function processes everything we need for an in - air restart
|
||||
#include "Rover.h"
|
||||
#include <AP_Common/AP_FWVersion.h>
|
||||
|
||||
static void mavlink_delay_cb_static()
|
||||
{
|
||||
rover.mavlink_delay_cb();
|
||||
}
|
||||
|
||||
static void failsafe_check_static()
|
||||
{
|
||||
rover.failsafe_check();
|
||||
@ -46,9 +41,7 @@ void Rover::init_ardupilot()
|
||||
// setup first port early to allow BoardConfig to report errors
|
||||
gcs().setup_console();
|
||||
|
||||
// Register mavlink_delay_cb, which will run anytime you have
|
||||
// more than 5ms remaining in your call to hal.scheduler->delay
|
||||
hal.scheduler->register_delay_callback(mavlink_delay_cb_static, 5);
|
||||
register_scheduler_delay_callback();
|
||||
|
||||
BoardConfig.init();
|
||||
#if HAL_WITH_UAVCAN
|
||||
|
Loading…
Reference in New Issue
Block a user