diff --git a/src/modules/temperature_compensation/TemperatureCompensation.cpp b/src/modules/temperature_compensation/TemperatureCompensation.cpp index 9dbdd7ee5e..cab7630bfd 100644 --- a/src/modules/temperature_compensation/TemperatureCompensation.cpp +++ b/src/modules/temperature_compensation/TemperatureCompensation.cpp @@ -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..919b4aa6a5 100644 --- a/src/modules/temperature_compensation/temperature_calibration/accel.cpp +++ b/src/modules/temperature_compensation/temperature_calibration/accel.cpp @@ -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..7cee4739df 100644 --- a/src/modules/temperature_compensation/temperature_calibration/baro.cpp +++ b/src/modules/temperature_compensation/temperature_calibration/baro.cpp @@ -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), ¶m); diff --git a/src/modules/temperature_compensation/temperature_calibration/common.h b/src/modules/temperature_compensation/temperature_calibration/common.h index 442ed01af3..1a74c44934 100644 --- a/src/modules/temperature_compensation/temperature_calibration/common.h +++ b/src/modules/temperature_compensation/temperature_calibration/common.h @@ -97,7 +97,7 @@ 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); + (void)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..d569af7289 100644 --- a/src/modules/temperature_compensation/temperature_calibration/gyro.cpp +++ b/src/modules/temperature_compensation/temperature_calibration/gyro.cpp @@ -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);