GCS_MAVLink: consolidate places we snprintf statustexts
This commit is contained in:
parent
9410d40b2f
commit
a9f62f196e
@ -37,8 +37,6 @@ const MAV_MISSION_TYPE GCS_MAVLINK::supported_mission_types[] = {
|
|||||||
*/
|
*/
|
||||||
void GCS::send_textv(MAV_SEVERITY severity, const char *fmt, va_list arg_list)
|
void GCS::send_textv(MAV_SEVERITY severity, const char *fmt, va_list arg_list)
|
||||||
{
|
{
|
||||||
char text[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1];
|
|
||||||
hal.util->vsnprintf(text, sizeof(text), fmt, arg_list);
|
|
||||||
uint8_t mask = GCS_MAVLINK::active_channel_mask() | GCS_MAVLINK::streaming_channel_mask();
|
uint8_t mask = GCS_MAVLINK::active_channel_mask() | GCS_MAVLINK::streaming_channel_mask();
|
||||||
if (!update_send_has_been_called) {
|
if (!update_send_has_been_called) {
|
||||||
// we have not yet initialised the streaming-channel-mask,
|
// we have not yet initialised the streaming-channel-mask,
|
||||||
@ -46,7 +44,7 @@ void GCS::send_textv(MAV_SEVERITY severity, const char *fmt, va_list arg_list)
|
|||||||
// it to all channels:
|
// it to all channels:
|
||||||
mask = (1<<_num_gcs)-1;
|
mask = (1<<_num_gcs)-1;
|
||||||
}
|
}
|
||||||
send_statustext(severity, mask, text);
|
send_textv(severity, fmt, arg_list, mask);
|
||||||
}
|
}
|
||||||
|
|
||||||
void GCS::send_text(MAV_SEVERITY severity, const char *fmt, ...)
|
void GCS::send_text(MAV_SEVERITY severity, const char *fmt, ...)
|
||||||
|
@ -838,8 +838,8 @@ public:
|
|||||||
|
|
||||||
void send_text(MAV_SEVERITY severity, const char *fmt, ...) FMT_PRINTF(3, 4);
|
void send_text(MAV_SEVERITY severity, const char *fmt, ...) FMT_PRINTF(3, 4);
|
||||||
void send_textv(MAV_SEVERITY severity, const char *fmt, va_list arg_list);
|
void send_textv(MAV_SEVERITY severity, const char *fmt, va_list arg_list);
|
||||||
virtual void send_statustext(MAV_SEVERITY severity, uint8_t dest_bitmask, const char *text);
|
virtual void send_textv(MAV_SEVERITY severity, const char *fmt, va_list arg_list, uint8_t mask);
|
||||||
void service_statustext(void);
|
|
||||||
virtual GCS_MAVLINK *chan(const uint8_t ofs) = 0;
|
virtual GCS_MAVLINK *chan(const uint8_t ofs) = 0;
|
||||||
virtual const GCS_MAVLINK *chan(const uint8_t ofs) const = 0;
|
virtual const GCS_MAVLINK *chan(const uint8_t ofs) const = 0;
|
||||||
// return the number of valid GCS objects
|
// return the number of valid GCS objects
|
||||||
@ -938,6 +938,7 @@ private:
|
|||||||
|
|
||||||
void update_sensor_status_flags();
|
void update_sensor_status_flags();
|
||||||
|
|
||||||
|
void service_statustext(void);
|
||||||
#if HAL_MEM_CLASS <= HAL_MEM_CLASS_192 || CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
#if HAL_MEM_CLASS <= HAL_MEM_CLASS_192 || CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||||
static const uint8_t _status_capacity = 5;
|
static const uint8_t _status_capacity = 5;
|
||||||
#else
|
#else
|
||||||
|
@ -600,12 +600,10 @@ void GCS_MAVLINK::handle_param_value(const mavlink_message_t &msg)
|
|||||||
|
|
||||||
void GCS_MAVLINK::send_text(MAV_SEVERITY severity, const char *fmt, ...) const
|
void GCS_MAVLINK::send_text(MAV_SEVERITY severity, const char *fmt, ...) const
|
||||||
{
|
{
|
||||||
char text[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1];
|
|
||||||
va_list arg_list;
|
va_list arg_list;
|
||||||
va_start(arg_list, fmt);
|
va_start(arg_list, fmt);
|
||||||
hal.util->vsnprintf(text, sizeof(text), fmt, arg_list);
|
gcs().send_textv(severity, fmt, arg_list, (1<<chan));
|
||||||
va_end(arg_list);
|
va_end(arg_list);
|
||||||
gcs().send_statustext(severity, (1<<chan), text);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void GCS_MAVLINK::handle_radio_status(const mavlink_message_t &msg, bool log_radio)
|
void GCS_MAVLINK::handle_radio_status(const mavlink_message_t &msg, bool log_radio)
|
||||||
@ -1762,13 +1760,14 @@ void GCS_MAVLINK::send_ahrs()
|
|||||||
/*
|
/*
|
||||||
send a statustext text string to specific MAVLink bitmask
|
send a statustext text string to specific MAVLink bitmask
|
||||||
*/
|
*/
|
||||||
void GCS::send_statustext(MAV_SEVERITY severity, uint8_t dest_bitmask, const char *text)
|
void GCS::send_textv(MAV_SEVERITY severity, const char *fmt, va_list arg_list, uint8_t dest_bitmask)
|
||||||
{
|
{
|
||||||
|
char text[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1];
|
||||||
|
if (hal.util->vsnprintf(text, sizeof(text), fmt, arg_list) > MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1) {
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||||
if (strlen(text) > MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN) {
|
|
||||||
AP_HAL::panic("Statustext (%s) too long", text);
|
AP_HAL::panic("Statustext (%s) too long", text);
|
||||||
}
|
|
||||||
#endif
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
AP_Logger *logger = AP_Logger::get_singleton();
|
AP_Logger *logger = AP_Logger::get_singleton();
|
||||||
if (logger != nullptr) {
|
if (logger != nullptr) {
|
||||||
|
@ -85,7 +85,10 @@ private:
|
|||||||
return (GCS_MAVLINK_Dummy *)_chan[ofs];
|
return (GCS_MAVLINK_Dummy *)_chan[ofs];
|
||||||
};
|
};
|
||||||
|
|
||||||
void send_statustext(MAV_SEVERITY severity, uint8_t dest_bitmask, const char *text) override { hal.console->printf("TOGCS: %s\n", text); }
|
void send_textv(MAV_SEVERITY severity, const char *fmt, va_list arg_list, uint8_t dest_bitmask) override {
|
||||||
|
hal.console->printf("TOGCS: ");
|
||||||
|
hal.console->vprintf(fmt, arg_list);
|
||||||
|
}
|
||||||
|
|
||||||
MAV_TYPE frame_type() const override { return MAV_TYPE_FIXED_WING; }
|
MAV_TYPE frame_type() const override { return MAV_TYPE_FIXED_WING; }
|
||||||
uint32_t custom_mode() const override { return 3; } // magic number
|
uint32_t custom_mode() const override { return 3; } // magic number
|
||||||
|
Loading…
Reference in New Issue
Block a user