Sub: let AP_Vehicle base class worry about scheduler delay callback

This commit is contained in:
Peter Barker 2020-01-16 14:04:21 +11:00 committed by Andrew Tridgell
parent 9466126fa8
commit e97582add0
3 changed files with 1 additions and 36 deletions

View File

@ -792,32 +792,6 @@ void GCS_MAVLINK_Sub::handle_rc_channels_override(const mavlink_message_t &msg)
* MAVLink to process packets while waiting for the initialisation to
* complete
*/
void Sub::mavlink_delay_cb()
{
static uint32_t last_1hz, last_50hz, last_5s;
logger.EnableWrites(false);
uint32_t tnow = AP_HAL::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);
}
MAV_RESULT GCS_MAVLINK_Sub::handle_flight_termination(const mavlink_command_long_t &packet) {
if (packet.param1 > 0.5f) {
sub.arming.disarm();

View File

@ -665,7 +665,6 @@ private:
public:
void mavlink_delay_cb();
void mainloop_failsafe_check();
};

View File

@ -7,11 +7,6 @@
*
*****************************************************************************/
static void mavlink_delay_cb_static()
{
sub.mavlink_delay_cb();
}
static void failsafe_check_static()
{
sub.mainloop_failsafe_check();
@ -78,10 +73,7 @@ void Sub::init_ardupilot()
barometer.init();
// Register the mavlink service callback. This will run
// anytime there are more than 5ms remaining in a call to
// hal.scheduler->delay.
hal.scheduler->register_delay_callback(mavlink_delay_cb_static, 5);
register_scheduler_delay_callback();
// setup telem slots with serial ports
gcs().setup_uarts();