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

AP_HAL: Util: make vsnprintf and snprintf always null-terminate #9289

Merged
merged 8 commits into from Oct 20, 2018
2 changes: 1 addition & 1 deletion libraries/AP_Arming/AP_Arming.cpp
Expand Up @@ -125,7 +125,7 @@ void AP_Arming::check_failed(const enum AP_Arming::ArmingChecks check, bool repo
return;
}
char taggedfmt[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1];
hal.util->snprintf((char*)taggedfmt, sizeof(taggedfmt)-1, "PreArm: %s", fmt);
hal.util->snprintf(taggedfmt, sizeof(taggedfmt), "PreArm: %s", fmt);
MAV_SEVERITY severity = check_severity(check);
va_list arg_list;
va_start(arg_list, fmt);
Expand Down
4 changes: 2 additions & 2 deletions libraries/AP_BattMonitor/AP_BattMonitor.cpp
Expand Up @@ -209,9 +209,9 @@ void AP_BattMonitor::convert_params(void) {
info.old_group_element = conversionTable[i].old_element;
info.type = (ap_var_type)AP_BattMonitor_Params::var_info[destination_index].type;
if (param_instance) {
hal.util->snprintf(param_name, 17, "BATT2_%s", AP_BattMonitor_Params::var_info[destination_index].name);
hal.util->snprintf(param_name, sizeof(param_name), "BATT2_%s", AP_BattMonitor_Params::var_info[destination_index].name);
} else {
hal.util->snprintf(param_name, 17, "BATT_%s", AP_BattMonitor_Params::var_info[destination_index].name);
hal.util->snprintf(param_name, sizeof(param_name), "BATT_%s", AP_BattMonitor_Params::var_info[destination_index].name);
}

AP_Param::convert_old_parameter(&info, 1.0f, 0);
Expand Down
7 changes: 5 additions & 2 deletions libraries/AP_HAL/Util.cpp
Expand Up @@ -52,9 +52,12 @@ int AP_HAL::Util::snprintf(char* str, size_t size, const char *format, ...)

int AP_HAL::Util::vsnprintf(char* str, size_t size, const char *format, va_list ap)
{
BufferPrinter buf(str, size);
if (size == 0) {
return 0;
}
BufferPrinter buf(str, size-1);
print_vprintf(&buf, format, ap);
// null terminate if possible
// null terminate
int ret = buf._offs;
buf.write(0);
return ret;
Expand Down
38 changes: 37 additions & 1 deletion libraries/AP_HAL/examples/Printf/Printf.cpp
Expand Up @@ -47,8 +47,10 @@ static const struct {
{ "%.1f", 10.6f, "10.6" },
};

static void test_printf(void)
static void test_printf_floats(void)
{
hal.console->printf("Starting Printf floats test\n");

uint8_t i;
char buf[30];
uint8_t failures = 0;
Expand All @@ -75,6 +77,40 @@ static void test_printf(void)
hal.console->printf("%u failures\n", (unsigned)failures);
}

static void test_printf_null_termination(void)
{
hal.console->printf("Starting Printf null-termination tests\n");

{
char buf[10];
int ret = hal.util->snprintf(buf,sizeof(buf), "%s", "ABCDEABCDE");
const int want = 9;
if (ret != want) {
hal.console->printf("snprintf returned %d expected %d\n", ret, want);
}
if (!strncmp(buf, "ABCDEABCD", sizeof(buf))) {
hal.console->printf("Bad snprintf string (%s)\n", buf);
}
}
{
char buf[10];
int ret = hal.util->snprintf(buf,sizeof(buf), "ABCDEABCDE");
const int want = 9;
if (ret != want) {
hal.console->printf("snprintf returned %d expected %d\n", ret, want);
}
if (!strncmp(buf, "ABCDEABCD", sizeof(buf))) {
hal.console->printf("Bad snprintf string (%s)\n", buf);
}
}
}

static void test_printf(void)
{
test_printf_floats();
test_printf_null_termination();
}

void loop(void)
{
test_printf();
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_NavEKF2/AP_NavEKF2_core.h
Expand Up @@ -1155,7 +1155,7 @@ class NavEKF2_core
} mag_state;

// string representing last reason for prearm failure
char prearm_fail_string[40];
char prearm_fail_string[41];

// performance counters
AP_HAL::Util::perf_counter_t _perf_UpdateFilter;
Expand Down
4 changes: 2 additions & 2 deletions libraries/AP_OSD/AP_OSD_Backend.cpp
Expand Up @@ -28,7 +28,7 @@ void AP_OSD_Backend::write(uint8_t x, uint8_t y, bool blink, const char *fmt, ..
if (blink && (blink_phase < 2)) {
return;
}
char buff[32];
char buff[32+1]; // +1 for snprintf null-termination
va_list ap;
va_start(ap, fmt);
int res = hal.util->vsnprintf(buff, sizeof(buff), fmt, ap);
Expand All @@ -43,7 +43,7 @@ void AP_OSD_Backend::write(uint8_t x, uint8_t y, bool blink, const char *fmt, ..
res--;
}
}
if (res < int(sizeof(buff))) {
if (res < int(sizeof(buff))-1) {
write(x, y, buff);
}
va_end(ap);
Expand Down
2 changes: 1 addition & 1 deletion libraries/DataFlash/DataFlash.cpp
Expand Up @@ -431,7 +431,7 @@ bool DataFlash_Class::logging_failed() const

void DataFlash_Class::Log_Write_MessageF(const char *fmt, ...)
{
char msg[64] {};
char msg[65] {}; // sizeof(log_Message.msg) + null-termination

va_list ap;
va_start(ap, fmt);
Expand Down
2 changes: 1 addition & 1 deletion libraries/DataFlash/DataFlash_Backend.cpp
Expand Up @@ -408,7 +408,7 @@ bool DataFlash_Backend::ShouldLog(bool is_critical)

bool DataFlash_Backend::Log_Write_MessageF(const char *fmt, ...)
{
char msg[64] {};
char msg[65] {}; // sizeof(log_Message.msg) + null-termination

va_list ap;
va_start(ap, fmt);
Expand Down
4 changes: 2 additions & 2 deletions libraries/GCS_MAVLink/GCS.cpp
Expand Up @@ -7,8 +7,8 @@ extern const AP_HAL::HAL& hal;
*/
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((char *)text, sizeof(text)-1, fmt, arg_list);
char text[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1];
hal.util->vsnprintf(text, sizeof(text), fmt, arg_list);
send_statustext(severity, GCS_MAVLINK::active_channel_mask() | GCS_MAVLINK::streaming_channel_mask(), text);
}

Expand Down
4 changes: 2 additions & 2 deletions libraries/GCS_MAVLink/GCS_Common.cpp
Expand Up @@ -628,8 +628,8 @@ void GCS_MAVLINK::handle_gimbal_report(AP_Mount &mount, mavlink_message_t *msg)

void GCS_MAVLINK::send_textv(MAV_SEVERITY severity, const char *fmt, va_list arg_list)
{
char text[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1] {};
hal.util->vsnprintf((char *)text, sizeof(text)-1, fmt, arg_list);
char text[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1];
hal.util->vsnprintf(text, sizeof(text), fmt, arg_list);
gcs().send_statustext(severity, (1<<chan), text);
}
void GCS_MAVLINK::send_text(MAV_SEVERITY severity, const char *fmt, ...)
Expand Down