2012-08-04 15:12:36 -07:00
|
|
|
/****************************************************************************
|
|
|
|
|
*
|
2015-02-28 04:01:10 +01:00
|
|
|
* Copyright (c) 2013-2015 PX4 Development Team. All rights reserved.
|
2012-08-04 15:12:36 -07:00
|
|
|
*
|
|
|
|
|
* 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.
|
|
|
|
|
*
|
|
|
|
|
****************************************************************************/
|
|
|
|
|
|
2012-08-06 23:43:09 +02:00
|
|
|
/**
|
2013-07-20 13:47:51 +02:00
|
|
|
* @file state_machine_helper.cpp
|
2012-08-06 23:43:09 +02:00
|
|
|
* State machine helper functions implementations
|
2014-05-27 21:56:32 +02:00
|
|
|
*
|
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>
|
2012-08-06 23:43:09 +02:00
|
|
|
*/
|
2016-05-28 14:56:17 +02:00
|
|
|
#include <px4_config.h>
|
2017-05-08 18:33:58 -07:00
|
|
|
#include <uORB/topics/vehicle_command.h>
|
|
|
|
|
#include <uORB/topics/vehicle_command_ack.h>
|
2012-08-04 15:12:36 -07:00
|
|
|
#include <uORB/topics/vehicle_status.h>
|
2016-03-15 18:25:02 +00:00
|
|
|
#include <systemlib/mavlink_log.h>
|
2012-10-23 18:02:36 -07:00
|
|
|
#include <drivers/drv_hrt.h>
|
2012-08-04 15:12:36 -07:00
|
|
|
|
2012-08-27 22:57:20 +02:00
|
|
|
#include "state_machine_helper.h"
|
2013-06-25 16:30:35 +02:00
|
|
|
#include "commander_helper.h"
|
2015-04-19 23:07:32 +02:00
|
|
|
#include "PreflightCheck.h"
|
2017-05-08 18:33:58 -07:00
|
|
|
#include "arm_auth.h"
|
2017-04-17 00:18:39 -04:00
|
|
|
|
2018-03-27 15:55:42 -04:00
|
|
|
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";
|
2016-10-12 01:51:09 -04:00
|
|
|
|
2014-03-26 14:51:57 -07:00
|
|
|
// 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
|
2014-03-26 14:51:57 -07:00
|
|
|
// 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.
|
2018-03-27 16:45:31 -04:00
|
|
|
static constexpr const bool arming_transitions[vehicle_status_s::ARMING_STATE_MAX][vehicle_status_s::ARMING_STATE_MAX]
|
|
|
|
|
= {
|
2018-03-27 16:04:17 -04:00
|
|
|
// INIT, STANDBY, ARMED, STANDBY_ERROR, REBOOT, 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_REBOOT */ true, true, false, true, true, true },
|
|
|
|
|
{ /* vehicle_status_s::ARMING_STATE_IN_AIR_RESTORE */ false, false, false, false, false, false }, // NYI
|
2014-03-26 14:51:57 -07:00
|
|
|
};
|
|
|
|
|
|
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
|
2018-03-29 20:14:20 -04:00
|
|
|
const char * const arming_state_names[vehicle_status_s::ARMING_STATE_MAX] = {
|
|
|
|
|
"INIT",
|
|
|
|
|
"STANDBY",
|
|
|
|
|
"ARMED",
|
|
|
|
|
"STANDBY_ERROR",
|
|
|
|
|
"REBOOT",
|
|
|
|
|
"IN_AIR_RESTORE",
|
2014-03-26 14:51:57 -07:00
|
|
|
};
|
|
|
|
|
|
2016-01-22 11:31:39 +01:00
|
|
|
static hrt_abstime last_preflight_check = 0; ///< initialize so it gets checked immediately
|
|
|
|
|
|
2018-03-27 16:45:31 -04:00
|
|
|
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,
|
2017-02-07 23:37:03 -05:00
|
|
|
uint8_t auto_recovery_nav_state);
|
2016-12-15 10:38:59 -08:00
|
|
|
|
2018-03-27 15:49:52 -04:00
|
|
|
void reset_link_loss_globals(actuator_armed_s *armed, const bool old_failsafe, const link_loss_actions_t link_loss_act);
|
2016-12-15 10:38:59 -08:00
|
|
|
|
2018-03-27 16:45:31 -04:00
|
|
|
transition_result_t arming_state_transition(vehicle_status_s *status, const battery_status_s &battery,
|
|
|
|
|
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 float avionics_power_rail_voltage,
|
|
|
|
|
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,
|
2017-02-07 23:37:03 -05:00
|
|
|
"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;
|
2014-06-26 12:11:39 +02:00
|
|
|
arming_state_t current_arming_state = status->arming_state;
|
2014-07-20 16:06:31 +02:00
|
|
|
bool feedback_provided = false;
|
2014-06-26 12:11:39 +02:00
|
|
|
|
2018-03-27 16:15:29 -04:00
|
|
|
const bool hil_enabled = (status->hil_state == vehicle_status_s::HIL_STATE_ON);
|
|
|
|
|
|
2013-02-21 18:10:34 -08:00
|
|
|
/* only check transition if the new state is actually different from the current one */
|
2014-06-26 12:11:39 +02:00
|
|
|
if (new_arming_state == current_arming_state) {
|
2013-07-28 23:12:16 +04:00
|
|
|
ret = TRANSITION_NOT_CHANGED;
|
|
|
|
|
|
2013-02-22 15:52:13 -08:00
|
|
|
} else {
|
2014-06-26 12:11:39 +02:00
|
|
|
|
|
|
|
|
/*
|
|
|
|
|
* Get sensing state if necessary
|
|
|
|
|
*/
|
2018-03-29 23:14:34 -04:00
|
|
|
bool preflight_check_ret = false;
|
|
|
|
|
bool prearm_check_ret = false;
|
2018-03-29 23:14:34 -04:00
|
|
|
|
2017-12-31 16:11:13 +01:00
|
|
|
bool checkAirspeed = false;
|
2018-03-27 16:15:29 -04:00
|
|
|
bool sensor_checks = !hil_enabled;
|
2017-12-31 16:11:13 +01:00
|
|
|
|
|
|
|
|
/* Perform airspeed check only if circuit breaker is not
|
|
|
|
|
* engaged and it's not a rotary wing */
|
|
|
|
|
if (!status_flags->circuit_breaker_engaged_airspd_check && (!status->is_rotary_wing || status->is_vtol)) {
|
|
|
|
|
checkAirspeed = true;
|
|
|
|
|
}
|
2014-06-26 12:11:39 +02:00
|
|
|
|
2015-11-10 19:33:14 +05:30
|
|
|
/* only perform the pre-arm check if we have to */
|
2015-06-06 07:56:48 -06:00
|
|
|
if (fRunPreArmChecks && new_arming_state == vehicle_status_s::ARMING_STATE_ARMED
|
2018-03-27 16:15:29 -04:00
|
|
|
&& !hil_enabled) {
|
2015-11-19 17:48:39 +01:00
|
|
|
|
2018-03-29 23:14:34 -04:00
|
|
|
preflight_check_ret = Preflight::preflightCheck(mavlink_log_pub, sensor_checks, checkAirspeed,
|
|
|
|
|
(status->rc_input_mode == vehicle_status_s::RC_IN_MODE_DEFAULT), arm_requirements & ARM_REQ_GPS_BIT, true,
|
|
|
|
|
status->is_vtol, true, true, time_since_boot);
|
2017-12-31 16:11:13 +01:00
|
|
|
|
2018-03-29 23:14:34 -04:00
|
|
|
if (preflight_check_ret) {
|
|
|
|
|
status_flags->condition_system_sensors_initialized = true;
|
2017-12-31 16:11:13 +01:00
|
|
|
|
2018-03-29 23:14:34 -04:00
|
|
|
// only both with prearm_check if preflight has passed
|
|
|
|
|
prearm_check_ret = prearm_check(mavlink_log_pub, *status_flags, battery, arm_requirements, time_since_boot);
|
2017-12-31 16:11:13 +01:00
|
|
|
}
|
|
|
|
|
|
2018-03-29 23:14:34 -04:00
|
|
|
feedback_provided = true;
|
2015-11-10 19:33:14 +05:30
|
|
|
}
|
2016-04-24 13:26:27 -04:00
|
|
|
|
2015-11-10 19:33:14 +05:30
|
|
|
/* re-run the pre-flight check as long as sensors are failing */
|
2016-02-25 17:00:39 +00:00
|
|
|
if (!status_flags->condition_system_sensors_initialized
|
2016-08-04 11:09:09 +02:00
|
|
|
&& (new_arming_state == vehicle_status_s::ARMING_STATE_ARMED
|
|
|
|
|
|| new_arming_state == vehicle_status_s::ARMING_STATE_STANDBY)
|
2018-03-27 16:15:29 -04:00
|
|
|
&& !hil_enabled) {
|
2015-11-19 17:48:39 +01:00
|
|
|
|
2016-01-22 11:31:39 +01:00
|
|
|
if (last_preflight_check == 0 || hrt_absolute_time() - last_preflight_check > 1000 * 1000) {
|
2017-12-31 16:11:13 +01:00
|
|
|
|
2018-03-29 23:14:34 -04:00
|
|
|
status_flags->condition_system_sensors_initialized = Preflight::preflightCheck(mavlink_log_pub, sensor_checks,
|
|
|
|
|
checkAirspeed,
|
|
|
|
|
(status->rc_input_mode == vehicle_status_s::RC_IN_MODE_DEFAULT), arm_requirements & ARM_REQ_GPS_BIT, true,
|
|
|
|
|
status->is_vtol, false, false, time_since_boot);
|
2017-12-31 16:11:13 +01:00
|
|
|
|
2016-01-22 11:31:39 +01:00
|
|
|
last_preflight_check = hrt_absolute_time();
|
|
|
|
|
}
|
2014-06-26 12:11:39 +02:00
|
|
|
}
|
|
|
|
|
|
|
|
|
|
/*
|
|
|
|
|
* Perform an atomic state update
|
|
|
|
|
*/
|
2016-08-04 11:09:09 +02:00
|
|
|
#ifdef __PX4_NUTTX
|
2016-05-28 14:56:17 +02:00
|
|
|
irqstate_t flags = px4_enter_critical_section();
|
2016-08-04 11:09:09 +02:00
|
|
|
#endif
|
2014-06-26 12:11:39 +02:00
|
|
|
|
2013-10-06 14:18:28 +02:00
|
|
|
/* enforce lockdown in HIL */
|
2018-03-27 16:15:29 -04:00
|
|
|
if (hil_enabled) {
|
2013-10-06 14:18:28 +02:00
|
|
|
armed->lockdown = true;
|
2018-03-29 23:14:34 -04:00
|
|
|
preflight_check_ret = true;
|
2018-03-29 23:14:34 -04:00
|
|
|
prearm_check_ret = true;
|
2016-02-25 17:00:39 +00:00
|
|
|
status_flags->condition_system_sensors_initialized = true;
|
2014-01-26 11:52:33 +01:00
|
|
|
|
2015-04-26 18:27:48 +02:00
|
|
|
/* 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;
|
|
|
|
|
}
|
2014-01-26 11:52:33 +01:00
|
|
|
|
2013-10-06 14:18:28 +02:00
|
|
|
} else {
|
|
|
|
|
armed->lockdown = false;
|
|
|
|
|
}
|
|
|
|
|
|
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.
|
2015-01-28 07:58:42 +01:00
|
|
|
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
|
2015-01-28 07:58:42 +01:00
|
|
|
// Allow if vehicle_status_s::HIL_STATE_ON
|
|
|
|
|
if (status->arming_state != vehicle_status_s::ARMING_STATE_IN_AIR_RESTORE &&
|
2018-03-27 16:15:29 -04:00
|
|
|
!hil_enabled) {
|
2014-06-24 21:33:03 +02:00
|
|
|
|
2014-06-26 12:11:39 +02:00
|
|
|
// Fail transition if pre-arm check fails
|
2018-03-29 23:14:34 -04:00
|
|
|
if (!(preflight_check_ret && prearm_check_ret)) {
|
2014-07-20 16:06:31 +02:00
|
|
|
/* the prearm check already prints the reject reason */
|
|
|
|
|
feedback_provided = true;
|
2014-06-26 12:11:39 +02:00
|
|
|
valid_transition = false;
|
|
|
|
|
|
2018-03-27 16:27:47 -04:00
|
|
|
} else if (safety.safety_switch_available && !safety.safety_off) {
|
2018-03-29 23:14:34 -04:00
|
|
|
// Fail transition if we need safety switch press
|
2013-03-25 14:53:54 -07:00
|
|
|
|
2016-09-20 12:56:08 +02:00
|
|
|
mavlink_log_critical(mavlink_log_pub, "NOT ARMING: Press safety switch first!");
|
2014-07-20 16:06:31 +02:00
|
|
|
feedback_provided = true;
|
2014-06-24 21:33:03 +02:00
|
|
|
valid_transition = false;
|
|
|
|
|
}
|
2014-05-25 08:22:54 +02:00
|
|
|
|
2014-06-30 16:24:48 +02:00
|
|
|
// Perform power checks only if circuit breaker is not
|
|
|
|
|
// engaged for these checks
|
2016-02-25 17:00:39 +00:00
|
|
|
if (!status_flags->circuit_breaker_engaged_power_check) {
|
2014-06-30 16:24:48 +02:00
|
|
|
// Fail transition if power is not good
|
2016-02-25 17:00:39 +00:00
|
|
|
if (!status_flags->condition_power_input_valid) {
|
2014-05-25 08:22:54 +02:00
|
|
|
|
2016-09-20 12:56:08 +02:00
|
|
|
mavlink_log_critical(mavlink_log_pub, "NOT ARMING: Connect power module.");
|
2014-07-20 16:06:31 +02:00
|
|
|
feedback_provided = true;
|
2014-06-30 16:24:48 +02:00
|
|
|
valid_transition = false;
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
// Fail transition if power levels on the avionics rail
|
|
|
|
|
// are measured but are insufficient
|
2016-02-26 11:01:12 +00:00
|
|
|
if (status_flags->condition_power_input_valid && (avionics_power_rail_voltage > 0.0f)) {
|
2014-08-24 13:32:46 +02:00
|
|
|
// Check avionics rail voltages
|
2016-02-26 11:01:12 +00:00
|
|
|
if (avionics_power_rail_voltage < 4.5f) {
|
2016-09-20 12:56:08 +02:00
|
|
|
mavlink_log_critical(mavlink_log_pub, "NOT ARMING: Avionics power low: %6.2f Volt",
|
2017-02-07 23:37:03 -05:00
|
|
|
(double)avionics_power_rail_voltage);
|
2014-08-24 13:32:46 +02:00
|
|
|
feedback_provided = true;
|
|
|
|
|
valid_transition = false;
|
2016-08-04 11:09:09 +02:00
|
|
|
|
2016-02-26 11:01:12 +00:00
|
|
|
} else if (avionics_power_rail_voltage < 4.9f) {
|
2017-02-07 23:37:03 -05:00
|
|
|
mavlink_log_critical(mavlink_log_pub, "CAUTION: Avionics power low: %6.2f Volt", (double)avionics_power_rail_voltage);
|
2014-08-24 13:32:46 +02:00
|
|
|
feedback_provided = true;
|
2016-08-04 11:09:09 +02:00
|
|
|
|
2016-02-26 11:01:12 +00:00
|
|
|
} else if (avionics_power_rail_voltage > 5.4f) {
|
2017-02-07 23:37:03 -05:00
|
|
|
mavlink_log_critical(mavlink_log_pub, "CAUTION: Avionics power high: %6.2f Volt", (double)avionics_power_rail_voltage);
|
2014-08-24 13:32:46 +02:00
|
|
|
feedback_provided = true;
|
|
|
|
|
}
|
2014-06-30 16:24:48 +02:00
|
|
|
}
|
2014-05-11 13:36:51 +02:00
|
|
|
}
|
2013-03-25 14:53:54 -07:00
|
|
|
}
|
2013-07-28 23:12:16 +04:00
|
|
|
}
|
2014-05-11 13:36:51 +02:00
|
|
|
}
|
2013-07-28 23:12:16 +04:00
|
|
|
|
2014-05-11 13:36:51 +02:00
|
|
|
// HIL can always go to standby
|
2018-03-27 16:15:29 -04:00
|
|
|
if (hil_enabled && new_arming_state == vehicle_status_s::ARMING_STATE_STANDBY) {
|
2014-05-11 13:36:51 +02:00
|
|
|
valid_transition = true;
|
|
|
|
|
}
|
2013-07-28 23:12:16 +04:00
|
|
|
|
2015-04-26 12:04:16 +02:00
|
|
|
// Check if we are trying to arm, checks look good but we are in STANDBY_ERROR
|
|
|
|
|
if (status->arming_state == vehicle_status_s::ARMING_STATE_STANDBY_ERROR) {
|
|
|
|
|
|
|
|
|
|
if (new_arming_state == vehicle_status_s::ARMING_STATE_ARMED) {
|
|
|
|
|
|
2016-02-25 17:00:39 +00:00
|
|
|
if (status_flags->condition_system_sensors_initialized) {
|
2016-09-20 12:56:08 +02:00
|
|
|
mavlink_log_critical(mavlink_log_pub, "Preflight check resolved, reboot before arming");
|
2016-08-04 11:09:09 +02:00
|
|
|
|
2015-04-26 12:04:16 +02:00
|
|
|
} else {
|
2016-09-20 12:56:08 +02:00
|
|
|
mavlink_log_critical(mavlink_log_pub, "Preflight check failed, refusing to arm");
|
2015-04-26 12:04:16 +02:00
|
|
|
}
|
2016-08-04 11:09:09 +02:00
|
|
|
|
2015-04-26 12:04:16 +02:00
|
|
|
feedback_provided = true;
|
|
|
|
|
|
|
|
|
|
} else if ((new_arming_state == vehicle_status_s::ARMING_STATE_STANDBY) &&
|
2016-08-04 11:09:09 +02:00
|
|
|
status_flags->condition_system_sensors_initialized) {
|
2016-09-20 12:56:08 +02:00
|
|
|
mavlink_log_critical(mavlink_log_pub, "Preflight check resolved, reboot to complete");
|
2015-04-26 12:04:16 +02:00
|
|
|
feedback_provided = true;
|
2016-08-04 11:09:09 +02:00
|
|
|
|
2015-04-20 09:13:31 +02:00
|
|
|
} else {
|
2015-05-21 17:25:37 +02:00
|
|
|
// Silent ignore
|
|
|
|
|
feedback_provided = true;
|
|
|
|
|
}
|
2015-04-26 17:39:00 +02:00
|
|
|
|
2016-08-04 11:09:09 +02:00
|
|
|
// Sensors need to be initialized for STANDBY state, except for HIL
|
|
|
|
|
|
2018-03-27 16:15:29 -04:00
|
|
|
} else if (!hil_enabled &&
|
2016-08-04 11:09:09 +02:00
|
|
|
(new_arming_state == vehicle_status_s::ARMING_STATE_STANDBY) &&
|
|
|
|
|
(status->arming_state != vehicle_status_s::ARMING_STATE_STANDBY_ERROR)) {
|
2016-07-12 13:41:09 +02:00
|
|
|
|
|
|
|
|
if (!status_flags->condition_system_sensors_initialized) {
|
|
|
|
|
feedback_provided = true;
|
|
|
|
|
valid_transition = false;
|
2015-09-23 18:36:29 +02:00
|
|
|
}
|
2015-04-19 23:15:51 +02:00
|
|
|
}
|
|
|
|
|
|
2014-05-11 13:36:51 +02:00
|
|
|
// Finish up the state transition
|
|
|
|
|
if (valid_transition) {
|
2018-03-27 16:04:17 -04:00
|
|
|
armed->armed = (new_arming_state == vehicle_status_s::ARMING_STATE_ARMED);
|
2016-08-04 11:09:09 +02: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;
|
2018-03-27 16:45:31 -04:00
|
|
|
|
|
|
|
|
if (new_arming_state == vehicle_status_s::ARMING_STATE_ARMED) {
|
2017-08-30 23:12:18 +05:30
|
|
|
armed->armed_time_ms = hrt_absolute_time() / 1000;
|
2018-03-27 16:45:31 -04:00
|
|
|
|
2017-08-30 23:12:18 +05:30
|
|
|
} else {
|
|
|
|
|
armed->armed_time_ms = 0;
|
|
|
|
|
}
|
2013-02-22 15:52:13 -08:00
|
|
|
}
|
|
|
|
|
|
2014-06-26 12:11:39 +02:00
|
|
|
/* end of atomic state update */
|
2016-08-04 11:09:09 +02:00
|
|
|
#ifdef __PX4_NUTTX
|
2016-05-28 14:56:17 +02:00
|
|
|
px4_leave_critical_section(flags);
|
2016-08-04 11:09:09 +02:00
|
|
|
#endif
|
2014-06-26 12:11:39 +02:00
|
|
|
}
|
2013-08-17 18:40:28 +02:00
|
|
|
|
2014-05-11 13:36:51 +02:00
|
|
|
if (ret == TRANSITION_DENIED) {
|
2015-09-26 17:20:08 +02:00
|
|
|
/* print to MAVLink and console if we didn't provide any feedback yet */
|
2014-07-20 16:06:31 +02:00
|
|
|
if (!feedback_provided) {
|
2018-03-29 20:14:20 -04:00
|
|
|
mavlink_log_critical(mavlink_log_pub, "TRANSITION_DENIED: %s to %s",
|
2018-03-27 16:45:31 -04:00
|
|
|
arming_state_names[status->arming_state], arming_state_names[new_arming_state]);
|
2014-07-20 16:06:31 +02:00
|
|
|
}
|
2014-05-11 13:36:51 +02:00
|
|
|
}
|
2013-08-17 18:40:28 +02:00
|
|
|
|
2013-02-21 18:10:34 -08:00
|
|
|
return ret;
|
|
|
|
|
}
|
|
|
|
|
|
2018-03-27 16:45:31 -04:00
|
|
|
bool is_safe(const safety_s &safety, const actuator_armed_s &armed)
|
2013-08-15 09:52:22 +02:00
|
|
|
{
|
|
|
|
|
// System is safe if:
|
|
|
|
|
// 1) Not armed
|
|
|
|
|
// 2) Armed, but in software lockdown (HIL)
|
|
|
|
|
// 3) Safety switch is present AND engaged -> actuators locked
|
2018-03-27 15:53:56 -04:00
|
|
|
const bool lockdown = (armed.lockdown || armed.manual_lockdown);
|
2017-02-07 23:37:03 -05:00
|
|
|
|
2018-03-27 15:53:56 -04:00
|
|
|
return !armed.armed || (armed.armed && lockdown) || (safety.safety_switch_available && !safety.safety_off);
|
2013-08-15 09:52:22 +02:00
|
|
|
}
|
|
|
|
|
|
2013-07-28 23:12:16 +04:00
|
|
|
transition_result_t
|
2018-03-27 16:45:31 -04:00
|
|
|
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
|
|
|
{
|
2017-11-30 12:08:25 +00:00
|
|
|
// IMPORTANT: The assumption of callers of this function is that the execution of
|
|
|
|
|
// this check if 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
|
|
|
|
2014-05-27 21:56:32 +02:00
|
|
|
/* transition may be denied even if the same state is requested because conditions may have changed */
|
2014-01-26 11:50:34 +01:00
|
|
|
switch (new_main_state) {
|
2016-02-26 15:41:03 +00:00
|
|
|
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;
|
|
|
|
|
|
2016-02-26 15:41:03 +00:00
|
|
|
case commander_state_s::MAIN_STATE_ALTCTL:
|
2016-08-04 11:09:09 +02:00
|
|
|
|
2014-01-26 11:50:34 +01:00
|
|
|
/* need at minimum altitude estimate */
|
2018-03-27 15:16:19 -04:00
|
|
|
if (status_flags.condition_local_altitude_valid ||
|
|
|
|
|
status_flags.condition_global_position_valid) {
|
2013-07-28 23:12:16 +04:00
|
|
|
ret = TRANSITION_CHANGED;
|
2014-01-26 11:50:34 +01:00
|
|
|
}
|
2016-08-04 11:09:09 +02:00
|
|
|
|
2014-01-26 11:50:34 +01:00
|
|
|
break;
|
2013-01-11 07:42:09 +01:00
|
|
|
|
2016-02-26 15:41:03 +00:00
|
|
|
case commander_state_s::MAIN_STATE_POSCTL:
|
2016-08-04 11:09:09 +02:00
|
|
|
|
2014-01-26 11:50:34 +01:00
|
|
|
/* need at minimum local position estimate */
|
2018-03-27 15:16:19 -04:00
|
|
|
if (status_flags.condition_local_position_valid ||
|
|
|
|
|
status_flags.condition_global_position_valid) {
|
2014-01-26 11:50:34 +01:00
|
|
|
ret = TRANSITION_CHANGED;
|
|
|
|
|
}
|
2016-08-04 11:09:09 +02:00
|
|
|
|
2014-01-26 11:50:34 +01:00
|
|
|
break;
|
2013-07-28 23:12:16 +04:00
|
|
|
|
2016-02-26 15:41:03 +00:00
|
|
|
case commander_state_s::MAIN_STATE_AUTO_LOITER:
|
2016-08-04 11:09:09 +02:00
|
|
|
|
2014-01-26 11:50:34 +01:00
|
|
|
/* need global position estimate */
|
2018-03-27 15:16:19 -04:00
|
|
|
if (status_flags.condition_global_position_valid) {
|
2014-01-26 11:50:34 +01:00
|
|
|
ret = TRANSITION_CHANGED;
|
2013-07-28 23:12:16 +04:00
|
|
|
}
|
2016-08-04 11:09:09 +02:00
|
|
|
|
2014-05-27 21:56:32 +02:00
|
|
|
break;
|
2013-06-15 19:41:54 +02:00
|
|
|
|
2016-02-26 15:41:03 +00:00
|
|
|
case commander_state_s::MAIN_STATE_AUTO_FOLLOW_TARGET:
|
2017-02-07 23:22:24 -05:00
|
|
|
|
|
|
|
|
/* FOLLOW only implemented in MC */
|
2018-03-27 15:16:19 -04:00
|
|
|
if (status.is_rotary_wing) {
|
2017-02-07 23:22:24 -05:00
|
|
|
ret = TRANSITION_CHANGED;
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
break;
|
|
|
|
|
|
2016-02-26 15:41:03 +00:00
|
|
|
case commander_state_s::MAIN_STATE_AUTO_MISSION:
|
2017-04-17 00:18:39 -04:00
|
|
|
|
|
|
|
|
/* need global position, home position, and a valid mission */
|
2018-03-27 15:16:19 -04:00
|
|
|
if (status_flags.condition_global_position_valid &&
|
|
|
|
|
status_flags.condition_auto_mission_available) {
|
2017-04-17 00:18:39 -04:00
|
|
|
|
|
|
|
|
ret = TRANSITION_CHANGED;
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
break;
|
|
|
|
|
|
2016-02-26 15:41:03 +00:00
|
|
|
case commander_state_s::MAIN_STATE_AUTO_RTL:
|
2016-08-04 11:09:09 +02:00
|
|
|
|
2014-05-27 21:56:32 +02:00
|
|
|
/* need global position and home position */
|
2018-03-27 15:16:19 -04:00
|
|
|
if (status_flags.condition_global_position_valid && status_flags.condition_home_position_valid) {
|
2014-05-27 21:56:32 +02:00
|
|
|
ret = TRANSITION_CHANGED;
|
|
|
|
|
}
|
2016-08-04 11:09:09 +02:00
|
|
|
|
2014-01-26 11:50:34 +01:00
|
|
|
break;
|
|
|
|
|
|
2017-02-06 16:48:37 +01:00
|
|
|
case commander_state_s::MAIN_STATE_AUTO_TAKEOFF:
|
|
|
|
|
case commander_state_s::MAIN_STATE_AUTO_LAND:
|
|
|
|
|
|
|
|
|
|
/* need local position */
|
2018-03-27 15:16:19 -04:00
|
|
|
if (status_flags.condition_local_position_valid) {
|
2017-02-06 16:48:37 +01:00
|
|
|
ret = TRANSITION_CHANGED;
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
break;
|
|
|
|
|
|
2018-01-14 23:23:14 +05:30
|
|
|
case commander_state_s::MAIN_STATE_AUTO_PRECLAND:
|
|
|
|
|
|
|
|
|
|
/* need local and global position, and precision land only implemented for multicopters */
|
2018-03-27 16:45:31 -04:00
|
|
|
if (status_flags.condition_local_position_valid
|
|
|
|
|
&& status_flags.condition_global_position_valid
|
|
|
|
|
&& status.is_rotary_wing) {
|
|
|
|
|
|
2018-01-14 23:23:14 +05:30
|
|
|
ret = TRANSITION_CHANGED;
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
break;
|
|
|
|
|
|
2016-02-26 15:41:03 +00:00
|
|
|
case commander_state_s::MAIN_STATE_OFFBOARD:
|
2014-01-22 17:04:07 +01:00
|
|
|
|
2017-04-17 00:18:39 -04:00
|
|
|
/* need offboard signal */
|
2018-03-27 15:16:19 -04:00
|
|
|
if (!status_flags.offboard_control_signal_lost) {
|
2017-02-07 23:22:24 -05:00
|
|
|
|
2014-01-22 17:04:07 +01:00
|
|
|
ret = TRANSITION_CHANGED;
|
2013-07-28 23:12:16 +04:00
|
|
|
}
|
2013-06-15 19:41:54 +02:00
|
|
|
|
2014-01-29 21:21:16 +01:00
|
|
|
break;
|
|
|
|
|
|
2016-02-26 15:41:03 +00:00
|
|
|
case commander_state_s::MAIN_STATE_MAX:
|
2014-05-27 21:56:32 +02:00
|
|
|
default:
|
|
|
|
|
break;
|
|
|
|
|
}
|
2016-08-04 11:09:09 +02:00
|
|
|
|
2014-01-26 11:50:34 +01:00
|
|
|
if (ret == TRANSITION_CHANGED) {
|
2016-02-26 15:41:03 +00:00
|
|
|
if (internal_state->main_state != new_main_state) {
|
|
|
|
|
internal_state->main_state = new_main_state;
|
2016-07-19 09:21:35 +02:00
|
|
|
internal_state->timestamp = hrt_absolute_time();
|
2016-08-04 11:09:09 +02:00
|
|
|
|
2014-01-26 11:50:34 +01:00
|
|
|
} else {
|
|
|
|
|
ret = TRANSITION_NOT_CHANGED;
|
2013-02-22 15:52:13 -08:00
|
|
|
}
|
2013-02-22 09:32:49 -08:00
|
|
|
}
|
|
|
|
|
|
2013-07-28 23:12:16 +04:00
|
|
|
return ret;
|
|
|
|
|
}
|
|
|
|
|
|
2013-02-22 09:32:49 -08:00
|
|
|
/**
|
2014-05-27 21:56:32 +02:00
|
|
|
* Transition from one hil state to another
|
|
|
|
|
*/
|
2016-08-04 11:09:09 +02:00
|
|
|
transition_result_t hil_state_transition(hil_state_t new_state, orb_advert_t status_pub,
|
2018-03-27 16:45:31 -04:00
|
|
|
vehicle_status_s *current_status, orb_advert_t *mavlink_log_pub)
|
2015-04-24 17:49:35 -07:00
|
|
|
{
|
2014-05-27 21:56:32 +02:00
|
|
|
transition_result_t ret = TRANSITION_DENIED;
|
2015-04-24 17:49:35 -07:00
|
|
|
|
2013-02-22 09:32:49 -08:00
|
|
|
if (current_status->hil_state == new_state) {
|
2014-05-27 21:56:32 +02:00
|
|
|
ret = TRANSITION_NOT_CHANGED;
|
2015-04-24 17:49:35 -07:00
|
|
|
|
2013-02-22 09:32:49 -08:00
|
|
|
} else {
|
|
|
|
|
switch (new_state) {
|
2015-01-28 07:58:42 +01:00
|
|
|
case vehicle_status_s::HIL_STATE_OFF:
|
2017-07-29 21:47:12 +02:00
|
|
|
/* The system is in HITL mode and unexpected things can happen if we disable HITL without rebooting. */
|
2017-07-29 17:45:35 +02:00
|
|
|
mavlink_log_critical(mavlink_log_pub, "Set SYS_HITL to 0 and reboot to disable HITL.");
|
2014-05-27 21:56:32 +02:00
|
|
|
ret = TRANSITION_DENIED;
|
2013-07-28 23:12:16 +04:00
|
|
|
break;
|
2015-04-24 17:49:35 -07:00
|
|
|
|
2015-01-28 07:58:42 +01:00
|
|
|
case vehicle_status_s::HIL_STATE_ON:
|
|
|
|
|
if (current_status->arming_state == vehicle_status_s::ARMING_STATE_INIT
|
|
|
|
|
|| current_status->arming_state == vehicle_status_s::ARMING_STATE_STANDBY
|
|
|
|
|
|| current_status->arming_state == vehicle_status_s::ARMING_STATE_STANDBY_ERROR) {
|
2015-04-24 17:49:35 -07:00
|
|
|
|
2015-06-29 16:24:34 +02:00
|
|
|
ret = TRANSITION_CHANGED;
|
2017-07-29 17:45:35 +02:00
|
|
|
|
|
|
|
|
int32_t hitl_on = 0;
|
|
|
|
|
param_get(param_find("SYS_HITL"), &hitl_on);
|
|
|
|
|
|
|
|
|
|
if (hitl_on) {
|
2017-12-28 15:28:15 +01:00
|
|
|
mavlink_log_info(mavlink_log_pub, "Enabled Hardware-in-the-loop simulation (HITL).");
|
2017-09-08 12:18:59 -04:00
|
|
|
|
2017-07-29 17:45:35 +02:00
|
|
|
} else {
|
2017-12-28 15:28:15 +01:00
|
|
|
mavlink_log_critical(mavlink_log_pub, "Set SYS_HITL to 1 and reboot to enable HITL.");
|
2017-07-30 21:27:53 +02:00
|
|
|
ret = TRANSITION_DENIED;
|
2017-07-29 17:45:35 +02:00
|
|
|
}
|
2015-06-29 16:24:34 +02:00
|
|
|
|
2014-05-27 21:56:32 +02:00
|
|
|
} else {
|
2017-07-29 17:45:35 +02:00
|
|
|
mavlink_log_critical(mavlink_log_pub, "Not switching to HITL when armed.");
|
2014-05-27 21:56:32 +02:00
|
|
|
ret = TRANSITION_DENIED;
|
2013-07-28 23:12:16 +04:00
|
|
|
}
|
2016-08-04 11:09:09 +02:00
|
|
|
|
2013-07-28 23:12:16 +04:00
|
|
|
break;
|
|
|
|
|
|
|
|
|
|
default:
|
2017-12-27 19:30:41 +01:00
|
|
|
PX4_WARN("Unknown HITL state");
|
2013-07-28 23:12:16 +04:00
|
|
|
break;
|
2013-02-22 09:32:49 -08:00
|
|
|
}
|
|
|
|
|
}
|
|
|
|
|
|
2014-06-16 17:34:21 +02:00
|
|
|
if (ret == TRANSITION_CHANGED) {
|
2013-02-22 09:32:49 -08:00
|
|
|
current_status->hil_state = new_state;
|
2013-06-25 16:30:35 +02:00
|
|
|
current_status->timestamp = hrt_absolute_time();
|
2014-05-27 21:56:32 +02:00
|
|
|
orb_publish(ORB_ID(vehicle_status), status_pub, current_status);
|
2013-02-22 09:32:49 -08:00
|
|
|
}
|
2016-08-04 11:09:09 +02:00
|
|
|
|
2013-02-22 09:32:49 -08:00
|
|
|
return ret;
|
|
|
|
|
}
|
2013-02-20 10:38:06 -08:00
|
|
|
|
2016-10-13 01:49:49 -04:00
|
|
|
/**
|
2017-02-07 23:37:03 -05:00
|
|
|
* Enable failsafe and report to user
|
2016-10-13 01:49:49 -04:00
|
|
|
*/
|
2018-03-27 16:45:31 -04:00
|
|
|
void enable_failsafe(vehicle_status_s *status, bool old_failsafe, orb_advert_t *mavlink_log_pub, const char *reason)
|
2017-02-07 23:37:03 -05:00
|
|
|
{
|
2017-12-31 16:11:13 +01:00
|
|
|
if (!old_failsafe && status->arming_state == vehicle_status_s::ARMING_STATE_ARMED) {
|
2017-04-09 12:22:50 +02:00
|
|
|
mavlink_log_critical(mavlink_log_pub, "Failsafe enabled: %s", reason);
|
2016-10-13 01:49:49 -04:00
|
|
|
}
|
2017-02-07 23:37:03 -05:00
|
|
|
|
2016-10-13 01:49:49 -04:00
|
|
|
status->failsafe = true;
|
|
|
|
|
}
|
|
|
|
|
|
2013-12-08 16:52:41 +01:00
|
|
|
/**
|
2014-05-27 21:56:32 +02:00
|
|
|
* Check failsafe and main status and set navigation status for navigator accordingly
|
|
|
|
|
*/
|
2018-03-27 16:45:31 -04:00
|
|
|
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 int offb_loss_act, const int offb_loss_rc_act,
|
2017-05-06 09:57:17 +10:00
|
|
|
const int posctl_nav_loss_act)
|
2013-12-08 16:52:41 +01:00
|
|
|
{
|
2014-06-17 13:19:50 +02:00
|
|
|
navigation_state_t nav_state_old = status->nav_state;
|
|
|
|
|
|
2016-12-15 10:38:59 -08:00
|
|
|
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;
|
2017-12-20 17:55:26 -05:00
|
|
|
const bool rc_lost = rc_loss_act_configured && (status->rc_signal_lost);
|
2016-12-15 10:38:59 -08:00
|
|
|
|
2018-03-27 16:04:17 -04:00
|
|
|
bool is_armed = (status->arming_state == vehicle_status_s::ARMING_STATE_ARMED);
|
2016-10-13 01:49:49 -04:00
|
|
|
bool old_failsafe = status->failsafe;
|
2016-04-08 13:19:11 +02:00
|
|
|
status->failsafe = false;
|
2014-01-26 11:58:50 +01:00
|
|
|
|
2016-12-15 10:38:59 -08:00
|
|
|
// 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);
|
|
|
|
|
|
2014-06-16 17:34:21 +02:00
|
|
|
/* evaluate main state to decide in normal (non-failsafe) mode */
|
2016-02-26 15:41:03 +00:00
|
|
|
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
|
|
|
|
2014-06-16 17:34:21 +02:00
|
|
|
/* require RC for all manual modes */
|
2016-12-15 10:38:59 -08:00
|
|
|
if (rc_lost && is_armed) {
|
2016-10-13 01:49:49 -04:00
|
|
|
enable_failsafe(status, old_failsafe, mavlink_log_pub, reason_no_rc);
|
2014-01-26 11:52:33 +01:00
|
|
|
|
2018-03-27 16:45:31 -04: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
|
|
|
|
2014-06-16 17:34:21 +02:00
|
|
|
} else {
|
2016-02-26 15:41:03 +00:00
|
|
|
switch (internal_state->main_state) {
|
|
|
|
|
case commander_state_s::MAIN_STATE_ACRO:
|
2015-01-28 07:58:42 +01:00
|
|
|
status->nav_state = vehicle_status_s::NAVIGATION_STATE_ACRO;
|
2014-06-16 17:34:21 +02:00
|
|
|
break;
|
|
|
|
|
|
2016-02-26 15:41:03 +00:00
|
|
|
case commander_state_s::MAIN_STATE_MANUAL:
|
2015-01-28 07:58:42 +01:00
|
|
|
status->nav_state = vehicle_status_s::NAVIGATION_STATE_MANUAL;
|
2014-06-16 17:34:21 +02:00
|
|
|
break;
|
|
|
|
|
|
2016-02-26 15:41:03 +00:00
|
|
|
case commander_state_s::MAIN_STATE_RATTITUDE:
|
2015-10-20 20:38:42 -04:00
|
|
|
status->nav_state = vehicle_status_s::NAVIGATION_STATE_RATTITUDE;
|
|
|
|
|
break;
|
|
|
|
|
|
2016-02-26 15:41:03 +00:00
|
|
|
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;
|
|
|
|
|
|
2016-02-26 15:41:03 +00:00
|
|
|
case commander_state_s::MAIN_STATE_ALTCTL:
|
2015-01-28 07:58:42 +01:00
|
|
|
status->nav_state = vehicle_status_s::NAVIGATION_STATE_ALTCTL;
|
2014-06-16 17:34:21 +02:00
|
|
|
break;
|
|
|
|
|
|
|
|
|
|
default:
|
2015-01-28 07:58:42 +01:00
|
|
|
status->nav_state = vehicle_status_s::NAVIGATION_STATE_MANUAL;
|
2014-06-16 17:34:21 +02:00
|
|
|
break;
|
|
|
|
|
}
|
|
|
|
|
}
|
2016-08-04 11:09:09 +02:00
|
|
|
|
2014-06-16 17:34:21 +02:00
|
|
|
break;
|
2014-01-26 11:52:33 +01:00
|
|
|
|
2016-08-04 11:09:09 +02:00
|
|
|
case commander_state_s::MAIN_STATE_POSCTL: {
|
2016-06-06 13:56:37 +02:00
|
|
|
|
2016-12-15 10:38:59 -08:00
|
|
|
if (rc_lost && is_armed) {
|
2016-10-13 01:49:49 -04:00
|
|
|
enable_failsafe(status, old_failsafe, mavlink_log_pub, reason_no_rc);
|
2016-06-06 13:56:37 +02:00
|
|
|
|
2018-03-27 16:45:31 -04:00
|
|
|
set_link_loss_nav_state(status, armed, status_flags, internal_state, rc_loss_act,
|
|
|
|
|
vehicle_status_s::NAVIGATION_STATE_AUTO_RCRECOVER);
|
2016-06-06 13:56:37 +02:00
|
|
|
|
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. */
|
|
|
|
|
|
2018-03-27 16:45:31 -04:00
|
|
|
} else if (is_armed
|
|
|
|
|
&& check_invalid_pos_nav_state(status, old_failsafe, mavlink_log_pub, status_flags, !(posctl_nav_loss_act == 1),
|
|
|
|
|
!status->is_rotary_wing)) {
|
2017-03-08 11:03:27 +11:00
|
|
|
// nothing to do - everything done in check_invalid_pos_nav_state
|
2017-09-08 12:18:59 -04:00
|
|
|
|
2016-06-06 13:56:37 +02:00
|
|
|
} else {
|
|
|
|
|
status->nav_state = vehicle_status_s::NAVIGATION_STATE_POSCTL;
|
|
|
|
|
}
|
|
|
|
|
}
|
|
|
|
|
break;
|
|
|
|
|
|
2016-02-26 15:41:03 +00:00
|
|
|
case commander_state_s::MAIN_STATE_AUTO_MISSION:
|
2014-11-10 21:40:13 +10:00
|
|
|
|
2014-06-18 19:01:41 +02:00
|
|
|
/* go into failsafe
|
2014-08-14 22:38:48 +02:00
|
|
|
* - if commanded to do so
|
2014-07-24 22:29:04 +02:00
|
|
|
* - if we have an engine failure
|
2016-02-05 13:06:51 +01:00
|
|
|
* - if we have vtol transition failure
|
2014-11-12 09:48:32 +10:00
|
|
|
* - depending on datalink, RC and if the mission is finished */
|
2014-11-10 21:40:13 +10:00
|
|
|
|
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)) {
|
2017-03-08 11:03:27 +11:00
|
|
|
// nothing to do - everything done in check_invalid_pos_nav_state
|
2014-09-07 15:33:11 +02:00
|
|
|
} else if (status->engine_failure) {
|
2015-01-28 07:58:42 +01:00
|
|
|
status->nav_state = vehicle_status_s::NAVIGATION_STATE_AUTO_LANDENGFAIL;
|
2016-08-04 11:09:09 +02:00
|
|
|
|
2018-03-27 15:49:52 -04: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
|
|
|
|
2016-02-13 01:08:07 +01:00
|
|
|
} else if (status->mission_failure) {
|
|
|
|
|
status->nav_state = vehicle_status_s::NAVIGATION_STATE_AUTO_RTL;
|
2014-11-10 21:40:13 +10:00
|
|
|
|
2017-09-08 12:18:59 -04:00
|
|
|
} else if (data_link_loss_act_configured && status->data_link_lost) {
|
2016-08-04 11:09:09 +02:00
|
|
|
/* datalink loss enabled:
|
|
|
|
|
* check for datalink lost: this should always trigger RTGS */
|
2016-10-13 01:49:49 -04:00
|
|
|
enable_failsafe(status, old_failsafe, mavlink_log_pub, reason_no_datalink);
|
2013-12-08 16:52:41 +01:00
|
|
|
|
2018-03-27 16:45:31 -04:00
|
|
|
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
|
|
|
|
2017-09-08 12:18:59 -04:00
|
|
|
} else if (!data_link_loss_act_configured && status->rc_signal_lost && status->data_link_lost && !landed
|
|
|
|
|
&& mission_finished) {
|
2016-12-15 10:38:59 -08:00
|
|
|
/* datalink loss DISABLED:
|
2016-08-04 11:09:09 +02:00
|
|
|
* check if both, RC and datalink are lost during the mission
|
2016-08-04 11:26:21 +02:00
|
|
|
* or all links are lost after the mission finishes in air: this should always trigger RCRECOVER */
|
2016-10-13 01:49:49 -04:00
|
|
|
enable_failsafe(status, old_failsafe, mavlink_log_pub, reason_no_datalink);
|
2014-11-10 21:40:13 +10:00
|
|
|
|
2018-03-27 16:45:31 -04: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
|
|
|
|
2016-08-04 11:09:09 +02:00
|
|
|
} else if (!stay_in_failsafe) {
|
2017-09-08 12:18:59 -04:00
|
|
|
/* stay where you are if you should stay in failsafe, otherwise everything is perfect */
|
2015-01-28 07:58:42 +01:00
|
|
|
status->nav_state = vehicle_status_s::NAVIGATION_STATE_AUTO_MISSION;
|
2014-01-25 23:24:12 +01:00
|
|
|
}
|
2016-08-04 11:09:09 +02:00
|
|
|
|
2014-05-27 21:56:32 +02:00
|
|
|
break;
|
2013-12-08 16:52:41 +01:00
|
|
|
|
2016-02-26 15:41:03 +00:00
|
|
|
case commander_state_s::MAIN_STATE_AUTO_LOITER:
|
2016-08-04 11:09:09 +02:00
|
|
|
|
2014-08-23 14:02:22 +02:00
|
|
|
/* go into failsafe on a engine failure */
|
2014-07-24 22:29:04 +02:00
|
|
|
if (status->engine_failure) {
|
2015-01-28 07:58:42 +01:00
|
|
|
status->nav_state = vehicle_status_s::NAVIGATION_STATE_AUTO_LANDENGFAIL;
|
2016-05-17 10:53:07 -04:00
|
|
|
|
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
|
2017-03-03 09:33:20 +00:00
|
|
|
} else if (status->data_link_lost && data_link_loss_act_configured && !landed) {
|
2017-09-08 12:18:59 -04:00
|
|
|
/* also go into failsafe if just datalink is lost, and we're actually in air */
|
2018-03-27 16:45:31 -04:00
|
|
|
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
|
|
|
|
2017-09-08 12:18:59 -04:00
|
|
|
enable_failsafe(status, old_failsafe, mavlink_log_pub, reason_no_datalink);
|
2014-06-18 19:01:41 +02:00
|
|
|
|
2016-12-15 10:38:59 -08:00
|
|
|
} else if (rc_lost && !data_link_loss_act_configured) {
|
2017-09-08 12:18:59 -04:00
|
|
|
/* go into failsafe if RC is lost and datalink loss is not set up and rc loss is not DISABLED */
|
2016-10-13 01:49:49 -04:00
|
|
|
enable_failsafe(status, old_failsafe, mavlink_log_pub, reason_no_rc);
|
2016-08-04 11:09:09 +02:00
|
|
|
|
2018-03-27 16:45:31 -04: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) {
|
2017-09-08 12:18:59 -04:00
|
|
|
/* don't bother if RC is lost if datalink is connected */
|
2014-06-18 19:01:41 +02:00
|
|
|
|
2016-12-15 10:38:59 -08:00
|
|
|
/* this mode is ok, we don't need RC for LOITERing */
|
2015-01-28 07:58:42 +01:00
|
|
|
status->nav_state = vehicle_status_s::NAVIGATION_STATE_AUTO_LOITER;
|
2016-08-04 11:09:09 +02:00
|
|
|
|
2014-06-16 17:34:21 +02:00
|
|
|
} else {
|
2014-06-18 19:01:41 +02:00
|
|
|
/* everything is perfect */
|
2015-01-28 07:58:42 +01:00
|
|
|
status->nav_state = vehicle_status_s::NAVIGATION_STATE_AUTO_LOITER;
|
2014-06-16 17:34:21 +02:00
|
|
|
}
|
2016-08-04 11:09:09 +02:00
|
|
|
|
2014-05-27 21:56:32 +02:00
|
|
|
break;
|
2013-12-08 16:52:41 +01:00
|
|
|
|
2016-02-26 15:41:03 +00:00
|
|
|
case commander_state_s::MAIN_STATE_AUTO_RTL:
|
2016-08-04 11:09:09 +02:00
|
|
|
|
2014-07-24 22:29:04 +02:00
|
|
|
/* require global position and home, also go into failsafe on an engine failure */
|
|
|
|
|
|
|
|
|
|
if (status->engine_failure) {
|
2015-01-28 07:58:42 +01:00
|
|
|
status->nav_state = vehicle_status_s::NAVIGATION_STATE_AUTO_LANDENGFAIL;
|
2016-05-17 10:53:07 -04:00
|
|
|
|
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 {
|
2015-01-28 07:58:42 +01:00
|
|
|
status->nav_state = vehicle_status_s::NAVIGATION_STATE_AUTO_RTL;
|
2014-06-16 17:34:21 +02:00
|
|
|
}
|
2016-08-04 11:09:09 +02:00
|
|
|
|
2014-05-27 21:56:32 +02:00
|
|
|
break;
|
2013-02-16 13:40:09 -08:00
|
|
|
|
2016-02-26 15:41:03 +00:00
|
|
|
case commander_state_s::MAIN_STATE_AUTO_FOLLOW_TARGET:
|
2016-08-04 11:09:09 +02:00
|
|
|
|
2016-02-18 06:57:01 -08: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
|
|
|
|
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
|
|
|
|
2016-02-18 06:57:01 -08:00
|
|
|
} else {
|
|
|
|
|
status->nav_state = vehicle_status_s::NAVIGATION_STATE_AUTO_FOLLOW_TARGET;
|
|
|
|
|
}
|
2016-08-04 11:09:09 +02:00
|
|
|
|
2016-02-18 06:57:01 -08:00
|
|
|
break;
|
|
|
|
|
|
2016-04-04 13:23:30 +02:00
|
|
|
case commander_state_s::MAIN_STATE_AUTO_TAKEOFF:
|
2016-08-04 11:09:09 +02:00
|
|
|
|
2017-02-13 09:42:31 +01:00
|
|
|
/* require local position */
|
2015-11-20 11:15:17 +01:00
|
|
|
|
|
|
|
|
if (status->engine_failure) {
|
|
|
|
|
status->nav_state = vehicle_status_s::NAVIGATION_STATE_AUTO_LANDENGFAIL;
|
2016-08-04 11:09:09 +02:00
|
|
|
|
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
|
|
|
|
2015-11-20 11:15:17 +01:00
|
|
|
} else {
|
|
|
|
|
status->nav_state = vehicle_status_s::NAVIGATION_STATE_AUTO_TAKEOFF;
|
|
|
|
|
}
|
2016-08-04 11:09:09 +02:00
|
|
|
|
2015-11-20 11:15:17 +01:00
|
|
|
break;
|
|
|
|
|
|
2016-02-26 15:41:03 +00:00
|
|
|
case commander_state_s::MAIN_STATE_AUTO_LAND:
|
2016-08-04 11:09:09 +02:00
|
|
|
|
2017-02-13 09:42:31 +01:00
|
|
|
/* require local position */
|
2015-12-17 00:11:50 +01:00
|
|
|
|
|
|
|
|
if (status->engine_failure) {
|
|
|
|
|
status->nav_state = vehicle_status_s::NAVIGATION_STATE_AUTO_LANDENGFAIL;
|
2016-08-04 11:09:09 +02:00
|
|
|
|
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
|
|
|
|
2015-12-17 00:11:50 +01:00
|
|
|
} else {
|
2016-03-13 15:39:35 +01:00
|
|
|
status->nav_state = vehicle_status_s::NAVIGATION_STATE_AUTO_LAND;
|
2015-12-17 00:11:50 +01:00
|
|
|
}
|
2016-08-04 11:09:09 +02:00
|
|
|
|
2015-12-17 00:11:50 +01:00
|
|
|
break;
|
|
|
|
|
|
2018-01-14 23:23:14 +05:30
|
|
|
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;
|
|
|
|
|
|
2016-02-26 15:41:03 +00:00
|
|
|
case commander_state_s::MAIN_STATE_OFFBOARD:
|
2016-08-04 11:09:09 +02:00
|
|
|
|
2014-06-21 12:24:37 +02:00
|
|
|
/* require offboard control, otherwise stay where you are */
|
2018-03-27 15:49:52 -04:00
|
|
|
if (status_flags.offboard_control_signal_lost && !status->rc_signal_lost) {
|
2016-11-15 20:01:52 +01:00
|
|
|
enable_failsafe(status, old_failsafe, mavlink_log_pub, reason_no_offboard);
|
2014-06-21 12:24:37 +02:00
|
|
|
|
2018-03-27 15:49:52 -04:00
|
|
|
if (status_flags.offboard_control_loss_timeout && offb_loss_rc_act < 6 && offb_loss_rc_act >= 0) {
|
|
|
|
|
if (offb_loss_rc_act == 3 && status_flags.condition_global_position_valid
|
|
|
|
|
&& status_flags.condition_home_position_valid) {
|
2015-11-26 17:45:20 +01:00
|
|
|
status->nav_state = vehicle_status_s::NAVIGATION_STATE_AUTO_RTL;
|
|
|
|
|
|
2018-03-27 15:49:52 -04:00
|
|
|
} else if (offb_loss_rc_act == 0 && status_flags.condition_global_position_valid) {
|
2015-11-26 17:45:20 +01:00
|
|
|
status->nav_state = vehicle_status_s::NAVIGATION_STATE_POSCTL;
|
|
|
|
|
|
2018-03-27 15:49:52 -04:00
|
|
|
} else if (offb_loss_rc_act == 1 && status_flags.condition_local_altitude_valid) {
|
2015-11-26 17:45:20 +01:00
|
|
|
status->nav_state = vehicle_status_s::NAVIGATION_STATE_ALTCTL;
|
|
|
|
|
|
|
|
|
|
} else if (offb_loss_rc_act == 2) {
|
|
|
|
|
status->nav_state = vehicle_status_s::NAVIGATION_STATE_MANUAL;
|
|
|
|
|
|
2018-03-27 15:49:52 -04:00
|
|
|
} else if (offb_loss_rc_act == 4 && status_flags.condition_global_position_valid) {
|
2015-11-26 17:45:20 +01:00
|
|
|
status->nav_state = vehicle_status_s::NAVIGATION_STATE_AUTO_LAND;
|
|
|
|
|
|
2018-03-27 15:49:52 -04:00
|
|
|
} else if (offb_loss_rc_act == 5 && status_flags.condition_global_position_valid) {
|
2017-05-08 11:17:29 -07:00
|
|
|
status->nav_state = vehicle_status_s::NAVIGATION_STATE_AUTO_LOITER;
|
|
|
|
|
|
2018-03-27 15:49:52 -04:00
|
|
|
} else if (status_flags.condition_local_altitude_valid) {
|
2017-09-08 12:18:59 -04:00
|
|
|
if (status->is_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;
|
|
|
|
|
}
|
2015-11-26 17:45:20 +01:00
|
|
|
|
|
|
|
|
} else {
|
|
|
|
|
status->nav_state = vehicle_status_s::NAVIGATION_STATE_TERMINATION;
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
} else {
|
2018-03-27 15:49:52 -04:00
|
|
|
if (status_flags.condition_global_position_valid) {
|
2015-11-26 17:45:20 +01:00
|
|
|
status->nav_state = vehicle_status_s::NAVIGATION_STATE_POSCTL;
|
|
|
|
|
|
2018-03-27 15:49:52 -04:00
|
|
|
} else if (status_flags.condition_local_altitude_valid) {
|
2015-11-26 17:45:20 +01:00
|
|
|
status->nav_state = vehicle_status_s::NAVIGATION_STATE_ALTCTL;
|
|
|
|
|
|
|
|
|
|
} else {
|
|
|
|
|
status->nav_state = vehicle_status_s::NAVIGATION_STATE_TERMINATION;
|
|
|
|
|
}
|
|
|
|
|
}
|
|
|
|
|
|
2018-03-27 15:49:52 -04:00
|
|
|
} else if (status_flags.offboard_control_signal_lost && status->rc_signal_lost) {
|
2016-11-15 20:01:52 +01:00
|
|
|
enable_failsafe(status, old_failsafe, mavlink_log_pub, reason_no_rc_and_no_offboard);
|
2014-06-21 12:24:37 +02:00
|
|
|
|
2018-03-27 15:49:52 -04:00
|
|
|
if (status_flags.offboard_control_loss_timeout && offb_loss_act < 3 && offb_loss_act >= 0) {
|
|
|
|
|
if (offb_loss_act == 2 && status_flags.condition_global_position_valid
|
|
|
|
|
&& status_flags.condition_home_position_valid) {
|
2015-11-26 17:45:20 +01:00
|
|
|
status->nav_state = vehicle_status_s::NAVIGATION_STATE_AUTO_RTL;
|
|
|
|
|
|
2018-03-27 15:49:52 -04:00
|
|
|
} else if (offb_loss_act == 1 && status_flags.condition_global_position_valid) {
|
2015-11-26 17:45:20 +01:00
|
|
|
status->nav_state = vehicle_status_s::NAVIGATION_STATE_AUTO_LOITER;
|
|
|
|
|
|
2018-03-27 15:49:52 -04:00
|
|
|
} else if (offb_loss_act == 0 && status_flags.condition_global_position_valid) {
|
2015-11-26 17:45:20 +01:00
|
|
|
status->nav_state = vehicle_status_s::NAVIGATION_STATE_AUTO_LAND;
|
|
|
|
|
|
2018-03-27 15:49:52 -04:00
|
|
|
} else if (status_flags.condition_local_altitude_valid) {
|
2017-09-08 12:18:59 -04:00
|
|
|
if (status->is_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;
|
|
|
|
|
}
|
2015-11-26 17:45:20 +01:00
|
|
|
|
|
|
|
|
} else {
|
|
|
|
|
status->nav_state = vehicle_status_s::NAVIGATION_STATE_TERMINATION;
|
|
|
|
|
}
|
|
|
|
|
|
2014-06-21 12:24:37 +02:00
|
|
|
} else {
|
2018-03-27 15:49:52 -04:00
|
|
|
if (status_flags.condition_global_position_valid) {
|
2015-11-26 17:45:20 +01:00
|
|
|
status->nav_state = vehicle_status_s::NAVIGATION_STATE_AUTO_LOITER;
|
|
|
|
|
|
2018-03-27 15:49:52 -04:00
|
|
|
} else if (status_flags.condition_local_altitude_valid) {
|
2017-09-08 12:18:59 -04:00
|
|
|
if (status->is_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;
|
|
|
|
|
}
|
2015-11-26 17:45:20 +01:00
|
|
|
|
|
|
|
|
} else {
|
|
|
|
|
status->nav_state = vehicle_status_s::NAVIGATION_STATE_TERMINATION;
|
|
|
|
|
}
|
2014-06-21 12:24:37 +02:00
|
|
|
}
|
2015-11-26 17:45:20 +01:00
|
|
|
|
2014-06-21 12:24:37 +02:00
|
|
|
} else {
|
2015-01-28 07:58:42 +01:00
|
|
|
status->nav_state = vehicle_status_s::NAVIGATION_STATE_OFFBOARD;
|
2014-06-21 12:24:37 +02:00
|
|
|
}
|
2016-08-04 11:09:09 +02:00
|
|
|
|
2014-05-27 21:56:32 +02:00
|
|
|
default:
|
|
|
|
|
break;
|
|
|
|
|
}
|
2014-06-16 17:34:21 +02:00
|
|
|
|
2014-06-17 13:19:50 +02:00
|
|
|
return status->nav_state != nav_state_old;
|
2014-05-27 21:56:32 +02:00
|
|
|
}
|
2013-06-25 16:30:35 +02:00
|
|
|
|
2018-03-27 16:45:31 -04:00
|
|
|
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)
|
2017-03-08 11:03:27 +11:00
|
|
|
{
|
|
|
|
|
bool fallback_required = false;
|
|
|
|
|
|
2018-03-27 15:49:52 -04:00
|
|
|
if (using_global_pos && !status_flags.condition_global_position_valid) {
|
2017-03-08 11:03:27 +11:00
|
|
|
fallback_required = true;
|
2018-03-27 16:45:31 -04:00
|
|
|
|
|
|
|
|
} else if (!using_global_pos
|
|
|
|
|
&& (!status_flags.condition_local_position_valid || !status_flags.condition_local_velocity_valid)) {
|
|
|
|
|
|
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
|
2018-03-27 15:49:52 -04:00
|
|
|
if (status->is_rotary_wing && status_flags.condition_local_position_valid) {
|
2017-03-08 11:03:27 +11:00
|
|
|
status->nav_state = vehicle_status_s::NAVIGATION_STATE_POSCTL;
|
2017-09-08 12:18:59 -04:00
|
|
|
|
2018-03-27 15:49:52 -04:00
|
|
|
} else if (status_flags.condition_local_altitude_valid) {
|
2017-03-08 11:03:27 +11:00
|
|
|
status->nav_state = vehicle_status_s::NAVIGATION_STATE_ALTCTL;
|
2017-09-08 12:18:59 -04:00
|
|
|
|
2017-03-08 11:03:27 +11:00
|
|
|
} else {
|
|
|
|
|
status->nav_state = vehicle_status_s::NAVIGATION_STATE_STAB;
|
|
|
|
|
}
|
2017-09-08 12:18:59 -04:00
|
|
|
|
2017-03-08 11:03:27 +11:00
|
|
|
} else {
|
|
|
|
|
// go into a descent that does not require stick control
|
2018-03-27 15:49:52 -04:00
|
|
|
if (status_flags.condition_local_position_valid) {
|
2017-03-08 11:03:27 +11:00
|
|
|
status->nav_state = vehicle_status_s::NAVIGATION_STATE_AUTO_LAND;
|
2017-09-08 12:18:59 -04:00
|
|
|
|
2018-03-27 15:49:52 -04:00
|
|
|
} else if (status_flags.condition_local_altitude_valid) {
|
2017-09-08 12:18:59 -04:00
|
|
|
if (status->is_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;
|
|
|
|
|
}
|
2018-03-27 16:45:31 -04:00
|
|
|
|
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);
|
2017-09-08 12:18:59 -04:00
|
|
|
|
2017-03-08 11:03:27 +11:00
|
|
|
} else {
|
|
|
|
|
enable_failsafe(status, old_failsafe, mavlink_log_pub, reason_no_local_position);
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
return fallback_required;
|
|
|
|
|
|
|
|
|
|
}
|
|
|
|
|
|
2018-03-27 16:45:31 -04:00
|
|
|
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,
|
2016-12-15 10:38:59 -08:00
|
|
|
uint8_t auto_recovery_nav_state)
|
|
|
|
|
{
|
|
|
|
|
// do the best you can according to the action set
|
|
|
|
|
if (link_loss_act == link_loss_actions_t::AUTO_RECOVER
|
2018-03-27 15:49:52 -04:00
|
|
|
&& status_flags.condition_global_position_valid && status_flags.condition_home_position_valid) {
|
2016-12-15 10:38:59 -08:00
|
|
|
status->nav_state = auto_recovery_nav_state;
|
2017-02-07 23:37:03 -05:00
|
|
|
|
2018-03-27 15:49:52 -04:00
|
|
|
} else if (link_loss_act == link_loss_actions_t::AUTO_LOITER && status_flags.condition_global_position_valid) {
|
2016-12-15 10:38:59 -08:00
|
|
|
status->nav_state = vehicle_status_s::NAVIGATION_STATE_AUTO_LOITER;
|
2017-02-07 23:37:03 -05:00
|
|
|
|
|
|
|
|
} else if (link_loss_act == link_loss_actions_t::AUTO_RTL
|
2018-03-27 15:49:52 -04:00
|
|
|
&& status_flags.condition_global_position_valid && status_flags.condition_home_position_valid) {
|
2017-07-09 22:32:54 -04:00
|
|
|
|
2018-03-27 15:49:52 -04:00
|
|
|
main_state_transition(*status, commander_state_s::MAIN_STATE_AUTO_RTL, status_flags, internal_state);
|
2016-12-15 10:38:59 -08:00
|
|
|
status->nav_state = vehicle_status_s::NAVIGATION_STATE_AUTO_RTL;
|
2017-02-07 23:37:03 -05:00
|
|
|
|
2018-03-27 15:49:52 -04:00
|
|
|
} else if (link_loss_act == link_loss_actions_t::AUTO_LAND && status_flags.condition_local_position_valid) {
|
2016-12-15 10:38:59 -08:00
|
|
|
status->nav_state = vehicle_status_s::NAVIGATION_STATE_AUTO_LAND;
|
2017-02-07 23:37:03 -05:00
|
|
|
|
|
|
|
|
} else if (link_loss_act == link_loss_actions_t::TERMINATE) {
|
2016-12-15 10:38:59 -08:00
|
|
|
status->nav_state = vehicle_status_s::NAVIGATION_STATE_TERMINATION;
|
|
|
|
|
armed->force_failsafe = true;
|
2017-02-07 23:37:03 -05:00
|
|
|
|
|
|
|
|
} else if (link_loss_act == link_loss_actions_t::LOCKDOWN) {
|
2016-12-15 10:38:59 -08:00
|
|
|
armed->lockdown = true;
|
|
|
|
|
|
|
|
|
|
// do the best you can according to the current state
|
2017-02-07 23:37:03 -05:00
|
|
|
|
2018-03-27 15:49:52 -04:00
|
|
|
} else if (status_flags.condition_global_position_valid && status_flags.condition_home_position_valid) {
|
2016-12-15 10:38:59 -08:00
|
|
|
status->nav_state = vehicle_status_s::NAVIGATION_STATE_AUTO_RTL;
|
2017-02-07 23:37:03 -05:00
|
|
|
|
2018-03-27 15:49:52 -04:00
|
|
|
} else if (status_flags.condition_local_position_valid) {
|
2016-12-15 10:38:59 -08:00
|
|
|
status->nav_state = vehicle_status_s::NAVIGATION_STATE_AUTO_LAND;
|
2017-02-07 23:37:03 -05:00
|
|
|
|
2018-03-27 15:49:52 -04:00
|
|
|
} else if (status_flags.condition_local_altitude_valid) {
|
2017-09-08 12:18:59 -04:00
|
|
|
if (status->is_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;
|
|
|
|
|
}
|
2017-02-07 23:37:03 -05:00
|
|
|
|
|
|
|
|
} else {
|
2016-12-15 10:38:59 -08:00
|
|
|
status->nav_state = vehicle_status_s::NAVIGATION_STATE_TERMINATION;
|
|
|
|
|
}
|
|
|
|
|
}
|
|
|
|
|
|
2018-03-27 15:49:52 -04:00
|
|
|
void reset_link_loss_globals(actuator_armed_s *armed, const bool old_failsafe, const link_loss_actions_t link_loss_act)
|
2016-12-15 10:38:59 -08:00
|
|
|
{
|
2017-02-07 23:37:03 -05:00
|
|
|
if (old_failsafe) {
|
|
|
|
|
if (link_loss_act == link_loss_actions_t::TERMINATE) {
|
2016-12-15 10:38:59 -08:00
|
|
|
armed->force_failsafe = false;
|
2017-02-07 23:37:03 -05:00
|
|
|
|
|
|
|
|
} else if (link_loss_act == link_loss_actions_t::LOCKDOWN) {
|
2016-12-15 10:38:59 -08:00
|
|
|
armed->lockdown = false;
|
|
|
|
|
}
|
|
|
|
|
}
|
|
|
|
|
}
|
|
|
|
|
|
2018-03-29 23:14:34 -04:00
|
|
|
bool prearm_check(orb_advert_t *mavlink_log_pub, const vehicle_status_flags_s &status_flags,
|
|
|
|
|
const battery_status_s &battery, const uint8_t arm_requirements, const hrt_abstime &time_since_boot)
|
2014-06-26 12:11:39 +02:00
|
|
|
{
|
2018-03-29 23:14:34 -04:00
|
|
|
bool reportFailures = true;
|
2017-12-31 16:11:13 +01:00
|
|
|
bool prearm_ok = true;
|
2016-03-15 18:25:02 +00:00
|
|
|
|
2018-03-29 23:14:34 -04:00
|
|
|
if (!status_flags.circuit_breaker_engaged_usb_check && status_flags.usb_connected) {
|
2017-12-31 16:11:13 +01:00
|
|
|
prearm_ok = false;
|
2016-08-04 11:09:09 +02:00
|
|
|
|
2015-11-19 17:48:39 +01:00
|
|
|
if (reportFailures) {
|
2016-09-20 12:56:08 +02:00
|
|
|
mavlink_log_critical(mavlink_log_pub, "ARMING DENIED: Flying with USB is not safe");
|
2016-04-10 10:57:38 -07:00
|
|
|
}
|
|
|
|
|
}
|
|
|
|
|
|
2018-03-29 23:14:34 -04:00
|
|
|
if (!status_flags.circuit_breaker_engaged_power_check && battery.warning >= battery_status_s::BATTERY_WARNING_LOW) {
|
2017-12-31 16:11:13 +01:00
|
|
|
prearm_ok = false;
|
2016-08-04 11:09:09 +02:00
|
|
|
|
2016-04-10 10:57:38 -07:00
|
|
|
if (reportFailures) {
|
2017-02-02 16:06:44 +01:00
|
|
|
mavlink_log_critical(mavlink_log_pub, "ARMING DENIED: LOW BATTERY");
|
2015-11-19 17:48:39 +01:00
|
|
|
}
|
|
|
|
|
}
|
2015-10-23 17:47:22 +02:00
|
|
|
|
2017-04-17 00:18:39 -04:00
|
|
|
// mission required
|
2018-03-27 16:45:31 -04:00
|
|
|
if ((arm_requirements & ARM_REQ_MISSION_BIT)
|
2018-03-29 23:14:34 -04:00
|
|
|
&& (!status_flags.condition_auto_mission_available || !status_flags.condition_global_position_valid)) {
|
2017-04-17 00:18:39 -04:00
|
|
|
|
2017-12-31 16:11:13 +01:00
|
|
|
prearm_ok = false;
|
2017-04-17 00:18:39 -04:00
|
|
|
|
|
|
|
|
if (reportFailures) {
|
|
|
|
|
mavlink_log_critical(mavlink_log_pub, "ARMING DENIED: valid mission required");
|
|
|
|
|
}
|
|
|
|
|
}
|
|
|
|
|
|
2018-03-29 23:14:34 -04:00
|
|
|
// arm authorization check
|
|
|
|
|
if (arm_requirements & ARM_REQ_ARM_AUTH_BIT) {
|
|
|
|
|
if (arm_auth_check() != vehicle_command_ack_s::VEHICLE_RESULT_ACCEPTED) {
|
|
|
|
|
// feedback provided in arm_auth_check
|
|
|
|
|
prearm_ok = false;
|
|
|
|
|
}
|
|
|
|
|
}
|
|
|
|
|
|
2018-03-29 23:14:34 -04:00
|
|
|
return prearm_ok;
|
2014-06-26 12:11:39 +02:00
|
|
|
}
|