mirror of https://github.com/ArduPilot/ardupilot
ArduCopter: tidy sending of winch messages
This commit is contained in:
parent
a8906ac491
commit
1059183758
|
@ -311,17 +311,17 @@ void GCS_MAVLINK_Copter::send_pid_tuning()
|
|||
}
|
||||
}
|
||||
|
||||
#if AP_WINCH_ENABLED
|
||||
// send winch status message
|
||||
void GCS_MAVLINK_Copter::send_winch_status() const
|
||||
{
|
||||
#if AP_WINCH_ENABLED
|
||||
AP_Winch *winch = AP::winch();
|
||||
if (winch == nullptr) {
|
||||
return;
|
||||
}
|
||||
winch->send_status(*this);
|
||||
#endif
|
||||
}
|
||||
#endif
|
||||
|
||||
uint8_t GCS_MAVLINK_Copter::sysid_my_gcs() const
|
||||
{
|
||||
|
|
|
@ -83,7 +83,9 @@ private:
|
|||
|
||||
void send_pid_tuning() override;
|
||||
|
||||
#if AP_WINCH_ENABLED
|
||||
void send_winch_status() const override;
|
||||
#endif
|
||||
|
||||
void send_wind() const;
|
||||
|
||||
|
|
Loading…
Reference in New Issue