mirror of https://github.com/ArduPilot/ardupilot
GCS_MAVLink: fixed build with updated mavlink xml
This commit is contained in:
parent
756863ee9d
commit
8c9efec4e3
|
@ -24,6 +24,7 @@
|
|||
|
||||
#define GCS_DEBUG_SEND_MESSAGE_TIMINGS 0
|
||||
|
||||
#ifndef HAL_NO_GCS
|
||||
// check if a message will fit in the payload space available
|
||||
#define PAYLOAD_SIZE(chan, id) (GCS_MAVLINK::packet_overhead_chan(chan)+MAVLINK_MSG_ID_ ## id ## _LEN)
|
||||
#define HAVE_PAYLOAD_SPACE(chan, id) (comm_get_txspace(chan) >= PAYLOAD_SIZE(chan, id))
|
||||
|
@ -941,3 +942,13 @@ private:
|
|||
};
|
||||
|
||||
GCS &gcs();
|
||||
|
||||
// send text when we do have a GCS
|
||||
#define GCS_SEND_TEXT(severity, format, args...) gcs().send_text(severity, format, ##args)
|
||||
|
||||
#else // HAL_NO_GCS
|
||||
// empty send text when we have no GCS
|
||||
#define GCS_SEND_TEXT(severity, format, args...)
|
||||
|
||||
#endif // HAL_NO_GCS
|
||||
|
||||
|
|
|
@ -1833,7 +1833,7 @@ void GCS::service_statustext(void)
|
|||
mavlink_channel_t chan_index = (mavlink_channel_t)(MAVLINK_COMM_0+i);
|
||||
if (HAVE_PAYLOAD_SPACE(chan_index, STATUSTEXT)) {
|
||||
// we have space so send then clear that channel bit on the mask
|
||||
mavlink_msg_statustext_send(chan_index, statustext->msg.severity, statustext->msg.text);
|
||||
mavlink_msg_statustext_send(chan_index, statustext->msg.severity, statustext->msg.text, 0, 0);
|
||||
statustext->bitmask &= ~chan_bit;
|
||||
}
|
||||
}
|
||||
|
|
|
@ -67,5 +67,6 @@ void GCS_MAVLINK::send_fence_status() const
|
|||
static_cast<int8_t>(fence->get_breaches() != 0),
|
||||
fence->get_breach_count(),
|
||||
mavlink_breach_type,
|
||||
fence->get_breach_time());
|
||||
fence->get_breach_time(),
|
||||
0);
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue