mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
Plane: remove unneeded telemetry_delayed parameter
This commit is contained in:
parent
7bb28175d7
commit
a250f47f13
@ -432,7 +432,7 @@ uint32_t GCS_MAVLINK_Plane::telem_delay() const
|
||||
// try to send a message, return false if it won't fit in the serial tx buffer
|
||||
bool GCS_MAVLINK_Plane::try_send_message(enum ap_message id)
|
||||
{
|
||||
if (telemetry_delayed(chan)) {
|
||||
if (telemetry_delayed()) {
|
||||
return false;
|
||||
}
|
||||
|
||||
|
@ -821,7 +821,6 @@ private:
|
||||
|
||||
void send_aoa_ssa(mavlink_channel_t chan);
|
||||
|
||||
bool telemetry_delayed(mavlink_channel_t chan);
|
||||
void gcs_data_stream_send(void);
|
||||
void gcs_update(void);
|
||||
void gcs_send_airspeed_calibration(const Vector3f &vg);
|
||||
|
Loading…
Reference in New Issue
Block a user