diff --git a/boards/beaglebone/blue/adc/adc.cpp b/boards/beaglebone/blue/adc/adc.cpp index 7d9aec5c5e..6b9dbf1864 100644 --- a/boards/beaglebone/blue/adc/adc.cpp +++ b/boards/beaglebone/blue/adc/adc.cpp @@ -74,7 +74,7 @@ uint32_t px4_arch_adc_sample(uint32_t base_address, unsigned channel) // ADC_SYSFS_PATH char channel_path[strlen(ADC_SYSFS_PATH) + 20] {}; - if (sprintf(channel_path, "%s/in_voltage%d_raw", ADC_SYSFS_PATH, channel) == -1) { + if (snprintf(channel_path, sizeof(channel_path), "%s/in_voltage%d_raw", ADC_SYSFS_PATH, channel) == -1) { PX4_ERR("adc channel: %d\n", channel); return UINT32_MAX; // error } diff --git a/boards/emlid/navio2/adc/adc.cpp b/boards/emlid/navio2/adc/adc.cpp index 017c600876..d804fbe74e 100644 --- a/boards/emlid/navio2/adc/adc.cpp +++ b/boards/emlid/navio2/adc/adc.cpp @@ -74,7 +74,7 @@ uint32_t px4_arch_adc_sample(uint32_t base_address, unsigned channel) // ADC_SYSFS_PATH char channel_path[strlen(ADC_SYSFS_PATH) + 5] {}; - if (sprintf(channel_path, "%s/ch%d", ADC_SYSFS_PATH, channel) == -1) { + if (snprintf(channel_path, sizeof(channel_path), "%s/ch%d", ADC_SYSFS_PATH, channel) == -1) { PX4_ERR("adc channel: %d\n", channel); return UINT32_MAX; // error } diff --git a/platforms/common/px4_log.cpp b/platforms/common/px4_log.cpp index 8e733b5ee4..cfe4b954ad 100644 --- a/platforms/common/px4_log.cpp +++ b/platforms/common/px4_log.cpp @@ -103,7 +103,7 @@ __EXPORT void px4_log_modulename(int level, const char *module_name, const char #if defined(PX4_LOG_COLORIZED_OUTPUT) if (use_color) { - pos += sprintf(buf + pos, "%s", __px4_log_level_color[level]); + pos += snprintf(buf + pos, math::max(max_length - pos, (ssize_t)0), "%s", __px4_log_level_color[level]); } #endif // PX4_LOG_COLORIZED_OUTPUT @@ -137,13 +137,14 @@ __EXPORT void px4_log_modulename(int level, const char *module_name, const char if (use_color) { // alway reset color - const ssize_t sz = math::min(pos, max_length - (ssize_t)strlen(PX4_ANSI_COLOR_RESET) - (ssize_t)1); - pos += sprintf(buf + sz, "%s\n", PX4_ANSI_COLOR_RESET); + const ssize_t sz = math::min(pos, (ssize_t)(max_length - strlen(PX4_ANSI_COLOR_RESET) - 1)); + pos += snprintf(buf + sz, math::max(max_length - sz, (ssize_t)0), "%s\n", PX4_ANSI_COLOR_RESET); } else #endif // PX4_LOG_COLORIZED_OUTPUT { - pos += sprintf(buf + math::min(pos, max_length - (ssize_t)1), "\n"); + const ssize_t sz = math::min(pos, max_length - 1); + pos += snprintf(buf + sz, math::max(max_length - sz, (ssize_t)0), "\n"); } // ensure NULL termination (buffer is max_length + 1) @@ -162,7 +163,7 @@ __EXPORT void px4_log_modulename(int level, const char *module_name, const char va_start(argptr, fmt); pos += vsnprintf(buf + pos, math::max(max_length - pos, (ssize_t)0), fmt, argptr); va_end(argptr); - pos += sprintf(buf + math::min(pos, max_length - (ssize_t)1), "\n"); + pos += snprintf(buf + math::min(pos, max_length - (ssize_t)1), math::max(max_length - pos, (ssize_t)0), "\n"); buf[max_length] = 0; // ensure NULL termination } @@ -197,6 +198,7 @@ __EXPORT void px4_log_modulename(int level, const char *module_name, const char va_start(argptr, fmt); pos += vsnprintf((char *)log_message.text + pos, math::max(max_length - pos, (ssize_t)0), fmt, argptr); va_end(argptr); + log_message.text[max_length - 1] = 0; //ensure 0-termination log_message.timestamp = hrt_absolute_time(); orb_publish(ORB_ID(log_message), orb_log_message_pub, &log_message); @@ -220,7 +222,7 @@ __EXPORT void px4_log_raw(int level, const char *fmt, ...) #if defined(PX4_LOG_COLORIZED_OUTPUT) if (use_color) { - pos += sprintf(buf + pos, "%s", __px4_log_level_color[level]); + pos += snprintf(buf + pos, math::max(max_length - pos, (ssize_t)0), "%s", __px4_log_level_color[level]); } #endif // PX4_LOG_COLORIZED_OUTPUT @@ -235,7 +237,7 @@ __EXPORT void px4_log_raw(int level, const char *fmt, ...) if (use_color) { // alway reset color const ssize_t sz = math::min(pos, max_length - (ssize_t)strlen(PX4_ANSI_COLOR_RESET)); - pos += sprintf(buf + sz, "%s", PX4_ANSI_COLOR_RESET); + pos += snprintf(buf + sz, math::max(max_length - sz, (ssize_t)0), "%s", PX4_ANSI_COLOR_RESET); } #endif // PX4_LOG_COLORIZED_OUTPUT @@ -280,9 +282,7 @@ __EXPORT void px4_log_raw(int level, const char *fmt, ...) __EXPORT void px4_log_history(FILE *out) { - #if defined(BOARD_ENABLE_LOG_HISTORY) - g_log_history.print(out); #endif // BOARD_ENABLE_LOG_HISTORY } diff --git a/platforms/common/px4_work_queue/WorkQueueManager.cpp b/platforms/common/px4_work_queue/WorkQueueManager.cpp index 3852215b29..39becbb62c 100644 --- a/platforms/common/px4_work_queue/WorkQueueManager.cpp +++ b/platforms/common/px4_work_queue/WorkQueueManager.cpp @@ -346,7 +346,7 @@ WorkQueueManagerRun(int, char **) // pack wq struct pointer into string, this is compatible with px4_task_spawn_cmd char arg1[sizeof(void *) * 3]; - sprintf(arg1, "%lx", (long unsigned)wq); + snprintf(arg1, sizeof(arg1), "%lx", (long unsigned)wq); const char *arg[2] = {arg1, nullptr}; int pid = px4_task_spawn_cmd(wq->name, diff --git a/platforms/common/uORB/uORB_tests/uORBTest_UnitTest.cpp b/platforms/common/uORB/uORB_tests/uORBTest_UnitTest.cpp index bc7cda5132..f8631fa04d 100644 --- a/platforms/common/uORB/uORB_tests/uORBTest_UnitTest.cpp +++ b/platforms/common/uORB/uORB_tests/uORBTest_UnitTest.cpp @@ -111,7 +111,7 @@ int uORBTest::UnitTest::pubsublatency_main() if (pubsubtest_print && timings) { char fname[32] {}; - sprintf(fname, PX4_STORAGEDIR"/uorb_timings%u.txt", timingsgroup); + snprintf(fname, sizeof(fname), PX4_STORAGEDIR"/uorb_timings%u.txt", timingsgroup); FILE *f = fopen(fname, "w"); if (f == nullptr) { diff --git a/src/drivers/telemetry/iridiumsbd/IridiumSBD.cpp b/src/drivers/telemetry/iridiumsbd/IridiumSBD.cpp index 95b72e4562..9d32145775 100644 --- a/src/drivers/telemetry/iridiumsbd/IridiumSBD.cpp +++ b/src/drivers/telemetry/iridiumsbd/IridiumSBD.cpp @@ -726,7 +726,7 @@ void IridiumSBD::write_tx_buf() pthread_mutex_lock(&_tx_buf_mutex); char command[13]; - sprintf(command, "AT+SBDWB=%d", _tx_buf_write_idx); + snprintf(command, sizeof(command), "AT+SBDWB=%d", _tx_buf_write_idx); write_at(command); if (read_at_command() != SATCOM_RESULT_READY) { diff --git a/src/lib/sensor_calibration/Utilities.cpp b/src/lib/sensor_calibration/Utilities.cpp index dd3f2d8cb2..80d618e92f 100644 --- a/src/lib/sensor_calibration/Utilities.cpp +++ b/src/lib/sensor_calibration/Utilities.cpp @@ -1,6 +1,6 @@ /**************************************************************************** * - * Copyright (c) 2020-2021 PX4 Development Team. All rights reserved. + * Copyright (c) 2020-2022 PX4 Development Team. All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions @@ -63,8 +63,8 @@ int8_t FindCurrentCalibrationIndex(const char *sensor_type, uint32_t device_id) } for (unsigned i = 0; i < MAX_SENSOR_COUNT; ++i) { - char str[20] {}; - sprintf(str, "CAL_%s%u_ID", sensor_type, i); + char str[16 + 1] {}; + snprintf(str, sizeof(str), "CAL_%s%u_ID", sensor_type, i); int32_t device_id_val = 0; @@ -102,8 +102,8 @@ int8_t FindAvailableCalibrationIndex(const char *sensor_type, uint32_t device_id uint32_t cal_device_ids[MAX_SENSOR_COUNT] {}; for (unsigned i = 0; i < MAX_SENSOR_COUNT; ++i) { - char str[20] {}; - sprintf(str, "CAL_%s%u_ID", sensor_type, i); + char str[16 + 1] {}; + snprintf(str, sizeof(str), "CAL_%s%u_ID", sensor_type, i); int32_t device_id_val = 0; if (param_get(param_find_no_notification(str), &device_id_val) == PX4_OK) { @@ -137,8 +137,8 @@ int8_t FindAvailableCalibrationIndex(const char *sensor_type, uint32_t device_id int32_t GetCalibrationParamInt32(const char *sensor_type, const char *cal_type, uint8_t instance) { // eg CAL_MAGn_ID/CAL_MAGn_ROT - char str[20] {}; - sprintf(str, "CAL_%s%" PRIu8 "_%s", sensor_type, instance, cal_type); + char str[16 + 1] {}; + snprintf(str, sizeof(str), "CAL_%s%" PRIu8 "_%s", sensor_type, instance, cal_type); int32_t value = 0; @@ -152,8 +152,8 @@ int32_t GetCalibrationParamInt32(const char *sensor_type, const char *cal_type, float GetCalibrationParamFloat(const char *sensor_type, const char *cal_type, uint8_t instance) { // eg CAL_BAROn_OFF - char str[20] {}; - sprintf(str, "CAL_%s%" PRIu8 "_%s", sensor_type, instance, cal_type); + char str[16 + 1] {}; + snprintf(str, sizeof(str), "CAL_%s%" PRIu8 "_%s", sensor_type, instance, cal_type); float value = NAN; @@ -168,13 +168,13 @@ Vector3f GetCalibrationParamsVector3f(const char *sensor_type, const char *cal_t { Vector3f values{0.f, 0.f, 0.f}; - char str[20] {}; + char str[16 + 1] {}; for (int axis = 0; axis < 3; axis++) { char axis_char = 'X' + axis; // eg CAL_MAGn_{X,Y,Z}OFF - sprintf(str, "CAL_%s%" PRIu8 "_%c%s", sensor_type, instance, axis_char, cal_type); + snprintf(str, sizeof(str), "CAL_%s%" PRIu8 "_%c%s", sensor_type, instance, axis_char, cal_type); if (param_get(param_find(str), &values(axis)) != 0) { PX4_ERR("failed to get %s", str); @@ -187,13 +187,13 @@ Vector3f GetCalibrationParamsVector3f(const char *sensor_type, const char *cal_t bool SetCalibrationParamsVector3f(const char *sensor_type, const char *cal_type, uint8_t instance, Vector3f values) { int ret = PX4_OK; - char str[20] {}; + char str[16 + 1] {}; for (int axis = 0; axis < 3; axis++) { char axis_char = 'X' + axis; // eg CAL_MAGn_{X,Y,Z}OFF - sprintf(str, "CAL_%s%" PRIu8 "_%c%s", sensor_type, instance, axis_char, cal_type); + snprintf(str, sizeof(str), "CAL_%s%" PRIu8 "_%c%s", sensor_type, instance, axis_char, cal_type); if (param_set_no_notification(param_find(str), &values(axis)) != 0) { PX4_ERR("failed to set %s = %.4f", str, (double)values(axis)); diff --git a/src/lib/sensor_calibration/Utilities.hpp b/src/lib/sensor_calibration/Utilities.hpp index 4696f01f36..fc5b938a3c 100644 --- a/src/lib/sensor_calibration/Utilities.hpp +++ b/src/lib/sensor_calibration/Utilities.hpp @@ -1,6 +1,6 @@ /**************************************************************************** * - * Copyright (c) 2020 PX4 Development Team. All rights reserved. + * Copyright (c) 2020-2022 PX4 Development Team. All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions @@ -85,10 +85,10 @@ float GetCalibrationParamFloat(const char *sensor_type, const char *cal_type, ui template bool SetCalibrationParam(const char *sensor_type, const char *cal_type, uint8_t instance, T value) { - char str[20] {}; + char str[16 + 1] {}; // eg CAL_MAGn_ID/CAL_MAGn_ROT - sprintf(str, "CAL_%s%u_%s", sensor_type, instance, cal_type); + snprintf(str, sizeof(str), "CAL_%s%u_%s", sensor_type, instance, cal_type); int ret = param_set_no_notification(param_find(str), &value); diff --git a/src/modules/commander/HealthAndArmingChecks/checks/rcCalibrationCheck.cpp b/src/modules/commander/HealthAndArmingChecks/checks/rcCalibrationCheck.cpp index 90f210ed66..fed8a459e4 100644 --- a/src/modules/commander/HealthAndArmingChecks/checks/rcCalibrationCheck.cpp +++ b/src/modules/commander/HealthAndArmingChecks/checks/rcCalibrationCheck.cpp @@ -50,19 +50,19 @@ RcCalibrationChecks::RcCalibrationChecks() { - char nbuf[20]; + char nbuf[16 + 1]; for (unsigned i = 0; i < input_rc_s::RC_INPUT_MAX_CHANNELS; i++) { - sprintf(nbuf, "RC%d_MIN", i + 1); + snprintf(nbuf, sizeof(nbuf), "RC%d_MIN", i + 1); _param_handles[i].min = param_find(nbuf); - sprintf(nbuf, "RC%d_TRIM", i + 1); + snprintf(nbuf, sizeof(nbuf), "RC%d_TRIM", i + 1); _param_handles[i].trim = param_find(nbuf); - sprintf(nbuf, "RC%d_MAX", i + 1); + snprintf(nbuf, sizeof(nbuf), "RC%d_MAX", i + 1); _param_handles[i].max = param_find(nbuf); - sprintf(nbuf, "RC%d_DZ", i + 1); + snprintf(nbuf, sizeof(nbuf), "RC%d_DZ", i + 1); _param_handles[i].dz = param_find(nbuf); } diff --git a/src/modules/mavlink/mavlink_shell.cpp b/src/modules/mavlink/mavlink_shell.cpp index cce39a472f..622e71a1aa 100644 --- a/src/modules/mavlink/mavlink_shell.cpp +++ b/src/modules/mavlink/mavlink_shell.cpp @@ -123,8 +123,8 @@ int MavlinkShell::start() char r_in[32]; char r_out[32]; - sprintf(r_in, "%d", remote_in_fd); - sprintf(r_out, "%d", remote_out_fd); + snprintf(r_in, sizeof(r_in), "%d", remote_in_fd); + snprintf(r_out, sizeof(r_out), "%d", remote_out_fd); char *const argv[3] = {r_in, r_out, nullptr}; #else diff --git a/src/modules/rc_update/rc_update.cpp b/src/modules/rc_update/rc_update.cpp index af4931c472..98ab159caf 100644 --- a/src/modules/rc_update/rc_update.cpp +++ b/src/modules/rc_update/rc_update.cpp @@ -69,26 +69,26 @@ RCUpdate::RCUpdate() : { // initialize parameter handles for (unsigned i = 0; i < RC_MAX_CHAN_COUNT; i++) { - char nbuf[16]; + char nbuf[16 + 1]; /* min values */ - sprintf(nbuf, "RC%d_MIN", i + 1); + snprintf(nbuf, sizeof(nbuf), "RC%d_MIN", i + 1); _parameter_handles.min[i] = param_find(nbuf); /* trim values */ - sprintf(nbuf, "RC%d_TRIM", i + 1); + snprintf(nbuf, sizeof(nbuf), "RC%d_TRIM", i + 1); _parameter_handles.trim[i] = param_find(nbuf); /* max values */ - sprintf(nbuf, "RC%d_MAX", i + 1); + snprintf(nbuf, sizeof(nbuf), "RC%d_MAX", i + 1); _parameter_handles.max[i] = param_find(nbuf); /* channel reverse */ - sprintf(nbuf, "RC%d_REV", i + 1); + snprintf(nbuf, sizeof(nbuf), "RC%d_REV", i + 1); _parameter_handles.rev[i] = param_find(nbuf); /* channel deadzone */ - sprintf(nbuf, "RC%d_DZ", i + 1); + snprintf(nbuf, sizeof(nbuf), "RC%d_DZ", i + 1); _parameter_handles.dz[i] = param_find(nbuf); } diff --git a/src/modules/temperature_compensation/TemperatureCompensation.cpp b/src/modules/temperature_compensation/TemperatureCompensation.cpp index c7508f4fbc..c1d53e31a1 100644 --- a/src/modules/temperature_compensation/TemperatureCompensation.cpp +++ b/src/modules/temperature_compensation/TemperatureCompensation.cpp @@ -49,7 +49,7 @@ namespace temperature_compensation int TemperatureCompensation::initialize_parameter_handles(ParameterHandles ¶meter_handles) { - char nbuf[16] {}; + char nbuf[16 + 1] {}; int ret = PX4_ERROR; /* rate gyro calibration parameters */ @@ -59,25 +59,25 @@ int TemperatureCompensation::initialize_parameter_handles(ParameterHandles ¶ if (ret == PX4_OK && gyro_tc_enabled) { for (unsigned j = 0; j < GYRO_COUNT_MAX; j++) { - sprintf(nbuf, "TC_G%d_ID", j); + snprintf(nbuf, sizeof(nbuf), "TC_G%d_ID", j); parameter_handles.gyro_cal_handles[j].ID = param_find(nbuf); for (unsigned i = 0; i < 3; i++) { - sprintf(nbuf, "TC_G%d_X3_%d", j, i); + snprintf(nbuf, sizeof(nbuf), "TC_G%d_X3_%d", j, i); parameter_handles.gyro_cal_handles[j].x3[i] = param_find(nbuf); - sprintf(nbuf, "TC_G%d_X2_%d", j, i); + snprintf(nbuf, sizeof(nbuf), "TC_G%d_X2_%d", j, i); parameter_handles.gyro_cal_handles[j].x2[i] = param_find(nbuf); - sprintf(nbuf, "TC_G%d_X1_%d", j, i); + snprintf(nbuf, sizeof(nbuf), "TC_G%d_X1_%d", j, i); parameter_handles.gyro_cal_handles[j].x1[i] = param_find(nbuf); - sprintf(nbuf, "TC_G%d_X0_%d", j, i); + snprintf(nbuf, sizeof(nbuf), "TC_G%d_X0_%d", j, i); parameter_handles.gyro_cal_handles[j].x0[i] = param_find(nbuf); } - sprintf(nbuf, "TC_G%d_TREF", j); + snprintf(nbuf, sizeof(nbuf), "TC_G%d_TREF", j); parameter_handles.gyro_cal_handles[j].ref_temp = param_find(nbuf); - sprintf(nbuf, "TC_G%d_TMIN", j); + snprintf(nbuf, sizeof(nbuf), "TC_G%d_TMIN", j); parameter_handles.gyro_cal_handles[j].min_temp = param_find(nbuf); - sprintf(nbuf, "TC_G%d_TMAX", j); + snprintf(nbuf, sizeof(nbuf), "TC_G%d_TMAX", j); parameter_handles.gyro_cal_handles[j].max_temp = param_find(nbuf); } } @@ -89,25 +89,25 @@ int TemperatureCompensation::initialize_parameter_handles(ParameterHandles ¶ if (ret == PX4_OK && accel_tc_enabled) { for (unsigned j = 0; j < ACCEL_COUNT_MAX; j++) { - sprintf(nbuf, "TC_A%d_ID", j); + snprintf(nbuf, sizeof(nbuf), "TC_A%d_ID", j); parameter_handles.accel_cal_handles[j].ID = param_find(nbuf); for (unsigned i = 0; i < 3; i++) { - sprintf(nbuf, "TC_A%d_X3_%d", j, i); + snprintf(nbuf, sizeof(nbuf), "TC_A%d_X3_%d", j, i); parameter_handles.accel_cal_handles[j].x3[i] = param_find(nbuf); - sprintf(nbuf, "TC_A%d_X2_%d", j, i); + snprintf(nbuf, sizeof(nbuf), "TC_A%d_X2_%d", j, i); parameter_handles.accel_cal_handles[j].x2[i] = param_find(nbuf); - sprintf(nbuf, "TC_A%d_X1_%d", j, i); + snprintf(nbuf, sizeof(nbuf), "TC_A%d_X1_%d", j, i); parameter_handles.accel_cal_handles[j].x1[i] = param_find(nbuf); - sprintf(nbuf, "TC_A%d_X0_%d", j, i); + snprintf(nbuf, sizeof(nbuf), "TC_A%d_X0_%d", j, i); parameter_handles.accel_cal_handles[j].x0[i] = param_find(nbuf); } - sprintf(nbuf, "TC_A%d_TREF", j); + snprintf(nbuf, sizeof(nbuf), "TC_A%d_TREF", j); parameter_handles.accel_cal_handles[j].ref_temp = param_find(nbuf); - sprintf(nbuf, "TC_A%d_TMIN", j); + snprintf(nbuf, sizeof(nbuf), "TC_A%d_TMIN", j); parameter_handles.accel_cal_handles[j].min_temp = param_find(nbuf); - sprintf(nbuf, "TC_A%d_TMAX", j); + snprintf(nbuf, sizeof(nbuf), "TC_A%d_TMAX", j); parameter_handles.accel_cal_handles[j].max_temp = param_find(nbuf); } } @@ -119,25 +119,25 @@ int TemperatureCompensation::initialize_parameter_handles(ParameterHandles ¶ if (ret == PX4_OK && baro_tc_enabled) { for (unsigned j = 0; j < BARO_COUNT_MAX; j++) { - sprintf(nbuf, "TC_B%d_ID", j); + snprintf(nbuf, sizeof(nbuf), "TC_B%d_ID", j); parameter_handles.baro_cal_handles[j].ID = param_find(nbuf); - sprintf(nbuf, "TC_B%d_X5", j); + snprintf(nbuf, sizeof(nbuf), "TC_B%d_X5", j); parameter_handles.baro_cal_handles[j].x5 = param_find(nbuf); - sprintf(nbuf, "TC_B%d_X4", j); + snprintf(nbuf, sizeof(nbuf), "TC_B%d_X4", j); parameter_handles.baro_cal_handles[j].x4 = param_find(nbuf); - sprintf(nbuf, "TC_B%d_X3", j); + snprintf(nbuf, sizeof(nbuf), "TC_B%d_X3", j); parameter_handles.baro_cal_handles[j].x3 = param_find(nbuf); - sprintf(nbuf, "TC_B%d_X2", j); + snprintf(nbuf, sizeof(nbuf), "TC_B%d_X2", j); parameter_handles.baro_cal_handles[j].x2 = param_find(nbuf); - sprintf(nbuf, "TC_B%d_X1", j); + snprintf(nbuf, sizeof(nbuf), "TC_B%d_X1", j); parameter_handles.baro_cal_handles[j].x1 = param_find(nbuf); - sprintf(nbuf, "TC_B%d_X0", j); + snprintf(nbuf, sizeof(nbuf), "TC_B%d_X0", j); parameter_handles.baro_cal_handles[j].x0 = param_find(nbuf); - sprintf(nbuf, "TC_B%d_TREF", j); + snprintf(nbuf, sizeof(nbuf), "TC_B%d_TREF", j); parameter_handles.baro_cal_handles[j].ref_temp = param_find(nbuf); - sprintf(nbuf, "TC_B%d_TMIN", j); + snprintf(nbuf, sizeof(nbuf), "TC_B%d_TMIN", j); parameter_handles.baro_cal_handles[j].min_temp = param_find(nbuf); - sprintf(nbuf, "TC_B%d_TMAX", j); + snprintf(nbuf, sizeof(nbuf), "TC_B%d_TMAX", j); parameter_handles.baro_cal_handles[j].max_temp = param_find(nbuf); } } diff --git a/src/modules/temperature_compensation/temperature_calibration/accel.cpp b/src/modules/temperature_compensation/temperature_calibration/accel.cpp index 9dc6c071f8..c807bb5e91 100644 --- a/src/modules/temperature_compensation/temperature_calibration/accel.cpp +++ b/src/modules/temperature_compensation/temperature_calibration/accel.cpp @@ -204,7 +204,7 @@ int TemperatureCalibrationAccel::finish_sensor_instance(PerSensorData &data, int (double)res[2][3]); data.tempcal_complete = true; - char str[30]; + char str[16 + 1]; float param = 0.0f; int result = PX4_OK; @@ -212,7 +212,7 @@ int TemperatureCalibrationAccel::finish_sensor_instance(PerSensorData &data, int for (unsigned axis_index = 0; axis_index < 3; axis_index++) { for (unsigned coef_index = 0; coef_index <= 3; coef_index++) { - sprintf(str, "TC_A%d_X%d_%d", sensor_index, 3 - coef_index, axis_index); + snprintf(str, sizeof(str), "TC_A%d_X%d_%d", sensor_index, 3 - coef_index, axis_index); param = (float)res[axis_index][coef_index]; result = param_set_no_notification(param_find(str), ¶m); diff --git a/src/modules/temperature_compensation/temperature_calibration/baro.cpp b/src/modules/temperature_compensation/temperature_calibration/baro.cpp index 4d1dc7be90..6a4e114582 100644 --- a/src/modules/temperature_compensation/temperature_calibration/baro.cpp +++ b/src/modules/temperature_compensation/temperature_calibration/baro.cpp @@ -190,14 +190,14 @@ int TemperatureCalibrationBaro::finish_sensor_instance(PerSensorData &data, int (double)res[1], (double)res[2], (double)res[3], (double)res[4], (double)res[5]); data.tempcal_complete = true; - char str[30]; + char str[16 + 1]; float param = 0.0f; int result = PX4_OK; set_parameter("TC_B%d_ID", sensor_index, &data.device_id); for (unsigned coef_index = 0; coef_index <= POLYFIT_ORDER; coef_index++) { - sprintf(str, "TC_B%d_X%d", sensor_index, (POLYFIT_ORDER - coef_index)); + snprintf(str, sizeof(str), "TC_B%d_X%d", sensor_index, (POLYFIT_ORDER - coef_index)); param = (float)res[coef_index]; result = param_set_no_notification(param_find(str), ¶m); diff --git a/src/modules/temperature_compensation/temperature_calibration/common.h b/src/modules/temperature_compensation/temperature_calibration/common.h index 442ed01af3..815d0bcd67 100644 --- a/src/modules/temperature_compensation/temperature_calibration/common.h +++ b/src/modules/temperature_compensation/temperature_calibration/common.h @@ -96,8 +96,8 @@ protected: int TemperatureCalibrationBase::set_parameter(const char *format_str, unsigned index, const void *value) { - char param_str[30] {}; - (void)sprintf(param_str, format_str, index); + char param_str[16 + 1] {}; + snprintf(param_str, sizeof(param_str), format_str, index); int result = param_set_no_notification(param_find(param_str), value); if (result != 0) { diff --git a/src/modules/temperature_compensation/temperature_calibration/gyro.cpp b/src/modules/temperature_compensation/temperature_calibration/gyro.cpp index 0f0f9c4a1e..60ff34a5d1 100644 --- a/src/modules/temperature_compensation/temperature_calibration/gyro.cpp +++ b/src/modules/temperature_compensation/temperature_calibration/gyro.cpp @@ -189,7 +189,7 @@ int TemperatureCalibrationGyro::finish_sensor_instance(PerSensorData &data, int (double)res[2][3]); data.tempcal_complete = true; - char str[30] {}; + char str[16 + 1] {}; float param = 0.0f; int result = PX4_OK; @@ -197,7 +197,7 @@ int TemperatureCalibrationGyro::finish_sensor_instance(PerSensorData &data, int for (unsigned axis_index = 0; axis_index < 3; axis_index++) { for (unsigned coef_index = 0; coef_index <= 3; coef_index++) { - sprintf(str, "TC_G%d_X%d_%d", sensor_index, 3 - coef_index, axis_index); + snprintf(str, sizeof(str), "TC_G%d_X%d_%d", sensor_index, 3 - coef_index, axis_index); param = (float)res[axis_index][coef_index]; result = param_set_no_notification(param_find(str), ¶m); diff --git a/src/systemcmds/tests/test_float.cpp b/src/systemcmds/tests/test_float.cpp index aaccf1a4f0..8316c5dbe2 100644 --- a/src/systemcmds/tests/test_float.cpp +++ b/src/systemcmds/tests/test_float.cpp @@ -89,7 +89,7 @@ bool FloatTest::singlePrecisionTests() fabsf(atan2f_ones - 0.785398163397448278999490867136f) < 2.0f * FLT_EPSILON); char sbuf[30]; - sprintf(sbuf, "%8.4f", (double)0.553415f); + snprintf(sbuf, sizeof(sbuf), "%8.4f", (double)0.553415f); ut_compare("sbuf[0]", sbuf[0], ' '); ut_compare("sbuf[1]", sbuf[1], ' '); ut_compare("sbuf[2]", sbuf[2], '0'); @@ -100,7 +100,7 @@ bool FloatTest::singlePrecisionTests() ut_compare("sbuf[7]", sbuf[7], '4'); ut_compare("sbuf[8]", sbuf[8], '\0'); - sprintf(sbuf, "%8.4f", (double) - 0.553415f); + snprintf(sbuf, sizeof(sbuf), "%8.4f", (double) - 0.553415f); ut_compare("sbuf[0]", sbuf[0], ' '); ut_compare("sbuf[1]", sbuf[1], '-'); ut_compare("sbuf[2]", sbuf[2], '0'); @@ -144,7 +144,7 @@ bool FloatTest::doublePrecisionTests() char sbuf[30]; - sprintf(sbuf, "%8.4f", 0.553415); + snprintf(sbuf, sizeof(sbuf), "%8.4f", 0.553415); ut_compare("sbuf[0]", sbuf[0], ' '); ut_compare("sbuf[1]", sbuf[1], ' '); ut_compare("sbuf[2]", sbuf[2], '0'); @@ -156,7 +156,7 @@ bool FloatTest::doublePrecisionTests() ut_compare("sbuf[8]", sbuf[8], '\0'); - sprintf(sbuf, "%8.4f", -0.553415); + snprintf(sbuf, sizeof(sbuf), "%8.4f", -0.553415); ut_compare("sbuf[0]", sbuf[0], ' '); ut_compare("sbuf[1]", sbuf[1], '-'); ut_compare("sbuf[2]", sbuf[2], '0'); diff --git a/src/systemcmds/tests/test_mount.cpp b/src/systemcmds/tests/test_mount.cpp index d7675714de..623fddd5bd 100644 --- a/src/systemcmds/tests/test_mount.cpp +++ b/src/systemcmds/tests/test_mount.cpp @@ -169,7 +169,7 @@ int test_mount(int argc, char *argv[]) } char buf[64]; - (void)sprintf(buf, "TEST: %d %d ", it_left_fsync, it_left_abort); + snprintf(buf, sizeof(buf), "TEST: %d %d ", it_left_fsync, it_left_abort); lseek(cmd_fd, 0, SEEK_SET); write(cmd_fd, buf, strlen(buf) + 1); fsync(cmd_fd); diff --git a/src/systemcmds/tests/test_uart_send.c b/src/systemcmds/tests/test_uart_send.c index ae37aa1e9b..55404d0ec6 100644 --- a/src/systemcmds/tests/test_uart_send.c +++ b/src/systemcmds/tests/test_uart_send.c @@ -80,7 +80,7 @@ int test_uart_send(int argc, char *argv[]) uint64_t start_time = hrt_absolute_time(); for (i = 0; i < 30000; i++) { - n = sprintf(sample_test_uart, "SAMPLE #%d\n", i); + n = snprintf(sample_test_uart, sizeof(sample_test_uart), "SAMPLE #%d\n", i); write(test_uart, sample_test_uart, n); }