mirror of
https://gitee.com/xiaohuolufeihua/bizhang_-obav.git
synced 2026-05-22 01:12:31 +00:00
Merge pull request #2095 from UAVenture/firefly_airspeed
Ensure that the airspeed preflight check logs to the console.
This commit is contained in:
@@ -254,13 +254,13 @@ static bool airspeedCheck(int mavlink_fd, bool optional)
|
||||
|
||||
if ((ret = orb_copy(ORB_ID(airspeed), fd, &airspeed)) ||
|
||||
(hrt_elapsed_time(&airspeed.timestamp) > (500 * 1000))) {
|
||||
mavlink_log_critical(mavlink_fd, "PREFLIGHT FAIL: AIRSPEED SENSOR MISSING");
|
||||
mavlink_and_console_log_critical(mavlink_fd, "PREFLIGHT FAIL: AIRSPEED SENSOR MISSING");
|
||||
success = false;
|
||||
goto out;
|
||||
}
|
||||
|
||||
if (fabsf(airspeed.indicated_airspeed_m_s > 6.0f)) {
|
||||
mavlink_log_critical(mavlink_fd, "AIRSPEED WARNING: WIND OR CALIBRATION ISSUE");
|
||||
mavlink_and_console_log_critical(mavlink_fd, "AIRSPEED WARNING: WIND OR CALIBRATION ISSUE");
|
||||
// XXX do not make this fatal yet
|
||||
}
|
||||
|
||||
|
||||
@@ -213,6 +213,8 @@ int commander_thread_main(int argc, char *argv[]);
|
||||
|
||||
void control_status_leds(vehicle_status_s *status, const actuator_armed_s *actuator_armed, bool changed);
|
||||
|
||||
void get_circuit_breaker_params();
|
||||
|
||||
void check_valid(hrt_abstime timestamp, hrt_abstime timeout, bool valid_in, bool *valid_out, bool *changed);
|
||||
|
||||
transition_result_t set_main_state_rc(struct vehicle_status_s *status, struct manual_control_setpoint_s *sp_man);
|
||||
@@ -1114,6 +1116,8 @@ int commander_thread_main(int argc, char *argv[])
|
||||
param_get(_param_sys_type, &(status.system_type)); // get system type
|
||||
status.is_rotary_wing = is_rotary_wing(&status) || is_vtol(&status);
|
||||
|
||||
get_circuit_breaker_params();
|
||||
|
||||
bool checkAirspeed = false;
|
||||
/* Perform airspeed check only if circuit breaker is not
|
||||
* engaged and it's not a rotary wing */
|
||||
@@ -1121,9 +1125,9 @@ int commander_thread_main(int argc, char *argv[])
|
||||
checkAirspeed = true;
|
||||
}
|
||||
|
||||
//Run preflight check
|
||||
// Run preflight check
|
||||
status.condition_system_sensors_initialized = Commander::preflightCheck(mavlink_fd, true, true, true, true, checkAirspeed, true);
|
||||
if(!status.condition_system_sensors_initialized) {
|
||||
if (!status.condition_system_sensors_initialized) {
|
||||
set_tune_override(TONE_GPS_WARNING_TUNE); //sensor fail tune
|
||||
}
|
||||
else {
|
||||
@@ -1207,14 +1211,7 @@ int commander_thread_main(int argc, char *argv[])
|
||||
param_get(_param_system_id, &(status.system_id));
|
||||
param_get(_param_component_id, &(status.component_id));
|
||||
|
||||
status.circuit_breaker_engaged_power_check =
|
||||
circuit_breaker_enabled("CBRK_SUPPLY_CHK", CBRK_SUPPLY_CHK_KEY);
|
||||
status.circuit_breaker_engaged_airspd_check =
|
||||
circuit_breaker_enabled("CBRK_AIRSPD_CHK", CBRK_AIRSPD_CHK_KEY);
|
||||
status.circuit_breaker_engaged_enginefailure_check =
|
||||
circuit_breaker_enabled("CBRK_ENGINEFAIL", CBRK_ENGINEFAIL_KEY);
|
||||
status.circuit_breaker_engaged_gpsfailure_check =
|
||||
circuit_breaker_enabled("CBRK_GPSFAIL", CBRK_GPSFAIL_KEY);
|
||||
get_circuit_breaker_params();
|
||||
|
||||
status_changed = true;
|
||||
|
||||
@@ -2107,6 +2104,19 @@ int commander_thread_main(int argc, char *argv[])
|
||||
return 0;
|
||||
}
|
||||
|
||||
void
|
||||
get_circuit_breaker_params()
|
||||
{
|
||||
status.circuit_breaker_engaged_power_check =
|
||||
circuit_breaker_enabled("CBRK_SUPPLY_CHK", CBRK_SUPPLY_CHK_KEY);
|
||||
status.circuit_breaker_engaged_airspd_check =
|
||||
circuit_breaker_enabled("CBRK_AIRSPD_CHK", CBRK_AIRSPD_CHK_KEY);
|
||||
status.circuit_breaker_engaged_enginefailure_check =
|
||||
circuit_breaker_enabled("CBRK_ENGINEFAIL", CBRK_ENGINEFAIL_KEY);
|
||||
status.circuit_breaker_engaged_gpsfailure_check =
|
||||
circuit_breaker_enabled("CBRK_GPSFAIL", CBRK_GPSFAIL_KEY);
|
||||
}
|
||||
|
||||
void
|
||||
check_valid(hrt_abstime timestamp, hrt_abstime timeout, bool valid_in, bool *valid_out, bool *changed)
|
||||
{
|
||||
|
||||
Reference in New Issue
Block a user