From 7908f75b8bd7e0bdd14dfe8ac1984dc345762534 Mon Sep 17 00:00:00 2001
From: bresch <brescianimathieu@gmail.com>
Date: Tue, 24 Jul 2018 18:24:38 +0200
Subject: [PATCH] FailureDetector - New class, first working simple
 implementation. Outputs PX4_ERR messages if roll or pitch is exceeded.

---
 src/modules/commander/CMakeLists.txt          |   1 +
 src/modules/commander/Commander.cpp           |  11 ++
 src/modules/commander/Commander.hpp           |   3 +
 .../failure_detector/FailureDetector.cpp      | 102 ++++++++++++++++++
 .../failure_detector/FailureDetector.hpp      |  91 ++++++++++++++++
 5 files changed, 208 insertions(+)
 create mode 100644 src/modules/commander/failure_detector/FailureDetector.cpp
 create mode 100644 src/modules/commander/failure_detector/FailureDetector.hpp

diff --git a/src/modules/commander/CMakeLists.txt b/src/modules/commander/CMakeLists.txt
index 7f62153bca..a60fe3a828 100644
--- a/src/modules/commander/CMakeLists.txt
+++ b/src/modules/commander/CMakeLists.txt
@@ -52,6 +52,7 @@ px4_add_module(
 		rc_calibration.cpp
 		rc_check.cpp
 		state_machine_helper.cpp
+		failure_detector/FailureDetector.cpp
 	DEPENDS
 		circuit_breaker
 		df_driver_framework
diff --git a/src/modules/commander/Commander.cpp b/src/modules/commander/Commander.cpp
index 3f90193bfb..aa2eb87597 100644
--- a/src/modules/commander/Commander.cpp
+++ b/src/modules/commander/Commander.cpp
@@ -1425,6 +1425,7 @@ Commander::run()
 			orb_copy(ORB_ID(parameter_update), param_changed_sub, &param_changed);
 
 			updateParams();
+			_failure_detector.update_params();
 
 			/* update parameters */
 			if (!armed.armed) {
@@ -2180,6 +2181,16 @@ Commander::run()
 			}
 		}
 
+		if (_failure_detector.update()) {
+			const auto _failure_status = _failure_detector.get();
+			if (_failure_status.roll) {
+				PX4_ERR("Roll angle exceeded");
+			}
+			if (_failure_status.pitch) {
+				PX4_ERR("Pitch angle exceeded");
+			}
+		}
+
 		/* Reset main state to loiter or auto-mission after takeoff is completed.
 		 * Sometimes, the mission result topic is outdated and the mission is still signaled
 		 * as finished even though we only just started with the takeoff. Therefore, we also
diff --git a/src/modules/commander/Commander.hpp b/src/modules/commander/Commander.hpp
index 5a703ee449..6f8b60c0fe 100644
--- a/src/modules/commander/Commander.hpp
+++ b/src/modules/commander/Commander.hpp
@@ -35,6 +35,7 @@
 #define COMMANDER_HPP_
 
 #include "state_machine_helper.h"
+#include "failure_detector/FailureDetector.hpp"
 
 #include <controllib/blocks.hpp>
 #include <px4_module.h>
@@ -128,6 +129,8 @@ private:
 	bool		_nav_test_passed{false};	/**< true if the post takeoff navigation test has passed */
 	bool		_nav_test_failed{false};	/**< true if the post takeoff navigation test has failed */
 
+	FailureDetector _failure_detector;
+
 	bool handle_command(vehicle_status_s *status, const vehicle_command_s &cmd,
 			    actuator_armed_s *armed, home_position_s *home, orb_advert_t *home_pub, orb_advert_t *command_ack_pub, bool *changed);
 
diff --git a/src/modules/commander/failure_detector/FailureDetector.cpp b/src/modules/commander/failure_detector/FailureDetector.cpp
new file mode 100644
index 0000000000..ce3e9f83e9
--- /dev/null
+++ b/src/modules/commander/failure_detector/FailureDetector.cpp
@@ -0,0 +1,102 @@
+/****************************************************************************
+ *
+ *   Copyright (c) 2018 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
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ *    notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ *    notice, this list of conditions and the following disclaimer in
+ *    the documentation and/or other materials provided with the
+ *    distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ *    used to endorse or promote products derived from this software
+ *    without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/**
+* @file FailureDetector.cpp
+*
+* @author Mathieu Bresciani	<brescianimathieu@gmail.com>
+*
+*/
+
+#include "FailureDetector.hpp"
+
+FailureDetector::FailureDetector() :
+	ModuleParams(nullptr),
+	_sub_vehicle_attitude_setpoint(ORB_ID(vehicle_attitude_setpoint)),
+	_sub_vehicule_attitude(ORB_ID(vehicle_attitude))
+{
+}
+
+void
+FailureDetector::update_params()
+{
+	updateParams();
+}
+
+bool
+FailureDetector::update()
+{
+	bool result(false);
+
+	result = update_attitude_status();
+
+	return result;
+}
+
+bool
+FailureDetector::update_attitude_status()
+{
+	bool result(false);
+
+	if (_sub_vehicule_attitude.update()) {
+		const vehicle_attitude_s &attitude = _sub_vehicule_attitude.get();
+
+		const matrix::Eulerf euler(matrix::Quatf(attitude.q));
+		const float roll(euler.phi());
+		const float pitch(euler.theta());
+
+		const float max_roll_deg = _fail_trig_roll.get();
+		const float max_pitch_deg = _fail_trig_pitch.get();
+		const float max_roll(fabsf(math::radians(max_roll_deg)));
+		const float max_pitch(fabsf(math::radians(max_pitch_deg)));
+
+		if (fabsf(roll) > max_roll) {
+			_status.roll = true;
+		} else {
+			_status.roll = false;
+		}
+
+		if (fabsf(pitch) > max_pitch) {
+			_status.pitch = true;
+		} else {
+			_status.pitch = false;
+		}
+
+		result = true;
+
+	} else {
+		result = false;
+	}
+
+	return result;
+}
diff --git a/src/modules/commander/failure_detector/FailureDetector.hpp b/src/modules/commander/failure_detector/FailureDetector.hpp
new file mode 100644
index 0000000000..9e3df8a82c
--- /dev/null
+++ b/src/modules/commander/failure_detector/FailureDetector.hpp
@@ -0,0 +1,91 @@
+
+/****************************************************************************
+ *
+ *   Copyright (c) 2018 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
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ *    notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ *    notice, this list of conditions and the following disclaimer in
+ *    the documentation and/or other materials provided with the
+ *    distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ *    used to endorse or promote products derived from this software
+ *    without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/**
+* @file FailureDetector.hpp
+* Base class for failure detection logic based on vehicle states
+* for failsafe triggering.
+*
+* @author Mathieu Bresciani 	<brescianimathieu@gmail.com>
+*
+*/
+
+#ifndef FAILURE_DETECTOR_HPP
+#define FAILURE_DETECTOR_HPP
+
+#include <matrix/matrix/math.hpp>
+#include <mathlib/mathlib.h>
+#include <px4_module_params.h>
+
+// subscriptions
+#include <uORB/Subscription.hpp>
+#include <uORB/topics/vehicle_attitude_setpoint.h>
+#include <uORB/topics/vehicle_attitude.h>
+
+using uORB::Subscription;
+
+class FailureDetector : public ModuleParams
+{
+public:
+	FailureDetector();
+
+	void update_params();
+
+	bool update();
+
+	struct failure_detector_status_s {
+		bool roll;
+		bool pitch;
+		bool altitude;
+	};
+
+	failure_detector_status_s get() {return _status;};
+
+private:
+
+	DEFINE_PARAMETERS(
+		(ParamInt<px4::params::VT_FW_QC_P>) _fail_trig_pitch,
+		(ParamInt<px4::params::VT_FW_QC_R>) _fail_trig_roll
+	)
+
+	// Subscriptions
+	Subscription<vehicle_attitude_s> _sub_vehicle_attitude_setpoint;
+	Subscription<vehicle_attitude_s> _sub_vehicule_attitude;
+
+	struct failure_detector_status_s _status;
+
+	bool update_attitude_status();
+};
+
+#endif /* FAILURE_DETECTOR_HPP */
-- 
GitLab