mirror of https://github.com/ArduPilot/ardupilot
Copter: implement send_winch_status
This commit is contained in:
parent
f607ff28b3
commit
54b714a24e
|
@ -229,6 +229,18 @@ void GCS_MAVLINK_Copter::send_pid_tuning()
|
|||
}
|
||||
}
|
||||
|
||||
// send winch status message
|
||||
void GCS_MAVLINK_Copter::send_winch_status() const
|
||||
{
|
||||
#if WINCH_ENABLED == ENABLED
|
||||
AP_Winch *winch = AP::winch();
|
||||
if (winch == nullptr) {
|
||||
return;
|
||||
}
|
||||
winch->send_status(*this);
|
||||
#endif
|
||||
}
|
||||
|
||||
uint8_t GCS_MAVLINK_Copter::sysid_my_gcs() const
|
||||
{
|
||||
return copter.g.sysid_my_gcs;
|
||||
|
@ -445,6 +457,7 @@ static const ap_message STREAM_EXTRA3_msgs[] = {
|
|||
MSG_RPM,
|
||||
MSG_ESC_TELEMETRY,
|
||||
MSG_GENERATOR_STATUS,
|
||||
MSG_WINCH_STATUS,
|
||||
};
|
||||
static const ap_message STREAM_PARAMS_msgs[] = {
|
||||
MSG_NEXT_PARAM
|
||||
|
|
|
@ -65,4 +65,5 @@ private:
|
|||
|
||||
void send_pid_tuning() override;
|
||||
|
||||
void send_winch_status() const override;
|
||||
};
|
||||
|
|
Loading…
Reference in New Issue