mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 16:23:56 -04:00
AP_ESC_Telem: allow build with AP_Periph
This commit is contained in:
parent
c6bde6745a
commit
9da03668ae
@ -231,6 +231,7 @@ bool AP_ESC_Telem::get_usage_seconds(uint8_t esc_index, uint32_t& usage_s) const
|
||||
// send ESC telemetry messages over MAVLink
|
||||
void AP_ESC_Telem::send_esc_telemetry_mavlink(uint8_t mav_chan)
|
||||
{
|
||||
#if HAL_GCS_ENABLED
|
||||
static_assert(ESC_TELEM_MAX_ESCS <= 12, "AP_ESC_Telem::send_esc_telemetry_mavlink() only supports up-to 12 motors");
|
||||
|
||||
if (!_have_data) {
|
||||
@ -295,6 +296,7 @@ void AP_ESC_Telem::send_esc_telemetry_mavlink(uint8_t mav_chan)
|
||||
break;
|
||||
}
|
||||
}
|
||||
#endif // HAL_GCS_ENABLED
|
||||
}
|
||||
|
||||
// record an update to the telemetry data together with timestamp
|
||||
|
Loading…
Reference in New Issue
Block a user