2017-07-08 21:24:43 -03:00
|
|
|
#include "GCS.h"
|
|
|
|
|
|
|
|
extern const AP_HAL::HAL& hal;
|
|
|
|
|
|
|
|
/*
|
|
|
|
send a text message to all GCS
|
|
|
|
*/
|
2017-08-01 02:13:34 -03:00
|
|
|
void GCS::send_textv(MAV_SEVERITY severity, const char *fmt, va_list arg_list)
|
2017-07-08 21:24:43 -03:00
|
|
|
{
|
2018-09-05 23:18:47 -03:00
|
|
|
char text[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1];
|
|
|
|
hal.util->vsnprintf(text, sizeof(text), fmt, arg_list);
|
2017-08-01 02:13:34 -03:00
|
|
|
send_statustext(severity, GCS_MAVLINK::active_channel_mask() | GCS_MAVLINK::streaming_channel_mask(), text);
|
|
|
|
}
|
|
|
|
|
|
|
|
void GCS::send_text(MAV_SEVERITY severity, const char *fmt, ...)
|
|
|
|
{
|
2017-07-08 21:24:43 -03:00
|
|
|
va_list arg_list;
|
|
|
|
va_start(arg_list, fmt);
|
2017-08-01 02:13:34 -03:00
|
|
|
send_textv(severity, fmt, arg_list);
|
2017-07-08 21:24:43 -03:00
|
|
|
va_end(arg_list);
|
|
|
|
}
|
2017-07-08 03:26:34 -03:00
|
|
|
|
|
|
|
#define FOR_EACH_ACTIVE_CHANNEL(methodcall) \
|
|
|
|
do { \
|
|
|
|
for (uint8_t i=0; i<num_gcs(); i++) { \
|
|
|
|
if (!chan(i).initialised) { \
|
|
|
|
continue; \
|
|
|
|
} \
|
2017-08-29 03:04:40 -03:00
|
|
|
if (!(GCS_MAVLINK::active_channel_mask() & (1 << (chan(i).get_chan()-MAVLINK_COMM_0)))) { \
|
2017-07-08 03:26:34 -03:00
|
|
|
continue; \
|
|
|
|
} \
|
|
|
|
chan(i).methodcall; \
|
|
|
|
} \
|
2017-08-29 03:04:40 -03:00
|
|
|
} while (0)
|
2017-07-08 03:26:34 -03:00
|
|
|
|
2018-05-15 02:20:30 -03:00
|
|
|
void GCS::send_named_float(const char *name, float value) const
|
|
|
|
{
|
|
|
|
FOR_EACH_ACTIVE_CHANNEL(send_named_float(name, value));
|
|
|
|
}
|
|
|
|
|
2018-05-16 01:48:42 -03:00
|
|
|
void GCS::send_home() const
|
2017-07-08 03:26:34 -03:00
|
|
|
{
|
2018-05-16 01:48:42 -03:00
|
|
|
FOR_EACH_ACTIVE_CHANNEL(send_home());
|
2017-07-08 03:26:34 -03:00
|
|
|
}
|
|
|
|
|
2018-05-16 01:48:42 -03:00
|
|
|
void GCS::send_ekf_origin() const
|
2017-09-17 22:35:12 -03:00
|
|
|
{
|
2018-05-16 01:48:42 -03:00
|
|
|
FOR_EACH_ACTIVE_CHANNEL(send_ekf_origin());
|
2017-09-17 22:35:12 -03:00
|
|
|
}
|
|
|
|
|
2018-03-25 07:45:48 -03:00
|
|
|
/*
|
|
|
|
install an alternative protocol handler. This allows another
|
|
|
|
protocol to take over the link if MAVLink goes idle. It is used to
|
|
|
|
allow for the AP_BLHeli pass-thru protocols to run on hal.uartA
|
|
|
|
*/
|
|
|
|
bool GCS::install_alternative_protocol(mavlink_channel_t c, GCS_MAVLINK::protocol_handler_fn_t handler)
|
|
|
|
{
|
|
|
|
if (c >= num_gcs()) {
|
|
|
|
return false;
|
|
|
|
}
|
2018-08-04 00:33:28 -03:00
|
|
|
if (chan(c).alternative.handler && handler) {
|
2018-03-25 07:45:48 -03:00
|
|
|
// already have one installed - we may need to add support for
|
|
|
|
// multiple alternative handlers
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
chan(c).alternative.handler = handler;
|
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
2017-07-08 03:26:34 -03:00
|
|
|
#undef FOR_EACH_ACTIVE_CHANNEL
|