Remove distance sensor checks again. These checks should be handled by EKF2 and should thus be added there later

This commit is contained in:
Philipp Oettershagen 2018-05-28 12:40:44 +02:00 committed by Beat Küng
parent be4ba32cf0
commit a807d34a7a
1 changed files with 0 additions and 31 deletions

View File

@ -710,20 +710,6 @@ bool preflightCheck(orb_advert_t *mavlink_log_pub, vehicle_status_s &status,
const bool checkDynamic = !hil_enabled;
const bool checkPower = (status_flags.condition_power_input_valid && !status_flags.circuit_breaker_engaged_power_check);
bool checkDistanceSensors = false;
int32_t distSensorEnabled[7];
param_get(param_find("SENS_EN_LEDDAR1"), &(distSensorEnabled[0]));
param_get(param_find("SENS_EN_LL40LS"), &distSensorEnabled[1]);
param_get(param_find("SENS_EN_MB12XX"), &distSensorEnabled[2]);
param_get(param_find("SENS_EN_SF0X"), &distSensorEnabled[3]);
param_get(param_find("SENS_EN_SF1XX"), &distSensorEnabled[4]);
param_get(param_find("SENS_EN_TFMINI"), &distSensorEnabled[5]);
param_get(param_find("SENS_EN_TRANGER"), &distSensorEnabled[6]);
if(distSensorEnabled[0]>0 || distSensorEnabled[1]>0 || distSensorEnabled[2]>0 || distSensorEnabled[3]>0 ||
distSensorEnabled[4]>0 || distSensorEnabled[5]>0 || distSensorEnabled[6]>0) {
checkDistanceSensors=true;
}
bool checkAirspeed = false;
/* Perform airspeed check only if circuit breaker is not
@ -936,23 +922,6 @@ bool preflightCheck(orb_advert_t *mavlink_log_pub, vehicle_status_s &status,
}
}
/* ---- DISTANCE SENSORS ---- */
if (checkDistanceSensors && time_since_boot > 10 * 1000000) {
int fd_distance_sensor = orb_subscribe(ORB_ID(distance_sensor));
distance_sensor_s dist_sensor = {};
bool present = true;
if ((orb_copy(ORB_ID(distance_sensor), fd_distance_sensor, &dist_sensor) != PX4_OK) ||
(hrt_elapsed_time(&dist_sensor.timestamp) > 2000000)) {
if (reportFailures) {
mavlink_log_critical(mavlink_log_pub, "PREFLIGHT FAIL: DISTANCE SENSOR MISSING");
}
present = false;
}
publish_subsystem_info(subsystem_info_s::SUBSYSTEM_TYPE_SENSORPROXIMITY, present, true, present, &status);
orb_unsubscribe(fd_distance_sensor);
}
/* ---- Navigation EKF ---- */
// only check EKF2 data if EKF2 is selected as the estimator and GNSS checking is enabled
int32_t estimator_type;