Browse Source

Failure Detector - Various cleanup and style changes.

- use pragma once guard in FailureDetector.hpp
- send Commander parent to ModuleParams and remove update_params() method
- simplify attitude checks
- FailureDetector::get_status() (previously named "get") is now a constant method that returns a constant reference
sbg
bresch 7 years ago committed by Daniel Agar
parent
commit
c4c8e8d2db
  1. 17
      src/modules/commander/Commander.cpp
  2. 1
      src/modules/commander/Commander.hpp
  3. 29
      src/modules/commander/failure_detector/FailureDetector.cpp
  4. 23
      src/modules/commander/failure_detector/FailureDetector.hpp

17
src/modules/commander/Commander.cpp

@ -540,7 +540,8 @@ transition_result_t arm_disarm(bool arm, orb_advert_t *mavlink_log_pub_local, co @@ -540,7 +540,8 @@ transition_result_t arm_disarm(bool arm, orb_advert_t *mavlink_log_pub_local, co
}
Commander::Commander() :
ModuleParams(nullptr)
ModuleParams(nullptr),
_failure_detector(this)
{
_battery_sub = orb_subscribe(ORB_ID(battery_status));
}
@ -1425,7 +1426,6 @@ Commander::run() @@ -1425,7 +1426,6 @@ Commander::run()
orb_copy(ORB_ID(parameter_update), param_changed_sub, &param_changed);
updateParams();
_failure_detector.update_params();
/* update parameters */
if (!armed.armed) {
@ -2289,21 +2289,20 @@ Commander::run() @@ -2289,21 +2289,20 @@ Commander::run()
if (_failure_detector.update()) {
const auto _failure_status = _failure_detector.get();
const failure_detector_status_s failure_status = _failure_detector.get_status();
if (_failure_status.roll ||
_failure_status.pitch) {
if (failure_status.roll ||
failure_status.pitch) {
armed.force_failsafe = true;
status_changed = true;
// Only display an user message if the circuit-breaker is disabled
if (!status_flags.circuit_breaker_flight_termination_disabled) {
static bool parachute_termination_printed = false;
if (!parachute_termination_printed) {
warnx("Flight termination because of attitude exceeding maximum values");
parachute_termination_printed = true;
if (!_failure_detector_termination_printed) {
PX4_WARN("Flight termination because of attitude exceeding maximum values");
_failure_detector_termination_printed = true;
}
if (counter % (1000000 / COMMANDER_MONITORING_INTERVAL) == 0) {

1
src/modules/commander/Commander.hpp

@ -129,6 +129,7 @@ private: @@ -129,6 +129,7 @@ private:
bool _nav_test_failed{false}; /**< true if the post takeoff navigation test has failed */
FailureDetector _failure_detector;
bool _failure_detector_termination_printed{false};
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);

29
src/modules/commander/failure_detector/FailureDetector.cpp

@ -40,19 +40,13 @@ @@ -40,19 +40,13 @@
#include "FailureDetector.hpp"
FailureDetector::FailureDetector() :
ModuleParams(nullptr),
FailureDetector::FailureDetector(ModuleParams *parent) :
ModuleParams(parent),
_sub_vehicle_attitude_setpoint(ORB_ID(vehicle_attitude_setpoint)),
_sub_vehicule_attitude(ORB_ID(vehicle_attitude))
{
}
void
FailureDetector::update_params()
{
updateParams();
}
bool
FailureDetector::update()
{
@ -80,23 +74,8 @@ FailureDetector::update_attitude_status() @@ -80,23 +74,8 @@ FailureDetector::update_attitude_status()
const float max_roll(fabsf(math::radians(max_roll_deg)));
const float max_pitch(fabsf(math::radians(max_pitch_deg)));
if ((max_roll > 0.0f) &&
(fabsf(roll) > max_roll)) {
_status.roll = true;
} else {
_status.roll = false;
}
if ((max_pitch > 0.0f) &&
(fabsf(pitch) > max_pitch)) {
_status.pitch = true;
} else {
_status.pitch = false;
}
_status.roll = (max_roll > 0.0f) && (fabsf(roll) > max_roll);
_status.pitch = (max_pitch > 0.0f) && (fabsf(pitch) > max_pitch);
updated = true;

23
src/modules/commander/failure_detector/FailureDetector.hpp

@ -41,8 +41,7 @@ @@ -41,8 +41,7 @@
*
*/
#ifndef FAILURE_DETECTOR_HPP
#define FAILURE_DETECTOR_HPP
#pragma once
#include <matrix/matrix/math.hpp>
#include <mathlib/mathlib.h>
@ -53,24 +52,22 @@ @@ -53,24 +52,22 @@
#include <uORB/topics/vehicle_attitude_setpoint.h>
#include <uORB/topics/vehicle_attitude.h>
struct failure_detector_status_s {
bool roll;
bool pitch;
bool altitude;
};
using uORB::Subscription;
class FailureDetector : public ModuleParams
{
public:
FailureDetector();
void update_params();
FailureDetector(ModuleParams *parent);
bool update();
struct failure_detector_status_s {
bool roll;
bool pitch;
bool altitude;
};
failure_detector_status_s get() {return _status;};
const failure_detector_status_s& get_status() const {return _status;}
private:
@ -87,5 +84,3 @@ private: @@ -87,5 +84,3 @@ private:
bool update_attitude_status();
};
#endif /* FAILURE_DETECTOR_HPP */

Loading…
Cancel
Save