mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-21 16:18:29 -04:00
Rover: allow GCS MAVLink base class to handle out-of-time for sending messages
This commit is contained in:
parent
973222c786
commit
ea2de1c11a
@ -315,16 +315,6 @@ bool GCS_Rover::vehicle_initialised() const
|
||||
// try to send a message, return false if it won't fit in the serial tx buffer
|
||||
bool GCS_MAVLINK_Rover::try_send_message(enum ap_message id)
|
||||
{
|
||||
// if we don't have at least 0.2ms remaining before the main loop
|
||||
// wants to fire then don't send a mavlink message. We want to
|
||||
// prioritise the main flight control loop over communications
|
||||
if (!hal.scheduler->in_delay_callback() &&
|
||||
!AP_BoardConfig::in_sensor_config_error() &&
|
||||
rover.scheduler.time_available_usec() < 200) {
|
||||
gcs().set_out_of_time(true);
|
||||
return false;
|
||||
}
|
||||
|
||||
switch (id) {
|
||||
|
||||
case MSG_SERVO_OUT:
|
||||
|
Loading…
Reference in New Issue
Block a user