From 96da46d1aa2793aa86eb0b0928be49f5810e5474 Mon Sep 17 00:00:00 2001 From: bresch Date: Mon, 1 Apr 2019 18:22:25 +0200 Subject: [PATCH] Failsafe - cosmetic changes --- src/drivers/px4io/px4io.cpp | 3 +-- src/lib/circuit_breaker/circuit_breaker_params.c | 2 +- src/modules/commander/PreflightCheck.cpp | 6 +++--- src/modules/commander/failure_detector/FailureDetector.hpp | 2 +- 4 files changed, 6 insertions(+), 7 deletions(-) diff --git a/src/drivers/px4io/px4io.cpp b/src/drivers/px4io/px4io.cpp index e6095430c5..1cb209f2ab 100644 --- a/src/drivers/px4io/px4io.cpp +++ b/src/drivers/px4io/px4io.cpp @@ -1024,8 +1024,7 @@ PX4IO::task_main() } /* Check if the IO safety circuit breaker has been updated */ - bool circuit_breaker_io_safety_enabled; - circuit_breaker_io_safety_enabled = circuit_breaker_enabled("CBRK_IO_SAFETY", CBRK_IO_SAFETY_KEY); + bool circuit_breaker_io_safety_enabled = circuit_breaker_enabled("CBRK_IO_SAFETY", CBRK_IO_SAFETY_KEY); /* Bypass IO safety switch logic by setting FORCE_SAFETY_OFF */ (void)io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_FORCE_SAFETY_OFF, circuit_breaker_io_safety_enabled); diff --git a/src/lib/circuit_breaker/circuit_breaker_params.c b/src/lib/circuit_breaker/circuit_breaker_params.c index 6939cdb91b..0d7708cb92 100644 --- a/src/lib/circuit_breaker/circuit_breaker_params.c +++ b/src/lib/circuit_breaker/circuit_breaker_params.c @@ -105,7 +105,7 @@ PARAM_DEFINE_INT32(CBRK_AIRSPD_CHK, 0); * * Setting this parameter to 121212 will disable the flight termination action if triggered * by the FailureDetector logic or if FMU is lost. - * WARNING: ENABLING THIS CIRCUIT BREAKER IS AT OWN RISK + * This circuit breaker does not affect the RC loss, data link loss and geofence safety logic. * * @reboot_required true * @min 0 diff --git a/src/modules/commander/PreflightCheck.cpp b/src/modules/commander/PreflightCheck.cpp index 14fad05310..738581d350 100644 --- a/src/modules/commander/PreflightCheck.cpp +++ b/src/modules/commander/PreflightCheck.cpp @@ -690,15 +690,15 @@ static bool failureDetectorCheck(orb_advert_t *mavlink_log_pub, const vehicle_st if (report_fail) { if (status.failure_detector_status & vehicle_status_s::FAILURE_ROLL) { - mavlink_log_critical(mavlink_log_pub, "PREFLIGHT FAIL: Roll failure detected"); + mavlink_log_critical(mavlink_log_pub, "Preflight Fail: Roll failure detected"); } if (status.failure_detector_status & vehicle_status_s::FAILURE_PITCH) { - mavlink_log_critical(mavlink_log_pub, "PREFLIGHT FAIL: Pitch failure detected"); + mavlink_log_critical(mavlink_log_pub, "Preflight Fail: Pitch failure detected"); } if (status.failure_detector_status & vehicle_status_s::FAILURE_ALT) { - mavlink_log_critical(mavlink_log_pub, "PREFLIGHT FAIL: Altitude failure detected"); + mavlink_log_critical(mavlink_log_pub, "Preflight Fail: Altitude failure detected"); } } } diff --git a/src/modules/commander/failure_detector/FailureDetector.hpp b/src/modules/commander/failure_detector/FailureDetector.hpp index 2a31a23dac..46bd6e4995 100644 --- a/src/modules/commander/failure_detector/FailureDetector.hpp +++ b/src/modules/commander/failure_detector/FailureDetector.hpp @@ -71,7 +71,7 @@ public: bool update(); uint8_t getStatus() const { return _status; } - bool isFailure() const { return (_status == FAILURE_NONE) ? false : true; } + bool isFailure() const { return _status != FAILURE_NONE; } private: