mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-04-14 10:07:39 +08:00
PreFlightCheck: remove unused device_id argument
This commit is contained in:
parent
5f1b577b6d
commit
b1c1163ee4
@ -246,9 +246,8 @@ bool PreFlightCheck::sensorAvailabilityCheck(const bool report_failure, const ui
|
||||
/* check all sensors, but fail only for mandatory ones */
|
||||
for (uint8_t i = 0u; i < max_optional_count; i++) {
|
||||
const bool required = (i < max_mandatory_count) || isSensorRequired(i);
|
||||
int32_t device_id = -1;
|
||||
|
||||
if (!sens_check(mavlink_log_pub, status, i, !required, device_id, report_fail)) {
|
||||
if (!sens_check(mavlink_log_pub, status, i, !required, report_fail)) {
|
||||
if (required) {
|
||||
pass_check = false;
|
||||
}
|
||||
|
||||
@ -48,7 +48,7 @@
|
||||
#include <drivers/drv_hrt.h>
|
||||
|
||||
typedef bool (*sens_check_func_t)(orb_advert_t *mavlink_log_pub, vehicle_status_s &status, const uint8_t instance,
|
||||
const bool optional, int32_t &device_id, const bool report_fail);
|
||||
const bool optional, const bool report_fail);
|
||||
typedef bool (*is_sens_req_func_t)(uint8_t instance);
|
||||
|
||||
class PreFlightCheck
|
||||
@ -105,20 +105,20 @@ private:
|
||||
vehicle_status_s &status, sens_check_func_t sens_check, is_sens_req_func_t isSensorRequired);
|
||||
static bool isMagRequired(uint8_t instance);
|
||||
static bool magnetometerCheck(orb_advert_t *mavlink_log_pub, vehicle_status_s &status, const uint8_t instance,
|
||||
const bool optional, int32_t &device_id, const bool report_fail);
|
||||
const bool optional, const bool report_fail);
|
||||
static bool magConsistencyCheck(orb_advert_t *mavlink_log_pub, vehicle_status_s &status, const bool report_status);
|
||||
static bool isAccelRequired(uint8_t instance);
|
||||
static bool accelerometerCheck(orb_advert_t *mavlink_log_pub, vehicle_status_s &status, const uint8_t instance,
|
||||
const bool optional, int32_t &device_id, const bool report_fail);
|
||||
const bool optional, const bool report_fail);
|
||||
static bool isGyroRequired(uint8_t instance);
|
||||
static bool gyroCheck(orb_advert_t *mavlink_log_pub, vehicle_status_s &status, const uint8_t instance,
|
||||
const bool optional, int32_t &device_id, const bool report_fail);
|
||||
const bool optional, const bool report_fail);
|
||||
static bool isBaroRequired(uint8_t instance);
|
||||
static bool baroCheck(orb_advert_t *mavlink_log_pub, vehicle_status_s &status, const uint8_t instance,
|
||||
const bool optional, int32_t &device_id, const bool report_fail);
|
||||
const bool optional, const bool report_fail);
|
||||
static bool isDistSensRequired(uint8_t instance);
|
||||
static bool distSensCheck(orb_advert_t *mavlink_log_pub, vehicle_status_s &status, const uint8_t instance,
|
||||
const bool optional, int32_t &device_id, const bool report_fail);
|
||||
const bool optional, const bool report_fail);
|
||||
static bool imuConsistencyCheck(orb_advert_t *mavlink_log_pub, vehicle_status_s &status, const bool report_status);
|
||||
static bool airspeedCheck(orb_advert_t *mavlink_log_pub, vehicle_status_s &status, const bool optional,
|
||||
const bool report_fail, const bool prearm, const bool max_airspeed_check_en, const float arming_max_airspeed_allowed);
|
||||
|
||||
@ -62,7 +62,7 @@ bool PreFlightCheck::isAccelRequired(const uint8_t instance)
|
||||
}
|
||||
|
||||
bool PreFlightCheck::accelerometerCheck(orb_advert_t *mavlink_log_pub, vehicle_status_s &status, const uint8_t instance,
|
||||
const bool optional, int32_t &device_id, const bool report_fail)
|
||||
const bool optional, const bool report_fail)
|
||||
{
|
||||
const bool exists = (orb_exists(ORB_ID(sensor_accel), instance) == PX4_OK);
|
||||
bool calibration_valid = false;
|
||||
@ -80,13 +80,11 @@ bool PreFlightCheck::accelerometerCheck(orb_advert_t *mavlink_log_pub, vehicle_s
|
||||
}
|
||||
}
|
||||
|
||||
device_id = accel.get().device_id;
|
||||
|
||||
if (status.hil_state == vehicle_status_s::HIL_STATE_ON) {
|
||||
calibration_valid = true;
|
||||
|
||||
} else {
|
||||
calibration_valid = (calibration::FindCurrentCalibrationIndex("ACC", device_id) >= 0);
|
||||
calibration_valid = (calibration::FindCurrentCalibrationIndex("ACC", accel.get().device_id) >= 0);
|
||||
}
|
||||
|
||||
if (!calibration_valid) {
|
||||
|
||||
@ -60,7 +60,7 @@ bool PreFlightCheck::isBaroRequired(const uint8_t instance)
|
||||
}
|
||||
|
||||
bool PreFlightCheck::baroCheck(orb_advert_t *mavlink_log_pub, vehicle_status_s &status, const uint8_t instance,
|
||||
const bool optional, int32_t &device_id, const bool report_fail)
|
||||
const bool optional, const bool report_fail)
|
||||
{
|
||||
const bool exists = (orb_exists(ORB_ID(sensor_baro), instance) == PX4_OK);
|
||||
bool valid = false;
|
||||
|
||||
@ -48,7 +48,7 @@ bool PreFlightCheck::isDistSensRequired(const uint8_t instance)
|
||||
}
|
||||
|
||||
bool PreFlightCheck::distSensCheck(orb_advert_t *mavlink_log_pub, vehicle_status_s &status, const uint8_t instance,
|
||||
const bool optional, int32_t &device_id, const bool report_fail)
|
||||
const bool optional, const bool report_fail)
|
||||
{
|
||||
const bool exists = (orb_exists(ORB_ID(distance_sensor), instance) == PX4_OK);
|
||||
bool check_valid = false;
|
||||
|
||||
@ -61,7 +61,7 @@ bool PreFlightCheck::isGyroRequired(const uint8_t instance)
|
||||
}
|
||||
|
||||
bool PreFlightCheck::gyroCheck(orb_advert_t *mavlink_log_pub, vehicle_status_s &status, const uint8_t instance,
|
||||
const bool optional, int32_t &device_id, const bool report_fail)
|
||||
const bool optional, const bool report_fail)
|
||||
{
|
||||
const bool exists = (orb_exists(ORB_ID(sensor_gyro), instance) == PX4_OK);
|
||||
bool calibration_valid = false;
|
||||
@ -79,13 +79,11 @@ bool PreFlightCheck::gyroCheck(orb_advert_t *mavlink_log_pub, vehicle_status_s &
|
||||
}
|
||||
}
|
||||
|
||||
device_id = gyro.get().device_id;
|
||||
|
||||
if (status.hil_state == vehicle_status_s::HIL_STATE_ON) {
|
||||
calibration_valid = true;
|
||||
|
||||
} else {
|
||||
calibration_valid = (calibration::FindCurrentCalibrationIndex("GYRO", device_id) >= 0);
|
||||
calibration_valid = (calibration::FindCurrentCalibrationIndex("GYRO", gyro.get().device_id) >= 0);
|
||||
}
|
||||
|
||||
if (!calibration_valid) {
|
||||
|
||||
@ -61,7 +61,7 @@ bool PreFlightCheck::isMagRequired(const uint8_t instance)
|
||||
}
|
||||
|
||||
bool PreFlightCheck::magnetometerCheck(orb_advert_t *mavlink_log_pub, vehicle_status_s &status, const uint8_t instance,
|
||||
const bool optional, int32_t &device_id, const bool report_fail)
|
||||
const bool optional, const bool report_fail)
|
||||
{
|
||||
const bool exists = (orb_exists(ORB_ID(sensor_mag), instance) == PX4_OK);
|
||||
bool calibration_valid = false;
|
||||
@ -80,13 +80,11 @@ bool PreFlightCheck::magnetometerCheck(orb_advert_t *mavlink_log_pub, vehicle_st
|
||||
}
|
||||
}
|
||||
|
||||
device_id = magnetometer.get().device_id;
|
||||
|
||||
if (status.hil_state == vehicle_status_s::HIL_STATE_ON) {
|
||||
calibration_valid = true;
|
||||
|
||||
} else {
|
||||
calibration_valid = (calibration::FindCurrentCalibrationIndex("MAG", device_id) >= 0);
|
||||
calibration_valid = (calibration::FindCurrentCalibrationIndex("MAG", magnetometer.get().device_id) >= 0);
|
||||
}
|
||||
|
||||
if (!calibration_valid) {
|
||||
@ -98,7 +96,7 @@ bool PreFlightCheck::magnetometerCheck(orb_advert_t *mavlink_log_pub, vehicle_st
|
||||
for (uint8_t i = 0; i < ORB_MULTI_MAX_INSTANCES; i++) {
|
||||
uORB::SubscriptionData<estimator_status_s> estimator_status_sub{ORB_ID(estimator_status), i};
|
||||
|
||||
if (estimator_status_sub.get().mag_device_id == static_cast<uint32_t>(device_id)) {
|
||||
if (estimator_status_sub.get().mag_device_id == static_cast<uint32_t>(magnetometer.get().device_id)) {
|
||||
if (estimator_status_sub.get().control_mode_flags & (1 << estimator_status_s::CS_MAG_FAULT)) {
|
||||
is_mag_fault = true;
|
||||
break;
|
||||
|
||||
Loading…
x
Reference in New Issue
Block a user