Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

GCS_MAVLink: consolidate places we snprintf statustexts #13245

Merged
merged 1 commit into from
Jan 13, 2020
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
4 changes: 1 addition & 3 deletions libraries/GCS_MAVLink/GCS.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -37,16 +37,14 @@ const MAV_MISSION_TYPE GCS_MAVLINK::supported_mission_types[] = {
*/
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();
if (!update_send_has_been_called) {
// we have not yet initialised the streaming-channel-mask,
// which is done as part of the update() call. So just send
// it to all channels:
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, ...)
Expand Down
5 changes: 3 additions & 2 deletions libraries/GCS_MAVLink/GCS.h
Original file line number Diff line number Diff line change
Expand Up @@ -838,8 +838,8 @@ class GCS

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);
virtual void send_statustext(MAV_SEVERITY severity, uint8_t dest_bitmask, const char *text);
void service_statustext(void);
virtual void send_textv(MAV_SEVERITY severity, const char *fmt, va_list arg_list, uint8_t mask);

virtual GCS_MAVLINK *chan(const uint8_t ofs) = 0;
virtual const GCS_MAVLINK *chan(const uint8_t ofs) const = 0;
// return the number of valid GCS objects
Expand Down Expand Up @@ -938,6 +938,7 @@ class GCS

void update_sensor_status_flags();

void service_statustext(void);
#if HAL_MEM_CLASS <= HAL_MEM_CLASS_192 || CONFIG_HAL_BOARD == HAL_BOARD_SITL
static const uint8_t _status_capacity = 5;
#else
Expand Down
11 changes: 5 additions & 6 deletions libraries/GCS_MAVLink/GCS_Common.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
{
char text[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1];
va_list arg_list;
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);
gcs().send_statustext(severity, (1<<chan), text);
}

void GCS_MAVLINK::handle_radio_status(const mavlink_message_t &msg, bool log_radio)
Expand Down Expand Up @@ -1762,13 +1760,14 @@ void GCS_MAVLINK::send_ahrs()
/*
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 (strlen(text) > MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN) {
AP_HAL::panic("Statustext (%s) too long", text);
}
#endif
}

AP_Logger *logger = AP_Logger::get_singleton();
if (logger != nullptr) {
Expand Down
5 changes: 4 additions & 1 deletion libraries/GCS_MAVLink/GCS_Dummy.h
Original file line number Diff line number Diff line change
Expand Up @@ -85,7 +85,10 @@ class GCS_Dummy : public GCS
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; }
uint32_t custom_mode() const override { return 3; } // magic number
Expand Down