mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-05 23:48:31 -04:00
GCS_MAVLink: tidy sending of winch messages
This commit is contained in:
parent
564e6ec77a
commit
a8906ac491
libraries/GCS_MAVLink
@ -24,6 +24,7 @@
|
||||
#include <AP_Mount/AP_Mount_config.h>
|
||||
#include <AP_SerialManager/AP_SerialManager.h>
|
||||
#include <AP_RangeFinder/AP_RangeFinder_config.h>
|
||||
#include <AP_Winch/AP_Winch_config.h>
|
||||
|
||||
#include "ap_message.h"
|
||||
|
||||
@ -385,7 +386,9 @@ public:
|
||||
void send_set_position_target_global_int(uint8_t target_system, uint8_t target_component, const Location& loc);
|
||||
void send_rpm() const;
|
||||
void send_generator_status() const;
|
||||
#if AP_WINCH_ENABLED
|
||||
virtual void send_winch_status() const {};
|
||||
#endif
|
||||
void send_water_depth() const;
|
||||
int8_t battery_remaining_pct(const uint8_t instance) const;
|
||||
|
||||
|
@ -6021,10 +6021,12 @@ bool GCS_MAVLINK::try_send_message(const enum ap_message id)
|
||||
}
|
||||
#endif
|
||||
|
||||
#if AP_WINCH_ENABLED
|
||||
case MSG_WINCH_STATUS:
|
||||
CHECK_PAYLOAD_SIZE(WINCH_STATUS);
|
||||
send_winch_status();
|
||||
break;
|
||||
#endif
|
||||
|
||||
case MSG_WATER_DEPTH:
|
||||
#if AP_RANGEFINDER_ENABLED && APM_BUILD_TYPE(APM_BUILD_Rover)
|
||||
|
Loading…
Reference in New Issue
Block a user