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

Use snprintf over sprintf #21583

Merged
merged 8 commits into from
May 22, 2023
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
12 changes: 6 additions & 6 deletions platforms/common/px4_log.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down Expand Up @@ -138,12 +138,12 @@ __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);
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");
pos += snprintf(buf + math::min(pos, max_length - (ssize_t)1), 2, "\n");
}

// ensure NULL termination (buffer is max_length + 1)
Expand All @@ -162,7 +162,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), 2, "\n");
buf[max_length] = 0; // ensure NULL termination
}

Expand Down Expand Up @@ -220,7 +220,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
Expand All @@ -235,7 +235,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
Expand Down
2 changes: 1 addition & 1 deletion platforms/common/uORB/uORB_tests/uORBTest_UnitTest.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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) {
Expand Down
12 changes: 6 additions & 6 deletions src/lib/sensor_calibration/Utilities.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -64,7 +64,7 @@ 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);
snprintf(str, sizeof(str), "CAL_%s%u_ID", sensor_type, i);

int32_t device_id_val = 0;

Expand Down Expand Up @@ -103,7 +103,7 @@ int8_t FindAvailableCalibrationIndex(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);
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) {
Expand Down Expand Up @@ -138,7 +138,7 @@ int32_t GetCalibrationParamInt32(const char *sensor_type, const char *cal_type,
{
// eg CAL_MAGn_ID/CAL_MAGn_ROT
char str[20] {};
sprintf(str, "CAL_%s%" PRIu8 "_%s", sensor_type, instance, cal_type);
snprintf(str, sizeof(str), "CAL_%s%" PRIu8 "_%s", sensor_type, instance, cal_type);

int32_t value = 0;

Expand All @@ -153,7 +153,7 @@ float GetCalibrationParamFloat(const char *sensor_type, const char *cal_type, ui
{
// eg CAL_BAROn_OFF
char str[20] {};
sprintf(str, "CAL_%s%" PRIu8 "_%s", sensor_type, instance, cal_type);
snprintf(str, sizeof(str), "CAL_%s%" PRIu8 "_%s", sensor_type, instance, cal_type);

float value = NAN;

Expand All @@ -174,7 +174,7 @@ Vector3f GetCalibrationParamsVector3f(const char *sensor_type, const char *cal_t
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);
Expand All @@ -193,7 +193,7 @@ bool SetCalibrationParamsVector3f(const char *sensor_type, const char *cal_type,
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));
Expand Down
2 changes: 1 addition & 1 deletion src/lib/sensor_calibration/Utilities.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -88,7 +88,7 @@ bool SetCalibrationParam(const char *sensor_type, const char *cal_type, uint8_t
char str[20] {};

// 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);

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -53,16 +53,16 @@ RcCalibrationChecks::RcCalibrationChecks()
char nbuf[20];

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);
}

Expand Down
4 changes: 2 additions & 2 deletions src/modules/mavlink/mavlink_shell.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -121,8 +121,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
Expand Down
10 changes: 5 additions & 5 deletions src/modules/rc_update/rc_update.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -72,23 +72,23 @@ RCUpdate::RCUpdate() :
char nbuf[16];

/* 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);
}

Expand Down
52 changes: 26 additions & 26 deletions src/modules/temperature_compensation/TemperatureCompensation.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -59,25 +59,25 @@ int TemperatureCompensation::initialize_parameter_handles(ParameterHandles &para

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);
}
}
Expand All @@ -89,25 +89,25 @@ int TemperatureCompensation::initialize_parameter_handles(ParameterHandles &para

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);
}
}
Expand All @@ -119,25 +119,25 @@ int TemperatureCompensation::initialize_parameter_handles(ParameterHandles &para

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);
}
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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), &param);

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -197,7 +197,7 @@ int TemperatureCalibrationBaro::finish_sensor_instance(PerSensorData &data, int
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), &param);

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -97,7 +97,7 @@ class TemperatureCalibrationBase
int TemperatureCalibrationBase::set_parameter(const char *format_str, unsigned index, const void *value)
{
char param_str[30] {};
(void)sprintf(param_str, format_str, index);
(void)snprintf(param_str, sizeof(param_str), format_str, index);
int result = param_set_no_notification(param_find(param_str), value);

if (result != 0) {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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), &param);

Expand Down
8 changes: 4 additions & 4 deletions src/systemcmds/tests/test_float.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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');
Expand All @@ -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');
Expand Down Expand Up @@ -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');
Expand All @@ -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');
Expand Down