sensor_calibration:Use inttytpes

This commit is contained in:
David Sidrane
2021-04-22 04:51:51 -07:00
committed by Julian Oes
parent 4bc7f1f3f3
commit 9c87766021
4 changed files with 29 additions and 28 deletions

View File

@@ -1,6 +1,6 @@
/**************************************************************************** /****************************************************************************
* *
* Copyright (c) 2020 PX4 Development Team. All rights reserved. * Copyright (c) 2020, 2021 PX4 Development Team. All rights reserved.
* *
* Redistribution and use in source and binary forms, with or without * Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions * modification, are permitted provided that the following conditions
@@ -173,7 +173,7 @@ void Accelerometer::ParametersUpdate()
if (_external) { if (_external) {
if ((rotation_value >= ROTATION_MAX) || (rotation_value < 0)) { if ((rotation_value >= ROTATION_MAX) || (rotation_value < 0)) {
PX4_ERR("External %s %d (%d) invalid rotation %d, resetting to rotation none", PX4_ERR("External %s %" PRIu32 " (%" PRId8 ") invalid rotation %" PRId32 ", resetting to rotation none",
SensorString(), _device_id, _calibration_index, rotation_value); SensorString(), _device_id, _calibration_index, rotation_value);
rotation_value = ROTATION_NONE; rotation_value = ROTATION_NONE;
SetCalibrationParam(SensorString(), "ROT", _calibration_index, rotation_value); SetCalibrationParam(SensorString(), "ROT", _calibration_index, rotation_value);
@@ -184,7 +184,7 @@ void Accelerometer::ParametersUpdate()
} else { } else {
// internal, CAL_ACCx_ROT -1 // internal, CAL_ACCx_ROT -1
if (rotation_value != -1) { if (rotation_value != -1) {
PX4_ERR("Internal %s %d (%d) invalid rotation %d, resetting", PX4_ERR("Internal %s %" PRIu32 " (%" PRId8 ") invalid rotation %" PRId32 " resetting",
SensorString(), _device_id, _calibration_index, rotation_value); SensorString(), _device_id, _calibration_index, rotation_value);
SetCalibrationParam(SensorString(), "ROT", _calibration_index, -1); SetCalibrationParam(SensorString(), "ROT", _calibration_index, -1);
} }
@@ -201,8 +201,8 @@ void Accelerometer::ParametersUpdate()
int32_t new_priority = _external ? DEFAULT_EXTERNAL_PRIORITY : DEFAULT_PRIORITY; int32_t new_priority = _external ? DEFAULT_EXTERNAL_PRIORITY : DEFAULT_PRIORITY;
if (_priority != -1) { if (_priority != -1) {
PX4_ERR("%s %d (%d) invalid priority %d, resetting to %d", SensorString(), _device_id, _calibration_index, _priority, PX4_ERR("%s %" PRIu32 " (%" PRId8 ") invalid priority %" PRId32 ", resetting to %" PRId32, SensorString(), _device_id,
new_priority); _calibration_index, _priority, new_priority);
} }
SetCalibrationParam(SensorString(), "PRIO", _calibration_index, new_priority); SetCalibrationParam(SensorString(), "PRIO", _calibration_index, new_priority);
@@ -267,11 +267,12 @@ bool Accelerometer::ParametersSave()
void Accelerometer::PrintStatus() void Accelerometer::PrintStatus()
{ {
PX4_INFO("%s %d EN: %d, offset: [%.4f %.4f %.4f] scale: [%.4f %.4f %.4f]", SensorString(), device_id(), enabled(), PX4_INFO("%s %" PRIu32 " EN: %d, offset: [%.4f %.4f %.4f] scale: [%.4f %.4f %.4f]", SensorString(), device_id(),
enabled(),
(double)_offset(0), (double)_offset(1), (double)_offset(2), (double)_scale(0), (double)_scale(1), (double)_scale(2)); (double)_offset(0), (double)_offset(1), (double)_offset(2), (double)_scale(0), (double)_scale(1), (double)_scale(2));
if (_thermal_offset.norm() > 0.f) { if (_thermal_offset.norm() > 0.f) {
PX4_INFO("%s %d temperature offset: [%.4f %.4f %.4f]", SensorString(), _device_id, PX4_INFO("%s %" PRIu32 " temperature offset: [%.4f %.4f %.4f]", SensorString(), _device_id,
(double)_thermal_offset(0), (double)_thermal_offset(1), (double)_thermal_offset(2)); (double)_thermal_offset(0), (double)_thermal_offset(1), (double)_thermal_offset(2));
} }
} }

View File

@@ -1,6 +1,6 @@
/**************************************************************************** /****************************************************************************
* *
* Copyright (c) 2020 PX4 Development Team. All rights reserved. * Copyright (c) 2020, 2021 PX4 Development Team. All rights reserved.
* *
* Redistribution and use in source and binary forms, with or without * Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions * modification, are permitted provided that the following conditions
@@ -158,7 +158,7 @@ void Gyroscope::ParametersUpdate()
if (_external) { if (_external) {
if ((rotation_value >= ROTATION_MAX) || (rotation_value < 0)) { if ((rotation_value >= ROTATION_MAX) || (rotation_value < 0)) {
PX4_ERR("External %s %d (%d) invalid rotation %d, resetting to rotation none", PX4_ERR("External %s %" PRIu32 " (%" PRId8 ") invalid rotation %" PRId32 ", resetting to rotation none",
SensorString(), _device_id, _calibration_index, rotation_value); SensorString(), _device_id, _calibration_index, rotation_value);
rotation_value = ROTATION_NONE; rotation_value = ROTATION_NONE;
SetCalibrationParam(SensorString(), "ROT", _calibration_index, rotation_value); SetCalibrationParam(SensorString(), "ROT", _calibration_index, rotation_value);
@@ -169,7 +169,7 @@ void Gyroscope::ParametersUpdate()
} else { } else {
// internal, CAL_GYROx_ROT -1 // internal, CAL_GYROx_ROT -1
if (rotation_value != -1) { if (rotation_value != -1) {
PX4_ERR("Internal %s %d (%d) invalid rotation %d, resetting", PX4_ERR("Internal %s %" PRIu32 " (%" PRId8 ") invalid rotation %" PRId32 " resetting",
SensorString(), _device_id, _calibration_index, rotation_value); SensorString(), _device_id, _calibration_index, rotation_value);
SetCalibrationParam(SensorString(), "ROT", _calibration_index, -1); SetCalibrationParam(SensorString(), "ROT", _calibration_index, -1);
} }
@@ -186,8 +186,8 @@ void Gyroscope::ParametersUpdate()
int32_t new_priority = _external ? DEFAULT_EXTERNAL_PRIORITY : DEFAULT_PRIORITY; int32_t new_priority = _external ? DEFAULT_EXTERNAL_PRIORITY : DEFAULT_PRIORITY;
if (_priority != -1) { if (_priority != -1) {
PX4_ERR("%s %d (%d) invalid priority %d, resetting to %d", SensorString(), _device_id, _calibration_index, _priority, PX4_ERR("%s %" PRIu32 " (%" PRId8 ") invalid priority %" PRId32 ", resetting to %" PRId32, SensorString(), _device_id,
new_priority); _calibration_index, _priority, new_priority);
} }
SetCalibrationParam(SensorString(), "PRIO", _calibration_index, new_priority); SetCalibrationParam(SensorString(), "PRIO", _calibration_index, new_priority);
@@ -247,11 +247,11 @@ bool Gyroscope::ParametersSave()
void Gyroscope::PrintStatus() void Gyroscope::PrintStatus()
{ {
PX4_INFO("%s %d EN: %d, offset: [%.4f %.4f %.4f]", SensorString(), device_id(), enabled(), PX4_INFO("%s %" PRIu32 " EN: %d, offset: [%.4f %.4f %.4f]", SensorString(), device_id(), enabled(),
(double)_offset(0), (double)_offset(1), (double)_offset(2)); (double)_offset(0), (double)_offset(1), (double)_offset(2));
if (_thermal_offset.norm() > 0.f) { if (_thermal_offset.norm() > 0.f) {
PX4_INFO("%s %d temperature offset: [%.4f %.4f %.4f]", SensorString(), _device_id, PX4_INFO("%s %" PRIu32 " temperature offset: [%.4f %.4f %.4f]", SensorString(), _device_id,
(double)_thermal_offset(0), (double)_thermal_offset(1), (double)_thermal_offset(2)); (double)_thermal_offset(0), (double)_thermal_offset(1), (double)_thermal_offset(2));
} }
} }

View File

@@ -1,6 +1,6 @@
/**************************************************************************** /****************************************************************************
* *
* Copyright (c) 2020 PX4 Development Team. All rights reserved. * Copyright (c) 2020, 2021 PX4 Development Team. All rights reserved.
* *
* Redistribution and use in source and binary forms, with or without * Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions * modification, are permitted provided that the following conditions
@@ -158,7 +158,7 @@ void Magnetometer::ParametersUpdate()
if (_external) { if (_external) {
if ((rotation_value >= ROTATION_MAX) || (rotation_value < 0)) { if ((rotation_value >= ROTATION_MAX) || (rotation_value < 0)) {
PX4_ERR("External %s %d (%d) invalid rotation %d, resetting to rotation none", PX4_ERR("External %s %" PRIu32 " (%" PRId8 ") invalid rotation %" PRId32 ", resetting to rotation none",
SensorString(), _device_id, _calibration_index, rotation_value); SensorString(), _device_id, _calibration_index, rotation_value);
rotation_value = ROTATION_NONE; rotation_value = ROTATION_NONE;
SetCalibrationParam(SensorString(), "ROT", _calibration_index, rotation_value); SetCalibrationParam(SensorString(), "ROT", _calibration_index, rotation_value);
@@ -169,7 +169,7 @@ void Magnetometer::ParametersUpdate()
} else { } else {
// internal mag, CAL_MAGx_ROT -1 // internal mag, CAL_MAGx_ROT -1
if (rotation_value != -1) { if (rotation_value != -1) {
PX4_ERR("Internal %s %d (%d) invalid rotation %d, resetting", PX4_ERR("Internal %s %" PRIu32 " (%" PRId8 ") invalid rotation %" PRId32 " resetting",
SensorString(), _device_id, _calibration_index, rotation_value); SensorString(), _device_id, _calibration_index, rotation_value);
SetCalibrationParam(SensorString(), "ROT", _calibration_index, -1); SetCalibrationParam(SensorString(), "ROT", _calibration_index, -1);
} }
@@ -186,8 +186,8 @@ void Magnetometer::ParametersUpdate()
int32_t new_priority = _external ? DEFAULT_EXTERNAL_PRIORITY : DEFAULT_PRIORITY; int32_t new_priority = _external ? DEFAULT_EXTERNAL_PRIORITY : DEFAULT_PRIORITY;
if (_priority != -1) { if (_priority != -1) {
PX4_ERR("%s %d (%d) invalid priority %d, resetting to %d", SensorString(), _device_id, _calibration_index, _priority, PX4_ERR("%s %" PRIu32 " (%" PRId8 ") invalid priority %" PRId32 ", resetting to %" PRId32, SensorString(), _device_id,
new_priority); _calibration_index, _priority, new_priority);
} }
SetCalibrationParam(SensorString(), "PRIO", _calibration_index, new_priority); SetCalibrationParam(SensorString(), "PRIO", _calibration_index, new_priority);
@@ -267,14 +267,14 @@ bool Magnetometer::ParametersSave()
void Magnetometer::PrintStatus() void Magnetometer::PrintStatus()
{ {
if (external()) { if (external()) {
PX4_INFO("%s %d EN: %d, offset: [% 05.3f % 05.3f % 05.3f], scale: [% 05.3f % 05.3f % 05.3f], External ROT: %d", PX4_INFO("%s %" PRIu32 " EN: %d, offset: [% 05.3f % 05.3f % 05.3f], scale: [% 05.3f % 05.3f % 05.3f], External ROT: %d",
SensorString(), device_id(), enabled(), SensorString(), device_id(), enabled(),
(double)_offset(0), (double)_offset(1), (double)_offset(2), (double)_offset(0), (double)_offset(1), (double)_offset(2),
(double)_scale(0, 0), (double)_scale(1, 1), (double)_scale(2, 2), (double)_scale(0, 0), (double)_scale(1, 1), (double)_scale(2, 2),
rotation_enum()); rotation_enum());
} else { } else {
PX4_INFO("%s %d EN: %d, offset: [% 05.3f % 05.3f % 05.3f], scale: [% 05.3f % 05.3f % 05.3f], Internal", PX4_INFO("%s %" PRIu32 " EN: %d, offset: [% 05.3f % 05.3f % 05.3f], scale: [% 05.3f % 05.3f % 05.3f], Internal",
SensorString(), device_id(), enabled(), SensorString(), device_id(), enabled(),
(double)_offset(0), (double)_offset(1), (double)_offset(2), (double)_offset(0), (double)_offset(1), (double)_offset(2),
(double)_scale(0, 0), (double)_scale(1, 1), (double)_scale(2, 2)); (double)_scale(0, 0), (double)_scale(1, 1), (double)_scale(2, 2));

View File

@@ -1,6 +1,6 @@
/**************************************************************************** /****************************************************************************
* *
* Copyright (c) 2020 PX4 Development Team. All rights reserved. * Copyright (c) 2020,2021 PX4 Development Team. All rights reserved.
* *
* Redistribution and use in source and binary forms, with or without * Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions * modification, are permitted provided that the following conditions
@@ -80,7 +80,7 @@ int32_t GetCalibrationParam(const char *sensor_type, const char *cal_type, uint8
{ {
// eg CAL_MAGn_ID/CAL_MAGn_ROT // eg CAL_MAGn_ID/CAL_MAGn_ROT
char str[20] {}; char str[20] {};
sprintf(str, "CAL_%s%u_%s", sensor_type, instance, cal_type); sprintf(str, "CAL_%s%" PRIu8 "_%s", sensor_type, instance, cal_type);
int32_t value = 0; int32_t value = 0;
@@ -96,12 +96,12 @@ bool SetCalibrationParam(const char *sensor_type, const char *cal_type, uint8_t
char str[20] {}; char str[20] {};
// eg CAL_MAGn_ID/CAL_MAGn_ROT // eg CAL_MAGn_ID/CAL_MAGn_ROT
sprintf(str, "CAL_%s%u_%s", sensor_type, instance, cal_type); sprintf(str, "CAL_%s%" PRIu8 "_%s", sensor_type, instance, cal_type);
int ret = param_set_no_notification(param_find(str), &value); int ret = param_set_no_notification(param_find(str), &value);
if (ret != PX4_OK) { if (ret != PX4_OK) {
PX4_ERR("failed to set %s = %d", str, value); PX4_ERR("failed to set %s = %" PRId32, str, value);
} }
return ret == PX4_OK; return ret == PX4_OK;
@@ -117,7 +117,7 @@ Vector3f GetCalibrationParamsVector3f(const char *sensor_type, const char *cal_t
char axis_char = 'X' + axis; char axis_char = 'X' + axis;
// eg CAL_MAGn_{X,Y,Z}OFF // eg CAL_MAGn_{X,Y,Z}OFF
sprintf(str, "CAL_%s%u_%c%s", sensor_type, instance, axis_char, cal_type); sprintf(str, "CAL_%s%" PRIu8 "_%c%s", sensor_type, instance, axis_char, cal_type);
if (param_get(param_find(str), &values(axis)) != 0) { if (param_get(param_find(str), &values(axis)) != 0) {
PX4_ERR("failed to get %s", str); PX4_ERR("failed to get %s", str);
@@ -136,7 +136,7 @@ bool SetCalibrationParamsVector3f(const char *sensor_type, const char *cal_type,
char axis_char = 'X' + axis; char axis_char = 'X' + axis;
// eg CAL_MAGn_{X,Y,Z}OFF // eg CAL_MAGn_{X,Y,Z}OFF
sprintf(str, "CAL_%s%u_%c%s", sensor_type, instance, axis_char, cal_type); sprintf(str, "CAL_%s%" PRIu8 "_%c%s", sensor_type, instance, axis_char, cal_type);
if (param_set_no_notification(param_find(str), &values(axis)) != 0) { if (param_set_no_notification(param_find(str), &values(axis)) != 0) {
PX4_ERR("failed to set %s = %.4f", str, (double)values(axis)); PX4_ERR("failed to set %s = %.4f", str, (double)values(axis));
@@ -169,7 +169,7 @@ enum Rotation GetBoardRotation()
return static_cast<enum Rotation>(board_rot); return static_cast<enum Rotation>(board_rot);
} else { } else {
PX4_ERR("invalid SENS_BOARD_ROT: %d", board_rot); PX4_ERR("invalid SENS_BOARD_ROT: %" PRId32, board_rot);
} }
return Rotation::ROTATION_NONE; return Rotation::ROTATION_NONE;