mirror of https://github.com/ArduPilot/ardupilot
Tracker: move sending of send_pid_tuning up
This commit is contained in:
parent
1debd88083
commit
166f246744
|
@ -92,8 +92,9 @@ void GCS_MAVLINK_Tracker::send_nav_controller_output() const
|
|||
/*
|
||||
send PID tuning message
|
||||
*/
|
||||
void Tracker::send_pid_tuning(mavlink_channel_t chan)
|
||||
void GCS_MAVLINK_Tracker::send_pid_tuning()
|
||||
{
|
||||
const Parameters &g = tracker.g;
|
||||
|
||||
// Pitch PID
|
||||
if (g.gcs_pid_mask & 1) {
|
||||
|
@ -139,23 +140,6 @@ void GCS_MAVLINK_Tracker::handle_change_alt_request(AP_Mission::Mission_Command&
|
|||
// do nothing
|
||||
}
|
||||
|
||||
|
||||
// try to send a message, return false if it won't fit in the serial tx buffer
|
||||
bool GCS_MAVLINK_Tracker::try_send_message(enum ap_message id)
|
||||
{
|
||||
switch (id) {
|
||||
|
||||
case MSG_PID_TUNING:
|
||||
CHECK_PAYLOAD_SIZE(PID_TUNING);
|
||||
tracker.send_pid_tuning(chan);
|
||||
break;
|
||||
|
||||
default:
|
||||
return GCS_MAVLINK::try_send_message(id);
|
||||
}
|
||||
return true;
|
||||
}
|
||||
|
||||
/*
|
||||
default stream rates to 1Hz
|
||||
*/
|
||||
|
|
|
@ -33,6 +33,7 @@ protected:
|
|||
uint64_t capabilities() const override;
|
||||
|
||||
void send_nav_controller_output() const override;
|
||||
void send_pid_tuning() override;
|
||||
|
||||
private:
|
||||
|
||||
|
|
|
@ -227,7 +227,6 @@ private:
|
|||
|
||||
// GCS_Mavlink.cpp
|
||||
void send_nav_controller_output(mavlink_channel_t chan);
|
||||
void send_pid_tuning(mavlink_channel_t chan);
|
||||
|
||||
// Log.cpp
|
||||
void Log_Write_Attitude();
|
||||
|
|
Loading…
Reference in New Issue