forked from Archive/PX4-Autopilot
sensors:Use inttypes
This commit is contained in:
parent
274c55a4ae
commit
d73f842151
|
@ -1,6 +1,6 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2019 PX4 Development Team. All rights reserved.
|
||||
* Copyright (c) 2019, 2021 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
|
||||
|
@ -164,7 +164,7 @@ bool VehicleAcceleration::SensorSelectionUpdate(bool force)
|
|||
if ((device_id != 0) && (device_id == sensor_selection.accel_device_id)) {
|
||||
|
||||
if (_sensor_sub.ChangeInstance(i) && _sensor_sub.registerCallback()) {
|
||||
PX4_DEBUG("selected sensor changed %d -> %d", _calibration.device_id(), device_id);
|
||||
PX4_DEBUG("selected sensor changed %" PRIu32 " -> %" PRIu32 "", _calibration.device_id(), device_id);
|
||||
|
||||
// clear bias and corrections
|
||||
_bias.zero();
|
||||
|
@ -178,7 +178,7 @@ bool VehicleAcceleration::SensorSelectionUpdate(bool force)
|
|||
}
|
||||
}
|
||||
|
||||
PX4_ERR("unable to find or subscribe to selected sensor (%d)", sensor_selection.accel_device_id);
|
||||
PX4_ERR("unable to find or subscribe to selected sensor (%" PRIu32 ")", sensor_selection.accel_device_id);
|
||||
_calibration.set_device_id(0);
|
||||
}
|
||||
}
|
||||
|
@ -256,7 +256,7 @@ void VehicleAcceleration::Run()
|
|||
|
||||
void VehicleAcceleration::PrintStatus()
|
||||
{
|
||||
PX4_INFO("selected sensor: %d, rate: %.1f Hz, estimated bias: [%.4f %.4f %.4f]",
|
||||
PX4_INFO("selected sensor: %" PRIu32 ", rate: %.1f Hz, estimated bias: [%.4f %.4f %.4f]",
|
||||
_calibration.device_id(), (double)_filter_sample_rate,
|
||||
(double)_bias(0), (double)_bias(1), (double)_bias(2));
|
||||
|
||||
|
|
|
@ -207,7 +207,7 @@ void VehicleAirData::Run()
|
|||
}
|
||||
|
||||
if (_selected_sensor_sub_index >= 0) {
|
||||
PX4_INFO("%s switch from #%u -> #%d", "BARO", _selected_sensor_sub_index, best_index);
|
||||
PX4_INFO("%s switch from #%" PRIu8 " -> #%d", "BARO", _selected_sensor_sub_index, best_index);
|
||||
}
|
||||
|
||||
_selected_sensor_sub_index = best_index;
|
||||
|
@ -316,10 +316,11 @@ void VehicleAirData::Run()
|
|||
void VehicleAirData::PrintStatus()
|
||||
{
|
||||
if (_selected_sensor_sub_index >= 0) {
|
||||
PX4_INFO("selected barometer: %d (%d)", _last_data[_selected_sensor_sub_index].device_id, _selected_sensor_sub_index);
|
||||
PX4_INFO("selected barometer: %" PRIu32 " (%" PRId8 ")", _last_data[_selected_sensor_sub_index].device_id,
|
||||
_selected_sensor_sub_index);
|
||||
|
||||
if (fabsf(_thermal_offset[_selected_sensor_sub_index]) > 0.f) {
|
||||
PX4_INFO("%d temperature offset: %.4f", _last_data[_selected_sensor_sub_index].device_id,
|
||||
PX4_INFO("%" PRIu32 " temperature offset: %.4f", _last_data[_selected_sensor_sub_index].device_id,
|
||||
(double)_thermal_offset[_selected_sensor_sub_index]);
|
||||
}
|
||||
}
|
||||
|
|
|
@ -265,7 +265,7 @@ bool VehicleAngularVelocity::SensorSelectionUpdate(bool force)
|
|||
}
|
||||
}
|
||||
|
||||
PX4_ERR("unable to find or subscribe to selected sensor (%d)", sensor_selection.gyro_device_id);
|
||||
PX4_ERR("unable to find or subscribe to selected sensor (%" PRIu32 ")", sensor_selection.gyro_device_id);
|
||||
_selected_sensor_device_id = 0;
|
||||
}
|
||||
}
|
||||
|
@ -784,7 +784,7 @@ void VehicleAngularVelocity::CalibrateAndPublish(bool publish, const hrt_abstime
|
|||
|
||||
void VehicleAngularVelocity::PrintStatus()
|
||||
{
|
||||
PX4_INFO("selected sensor: %d, rate: %.1f Hz %s",
|
||||
PX4_INFO("selected sensor: %" PRIu32 ", rate: %.1f Hz %s",
|
||||
_selected_sensor_device_id, (double)_filter_sample_rate_hz, _fifo_available ? "FIFO" : "");
|
||||
PX4_INFO("estimated bias: [%.4f %.4f %.4f]", (double)_bias(0), (double)_bias(1), (double)_bias(2));
|
||||
|
||||
|
|
|
@ -119,10 +119,10 @@ void VehicleIMU::ParametersUpdate(bool force)
|
|||
|
||||
// constrain IMU integration time 1-10 milliseconds (100-1000 Hz)
|
||||
int32_t imu_integration_rate_hz = constrain(_param_imu_integ_rate.get(),
|
||||
100, math::max(_param_imu_gyro_ratemax.get(), 1000));
|
||||
(int32_t)100, math::max(_param_imu_gyro_ratemax.get(), (int32_t) 1000));
|
||||
|
||||
if (imu_integration_rate_hz != _param_imu_integ_rate.get()) {
|
||||
PX4_WARN("IMU_INTEG_RATE updated %d -> %d", _param_imu_integ_rate.get(), imu_integration_rate_hz);
|
||||
PX4_WARN("IMU_INTEG_RATE updated %" PRId32 " -> %" PRIu32, _param_imu_integ_rate.get(), imu_integration_rate_hz);
|
||||
_param_imu_integ_rate.set(imu_integration_rate_hz);
|
||||
_param_imu_integ_rate.commit_no_notification();
|
||||
}
|
||||
|
@ -322,7 +322,7 @@ bool VehicleIMU::UpdateAccel()
|
|||
const uint64_t clipping_total = _status.accel_clipping[0] + _status.accel_clipping[1] + _status.accel_clipping[2];
|
||||
|
||||
if (clipping_total > _last_clipping_notify_total_count + 1000) {
|
||||
mavlink_log_critical(&_mavlink_log_pub, "Accel %d clipping, not safe to fly!", _instance);
|
||||
mavlink_log_critical(&_mavlink_log_pub, "Accel %" PRIu8 " clipping, not safe to fly!", _instance);
|
||||
_last_clipping_notify_time = accel.timestamp_sample;
|
||||
_last_clipping_notify_total_count = clipping_total;
|
||||
}
|
||||
|
@ -530,7 +530,8 @@ void VehicleIMU::UpdateIntegratorConfiguration()
|
|||
_intervals_configured = true;
|
||||
_update_integrator_config = false;
|
||||
|
||||
PX4_DEBUG("accel (%d), gyro (%d), accel samples: %d, gyro samples: %d, accel interval: %.1f, gyro interval: %.1f sub samples: %d",
|
||||
PX4_DEBUG("accel (%" PRIu32 "), gyro (%" PRIu32 "), accel samples: %" PRIu8 ", gyro samples: %" PRIu8
|
||||
", accel interval: %.1f, gyro interval: %.1f sub samples: %d",
|
||||
_accel_calibration.device_id(), _gyro_calibration.device_id(), accel_integral_samples, gyro_integral_samples,
|
||||
(double)_accel_interval_us, (double)_gyro_interval_us, n);
|
||||
|
||||
|
@ -564,8 +565,10 @@ void VehicleIMU::UpdateGyroVibrationMetrics(const Vector3f &delta_angle)
|
|||
|
||||
void VehicleIMU::PrintStatus()
|
||||
{
|
||||
PX4_INFO("%d - Accel ID: %d, interval: %.1f us (SD %.1f us), Gyro ID: %d, interval: %.1f us (SD %.1f us)", _instance,
|
||||
_accel_calibration.device_id(), (double)_accel_interval_us, (double)sqrtf(_accel_interval_best_variance),
|
||||
|
||||
PX4_INFO("%" PRIu8 " - Accel ID: %" PRIu32 ", interval: %.1f us (SD %.1f us), Gyro ID: %" PRIu32
|
||||
", interval: %.1f us (SD %.1f us)",
|
||||
_instance, _accel_calibration.device_id(), (double)_accel_interval_us, (double)sqrtf(_accel_interval_best_variance),
|
||||
_gyro_calibration.device_id(), (double)_gyro_interval_us, (double)sqrtf(_gyro_interval_best_variance));
|
||||
|
||||
perf_print_counter(_accel_generation_gap_perf);
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2020 PX4 Development Team. All rights reserved.
|
||||
* Copyright (c) 2020, 2001 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
|
||||
|
@ -217,7 +217,7 @@ void VehicleMagnetometer::MagCalibrationUpdate()
|
|||
|
||||
if (_calibration[mag_index].set_offset(mag_cal_offset)) {
|
||||
|
||||
PX4_INFO("%d (%d) EST:%d offset committed: [%.2f %.2f %.2f]->[%.2f %.2f %.2f] (full [%.2f %.2f %.2f])",
|
||||
PX4_INFO("%d (%" PRIu32 ") EST:%d offset committed: [%.2f %.2f %.2f]->[%.2f %.2f %.2f] (full [%.2f %.2f %.2f])",
|
||||
mag_index, _calibration[mag_index].device_id(), i,
|
||||
(double)mag_cal_orig(0), (double)mag_cal_orig(1), (double)mag_cal_orig(2),
|
||||
(double)mag_cal_offset(0), (double)mag_cal_offset(1), (double)mag_cal_offset(2),
|
||||
|
@ -375,7 +375,7 @@ void VehicleMagnetometer::Run()
|
|||
|
||||
if (_param_sens_mag_mode.get()) {
|
||||
if (_selected_sensor_sub_index >= 0) {
|
||||
PX4_INFO("%s switch from #%u -> #%d", "MAG", _selected_sensor_sub_index, best_index);
|
||||
PX4_INFO("%s switch from #%" PRId8 " -> #%d", "MAG", _selected_sensor_sub_index, best_index);
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -530,7 +530,7 @@ void VehicleMagnetometer::calcMagInconsistency()
|
|||
void VehicleMagnetometer::PrintStatus()
|
||||
{
|
||||
if (_selected_sensor_sub_index >= 0) {
|
||||
PX4_INFO("selected magnetometer: %d (%d)", _last_data[_selected_sensor_sub_index].device_id,
|
||||
PX4_INFO("selected magnetometer: %" PRIu32 " (%" PRId8 ")", _last_data[_selected_sensor_sub_index].device_id,
|
||||
_selected_sensor_sub_index);
|
||||
}
|
||||
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2016 PX4 Development Team. All rights reserved.
|
||||
* Copyright (c) 2016, 2021 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
|
||||
|
@ -106,7 +106,8 @@ void VotedSensorsUpdate::parametersUpdate()
|
|||
} else {
|
||||
// change relative priority to incorporate any sensor faults
|
||||
int priority_change = _accel.priority_configured[uorb_index] - accel_priority_old;
|
||||
_accel.priority[uorb_index] = math::constrain(_accel.priority[uorb_index] + priority_change, 1, 100);
|
||||
_accel.priority[uorb_index] = math::constrain(_accel.priority[uorb_index] + priority_change, static_cast<int32_t>(1),
|
||||
static_cast<int32_t>(100));
|
||||
}
|
||||
}
|
||||
}
|
||||
|
@ -128,7 +129,8 @@ void VotedSensorsUpdate::parametersUpdate()
|
|||
} else {
|
||||
// change relative priority to incorporate any sensor faults
|
||||
int priority_change = _gyro.priority_configured[uorb_index] - gyro_priority_old;
|
||||
_gyro.priority[uorb_index] = math::constrain(_gyro.priority[uorb_index] + priority_change, 1, 100);
|
||||
_gyro.priority[uorb_index] = math::constrain(_gyro.priority[uorb_index] + priority_change, static_cast<int32_t>(1),
|
||||
static_cast<int32_t>(100));
|
||||
}
|
||||
}
|
||||
}
|
||||
|
@ -355,11 +357,11 @@ void VotedSensorsUpdate::initSensorClass(SensorData &sensor_data, uint8_t sensor
|
|||
|
||||
void VotedSensorsUpdate::printStatus()
|
||||
{
|
||||
PX4_INFO("selected gyro: %d (%d)", _selection.gyro_device_id, _gyro.last_best_vote);
|
||||
PX4_INFO("selected gyro: %" PRIu32 " (%" PRIu8 ")", _selection.gyro_device_id, _gyro.last_best_vote);
|
||||
_gyro.voter.print();
|
||||
|
||||
PX4_INFO_RAW("\n");
|
||||
PX4_INFO("selected accel: %d (%d)", _selection.accel_device_id, _accel.last_best_vote);
|
||||
PX4_INFO("selected accel: %" PRIu32 " (%" PRIu8 ")", _selection.accel_device_id, _accel.last_best_vote);
|
||||
_accel.voter.print();
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue