mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
Copter: move sending of send_pid_tuning up
This commit is contained in:
parent
166f246744
commit
eed73749f9
@ -268,11 +268,6 @@ bool GCS_MAVLINK_Copter::try_send_message(enum ap_message id)
|
||||
// unused
|
||||
break;
|
||||
|
||||
case MSG_PID_TUNING:
|
||||
CHECK_PAYLOAD_SIZE(PID_TUNING);
|
||||
send_pid_tuning();
|
||||
break;
|
||||
|
||||
case MSG_ADSB_VEHICLE:
|
||||
#if ADSB_ENABLED == ENABLED
|
||||
CHECK_PAYLOAD_SIZE(ADSB_VEHICLE);
|
||||
|
@ -64,6 +64,6 @@ private:
|
||||
int16_t vfr_hud_throttle() const override;
|
||||
float vfr_hud_alt() const override;
|
||||
|
||||
void send_pid_tuning();
|
||||
void send_pid_tuning() override;
|
||||
|
||||
};
|
||||
|
Loading…
Reference in New Issue
Block a user