Files
bizhang_-obav/src/modules/commander/state_machine_helper.cpp

1215 lines
41 KiB
C++
Raw Normal View History

/****************************************************************************
*
* Copyright (c) 2013-2015 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 state_machine_helper.cpp
* State machine helper functions implementations
*
2016-02-05 13:06:51 +01:00
* @author Thomas Gubler <thomas@px4.io>
* @author Julian Oes <julian@oes.ch>
* @author Sander Smeets <sander@droneslab.com>
*/
#include <px4_platform_common/px4_config.h>
#include <uORB/topics/vehicle_command.h>
#include <uORB/topics/vehicle_command_ack.h>
#include <uORB/topics/vehicle_status.h>
#include <systemlib/mavlink_log.h>
#include <drivers/drv_hrt.h>
#include "state_machine_helper.h"
#include "commander_helper.h"
#include "PreflightCheck.h"
#include "arm_auth.h"
static constexpr const char reason_no_rc[] = "no RC";
static constexpr const char reason_no_offboard[] = "no offboard";
static constexpr const char reason_no_rc_and_no_offboard[] = "no RC and no offboard";
static constexpr const char reason_no_local_position[] = "no local position";
static constexpr const char reason_no_global_position[] = "no global position";
static constexpr const char reason_no_datalink[] = "no datalink";
// This array defines the arming state transitions. The rows are the new state, and the columns
2016-04-24 13:26:27 -04:00
// are the current state. Using new state and current state you can index into the array which
// will be true for a valid transition or false for a invalid transition. In some cases even
// though the transition is marked as true additional checks must be made. See arming_state_transition
// code for those checks.
static constexpr const bool arming_transitions[vehicle_status_s::ARMING_STATE_MAX][vehicle_status_s::ARMING_STATE_MAX]
= {
// INIT, STANDBY, ARMED, STANDBY_ERROR, SHUTDOWN, IN_AIR_RESTORE
{ /* vehicle_status_s::ARMING_STATE_INIT */ true, true, false, true, false, false },
{ /* vehicle_status_s::ARMING_STATE_STANDBY */ true, true, true, false, false, false },
{ /* vehicle_status_s::ARMING_STATE_ARMED */ false, true, true, false, false, true },
{ /* vehicle_status_s::ARMING_STATE_STANDBY_ERROR */ true, true, true, true, false, false },
{ /* vehicle_status_s::ARMING_STATE_SHUTDOWN */ true, true, false, true, true, true },
{ /* vehicle_status_s::ARMING_STATE_IN_AIR_RESTORE */ false, false, false, false, false, false }, // NYI
};
2016-04-10 10:57:38 -07:00
// You can index into the array with an arming_state_t in order to get its textual representation
const char *const arming_state_names[vehicle_status_s::ARMING_STATE_MAX] = {
"INIT",
"STANDBY",
"ARMED",
"STANDBY_ERROR",
"SHUTDOWN",
"IN_AIR_RESTORE",
};
2016-01-22 11:31:39 +01:00
static hrt_abstime last_preflight_check = 0; ///< initialize so it gets checked immediately
void set_link_loss_nav_state(vehicle_status_s *status, actuator_armed_s *armed,
const vehicle_status_flags_s &status_flags, commander_state_s *internal_state, const link_loss_actions_t link_loss_act,
uint8_t auto_recovery_nav_state);
void reset_link_loss_globals(actuator_armed_s *armed, const bool old_failsafe, const link_loss_actions_t link_loss_act);
void set_offboard_loss_nav_state(vehicle_status_s *status, actuator_armed_s *armed,
const vehicle_status_flags_s &status_flags,
const offboard_loss_actions_t offboard_loss_act);
void set_offboard_loss_rc_nav_state(vehicle_status_s *status, actuator_armed_s *armed,
const vehicle_status_flags_s &status_flags,
const offboard_loss_rc_actions_t offboard_loss_rc_act);
void reset_offboard_loss_globals(actuator_armed_s *armed, const bool old_failsafe,
const offboard_loss_actions_t offboard_loss_act,
const offboard_loss_rc_actions_t offboard_loss_rc_act);
transition_result_t arming_state_transition(vehicle_status_s *status, const safety_s &safety,
const arming_state_t new_arming_state, actuator_armed_s *armed, const bool fRunPreArmChecks,
orb_advert_t *mavlink_log_pub, vehicle_status_flags_s *status_flags, const uint8_t arm_requirements,
const hrt_abstime &time_since_boot)
2013-07-28 23:12:16 +04:00
{
2014-05-11 13:36:51 +02:00
// Double check that our static arrays are still valid
2017-01-29 21:49:15 -05:00
static_assert(vehicle_status_s::ARMING_STATE_INIT == 0, "ARMING_STATE_INIT == 0");
static_assert(vehicle_status_s::ARMING_STATE_IN_AIR_RESTORE == vehicle_status_s::ARMING_STATE_MAX - 1,
"ARMING_STATE_IN_AIR_RESTORE == ARMING_STATE_MAX - 1");
2014-05-11 13:36:51 +02:00
2013-07-28 23:12:16 +04:00
transition_result_t ret = TRANSITION_DENIED;
arming_state_t current_arming_state = status->arming_state;
bool feedback_provided = false;
const bool hil_enabled = (status->hil_state == vehicle_status_s::HIL_STATE_ON);
/* only check transition if the new state is actually different from the current one */
if (new_arming_state == current_arming_state) {
2013-07-28 23:12:16 +04:00
ret = TRANSITION_NOT_CHANGED;
} else {
/*
* Get sensing state if necessary
*/
bool preflight_check_ret = true;
const bool checkGNSS = (arm_requirements & ARM_REQ_GPS_BIT);
/* only perform the pre-arm check if we have to */
2018-03-29 23:14:34 -04:00
if (fRunPreArmChecks && (new_arming_state == vehicle_status_s::ARMING_STATE_ARMED)
&& !hil_enabled) {
2015-11-19 17:48:39 +01:00
2018-11-28 17:11:15 -05:00
preflight_check_ret = Preflight::preflightCheck(mavlink_log_pub, *status, *status_flags, checkGNSS, true, true,
time_since_boot);
if (preflight_check_ret) {
status_flags->condition_system_sensors_initialized = true;
}
feedback_provided = true;
}
2016-04-24 13:26:27 -04:00
/* re-run the pre-flight check as long as sensors are failing */
if (!status_flags->condition_system_sensors_initialized
2018-11-28 17:11:15 -05:00
&& fRunPreArmChecks
&& ((new_arming_state == vehicle_status_s::ARMING_STATE_ARMED)
|| (new_arming_state == vehicle_status_s::ARMING_STATE_STANDBY))
&& !hil_enabled) {
2015-11-19 17:48:39 +01:00
2018-03-29 23:14:34 -04:00
if ((last_preflight_check == 0) || (hrt_elapsed_time(&last_preflight_check) > 1000 * 1000)) {
2018-11-28 17:11:15 -05:00
status_flags->condition_system_sensors_initialized = Preflight::preflightCheck(mavlink_log_pub, *status, *status_flags,
checkGNSS, false, false, time_since_boot);
2016-01-22 11:31:39 +01:00
last_preflight_check = hrt_absolute_time();
}
}
2014-05-11 13:36:51 +02:00
// Check that we have a valid state transition
bool valid_transition = arming_transitions[new_arming_state][status->arming_state];
if (valid_transition) {
// We have a good transition. Now perform any secondary validation.
if (new_arming_state == vehicle_status_s::ARMING_STATE_ARMED) {
2014-06-30 16:24:48 +02:00
// Do not perform pre-arm checks if coming from in air restore
// Allow if vehicle_status_s::HIL_STATE_ON
if (status->arming_state != vehicle_status_s::ARMING_STATE_IN_AIR_RESTORE && !hil_enabled) {
bool prearm_check_ret = true;
if (fRunPreArmChecks && preflight_check_ret) {
2018-03-29 23:14:34 -04:00
// only bother running prearm if preflight was successful
prearm_check_ret = prearm_check(mavlink_log_pub, *status_flags, safety, arm_requirements);
2018-03-29 23:14:34 -04:00
}
if (!preflight_check_ret || !prearm_check_ret) {
2018-03-29 23:14:34 -04:00
// the prearm and preflight checks already print the rejection reason
feedback_provided = true;
valid_transition = false;
}
}
2013-07-28 23:12:16 +04:00
}
2014-05-11 13:36:51 +02:00
}
2013-07-28 23:12:16 +04:00
if (hil_enabled) {
/* enforce lockdown in HIL */
armed->lockdown = true;
status_flags->condition_system_sensors_initialized = true;
/* recover from a prearm fail */
if (status->arming_state == vehicle_status_s::ARMING_STATE_STANDBY_ERROR) {
status->arming_state = vehicle_status_s::ARMING_STATE_STANDBY;
}
// HIL can always go to standby
if (new_arming_state == vehicle_status_s::ARMING_STATE_STANDBY) {
valid_transition = true;
}
2014-05-11 13:36:51 +02:00
}
2013-07-28 23:12:16 +04:00
if (!hil_enabled &&
2018-03-29 23:14:34 -04:00
(new_arming_state == vehicle_status_s::ARMING_STATE_STANDBY) &&
(status->arming_state != vehicle_status_s::ARMING_STATE_STANDBY_ERROR)) {
// Sensors need to be initialized for STANDBY state, except for HIL
if (!status_flags->condition_system_sensors_initialized) {
feedback_provided = true;
valid_transition = false;
}
}
2014-05-11 13:36:51 +02:00
// Finish up the state transition
if (valid_transition) {
armed->armed = (new_arming_state == vehicle_status_s::ARMING_STATE_ARMED);
2018-11-28 17:11:15 -05:00
armed->ready_to_arm = (new_arming_state == vehicle_status_s::ARMING_STATE_ARMED)
|| (new_arming_state == vehicle_status_s::ARMING_STATE_STANDBY);
2014-05-11 13:36:51 +02:00
ret = TRANSITION_CHANGED;
2013-07-28 23:12:16 +04:00
status->arming_state = new_arming_state;
if (new_arming_state == vehicle_status_s::ARMING_STATE_ARMED) {
armed->armed_time_ms = hrt_absolute_time() / 1000;
} else {
armed->armed_time_ms = 0;
}
}
}
2014-05-11 13:36:51 +02:00
if (ret == TRANSITION_DENIED) {
/* print to MAVLink and console if we didn't provide any feedback yet */
if (!feedback_provided) {
mavlink_log_critical(mavlink_log_pub, "Transition denied: %s to %s",
arming_state_names[status->arming_state], arming_state_names[new_arming_state]);
}
2014-05-11 13:36:51 +02:00
}
return ret;
}
bool is_safe(const safety_s &safety, const actuator_armed_s &armed)
{
// System is safe if:
// 1) Not armed
// 2) Armed, but in software lockdown (HIL)
// 3) Safety switch is present AND engaged -> actuators locked
const bool lockdown = (armed.lockdown || armed.manual_lockdown);
return !armed.armed || (armed.armed && lockdown) || (safety.safety_switch_available && !safety.safety_off);
}
2013-07-28 23:12:16 +04:00
transition_result_t
main_state_transition(const vehicle_status_s &status, const main_state_t new_main_state,
const vehicle_status_flags_s &status_flags, commander_state_s *internal_state)
2013-07-28 23:12:16 +04:00
{
// IMPORTANT: The assumption of callers of this function is that the execution of
2018-10-18 16:32:56 +02:00
// this check is essentially "free". Therefore any runtime checking in here has to be
// kept super lightweight. No complex logic or calls on external function should be
// implemented here.
2013-07-28 23:12:16 +04:00
transition_result_t ret = TRANSITION_DENIED;
2013-01-11 07:42:09 +01:00
/* transition may be denied even if the same state is requested because conditions may have changed */
switch (new_main_state) {
case commander_state_s::MAIN_STATE_MANUAL:
case commander_state_s::MAIN_STATE_STAB:
2016-05-27 16:10:03 -04:00
case commander_state_s::MAIN_STATE_ACRO:
case commander_state_s::MAIN_STATE_RATTITUDE:
2017-02-15 23:44:25 -05:00
ret = TRANSITION_CHANGED;
2016-05-27 16:10:03 -04:00
break;
case commander_state_s::MAIN_STATE_ALTCTL:
2016-08-04 11:09:09 +02:00
/* need at minimum altitude estimate */
if (status_flags.condition_local_altitude_valid ||
status_flags.condition_global_position_valid) {
2013-07-28 23:12:16 +04:00
ret = TRANSITION_CHANGED;
}
2016-08-04 11:09:09 +02:00
break;
2013-01-11 07:42:09 +01:00
case commander_state_s::MAIN_STATE_POSCTL:
2016-08-04 11:09:09 +02:00
/* need at minimum local position estimate */
if (status_flags.condition_local_position_valid ||
status_flags.condition_global_position_valid) {
ret = TRANSITION_CHANGED;
}
2016-08-04 11:09:09 +02:00
break;
2013-07-28 23:12:16 +04:00
case commander_state_s::MAIN_STATE_AUTO_LOITER:
2016-08-04 11:09:09 +02:00
/* need global position estimate */
if (status_flags.condition_global_position_valid) {
ret = TRANSITION_CHANGED;
2013-07-28 23:12:16 +04:00
}
2016-08-04 11:09:09 +02:00
break;
case commander_state_s::MAIN_STATE_AUTO_FOLLOW_TARGET:
2018-11-25 11:11:51 +00:00
case commander_state_s::MAIN_STATE_ORBIT:
2018-11-25 11:11:51 +00:00
/* Follow and orbit only implemented for multicopter */
if (status.vehicle_type == vehicle_status_s::VEHICLE_TYPE_ROTARY_WING) {
ret = TRANSITION_CHANGED;
}
break;
case commander_state_s::MAIN_STATE_AUTO_MISSION:
/* need global position, home position, and a valid mission */
if (status_flags.condition_global_position_valid &&
status_flags.condition_auto_mission_available) {
ret = TRANSITION_CHANGED;
}
break;
case commander_state_s::MAIN_STATE_AUTO_RTL:
2016-08-04 11:09:09 +02:00
/* need global position and home position */
if (status_flags.condition_global_position_valid && status_flags.condition_home_position_valid) {
ret = TRANSITION_CHANGED;
}
2016-08-04 11:09:09 +02:00
break;
case commander_state_s::MAIN_STATE_AUTO_TAKEOFF:
case commander_state_s::MAIN_STATE_AUTO_LAND:
/* need local position */
if (status_flags.condition_local_position_valid) {
ret = TRANSITION_CHANGED;
}
break;
case commander_state_s::MAIN_STATE_AUTO_PRECLAND:
/* need local and global position, and precision land only implemented for multicopters */
if (status_flags.condition_local_position_valid
&& status_flags.condition_global_position_valid
&& status.vehicle_type == vehicle_status_s::VEHICLE_TYPE_ROTARY_WING) {
ret = TRANSITION_CHANGED;
}
break;
case commander_state_s::MAIN_STATE_OFFBOARD:
2014-01-22 17:04:07 +01:00
/* need offboard signal */
if (!status_flags.offboard_control_signal_lost) {
2014-01-22 17:04:07 +01:00
ret = TRANSITION_CHANGED;
2013-07-28 23:12:16 +04:00
}
2014-01-29 21:21:16 +01:00
break;
case commander_state_s::MAIN_STATE_MAX:
default:
break;
}
2016-08-04 11:09:09 +02:00
if (ret == TRANSITION_CHANGED) {
if (internal_state->main_state != new_main_state) {
internal_state->main_state = new_main_state;
internal_state->timestamp = hrt_absolute_time();
2016-08-04 11:09:09 +02:00
} else {
ret = TRANSITION_NOT_CHANGED;
}
}
2013-07-28 23:12:16 +04:00
return ret;
}
/**
* Enable failsafe and report to user
*/
void enable_failsafe(vehicle_status_s *status, bool old_failsafe, orb_advert_t *mavlink_log_pub, const char *reason)
{
if (!old_failsafe && status->arming_state == vehicle_status_s::ARMING_STATE_ARMED) {
mavlink_log_critical(mavlink_log_pub, "Failsafe enabled: %s", reason);
}
status->failsafe = true;
}
/**
* Check failsafe and main status and set navigation status for navigator accordingly
*/
bool set_nav_state(vehicle_status_s *status, actuator_armed_s *armed, commander_state_s *internal_state,
orb_advert_t *mavlink_log_pub, const link_loss_actions_t data_link_loss_act, const bool mission_finished,
const bool stay_in_failsafe, const vehicle_status_flags_s &status_flags, bool landed,
const link_loss_actions_t rc_loss_act, const offboard_loss_actions_t offb_loss_act,
const offboard_loss_rc_actions_t offb_loss_rc_act,
const position_nav_loss_actions_t posctl_nav_loss_act)
{
navigation_state_t nav_state_old = status->nav_state;
const bool data_link_loss_act_configured = data_link_loss_act > link_loss_actions_t::DISABLED;
const bool rc_loss_act_configured = rc_loss_act > link_loss_actions_t::DISABLED;
const bool rc_lost = rc_loss_act_configured && (status->rc_signal_lost);
bool is_armed = (status->arming_state == vehicle_status_s::ARMING_STATE_ARMED);
bool old_failsafe = status->failsafe;
2016-04-08 13:19:11 +02:00
status->failsafe = false;
// Safe to do reset flags here, as if loss state persists flags will be restored in the code below
reset_link_loss_globals(armed, old_failsafe, rc_loss_act);
reset_link_loss_globals(armed, old_failsafe, data_link_loss_act);
reset_offboard_loss_globals(armed, old_failsafe, offb_loss_act, offb_loss_rc_act);
/* evaluate main state to decide in normal (non-failsafe) mode */
switch (internal_state->main_state) {
case commander_state_s::MAIN_STATE_ACRO:
case commander_state_s::MAIN_STATE_MANUAL:
case commander_state_s::MAIN_STATE_RATTITUDE:
case commander_state_s::MAIN_STATE_STAB:
case commander_state_s::MAIN_STATE_ALTCTL:
2016-08-04 11:09:09 +02:00
/* require RC for all manual modes */
if (rc_lost && is_armed) {
enable_failsafe(status, old_failsafe, mavlink_log_pub, reason_no_rc);
set_link_loss_nav_state(status, armed, status_flags, internal_state, rc_loss_act,
vehicle_status_s::NAVIGATION_STATE_AUTO_RCRECOVER);
2014-06-18 19:01:41 +02:00
} else {
switch (internal_state->main_state) {
case commander_state_s::MAIN_STATE_ACRO:
status->nav_state = vehicle_status_s::NAVIGATION_STATE_ACRO;
break;
case commander_state_s::MAIN_STATE_MANUAL:
status->nav_state = vehicle_status_s::NAVIGATION_STATE_MANUAL;
break;
case commander_state_s::MAIN_STATE_RATTITUDE:
status->nav_state = vehicle_status_s::NAVIGATION_STATE_RATTITUDE;
break;
case commander_state_s::MAIN_STATE_STAB:
2015-05-17 12:58:44 +02:00
status->nav_state = vehicle_status_s::NAVIGATION_STATE_STAB;
break;
case commander_state_s::MAIN_STATE_ALTCTL:
status->nav_state = vehicle_status_s::NAVIGATION_STATE_ALTCTL;
break;
default:
status->nav_state = vehicle_status_s::NAVIGATION_STATE_MANUAL;
break;
}
}
2016-08-04 11:09:09 +02:00
break;
2016-08-04 11:09:09 +02:00
case commander_state_s::MAIN_STATE_POSCTL: {
if (rc_lost && is_armed) {
enable_failsafe(status, old_failsafe, mavlink_log_pub, reason_no_rc);
set_link_loss_nav_state(status, armed, status_flags, internal_state, rc_loss_act,
vehicle_status_s::NAVIGATION_STATE_AUTO_RCRECOVER);
2016-08-04 11:09:09 +02:00
/* As long as there is RC, we can fallback to ALTCTL, or STAB. */
/* A local position estimate is enough for POSCTL for multirotors,
* this enables POSCTL using e.g. flow.
* For fixedwing, a global position is needed. */
} else if (is_armed
&& check_invalid_pos_nav_state(status, old_failsafe, mavlink_log_pub, status_flags,
!(posctl_nav_loss_act == position_nav_loss_actions_t::LAND_TERMINATE),
status->vehicle_type == vehicle_status_s::VEHICLE_TYPE_FIXED_WING)) {
commander: rework posvel validity checks Move into functions. Reset probation time and recalculate checks if a mode change is demanded to give the operator ability to regain control as soon as possible after nav performance is regained. (+11 squashed commits) Squashed commits: [a4bb800] commander: enable pilot to quickly recover from loss of position accuracy [19e16a0] commander: rework postal probation time [f96284e] commander: rework bad pos and vel test probation time [00d5f0c] commander: Allow EKF preflight checks to pass with moving vehicle Separates the 'is using GPS' and the GPS quality checks. Uses a reasonable subset of the GPS quality checks which allows checks to pass if the vehicle is moving. [4cdfb5c] commander: remove unused variable [349385a] commander: add EKF GPS quality checks to pre-arm checking Only perform check if GPs checking is activated by parameter setting. Display fault messages that makes it clear if EKF quality checks are failing or the EKF is not using GPS for another reason. We do not want to confuse this with GPS lock. [340ae29] commander: make position invalid fail-safe more sticky Require check to pass for 7 seconds before exiting failsafe. This is required because if GPs is failing innovation tests for a prolonged period, the EKF will periodically reset to the GPS and report good accuracy at the time of reset. Adding this delay gives time for an underlying error condition (eg bad IMU or compass) to be re-detected. [b04ac95] commander: Increase RAM allocation to eliminate low stack warnings [9dca12f] commander: add missing position invalid fail-safe responses [69f264d] commander: Update position invalid fail-safe responses Replace separate logic for each case with a generic function Add velocity checks. [8e8cef1] commander: rework position validity checks Consolidate existing checks for global and local position validity and add checking of velocity accuracy. Enable checks to be bypassed using the CBRK_VELPOSERR parameter.
2017-03-08 11:03:27 +11:00
// nothing to do - everything done in check_invalid_pos_nav_state
} else {
status->nav_state = vehicle_status_s::NAVIGATION_STATE_POSCTL;
}
}
break;
case commander_state_s::MAIN_STATE_AUTO_MISSION:
2014-06-18 19:01:41 +02:00
/* go into failsafe
2014-08-14 22:38:48 +02:00
* - if commanded to do so
* - if we have an engine failure
2016-02-05 13:06:51 +01:00
* - if we have vtol transition failure
* - depending on datalink, RC and if the mission is finished */
2018-02-18 17:24:01 -05:00
if (is_armed && check_invalid_pos_nav_state(status, old_failsafe, mavlink_log_pub, status_flags, false, true)) {
commander: rework posvel validity checks Move into functions. Reset probation time and recalculate checks if a mode change is demanded to give the operator ability to regain control as soon as possible after nav performance is regained. (+11 squashed commits) Squashed commits: [a4bb800] commander: enable pilot to quickly recover from loss of position accuracy [19e16a0] commander: rework postal probation time [f96284e] commander: rework bad pos and vel test probation time [00d5f0c] commander: Allow EKF preflight checks to pass with moving vehicle Separates the 'is using GPS' and the GPS quality checks. Uses a reasonable subset of the GPS quality checks which allows checks to pass if the vehicle is moving. [4cdfb5c] commander: remove unused variable [349385a] commander: add EKF GPS quality checks to pre-arm checking Only perform check if GPs checking is activated by parameter setting. Display fault messages that makes it clear if EKF quality checks are failing or the EKF is not using GPS for another reason. We do not want to confuse this with GPS lock. [340ae29] commander: make position invalid fail-safe more sticky Require check to pass for 7 seconds before exiting failsafe. This is required because if GPs is failing innovation tests for a prolonged period, the EKF will periodically reset to the GPS and report good accuracy at the time of reset. Adding this delay gives time for an underlying error condition (eg bad IMU or compass) to be re-detected. [b04ac95] commander: Increase RAM allocation to eliminate low stack warnings [9dca12f] commander: add missing position invalid fail-safe responses [69f264d] commander: Update position invalid fail-safe responses Replace separate logic for each case with a generic function Add velocity checks. [8e8cef1] commander: rework position validity checks Consolidate existing checks for global and local position validity and add checking of velocity accuracy. Enable checks to be bypassed using the CBRK_VELPOSERR parameter.
2017-03-08 11:03:27 +11:00
// nothing to do - everything done in check_invalid_pos_nav_state
} else if (status->engine_failure) {
status->nav_state = vehicle_status_s::NAVIGATION_STATE_AUTO_LANDENGFAIL;
2016-08-04 11:09:09 +02:00
} else if (status_flags.vtol_transition_failure) {
2016-02-05 13:06:51 +01:00
status->nav_state = vehicle_status_s::NAVIGATION_STATE_AUTO_RTL;
2016-08-04 11:09:09 +02:00
} else if (status->mission_failure) {
status->nav_state = vehicle_status_s::NAVIGATION_STATE_AUTO_RTL;
} else if (data_link_loss_act_configured && status->data_link_lost && is_armed) {
2016-08-04 11:09:09 +02:00
/* datalink loss enabled:
* check for datalink lost: this should always trigger RTGS */
enable_failsafe(status, old_failsafe, mavlink_log_pub, reason_no_datalink);
set_link_loss_nav_state(status, armed, status_flags, internal_state, data_link_loss_act,
vehicle_status_s::NAVIGATION_STATE_AUTO_RTGS);
2016-08-04 11:09:09 +02:00
} else if (!data_link_loss_act_configured && status->rc_signal_lost && status->data_link_lost && !landed
&& mission_finished && is_armed) {
/* datalink loss DISABLED:
2016-08-04 11:09:09 +02:00
* check if both, RC and datalink are lost during the mission
* or all links are lost after the mission finishes in air: this should always trigger RCRECOVER */
enable_failsafe(status, old_failsafe, mavlink_log_pub, reason_no_datalink);
set_link_loss_nav_state(status, armed, status_flags, internal_state, rc_loss_act,
vehicle_status_s::NAVIGATION_STATE_AUTO_RCRECOVER);
2014-06-18 19:01:41 +02:00
2016-08-04 11:09:09 +02:00
} else if (!stay_in_failsafe) {
/* stay where you are if you should stay in failsafe, otherwise everything is perfect */
status->nav_state = vehicle_status_s::NAVIGATION_STATE_AUTO_MISSION;
}
2016-08-04 11:09:09 +02:00
break;
case commander_state_s::MAIN_STATE_AUTO_LOITER:
2016-08-04 11:09:09 +02:00
/* go into failsafe on a engine failure */
if (status->engine_failure) {
status->nav_state = vehicle_status_s::NAVIGATION_STATE_AUTO_LANDENGFAIL;
commander: rework posvel validity checks Move into functions. Reset probation time and recalculate checks if a mode change is demanded to give the operator ability to regain control as soon as possible after nav performance is regained. (+11 squashed commits) Squashed commits: [a4bb800] commander: enable pilot to quickly recover from loss of position accuracy [19e16a0] commander: rework postal probation time [f96284e] commander: rework bad pos and vel test probation time [00d5f0c] commander: Allow EKF preflight checks to pass with moving vehicle Separates the 'is using GPS' and the GPS quality checks. Uses a reasonable subset of the GPS quality checks which allows checks to pass if the vehicle is moving. [4cdfb5c] commander: remove unused variable [349385a] commander: add EKF GPS quality checks to pre-arm checking Only perform check if GPs checking is activated by parameter setting. Display fault messages that makes it clear if EKF quality checks are failing or the EKF is not using GPS for another reason. We do not want to confuse this with GPS lock. [340ae29] commander: make position invalid fail-safe more sticky Require check to pass for 7 seconds before exiting failsafe. This is required because if GPs is failing innovation tests for a prolonged period, the EKF will periodically reset to the GPS and report good accuracy at the time of reset. Adding this delay gives time for an underlying error condition (eg bad IMU or compass) to be re-detected. [b04ac95] commander: Increase RAM allocation to eliminate low stack warnings [9dca12f] commander: add missing position invalid fail-safe responses [69f264d] commander: Update position invalid fail-safe responses Replace separate logic for each case with a generic function Add velocity checks. [8e8cef1] commander: rework position validity checks Consolidate existing checks for global and local position validity and add checking of velocity accuracy. Enable checks to be bypassed using the CBRK_VELPOSERR parameter.
2017-03-08 11:03:27 +11:00
} else if (is_armed && check_invalid_pos_nav_state(status, old_failsafe, mavlink_log_pub, status_flags, false, true)) {
// nothing to do - everything done in check_invalid_pos_nav_state
} else if (status->data_link_lost && data_link_loss_act_configured && !landed && is_armed) {
/* also go into failsafe if just datalink is lost, and we're actually in air */
set_link_loss_nav_state(status, armed, status_flags, internal_state, data_link_loss_act,
vehicle_status_s::NAVIGATION_STATE_AUTO_RTGS);
2016-08-04 11:09:09 +02:00
enable_failsafe(status, old_failsafe, mavlink_log_pub, reason_no_datalink);
2014-06-18 19:01:41 +02:00
} else if (rc_lost && !data_link_loss_act_configured && is_armed) {
/* go into failsafe if RC is lost and datalink loss is not set up and rc loss is not DISABLED */
enable_failsafe(status, old_failsafe, mavlink_log_pub, reason_no_rc);
2016-08-04 11:09:09 +02:00
set_link_loss_nav_state(status, armed, status_flags, internal_state, rc_loss_act,
vehicle_status_s::NAVIGATION_STATE_AUTO_RCRECOVER);
2014-06-18 19:01:41 +02:00
} else if (status->rc_signal_lost) {
/* don't bother if RC is lost if datalink is connected */
2014-06-18 19:01:41 +02:00
/* this mode is ok, we don't need RC for LOITERing */
status->nav_state = vehicle_status_s::NAVIGATION_STATE_AUTO_LOITER;
2016-08-04 11:09:09 +02:00
} else {
2014-06-18 19:01:41 +02:00
/* everything is perfect */
status->nav_state = vehicle_status_s::NAVIGATION_STATE_AUTO_LOITER;
}
2016-08-04 11:09:09 +02:00
break;
case commander_state_s::MAIN_STATE_AUTO_RTL:
2016-08-04 11:09:09 +02:00
/* require global position and home, also go into failsafe on an engine failure */
if (status->engine_failure) {
status->nav_state = vehicle_status_s::NAVIGATION_STATE_AUTO_LANDENGFAIL;
commander: rework posvel validity checks Move into functions. Reset probation time and recalculate checks if a mode change is demanded to give the operator ability to regain control as soon as possible after nav performance is regained. (+11 squashed commits) Squashed commits: [a4bb800] commander: enable pilot to quickly recover from loss of position accuracy [19e16a0] commander: rework postal probation time [f96284e] commander: rework bad pos and vel test probation time [00d5f0c] commander: Allow EKF preflight checks to pass with moving vehicle Separates the 'is using GPS' and the GPS quality checks. Uses a reasonable subset of the GPS quality checks which allows checks to pass if the vehicle is moving. [4cdfb5c] commander: remove unused variable [349385a] commander: add EKF GPS quality checks to pre-arm checking Only perform check if GPs checking is activated by parameter setting. Display fault messages that makes it clear if EKF quality checks are failing or the EKF is not using GPS for another reason. We do not want to confuse this with GPS lock. [340ae29] commander: make position invalid fail-safe more sticky Require check to pass for 7 seconds before exiting failsafe. This is required because if GPs is failing innovation tests for a prolonged period, the EKF will periodically reset to the GPS and report good accuracy at the time of reset. Adding this delay gives time for an underlying error condition (eg bad IMU or compass) to be re-detected. [b04ac95] commander: Increase RAM allocation to eliminate low stack warnings [9dca12f] commander: add missing position invalid fail-safe responses [69f264d] commander: Update position invalid fail-safe responses Replace separate logic for each case with a generic function Add velocity checks. [8e8cef1] commander: rework position validity checks Consolidate existing checks for global and local position validity and add checking of velocity accuracy. Enable checks to be bypassed using the CBRK_VELPOSERR parameter.
2017-03-08 11:03:27 +11:00
} else if (is_armed && check_invalid_pos_nav_state(status, old_failsafe, mavlink_log_pub, status_flags, false, true)) {
// nothing to do - everything done in check_invalid_pos_nav_state
2014-06-18 19:01:41 +02:00
} else {
status->nav_state = vehicle_status_s::NAVIGATION_STATE_AUTO_RTL;
}
2016-08-04 11:09:09 +02:00
break;
case commander_state_s::MAIN_STATE_AUTO_FOLLOW_TARGET:
2016-08-04 11:09:09 +02:00
/* require global position and home */
if (status->engine_failure) {
status->nav_state = vehicle_status_s::NAVIGATION_STATE_AUTO_LANDENGFAIL;
2016-08-04 11:09:09 +02:00
commander: rework posvel validity checks Move into functions. Reset probation time and recalculate checks if a mode change is demanded to give the operator ability to regain control as soon as possible after nav performance is regained. (+11 squashed commits) Squashed commits: [a4bb800] commander: enable pilot to quickly recover from loss of position accuracy [19e16a0] commander: rework postal probation time [f96284e] commander: rework bad pos and vel test probation time [00d5f0c] commander: Allow EKF preflight checks to pass with moving vehicle Separates the 'is using GPS' and the GPS quality checks. Uses a reasonable subset of the GPS quality checks which allows checks to pass if the vehicle is moving. [4cdfb5c] commander: remove unused variable [349385a] commander: add EKF GPS quality checks to pre-arm checking Only perform check if GPs checking is activated by parameter setting. Display fault messages that makes it clear if EKF quality checks are failing or the EKF is not using GPS for another reason. We do not want to confuse this with GPS lock. [340ae29] commander: make position invalid fail-safe more sticky Require check to pass for 7 seconds before exiting failsafe. This is required because if GPs is failing innovation tests for a prolonged period, the EKF will periodically reset to the GPS and report good accuracy at the time of reset. Adding this delay gives time for an underlying error condition (eg bad IMU or compass) to be re-detected. [b04ac95] commander: Increase RAM allocation to eliminate low stack warnings [9dca12f] commander: add missing position invalid fail-safe responses [69f264d] commander: Update position invalid fail-safe responses Replace separate logic for each case with a generic function Add velocity checks. [8e8cef1] commander: rework position validity checks Consolidate existing checks for global and local position validity and add checking of velocity accuracy. Enable checks to be bypassed using the CBRK_VELPOSERR parameter.
2017-03-08 11:03:27 +11:00
} else if (is_armed && check_invalid_pos_nav_state(status, old_failsafe, mavlink_log_pub, status_flags, false, true)) {
// nothing to do - everything done in check_invalid_pos_nav_state
2016-08-04 11:09:09 +02:00
} else {
status->nav_state = vehicle_status_s::NAVIGATION_STATE_AUTO_FOLLOW_TARGET;
}
2016-08-04 11:09:09 +02:00
break;
2018-11-25 11:11:51 +00:00
case commander_state_s::MAIN_STATE_ORBIT:
if (status->engine_failure) {
// failsafe: on engine failure
2018-11-25 11:11:51 +00:00
status->nav_state = vehicle_status_s::NAVIGATION_STATE_AUTO_LANDENGFAIL;
// Orbit can only be started via vehicle_command (mavlink). Recovery from failsafe into orbit
// is not possible and therefore the internal_state needs to be adjusted.
internal_state->main_state = commander_state_s::MAIN_STATE_POSCTL;
} else if (is_armed && check_invalid_pos_nav_state(status, old_failsafe, mavlink_log_pub, status_flags, false, true)) {
2019-08-15 10:18:08 +02:00
// failsafe: necessary position estimate lost; switching is done in check_invalid_pos_nav_state
// Orbit can only be started via vehicle_command (mavlink). Consequently, recovery from failsafe into orbit
// is not possible and therefore the internal_state needs to be adjusted.
internal_state->main_state = commander_state_s::MAIN_STATE_POSCTL;
} else if (status->data_link_lost && data_link_loss_act_configured && !landed && is_armed) {
// failsafe: just datalink is lost and we're in air
set_link_loss_nav_state(status, armed, status_flags, internal_state, data_link_loss_act,
vehicle_status_s::NAVIGATION_STATE_AUTO_RTGS);
enable_failsafe(status, old_failsafe, mavlink_log_pub, reason_no_datalink);
// Orbit can only be started via vehicle_command (mavlink). Consequently, recovery from failsafe into orbit
// is not possible and therefore the internal_state needs to be adjusted.
internal_state->main_state = commander_state_s::MAIN_STATE_POSCTL;
} else if (rc_lost && !data_link_loss_act_configured && is_armed) {
// failsafe: RC is lost, datalink loss is not set up and rc loss is not disabled
enable_failsafe(status, old_failsafe, mavlink_log_pub, reason_no_rc);
set_link_loss_nav_state(status, armed, status_flags, internal_state, rc_loss_act,
vehicle_status_s::NAVIGATION_STATE_AUTO_RCRECOVER);
2018-11-25 11:11:51 +00:00
// Orbit can only be started via vehicle_command (mavlink). Consequently, recovery from failsafe into orbit
// is not possible and therefore the internal_state needs to be adjusted.
internal_state->main_state = commander_state_s::MAIN_STATE_POSCTL;
2018-11-25 11:11:51 +00:00
} else {
// no failsafe, RC is not mandatory for orbit
2018-11-25 11:11:51 +00:00
status->nav_state = vehicle_status_s::NAVIGATION_STATE_ORBIT;
}
2018-11-25 11:11:51 +00:00
break;
case commander_state_s::MAIN_STATE_AUTO_TAKEOFF:
2016-08-04 11:09:09 +02:00
/* require local position */
if (status->engine_failure) {
status->nav_state = vehicle_status_s::NAVIGATION_STATE_AUTO_LANDENGFAIL;
2016-08-04 11:09:09 +02:00
commander: rework posvel validity checks Move into functions. Reset probation time and recalculate checks if a mode change is demanded to give the operator ability to regain control as soon as possible after nav performance is regained. (+11 squashed commits) Squashed commits: [a4bb800] commander: enable pilot to quickly recover from loss of position accuracy [19e16a0] commander: rework postal probation time [f96284e] commander: rework bad pos and vel test probation time [00d5f0c] commander: Allow EKF preflight checks to pass with moving vehicle Separates the 'is using GPS' and the GPS quality checks. Uses a reasonable subset of the GPS quality checks which allows checks to pass if the vehicle is moving. [4cdfb5c] commander: remove unused variable [349385a] commander: add EKF GPS quality checks to pre-arm checking Only perform check if GPs checking is activated by parameter setting. Display fault messages that makes it clear if EKF quality checks are failing or the EKF is not using GPS for another reason. We do not want to confuse this with GPS lock. [340ae29] commander: make position invalid fail-safe more sticky Require check to pass for 7 seconds before exiting failsafe. This is required because if GPs is failing innovation tests for a prolonged period, the EKF will periodically reset to the GPS and report good accuracy at the time of reset. Adding this delay gives time for an underlying error condition (eg bad IMU or compass) to be re-detected. [b04ac95] commander: Increase RAM allocation to eliminate low stack warnings [9dca12f] commander: add missing position invalid fail-safe responses [69f264d] commander: Update position invalid fail-safe responses Replace separate logic for each case with a generic function Add velocity checks. [8e8cef1] commander: rework position validity checks Consolidate existing checks for global and local position validity and add checking of velocity accuracy. Enable checks to be bypassed using the CBRK_VELPOSERR parameter.
2017-03-08 11:03:27 +11:00
} else if (is_armed && check_invalid_pos_nav_state(status, old_failsafe, mavlink_log_pub, status_flags, false, false)) {
// nothing to do - everything done in check_invalid_pos_nav_state
2016-08-04 11:09:09 +02:00
} else {
status->nav_state = vehicle_status_s::NAVIGATION_STATE_AUTO_TAKEOFF;
}
2016-08-04 11:09:09 +02:00
break;
case commander_state_s::MAIN_STATE_AUTO_LAND:
2016-08-04 11:09:09 +02:00
/* require local position */
if (status->engine_failure) {
status->nav_state = vehicle_status_s::NAVIGATION_STATE_AUTO_LANDENGFAIL;
2016-08-04 11:09:09 +02:00
commander: rework posvel validity checks Move into functions. Reset probation time and recalculate checks if a mode change is demanded to give the operator ability to regain control as soon as possible after nav performance is regained. (+11 squashed commits) Squashed commits: [a4bb800] commander: enable pilot to quickly recover from loss of position accuracy [19e16a0] commander: rework postal probation time [f96284e] commander: rework bad pos and vel test probation time [00d5f0c] commander: Allow EKF preflight checks to pass with moving vehicle Separates the 'is using GPS' and the GPS quality checks. Uses a reasonable subset of the GPS quality checks which allows checks to pass if the vehicle is moving. [4cdfb5c] commander: remove unused variable [349385a] commander: add EKF GPS quality checks to pre-arm checking Only perform check if GPs checking is activated by parameter setting. Display fault messages that makes it clear if EKF quality checks are failing or the EKF is not using GPS for another reason. We do not want to confuse this with GPS lock. [340ae29] commander: make position invalid fail-safe more sticky Require check to pass for 7 seconds before exiting failsafe. This is required because if GPs is failing innovation tests for a prolonged period, the EKF will periodically reset to the GPS and report good accuracy at the time of reset. Adding this delay gives time for an underlying error condition (eg bad IMU or compass) to be re-detected. [b04ac95] commander: Increase RAM allocation to eliminate low stack warnings [9dca12f] commander: add missing position invalid fail-safe responses [69f264d] commander: Update position invalid fail-safe responses Replace separate logic for each case with a generic function Add velocity checks. [8e8cef1] commander: rework position validity checks Consolidate existing checks for global and local position validity and add checking of velocity accuracy. Enable checks to be bypassed using the CBRK_VELPOSERR parameter.
2017-03-08 11:03:27 +11:00
} else if (is_armed && check_invalid_pos_nav_state(status, old_failsafe, mavlink_log_pub, status_flags, false, false)) {
// nothing to do - everything done in check_invalid_pos_nav_state
2016-08-04 11:09:09 +02:00
} else {
status->nav_state = vehicle_status_s::NAVIGATION_STATE_AUTO_LAND;
}
2016-08-04 11:09:09 +02:00
break;
case commander_state_s::MAIN_STATE_AUTO_PRECLAND:
/* must be rotary wing plus same requirements as normal landing */
if (status->engine_failure) {
status->nav_state = vehicle_status_s::NAVIGATION_STATE_AUTO_LANDENGFAIL;
} else if (is_armed && check_invalid_pos_nav_state(status, old_failsafe, mavlink_log_pub, status_flags, false, false)) {
// nothing to do - everything done in check_invalid_pos_nav_state
} else {
status->nav_state = vehicle_status_s::NAVIGATION_STATE_AUTO_PRECLAND;
}
break;
case commander_state_s::MAIN_STATE_OFFBOARD:
2016-08-04 11:09:09 +02:00
/* require offboard control, otherwise stay where you are */
if (status_flags.offboard_control_signal_lost && status_flags.offboard_control_loss_timeout) {
if (status->rc_signal_lost) {
// Offboard and RC are lost
enable_failsafe(status, old_failsafe, mavlink_log_pub, reason_no_rc_and_no_offboard);
set_offboard_loss_nav_state(status, armed, status_flags, offb_loss_act);
} else {
// Offboard is lost, RC is ok
enable_failsafe(status, old_failsafe, mavlink_log_pub, reason_no_offboard);
set_offboard_loss_rc_nav_state(status, armed, status_flags, offb_loss_rc_act);
}
} else {
status->nav_state = vehicle_status_s::NAVIGATION_STATE_OFFBOARD;
}
2016-08-04 11:09:09 +02:00
default:
break;
}
return status->nav_state != nav_state_old;
}
bool check_invalid_pos_nav_state(vehicle_status_s *status, bool old_failsafe, orb_advert_t *mavlink_log_pub,
const vehicle_status_flags_s &status_flags, const bool use_rc, const bool using_global_pos)
commander: rework posvel validity checks Move into functions. Reset probation time and recalculate checks if a mode change is demanded to give the operator ability to regain control as soon as possible after nav performance is regained. (+11 squashed commits) Squashed commits: [a4bb800] commander: enable pilot to quickly recover from loss of position accuracy [19e16a0] commander: rework postal probation time [f96284e] commander: rework bad pos and vel test probation time [00d5f0c] commander: Allow EKF preflight checks to pass with moving vehicle Separates the 'is using GPS' and the GPS quality checks. Uses a reasonable subset of the GPS quality checks which allows checks to pass if the vehicle is moving. [4cdfb5c] commander: remove unused variable [349385a] commander: add EKF GPS quality checks to pre-arm checking Only perform check if GPs checking is activated by parameter setting. Display fault messages that makes it clear if EKF quality checks are failing or the EKF is not using GPS for another reason. We do not want to confuse this with GPS lock. [340ae29] commander: make position invalid fail-safe more sticky Require check to pass for 7 seconds before exiting failsafe. This is required because if GPs is failing innovation tests for a prolonged period, the EKF will periodically reset to the GPS and report good accuracy at the time of reset. Adding this delay gives time for an underlying error condition (eg bad IMU or compass) to be re-detected. [b04ac95] commander: Increase RAM allocation to eliminate low stack warnings [9dca12f] commander: add missing position invalid fail-safe responses [69f264d] commander: Update position invalid fail-safe responses Replace separate logic for each case with a generic function Add velocity checks. [8e8cef1] commander: rework position validity checks Consolidate existing checks for global and local position validity and add checking of velocity accuracy. Enable checks to be bypassed using the CBRK_VELPOSERR parameter.
2017-03-08 11:03:27 +11:00
{
bool fallback_required = false;
if (using_global_pos && !status_flags.condition_global_position_valid) {
commander: rework posvel validity checks Move into functions. Reset probation time and recalculate checks if a mode change is demanded to give the operator ability to regain control as soon as possible after nav performance is regained. (+11 squashed commits) Squashed commits: [a4bb800] commander: enable pilot to quickly recover from loss of position accuracy [19e16a0] commander: rework postal probation time [f96284e] commander: rework bad pos and vel test probation time [00d5f0c] commander: Allow EKF preflight checks to pass with moving vehicle Separates the 'is using GPS' and the GPS quality checks. Uses a reasonable subset of the GPS quality checks which allows checks to pass if the vehicle is moving. [4cdfb5c] commander: remove unused variable [349385a] commander: add EKF GPS quality checks to pre-arm checking Only perform check if GPs checking is activated by parameter setting. Display fault messages that makes it clear if EKF quality checks are failing or the EKF is not using GPS for another reason. We do not want to confuse this with GPS lock. [340ae29] commander: make position invalid fail-safe more sticky Require check to pass for 7 seconds before exiting failsafe. This is required because if GPs is failing innovation tests for a prolonged period, the EKF will periodically reset to the GPS and report good accuracy at the time of reset. Adding this delay gives time for an underlying error condition (eg bad IMU or compass) to be re-detected. [b04ac95] commander: Increase RAM allocation to eliminate low stack warnings [9dca12f] commander: add missing position invalid fail-safe responses [69f264d] commander: Update position invalid fail-safe responses Replace separate logic for each case with a generic function Add velocity checks. [8e8cef1] commander: rework position validity checks Consolidate existing checks for global and local position validity and add checking of velocity accuracy. Enable checks to be bypassed using the CBRK_VELPOSERR parameter.
2017-03-08 11:03:27 +11:00
fallback_required = true;
} else if (!using_global_pos
&& (!status_flags.condition_local_position_valid || !status_flags.condition_local_velocity_valid)) {
commander: rework posvel validity checks Move into functions. Reset probation time and recalculate checks if a mode change is demanded to give the operator ability to regain control as soon as possible after nav performance is regained. (+11 squashed commits) Squashed commits: [a4bb800] commander: enable pilot to quickly recover from loss of position accuracy [19e16a0] commander: rework postal probation time [f96284e] commander: rework bad pos and vel test probation time [00d5f0c] commander: Allow EKF preflight checks to pass with moving vehicle Separates the 'is using GPS' and the GPS quality checks. Uses a reasonable subset of the GPS quality checks which allows checks to pass if the vehicle is moving. [4cdfb5c] commander: remove unused variable [349385a] commander: add EKF GPS quality checks to pre-arm checking Only perform check if GPs checking is activated by parameter setting. Display fault messages that makes it clear if EKF quality checks are failing or the EKF is not using GPS for another reason. We do not want to confuse this with GPS lock. [340ae29] commander: make position invalid fail-safe more sticky Require check to pass for 7 seconds before exiting failsafe. This is required because if GPs is failing innovation tests for a prolonged period, the EKF will periodically reset to the GPS and report good accuracy at the time of reset. Adding this delay gives time for an underlying error condition (eg bad IMU or compass) to be re-detected. [b04ac95] commander: Increase RAM allocation to eliminate low stack warnings [9dca12f] commander: add missing position invalid fail-safe responses [69f264d] commander: Update position invalid fail-safe responses Replace separate logic for each case with a generic function Add velocity checks. [8e8cef1] commander: rework position validity checks Consolidate existing checks for global and local position validity and add checking of velocity accuracy. Enable checks to be bypassed using the CBRK_VELPOSERR parameter.
2017-03-08 11:03:27 +11:00
fallback_required = true;
}
if (fallback_required) {
if (use_rc) {
// fallback to a mode that gives the operator stick control
if (status->vehicle_type == vehicle_status_s::VEHICLE_TYPE_ROTARY_WING
&& status_flags.condition_local_position_valid) {
commander: rework posvel validity checks Move into functions. Reset probation time and recalculate checks if a mode change is demanded to give the operator ability to regain control as soon as possible after nav performance is regained. (+11 squashed commits) Squashed commits: [a4bb800] commander: enable pilot to quickly recover from loss of position accuracy [19e16a0] commander: rework postal probation time [f96284e] commander: rework bad pos and vel test probation time [00d5f0c] commander: Allow EKF preflight checks to pass with moving vehicle Separates the 'is using GPS' and the GPS quality checks. Uses a reasonable subset of the GPS quality checks which allows checks to pass if the vehicle is moving. [4cdfb5c] commander: remove unused variable [349385a] commander: add EKF GPS quality checks to pre-arm checking Only perform check if GPs checking is activated by parameter setting. Display fault messages that makes it clear if EKF quality checks are failing or the EKF is not using GPS for another reason. We do not want to confuse this with GPS lock. [340ae29] commander: make position invalid fail-safe more sticky Require check to pass for 7 seconds before exiting failsafe. This is required because if GPs is failing innovation tests for a prolonged period, the EKF will periodically reset to the GPS and report good accuracy at the time of reset. Adding this delay gives time for an underlying error condition (eg bad IMU or compass) to be re-detected. [b04ac95] commander: Increase RAM allocation to eliminate low stack warnings [9dca12f] commander: add missing position invalid fail-safe responses [69f264d] commander: Update position invalid fail-safe responses Replace separate logic for each case with a generic function Add velocity checks. [8e8cef1] commander: rework position validity checks Consolidate existing checks for global and local position validity and add checking of velocity accuracy. Enable checks to be bypassed using the CBRK_VELPOSERR parameter.
2017-03-08 11:03:27 +11:00
status->nav_state = vehicle_status_s::NAVIGATION_STATE_POSCTL;
} else if (status_flags.condition_local_altitude_valid) {
commander: rework posvel validity checks Move into functions. Reset probation time and recalculate checks if a mode change is demanded to give the operator ability to regain control as soon as possible after nav performance is regained. (+11 squashed commits) Squashed commits: [a4bb800] commander: enable pilot to quickly recover from loss of position accuracy [19e16a0] commander: rework postal probation time [f96284e] commander: rework bad pos and vel test probation time [00d5f0c] commander: Allow EKF preflight checks to pass with moving vehicle Separates the 'is using GPS' and the GPS quality checks. Uses a reasonable subset of the GPS quality checks which allows checks to pass if the vehicle is moving. [4cdfb5c] commander: remove unused variable [349385a] commander: add EKF GPS quality checks to pre-arm checking Only perform check if GPs checking is activated by parameter setting. Display fault messages that makes it clear if EKF quality checks are failing or the EKF is not using GPS for another reason. We do not want to confuse this with GPS lock. [340ae29] commander: make position invalid fail-safe more sticky Require check to pass for 7 seconds before exiting failsafe. This is required because if GPs is failing innovation tests for a prolonged period, the EKF will periodically reset to the GPS and report good accuracy at the time of reset. Adding this delay gives time for an underlying error condition (eg bad IMU or compass) to be re-detected. [b04ac95] commander: Increase RAM allocation to eliminate low stack warnings [9dca12f] commander: add missing position invalid fail-safe responses [69f264d] commander: Update position invalid fail-safe responses Replace separate logic for each case with a generic function Add velocity checks. [8e8cef1] commander: rework position validity checks Consolidate existing checks for global and local position validity and add checking of velocity accuracy. Enable checks to be bypassed using the CBRK_VELPOSERR parameter.
2017-03-08 11:03:27 +11:00
status->nav_state = vehicle_status_s::NAVIGATION_STATE_ALTCTL;
commander: rework posvel validity checks Move into functions. Reset probation time and recalculate checks if a mode change is demanded to give the operator ability to regain control as soon as possible after nav performance is regained. (+11 squashed commits) Squashed commits: [a4bb800] commander: enable pilot to quickly recover from loss of position accuracy [19e16a0] commander: rework postal probation time [f96284e] commander: rework bad pos and vel test probation time [00d5f0c] commander: Allow EKF preflight checks to pass with moving vehicle Separates the 'is using GPS' and the GPS quality checks. Uses a reasonable subset of the GPS quality checks which allows checks to pass if the vehicle is moving. [4cdfb5c] commander: remove unused variable [349385a] commander: add EKF GPS quality checks to pre-arm checking Only perform check if GPs checking is activated by parameter setting. Display fault messages that makes it clear if EKF quality checks are failing or the EKF is not using GPS for another reason. We do not want to confuse this with GPS lock. [340ae29] commander: make position invalid fail-safe more sticky Require check to pass for 7 seconds before exiting failsafe. This is required because if GPs is failing innovation tests for a prolonged period, the EKF will periodically reset to the GPS and report good accuracy at the time of reset. Adding this delay gives time for an underlying error condition (eg bad IMU or compass) to be re-detected. [b04ac95] commander: Increase RAM allocation to eliminate low stack warnings [9dca12f] commander: add missing position invalid fail-safe responses [69f264d] commander: Update position invalid fail-safe responses Replace separate logic for each case with a generic function Add velocity checks. [8e8cef1] commander: rework position validity checks Consolidate existing checks for global and local position validity and add checking of velocity accuracy. Enable checks to be bypassed using the CBRK_VELPOSERR parameter.
2017-03-08 11:03:27 +11:00
} else {
status->nav_state = vehicle_status_s::NAVIGATION_STATE_STAB;
}
commander: rework posvel validity checks Move into functions. Reset probation time and recalculate checks if a mode change is demanded to give the operator ability to regain control as soon as possible after nav performance is regained. (+11 squashed commits) Squashed commits: [a4bb800] commander: enable pilot to quickly recover from loss of position accuracy [19e16a0] commander: rework postal probation time [f96284e] commander: rework bad pos and vel test probation time [00d5f0c] commander: Allow EKF preflight checks to pass with moving vehicle Separates the 'is using GPS' and the GPS quality checks. Uses a reasonable subset of the GPS quality checks which allows checks to pass if the vehicle is moving. [4cdfb5c] commander: remove unused variable [349385a] commander: add EKF GPS quality checks to pre-arm checking Only perform check if GPs checking is activated by parameter setting. Display fault messages that makes it clear if EKF quality checks are failing or the EKF is not using GPS for another reason. We do not want to confuse this with GPS lock. [340ae29] commander: make position invalid fail-safe more sticky Require check to pass for 7 seconds before exiting failsafe. This is required because if GPs is failing innovation tests for a prolonged period, the EKF will periodically reset to the GPS and report good accuracy at the time of reset. Adding this delay gives time for an underlying error condition (eg bad IMU or compass) to be re-detected. [b04ac95] commander: Increase RAM allocation to eliminate low stack warnings [9dca12f] commander: add missing position invalid fail-safe responses [69f264d] commander: Update position invalid fail-safe responses Replace separate logic for each case with a generic function Add velocity checks. [8e8cef1] commander: rework position validity checks Consolidate existing checks for global and local position validity and add checking of velocity accuracy. Enable checks to be bypassed using the CBRK_VELPOSERR parameter.
2017-03-08 11:03:27 +11:00
} else {
// go into a descent that does not require stick control
if (status_flags.condition_local_position_valid) {
commander: rework posvel validity checks Move into functions. Reset probation time and recalculate checks if a mode change is demanded to give the operator ability to regain control as soon as possible after nav performance is regained. (+11 squashed commits) Squashed commits: [a4bb800] commander: enable pilot to quickly recover from loss of position accuracy [19e16a0] commander: rework postal probation time [f96284e] commander: rework bad pos and vel test probation time [00d5f0c] commander: Allow EKF preflight checks to pass with moving vehicle Separates the 'is using GPS' and the GPS quality checks. Uses a reasonable subset of the GPS quality checks which allows checks to pass if the vehicle is moving. [4cdfb5c] commander: remove unused variable [349385a] commander: add EKF GPS quality checks to pre-arm checking Only perform check if GPs checking is activated by parameter setting. Display fault messages that makes it clear if EKF quality checks are failing or the EKF is not using GPS for another reason. We do not want to confuse this with GPS lock. [340ae29] commander: make position invalid fail-safe more sticky Require check to pass for 7 seconds before exiting failsafe. This is required because if GPs is failing innovation tests for a prolonged period, the EKF will periodically reset to the GPS and report good accuracy at the time of reset. Adding this delay gives time for an underlying error condition (eg bad IMU or compass) to be re-detected. [b04ac95] commander: Increase RAM allocation to eliminate low stack warnings [9dca12f] commander: add missing position invalid fail-safe responses [69f264d] commander: Update position invalid fail-safe responses Replace separate logic for each case with a generic function Add velocity checks. [8e8cef1] commander: rework position validity checks Consolidate existing checks for global and local position validity and add checking of velocity accuracy. Enable checks to be bypassed using the CBRK_VELPOSERR parameter.
2017-03-08 11:03:27 +11:00
status->nav_state = vehicle_status_s::NAVIGATION_STATE_AUTO_LAND;
} else if (status_flags.condition_local_altitude_valid) {
if (status->vehicle_type == vehicle_status_s::VEHICLE_TYPE_ROTARY_WING) {
status->nav_state = vehicle_status_s::NAVIGATION_STATE_DESCEND;
} else {
// TODO: FW position controller doesn't run without condition_global_position_valid
status->nav_state = vehicle_status_s::NAVIGATION_STATE_AUTO_LANDGPSFAIL;
}
commander: rework posvel validity checks Move into functions. Reset probation time and recalculate checks if a mode change is demanded to give the operator ability to regain control as soon as possible after nav performance is regained. (+11 squashed commits) Squashed commits: [a4bb800] commander: enable pilot to quickly recover from loss of position accuracy [19e16a0] commander: rework postal probation time [f96284e] commander: rework bad pos and vel test probation time [00d5f0c] commander: Allow EKF preflight checks to pass with moving vehicle Separates the 'is using GPS' and the GPS quality checks. Uses a reasonable subset of the GPS quality checks which allows checks to pass if the vehicle is moving. [4cdfb5c] commander: remove unused variable [349385a] commander: add EKF GPS quality checks to pre-arm checking Only perform check if GPs checking is activated by parameter setting. Display fault messages that makes it clear if EKF quality checks are failing or the EKF is not using GPS for another reason. We do not want to confuse this with GPS lock. [340ae29] commander: make position invalid fail-safe more sticky Require check to pass for 7 seconds before exiting failsafe. This is required because if GPs is failing innovation tests for a prolonged period, the EKF will periodically reset to the GPS and report good accuracy at the time of reset. Adding this delay gives time for an underlying error condition (eg bad IMU or compass) to be re-detected. [b04ac95] commander: Increase RAM allocation to eliminate low stack warnings [9dca12f] commander: add missing position invalid fail-safe responses [69f264d] commander: Update position invalid fail-safe responses Replace separate logic for each case with a generic function Add velocity checks. [8e8cef1] commander: rework position validity checks Consolidate existing checks for global and local position validity and add checking of velocity accuracy. Enable checks to be bypassed using the CBRK_VELPOSERR parameter.
2017-03-08 11:03:27 +11:00
} else {
status->nav_state = vehicle_status_s::NAVIGATION_STATE_TERMINATION;
}
}
if (using_global_pos) {
enable_failsafe(status, old_failsafe, mavlink_log_pub, reason_no_global_position);
commander: rework posvel validity checks Move into functions. Reset probation time and recalculate checks if a mode change is demanded to give the operator ability to regain control as soon as possible after nav performance is regained. (+11 squashed commits) Squashed commits: [a4bb800] commander: enable pilot to quickly recover from loss of position accuracy [19e16a0] commander: rework postal probation time [f96284e] commander: rework bad pos and vel test probation time [00d5f0c] commander: Allow EKF preflight checks to pass with moving vehicle Separates the 'is using GPS' and the GPS quality checks. Uses a reasonable subset of the GPS quality checks which allows checks to pass if the vehicle is moving. [4cdfb5c] commander: remove unused variable [349385a] commander: add EKF GPS quality checks to pre-arm checking Only perform check if GPs checking is activated by parameter setting. Display fault messages that makes it clear if EKF quality checks are failing or the EKF is not using GPS for another reason. We do not want to confuse this with GPS lock. [340ae29] commander: make position invalid fail-safe more sticky Require check to pass for 7 seconds before exiting failsafe. This is required because if GPs is failing innovation tests for a prolonged period, the EKF will periodically reset to the GPS and report good accuracy at the time of reset. Adding this delay gives time for an underlying error condition (eg bad IMU or compass) to be re-detected. [b04ac95] commander: Increase RAM allocation to eliminate low stack warnings [9dca12f] commander: add missing position invalid fail-safe responses [69f264d] commander: Update position invalid fail-safe responses Replace separate logic for each case with a generic function Add velocity checks. [8e8cef1] commander: rework position validity checks Consolidate existing checks for global and local position validity and add checking of velocity accuracy. Enable checks to be bypassed using the CBRK_VELPOSERR parameter.
2017-03-08 11:03:27 +11:00
} else {
enable_failsafe(status, old_failsafe, mavlink_log_pub, reason_no_local_position);
}
}
return fallback_required;
}
void set_link_loss_nav_state(vehicle_status_s *status, actuator_armed_s *armed,
const vehicle_status_flags_s &status_flags, commander_state_s *internal_state, const link_loss_actions_t link_loss_act,
uint8_t auto_recovery_nav_state)
{
// do the best you can according to the action set
switch (link_loss_act) {
case link_loss_actions_t::DISABLED:
// If datalink loss failsafe is disabled then no action must be taken.
break;
case link_loss_actions_t::AUTO_RECOVER:
if (status_flags.condition_global_position_valid && status_flags.condition_home_position_valid) {
status->nav_state = auto_recovery_nav_state;
return;
}
// FALLTHROUGH
case link_loss_actions_t::AUTO_RTL:
if (status_flags.condition_global_position_valid && status_flags.condition_home_position_valid) {
main_state_transition(*status, commander_state_s::MAIN_STATE_AUTO_RTL, status_flags, internal_state);
status->nav_state = vehicle_status_s::NAVIGATION_STATE_AUTO_RTL;
return;
}
// FALLTHROUGH
case link_loss_actions_t::AUTO_LOITER:
if (status_flags.condition_global_position_valid) {
status->nav_state = vehicle_status_s::NAVIGATION_STATE_AUTO_LOITER;
return;
}
// FALLTHROUGH
case link_loss_actions_t::AUTO_LAND:
if (status_flags.condition_global_position_valid) {
status->nav_state = vehicle_status_s::NAVIGATION_STATE_AUTO_LAND;
return;
} else {
if (status->vehicle_type == vehicle_status_s::VEHICLE_TYPE_ROTARY_WING) {
if (status_flags.condition_local_position_valid) {
status->nav_state = vehicle_status_s::NAVIGATION_STATE_AUTO_LAND;
return;
} else if (status_flags.condition_local_altitude_valid) {
status->nav_state = vehicle_status_s::NAVIGATION_STATE_DESCEND;
return;
}
} else {
// TODO: FW position controller doesn't run without condition_global_position_valid
status->nav_state = vehicle_status_s::NAVIGATION_STATE_AUTO_LANDGPSFAIL;
return;
}
}
// FALLTHROUGH
case link_loss_actions_t::TERMINATE:
status->nav_state = vehicle_status_s::NAVIGATION_STATE_TERMINATION;
armed->force_failsafe = true;
break;
case link_loss_actions_t::LOCKDOWN:
armed->lockdown = true;
break;
}
}
void reset_link_loss_globals(actuator_armed_s *armed, const bool old_failsafe, const link_loss_actions_t link_loss_act)
{
if (old_failsafe) {
if (link_loss_act == link_loss_actions_t::TERMINATE) {
armed->force_failsafe = false;
} else if (link_loss_act == link_loss_actions_t::LOCKDOWN) {
armed->lockdown = false;
}
}
}
void set_offboard_loss_nav_state(vehicle_status_s *status, actuator_armed_s *armed,
const vehicle_status_flags_s &status_flags,
const offboard_loss_actions_t offboard_loss_act)
{
switch (offboard_loss_act) {
case offboard_loss_actions_t::DISABLED:
// If offboard loss failsafe is disabled then no action must be taken.
return;
case offboard_loss_actions_t::TERMINATE:
status->nav_state = vehicle_status_s::NAVIGATION_STATE_TERMINATION;
armed->force_failsafe = true;
return;
case offboard_loss_actions_t::LOCKDOWN:
armed->lockdown = true;
return;
case offboard_loss_actions_t::AUTO_RTL:
if (status_flags.condition_global_position_valid && status_flags.condition_home_position_valid) {
status->nav_state = vehicle_status_s::NAVIGATION_STATE_AUTO_RTL;
return;
}
// FALLTHROUGH
case offboard_loss_actions_t::AUTO_LOITER:
if (status_flags.condition_global_position_valid) {
status->nav_state = vehicle_status_s::NAVIGATION_STATE_AUTO_LOITER;
return;
}
// FALLTHROUGH
case offboard_loss_actions_t::AUTO_LAND:
if (status_flags.condition_global_position_valid) {
status->nav_state = vehicle_status_s::NAVIGATION_STATE_AUTO_LAND;
return;
}
}
// If none of the above worked, try to mitigate
if (status_flags.condition_local_altitude_valid) {
if (status->vehicle_type == vehicle_status_s::VEHICLE_TYPE_ROTARY_WING) {
status->nav_state = vehicle_status_s::NAVIGATION_STATE_DESCEND;
} else {
// TODO: FW position controller doesn't run without condition_global_position_valid
status->nav_state = vehicle_status_s::NAVIGATION_STATE_AUTO_LANDGPSFAIL;
}
} else {
status->nav_state = vehicle_status_s::NAVIGATION_STATE_TERMINATION;
}
}
void set_offboard_loss_rc_nav_state(vehicle_status_s *status, actuator_armed_s *armed,
const vehicle_status_flags_s &status_flags,
const offboard_loss_rc_actions_t offboard_loss_rc_act)
{
switch (offboard_loss_rc_act) {
case offboard_loss_rc_actions_t::DISABLED:
// If offboard loss failsafe is disabled then no action must be taken.
return;
case offboard_loss_rc_actions_t::TERMINATE:
status->nav_state = vehicle_status_s::NAVIGATION_STATE_TERMINATION;
armed->force_failsafe = true;
return;
case offboard_loss_rc_actions_t::LOCKDOWN:
armed->lockdown = true;
return;
case offboard_loss_rc_actions_t::MANUAL_POSITION:
if (status_flags.condition_global_position_valid) {
status->nav_state = vehicle_status_s::NAVIGATION_STATE_POSCTL;
return;
}
// FALLTHROUGH
case offboard_loss_rc_actions_t::MANUAL_ALTITUDE:
if (status_flags.condition_local_altitude_valid) {
status->nav_state = vehicle_status_s::NAVIGATION_STATE_ALTCTL;
return;
}
// FALLTHROUGH
case offboard_loss_rc_actions_t::MANUAL_ATTITUDE:
status->nav_state = vehicle_status_s::NAVIGATION_STATE_MANUAL;
return;
case offboard_loss_rc_actions_t::AUTO_RTL:
if (status_flags.condition_global_position_valid && status_flags.condition_home_position_valid) {
status->nav_state = vehicle_status_s::NAVIGATION_STATE_AUTO_RTL;
return;
}
// FALLTHROUGH
case offboard_loss_rc_actions_t::AUTO_LOITER:
if (status_flags.condition_global_position_valid) {
status->nav_state = vehicle_status_s::NAVIGATION_STATE_AUTO_LOITER;
return;
}
// FALLTHROUGH
case offboard_loss_rc_actions_t::AUTO_LAND:
if (status_flags.condition_global_position_valid) {
status->nav_state = vehicle_status_s::NAVIGATION_STATE_AUTO_LAND;
return;
}
}
// If none of the above worked, try to mitigate
if (status_flags.condition_local_altitude_valid) {
//TODO: Add case for rover
if (status->vehicle_type == vehicle_status_s::VEHICLE_TYPE_ROTARY_WING) {
status->nav_state = vehicle_status_s::NAVIGATION_STATE_DESCEND;
} else {
// TODO: FW position controller doesn't run without condition_global_position_valid
status->nav_state = vehicle_status_s::NAVIGATION_STATE_AUTO_LANDGPSFAIL;
}
} else {
status->nav_state = vehicle_status_s::NAVIGATION_STATE_TERMINATION;
}
}
void reset_offboard_loss_globals(actuator_armed_s *armed, const bool old_failsafe,
const offboard_loss_actions_t offboard_loss_act,
const offboard_loss_rc_actions_t offboard_loss_rc_act)
{
if (old_failsafe) {
if (offboard_loss_act == offboard_loss_actions_t::TERMINATE
|| offboard_loss_rc_act == offboard_loss_rc_actions_t::TERMINATE) {
armed->force_failsafe = false;
}
if (offboard_loss_act == offboard_loss_actions_t::LOCKDOWN
|| offboard_loss_rc_act == offboard_loss_rc_actions_t::LOCKDOWN) {
armed->lockdown = false;
}
}
}
bool prearm_check(orb_advert_t *mavlink_log_pub, const vehicle_status_flags_s &status_flags, const safety_s &safety,
const uint8_t arm_requirements)
{
bool reportFailures = true;
bool prearm_ok = true;
// USB not connected
if (!status_flags.circuit_breaker_engaged_usb_check && status_flags.usb_connected) {
2015-11-19 17:48:39 +01:00
if (reportFailures) {
mavlink_log_critical(mavlink_log_pub, "Arming denied! Flying with USB is not safe");
2016-04-10 10:57:38 -07:00
}
prearm_ok = false;
2016-04-10 10:57:38 -07:00
}
// battery and system power status
if (!status_flags.circuit_breaker_engaged_power_check) {
2016-08-04 11:09:09 +02:00
// Fail transition if power is not good
if (!status_flags.condition_power_input_valid) {
if (reportFailures) {
mavlink_log_critical(mavlink_log_pub, "Arming denied! Connect power module");
}
prearm_ok = false;
}
// main battery level
if (!status_flags.condition_battery_healthy) {
if (prearm_ok && reportFailures) {
mavlink_log_critical(mavlink_log_pub, "Arming denied! Check battery");
}
prearm_ok = false;
2015-11-19 17:48:39 +01:00
}
}
// Arm Requirements: mission
2018-03-29 23:18:53 -04:00
if (arm_requirements & ARM_REQ_MISSION_BIT) {
if (!status_flags.condition_auto_mission_available) {
if (prearm_ok && reportFailures) {
mavlink_log_critical(mavlink_log_pub, "Arming denied! No valid mission");
}
prearm_ok = false;
}
if (!status_flags.condition_global_position_valid) {
if (prearm_ok && reportFailures) {
mavlink_log_critical(mavlink_log_pub, "Arming denied! Missions require a global position");
}
prearm_ok = false;
}
}
// Arm Requirements: global position
2018-03-29 23:18:53 -04:00
if (arm_requirements & ARM_REQ_GPS_BIT) {
2018-03-29 23:18:53 -04:00
if (!status_flags.condition_global_position_valid) {
if (prearm_ok && reportFailures) {
mavlink_log_critical(mavlink_log_pub, "Arming denied! Global position required");
2018-03-29 23:18:53 -04:00
}
prearm_ok = false;
}
}
2018-03-29 23:18:53 -04:00
// safety button
if (safety.safety_switch_available && !safety.safety_off) {
2018-03-29 23:14:34 -04:00
// Fail transition if we need safety switch press
if (prearm_ok && reportFailures) {
mavlink_log_critical(mavlink_log_pub, "Arming denied! Press safety switch first");
2018-03-29 23:14:34 -04:00
}
prearm_ok = false;
2018-03-29 23:14:34 -04:00
}
if (status_flags.avoidance_system_required && !status_flags.avoidance_system_valid) {
if (prearm_ok && reportFailures) {
mavlink_log_critical(mavlink_log_pub, "Arming denied! Avoidance system not ready");
}
prearm_ok = false;
}
if (status_flags.condition_escs_error && (arm_requirements & ARM_REQ_ESCS_CHECK_BIT)) {
if (prearm_ok && reportFailures) {
mavlink_log_critical(mavlink_log_pub, "Arming denied! One or more ESCs are offline");
prearm_ok = false;
}
}
// Arm Requirements: authorization
// check last, and only if everything else has passed
if ((arm_requirements & ARM_REQ_ARM_AUTH_BIT) && prearm_ok) {
if (arm_auth_check() != vehicle_command_ack_s::VEHICLE_RESULT_ACCEPTED) {
// feedback provided in arm_auth_check
prearm_ok = false;
}
}
return prearm_ok;
}
void battery_failsafe(orb_advert_t *mavlink_log_pub, const vehicle_status_s &status,
const vehicle_status_flags_s &status_flags, commander_state_s *internal_state, const uint8_t battery_warning,
const low_battery_action_t low_battery_action)
{
switch (battery_warning) {
case battery_status_s::BATTERY_WARNING_NONE:
break;
case battery_status_s::BATTERY_WARNING_LOW:
mavlink_log_critical(mavlink_log_pub, "Low battery level! Return advised");
break;
case battery_status_s::BATTERY_WARNING_CRITICAL:
static constexpr char battery_critical[] = "Critical battery level!";
switch (low_battery_action) {
case LOW_BAT_ACTION::WARNING:
mavlink_log_critical(mavlink_log_pub, "%s, Landing advised", battery_critical);
break;
case LOW_BAT_ACTION::RETURN:
2018-11-28 17:11:15 -05:00
// FALLTHROUGH
case LOW_BAT_ACTION::RETURN_OR_LAND:
// let us send the critical message even if already in RTL
2018-11-28 17:11:15 -05:00
if (TRANSITION_DENIED != main_state_transition(status, commander_state_s::MAIN_STATE_AUTO_RTL, status_flags,
internal_state)) {
mavlink_log_critical(mavlink_log_pub, "%s, Executing RTL", battery_critical);
} else {
mavlink_log_emergency(mavlink_log_pub, "%s, Can't execute RTL", battery_critical);
}
break;
case LOW_BAT_ACTION::LAND:
2018-11-28 17:11:15 -05:00
if (TRANSITION_DENIED != main_state_transition(status, commander_state_s::MAIN_STATE_AUTO_LAND, status_flags,
internal_state)) {
mavlink_log_critical(mavlink_log_pub, "%s, Landing immediately", battery_critical);
} else {
mavlink_log_emergency(mavlink_log_pub, "%s, Can't execute landing", battery_critical);
}
break;
}
break;
case battery_status_s::BATTERY_WARNING_EMERGENCY:
static constexpr char battery_dangerous[] = "Dangerous battery level!";
switch (low_battery_action) {
case LOW_BAT_ACTION::WARNING:
mavlink_log_emergency(mavlink_log_pub, "%s, Please land!", battery_dangerous);
break;
case LOW_BAT_ACTION::RETURN:
2018-11-28 17:11:15 -05:00
if (TRANSITION_DENIED != main_state_transition(status, commander_state_s::MAIN_STATE_AUTO_RTL, status_flags,
internal_state)) {
mavlink_log_emergency(mavlink_log_pub, "%s, Executing RTL", battery_dangerous);
} else {
mavlink_log_emergency(mavlink_log_pub, "%s, Can't execute RTL", battery_dangerous);
}
break;
case LOW_BAT_ACTION::RETURN_OR_LAND:
2018-11-28 17:11:15 -05:00
// FALLTHROUGH
case LOW_BAT_ACTION::LAND:
2018-11-28 17:11:15 -05:00
if (TRANSITION_DENIED != main_state_transition(status, commander_state_s::MAIN_STATE_AUTO_LAND, status_flags,
internal_state)) {
mavlink_log_emergency(mavlink_log_pub, "%s, Landing immediately", battery_dangerous);
} else {
mavlink_log_emergency(mavlink_log_pub, "%s, Can't execute landing", battery_dangerous);
}
break;
}
break;
case battery_status_s::BATTERY_WARNING_FAILED:
mavlink_log_emergency(mavlink_log_pub, "Battery failure detected");
break;
}
}