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>
|
2012-08-04 15:12:36 -07:00
|
|
|
|
|
|
|
|
#include <stdio.h>
|
2012-08-27 22:57:20 +02:00
|
|
|
#include <unistd.h>
|
2013-03-11 10:39:57 -07:00
|
|
|
#include <stdint.h>
|
2013-02-16 13:40:09 -08:00
|
|
|
#include <stdbool.h>
|
2014-01-12 11:47:35 +01:00
|
|
|
#include <dirent.h>
|
|
|
|
|
#include <fcntl.h>
|
2014-03-16 19:16:18 +01:00
|
|
|
#include <string.h>
|
2014-06-26 12:11:39 +02:00
|
|
|
#include <math.h>
|
2012-08-04 15:12:36 -07:00
|
|
|
|
2015-09-20 10:58:04 +02:00
|
|
|
#include <px4_posix.h>
|
|
|
|
|
|
2012-08-04 15:12:36 -07:00
|
|
|
#include <uORB/uORB.h>
|
|
|
|
|
#include <uORB/topics/vehicle_status.h>
|
2012-09-02 11:33:52 +02:00
|
|
|
#include <uORB/topics/actuator_controls.h>
|
2014-06-26 12:11:39 +02:00
|
|
|
#include <uORB/topics/differential_pressure.h>
|
2012-08-04 15:12:36 -07:00
|
|
|
#include <systemlib/systemlib.h>
|
2013-03-11 10:39:57 -07:00
|
|
|
#include <systemlib/param/param.h>
|
2013-02-16 13:40:09 -08:00
|
|
|
#include <systemlib/err.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>
|
2014-06-26 12:11:39 +02:00
|
|
|
#include <drivers/drv_accel.h>
|
2014-01-12 11:47:35 +01:00
|
|
|
#include <drivers/drv_device.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"
|
2015-11-10 07:45:13 -08:00
|
|
|
#ifndef __PX4_NUTTX
|
|
|
|
|
#include "DevMgr.hpp"
|
|
|
|
|
using namespace DriverFramework;
|
|
|
|
|
#endif
|
2012-08-27 22:57:20 +02:00
|
|
|
|
2016-03-12 12:50:14 +08:00
|
|
|
#ifdef CONFIG_ARCH_BOARD_MINDPX_V2
|
|
|
|
|
#define AVIONICS_ERROR_VOLTAGE 3.75f
|
|
|
|
|
#define AVIONICS_WARN_VOLTAGE 3.9f
|
|
|
|
|
#else
|
|
|
|
|
#define AVIONICS_ERROR_VOLTAGE 4.5f
|
|
|
|
|
#define AVIONICS_WARN_VOLTAGE 4.9f
|
|
|
|
|
#endif
|
|
|
|
|
|
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.
|
2015-01-28 07:58:42 +01:00
|
|
|
static const bool arming_transitions[vehicle_status_s::ARMING_STATE_MAX][vehicle_status_s::ARMING_STATE_MAX] = {
|
2015-04-19 13:57:07 +02:00
|
|
|
// INIT, STANDBY, ARMED, ARMED_ERROR, STANDBY_ERROR, REBOOT, IN_AIR_RESTORE
|
|
|
|
|
{ /* vehicle_status_s::ARMING_STATE_INIT */ true, true, false, false, true, false, false },
|
2015-01-28 07:58:42 +01:00
|
|
|
{ /* vehicle_status_s::ARMING_STATE_STANDBY */ true, true, true, true, false, false, false },
|
|
|
|
|
{ /* vehicle_status_s::ARMING_STATE_ARMED */ false, true, true, false, false, false, true },
|
|
|
|
|
{ /* vehicle_status_s::ARMING_STATE_ARMED_ERROR */ false, false, true, true, false, false, false },
|
2015-03-08 14:51:59 +01:00
|
|
|
{ /* vehicle_status_s::ARMING_STATE_STANDBY_ERROR */ true, true, true, true, true, false, false },
|
2015-01-28 07:58:42 +01:00
|
|
|
{ /* vehicle_status_s::ARMING_STATE_REBOOT */ true, true, false, false, true, true, true },
|
|
|
|
|
{ /* vehicle_status_s::ARMING_STATE_IN_AIR_RESTORE */ false, 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
|
2015-01-28 07:58:42 +01:00
|
|
|
static const char * const state_names[vehicle_status_s::ARMING_STATE_MAX] = {
|
2014-05-11 13:36:51 +02:00
|
|
|
"ARMING_STATE_INIT",
|
|
|
|
|
"ARMING_STATE_STANDBY",
|
|
|
|
|
"ARMING_STATE_ARMED",
|
|
|
|
|
"ARMING_STATE_ARMED_ERROR",
|
|
|
|
|
"ARMING_STATE_STANDBY_ERROR",
|
|
|
|
|
"ARMING_STATE_REBOOT",
|
|
|
|
|
"ARMING_STATE_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
|
|
|
|
|
static int last_prearm_ret = 1; ///< initialize to fail
|
|
|
|
|
|
2016-02-25 17:00:39 +00:00
|
|
|
transition_result_t arming_state_transition(struct vehicle_status_s *status,
|
2016-04-07 16:19:20 +02:00
|
|
|
struct battery_status_s *battery,
|
2016-02-25 17:00:39 +00:00
|
|
|
const struct safety_s *safety,
|
|
|
|
|
arming_state_t new_arming_state,
|
|
|
|
|
struct actuator_armed_s *armed,
|
|
|
|
|
bool fRunPreArmChecks,
|
2016-02-26 11:01:12 +00:00
|
|
|
orb_advert_t *mavlink_log_pub, ///< uORB handle for mavlink log
|
|
|
|
|
status_flags_s *status_flags,
|
|
|
|
|
float avionics_power_rail_voltage)
|
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
|
2015-01-28 07:58:42 +01:00
|
|
|
ASSERT(vehicle_status_s::ARMING_STATE_INIT == 0);
|
|
|
|
|
ASSERT(vehicle_status_s::ARMING_STATE_IN_AIR_RESTORE == vehicle_status_s::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
|
|
|
|
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
|
|
|
|
|
*/
|
|
|
|
|
int prearm_ret = OK;
|
|
|
|
|
|
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
|
|
|
|
|
&& status->hil_state == vehicle_status_s::HIL_STATE_OFF) {
|
2015-11-19 17:48:39 +01:00
|
|
|
|
2016-02-24 08:00:33 +00:00
|
|
|
prearm_ret = preflight_check(status, mavlink_log_pub, true /* pre-arm */, false /* force_report */,
|
2016-04-07 16:19:20 +02:00
|
|
|
status_flags, battery);
|
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-04-24 19:32:32 -04:00
|
|
|
&& (new_arming_state == vehicle_status_s::ARMING_STATE_ARMED
|
|
|
|
|
|| new_arming_state == vehicle_status_s::ARMING_STATE_STANDBY)
|
2016-01-22 11:31:39 +01:00
|
|
|
&& status->hil_state == vehicle_status_s::HIL_STATE_OFF) {
|
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) {
|
2016-04-11 12:02:23 +02:00
|
|
|
prearm_ret = preflight_check(status, mavlink_log_pub, false /* pre-flight */, false /* force_report */,
|
2016-04-07 16:19:20 +02:00
|
|
|
status_flags, battery);
|
2016-02-25 17:00:39 +00:00
|
|
|
status_flags->condition_system_sensors_initialized = !prearm_ret;
|
2016-01-22 11:31:39 +01:00
|
|
|
last_preflight_check = hrt_absolute_time();
|
|
|
|
|
last_prearm_ret = prearm_ret;
|
|
|
|
|
} else {
|
|
|
|
|
prearm_ret = last_prearm_ret;
|
|
|
|
|
}
|
2014-06-26 12:11:39 +02:00
|
|
|
}
|
|
|
|
|
|
|
|
|
|
/*
|
|
|
|
|
* Perform an atomic state update
|
|
|
|
|
*/
|
2015-06-25 21:45:17 +02:00
|
|
|
#ifdef __PX4_NUTTX
|
2016-05-28 14:56:17 +02:00
|
|
|
irqstate_t flags = px4_enter_critical_section();
|
2015-06-25 21:45:17 +02:00
|
|
|
#endif
|
2014-06-26 12:11:39 +02:00
|
|
|
|
2013-10-06 14:18:28 +02:00
|
|
|
/* enforce lockdown in HIL */
|
2015-01-28 07:58:42 +01:00
|
|
|
if (status->hil_state == vehicle_status_s::HIL_STATE_ON) {
|
2013-10-06 14:18:28 +02:00
|
|
|
armed->lockdown = true;
|
2015-04-22 00:38:03 +02:00
|
|
|
prearm_ret = OK;
|
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 &&
|
|
|
|
|
status->hil_state == vehicle_status_s::HIL_STATE_OFF) {
|
2014-06-24 21:33:03 +02:00
|
|
|
|
2014-06-26 12:11:39 +02:00
|
|
|
// Fail transition if pre-arm check fails
|
|
|
|
|
if (prearm_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;
|
|
|
|
|
|
2014-06-24 21:33:03 +02:00
|
|
|
// Fail transition if we need safety switch press
|
2014-06-26 12:11:39 +02:00
|
|
|
} else if (safety->safety_switch_available && !safety->safety_off) {
|
2013-03-25 14:53:54 -07:00
|
|
|
|
2016-03-15 18:25:02 +00:00
|
|
|
mavlink_and_console_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-03-15 18:25:02 +00:00
|
|
|
mavlink_and_console_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) {
|
|
|
|
|
mavlink_and_console_log_critical(mavlink_log_pub, "NOT ARMING: Avionics power low: %6.2f Volt", (double)avionics_power_rail_voltage);
|
2014-08-24 13:32:46 +02:00
|
|
|
feedback_provided = true;
|
|
|
|
|
valid_transition = false;
|
2016-02-26 11:01:12 +00:00
|
|
|
} else if (avionics_power_rail_voltage < 4.9f) {
|
|
|
|
|
mavlink_and_console_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-02-26 11:01:12 +00:00
|
|
|
} else if (avionics_power_rail_voltage > 5.4f) {
|
|
|
|
|
mavlink_and_console_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
|
|
|
|
2015-01-28 07:58:42 +01:00
|
|
|
} else if (new_arming_state == vehicle_status_s::ARMING_STATE_STANDBY && status->arming_state == vehicle_status_s::ARMING_STATE_ARMED_ERROR) {
|
|
|
|
|
new_arming_state = vehicle_status_s::ARMING_STATE_STANDBY_ERROR;
|
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
|
2015-01-28 07:58:42 +01:00
|
|
|
if (status->hil_state == vehicle_status_s::HIL_STATE_ON && 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-04-07 16:19:20 +02:00
|
|
|
mavlink_and_console_log_critical(mavlink_log_pub, "Preflight check resolved, reboot before arming");
|
2015-04-26 12:04:16 +02:00
|
|
|
} else {
|
2016-03-15 18:25:02 +00:00
|
|
|
mavlink_and_console_log_critical(mavlink_log_pub, "Preflight check failed, refusing to arm");
|
2015-04-26 12:04:16 +02:00
|
|
|
}
|
|
|
|
|
feedback_provided = true;
|
|
|
|
|
|
|
|
|
|
} else if ((new_arming_state == vehicle_status_s::ARMING_STATE_STANDBY) &&
|
2016-02-25 17:00:39 +00:00
|
|
|
status_flags->condition_system_sensors_initialized) {
|
2016-04-07 16:19:20 +02:00
|
|
|
mavlink_and_console_log_critical(mavlink_log_pub, "Preflight check resolved, reboot to complete");
|
2015-04-26 12:04:16 +02:00
|
|
|
feedback_provided = true;
|
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
|
|
|
|
2015-05-21 17:25:37 +02:00
|
|
|
// Sensors need to be initialized for STANDBY state, except for HIL
|
|
|
|
|
} else if ((status->hil_state != vehicle_status_s::HIL_STATE_ON) &&
|
|
|
|
|
(new_arming_state == vehicle_status_s::ARMING_STATE_STANDBY) &&
|
|
|
|
|
(status->arming_state != vehicle_status_s::ARMING_STATE_STANDBY_ERROR) &&
|
2016-02-25 17:00:39 +00:00
|
|
|
(!status_flags->condition_system_sensors_initialized)) {
|
|
|
|
|
if ((!status_flags->condition_system_prearm_error_reported &&
|
|
|
|
|
status_flags->condition_system_hotplug_timeout) ||
|
2015-11-10 19:33:14 +05:30
|
|
|
(new_arming_state == vehicle_status_s::ARMING_STATE_ARMED)) {
|
2016-04-24 13:26:27 -04:00
|
|
|
|
2016-04-10 10:57:38 -07:00
|
|
|
mavlink_and_console_log_critical(mavlink_log_pub, "Not ready to fly: Sensors not set up correctly");
|
2016-02-25 17:00:39 +00:00
|
|
|
status_flags->condition_system_prearm_error_reported = true;
|
2015-09-23 18:36:29 +02:00
|
|
|
}
|
2015-05-21 17:25:37 +02:00
|
|
|
feedback_provided = true;
|
|
|
|
|
valid_transition = false;
|
2015-04-19 23:15:51 +02:00
|
|
|
}
|
|
|
|
|
|
2014-05-11 13:36:51 +02:00
|
|
|
// Finish up the state transition
|
|
|
|
|
if (valid_transition) {
|
2015-01-28 07:58:42 +01:00
|
|
|
armed->armed = new_arming_state == vehicle_status_s::ARMING_STATE_ARMED || new_arming_state == vehicle_status_s::ARMING_STATE_ARMED_ERROR;
|
|
|
|
|
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;
|
2013-02-22 15:52:13 -08:00
|
|
|
}
|
|
|
|
|
|
2015-09-23 18:36:29 +02:00
|
|
|
/* reset feedback state */
|
2015-09-26 17:20:08 +02:00
|
|
|
if (status->arming_state != vehicle_status_s::ARMING_STATE_STANDBY_ERROR &&
|
2015-11-19 18:28:16 +01:00
|
|
|
status->arming_state != vehicle_status_s::ARMING_STATE_INIT &&
|
2015-09-26 17:20:08 +02:00
|
|
|
valid_transition) {
|
2016-02-25 17:00:39 +00:00
|
|
|
status_flags->condition_system_prearm_error_reported = false;
|
2015-09-23 18:36:29 +02:00
|
|
|
}
|
|
|
|
|
|
2014-06-26 12:11:39 +02:00
|
|
|
/* end of atomic state update */
|
2015-06-25 21:45:17 +02:00
|
|
|
#ifdef __PX4_NUTTX
|
2016-05-28 14:56:17 +02:00
|
|
|
px4_leave_critical_section(flags);
|
2015-06-25 21:45:17 +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) {
|
2016-04-10 10:57:38 -07:00
|
|
|
mavlink_and_console_log_critical(mavlink_log_pub, "TRANSITION_DENIED: %s - %s", state_names[status->arming_state], 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;
|
|
|
|
|
}
|
|
|
|
|
|
2013-08-27 23:08:00 +02:00
|
|
|
bool is_safe(const struct vehicle_status_s *status, const struct safety_s *safety, const struct 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
|
|
|
|
|
if (!armed->armed || (armed->armed && armed->lockdown) || (safety->safety_switch_available && !safety->safety_off)) {
|
|
|
|
|
return true;
|
2013-08-16 23:36:49 +02:00
|
|
|
|
2013-08-15 09:52:22 +02:00
|
|
|
} else {
|
|
|
|
|
return false;
|
|
|
|
|
}
|
|
|
|
|
}
|
|
|
|
|
|
2013-07-28 23:12:16 +04:00
|
|
|
transition_result_t
|
2016-02-25 17:00:39 +00:00
|
|
|
main_state_transition(struct vehicle_status_s *status, main_state_t new_main_state, uint8_t &main_state_prev,
|
2016-02-26 15:41:03 +00:00
|
|
|
status_flags_s *status_flags, struct commander_state_s *internal_state)
|
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_ACRO:
|
|
|
|
|
case commander_state_s::MAIN_STATE_RATTITUDE:
|
|
|
|
|
case commander_state_s::MAIN_STATE_STAB:
|
2014-01-31 22:44:05 +01:00
|
|
|
ret = TRANSITION_CHANGED;
|
|
|
|
|
break;
|
|
|
|
|
|
2016-02-26 15:41:03 +00:00
|
|
|
case commander_state_s::MAIN_STATE_ALTCTL:
|
2014-01-26 11:50:34 +01:00
|
|
|
/* need at minimum altitude estimate */
|
2014-05-27 21:56:32 +02:00
|
|
|
/* TODO: add this for fixedwing as well */
|
2014-01-26 11:52:33 +01:00
|
|
|
if (!status->is_rotary_wing ||
|
2016-02-25 17:00:39 +00:00
|
|
|
(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
|
|
|
}
|
|
|
|
|
break;
|
2013-01-11 07:42:09 +01:00
|
|
|
|
2016-02-26 15:41:03 +00:00
|
|
|
case commander_state_s::MAIN_STATE_POSCTL:
|
2014-01-26 11:50:34 +01:00
|
|
|
/* need at minimum local position estimate */
|
2016-02-25 17:00:39 +00: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;
|
|
|
|
|
}
|
|
|
|
|
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:
|
2014-01-26 11:50:34 +01:00
|
|
|
/* need global position estimate */
|
2016-02-25 17:00:39 +00: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
|
|
|
}
|
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:
|
|
|
|
|
case commander_state_s::MAIN_STATE_AUTO_MISSION:
|
|
|
|
|
case commander_state_s::MAIN_STATE_AUTO_RTL:
|
|
|
|
|
case commander_state_s::MAIN_STATE_AUTO_TAKEOFF:
|
|
|
|
|
case commander_state_s::MAIN_STATE_AUTO_LAND:
|
2014-05-27 21:56:32 +02:00
|
|
|
/* need global position and home position */
|
2016-02-25 17:00:39 +00: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;
|
|
|
|
|
}
|
2014-01-26 11:50:34 +01:00
|
|
|
break;
|
|
|
|
|
|
2016-02-26 15:41:03 +00:00
|
|
|
case commander_state_s::MAIN_STATE_OFFBOARD:
|
2014-01-22 17:04:07 +01:00
|
|
|
|
2014-05-16 12:12:43 +02:00
|
|
|
/* need offboard signal */
|
2016-02-26 10:20:52 +00:00
|
|
|
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
|
|
|
}
|
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;
|
|
|
|
|
}
|
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) {
|
|
|
|
|
main_state_prev = internal_state->main_state;
|
|
|
|
|
internal_state->main_state = new_main_state;
|
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-03-15 18:25:02 +00:00
|
|
|
transition_result_t hil_state_transition(hil_state_t new_state, orb_advert_t status_pub, struct 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:
|
2013-10-06 14:18:28 +02:00
|
|
|
/* we're in HIL and unexpected things can happen if we disable HIL now */
|
2016-03-15 18:25:02 +00:00
|
|
|
mavlink_and_console_log_critical(mavlink_log_pub, "Not switching off HIL (safety)");
|
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-25 21:45:17 +02:00
|
|
|
#ifdef __PX4_NUTTX
|
2014-05-27 21:56:32 +02:00
|
|
|
/* Disable publication of all attached sensors */
|
2014-01-12 11:47:35 +01:00
|
|
|
/* list directory */
|
|
|
|
|
DIR *d;
|
|
|
|
|
d = opendir("/dev");
|
2015-04-24 17:49:35 -07:00
|
|
|
|
2014-01-12 11:47:35 +01:00
|
|
|
if (d) {
|
2014-03-16 18:41:03 +01:00
|
|
|
struct dirent *direntry;
|
2014-03-16 19:16:18 +01:00
|
|
|
char devname[24];
|
2015-04-24 17:49:35 -07:00
|
|
|
|
2014-01-12 11:47:35 +01:00
|
|
|
while ((direntry = readdir(d)) != NULL) {
|
2015-04-24 17:49:35 -07:00
|
|
|
|
2014-03-16 18:50:20 +01:00
|
|
|
/* skip serial ports */
|
2014-03-16 19:16:18 +01:00
|
|
|
if (!strncmp("tty", direntry->d_name, 3)) {
|
2014-03-16 18:50:20 +01:00
|
|
|
continue;
|
|
|
|
|
}
|
2015-04-24 17:49:35 -07:00
|
|
|
|
2014-03-16 18:50:20 +01:00
|
|
|
/* skip mtd devices */
|
2014-03-16 19:16:18 +01:00
|
|
|
if (!strncmp("mtd", direntry->d_name, 3)) {
|
2014-03-16 18:50:20 +01:00
|
|
|
continue;
|
|
|
|
|
}
|
2015-04-24 17:49:35 -07:00
|
|
|
|
2014-03-16 18:50:20 +01:00
|
|
|
/* skip ram devices */
|
2014-03-16 19:16:18 +01:00
|
|
|
if (!strncmp("ram", direntry->d_name, 3)) {
|
|
|
|
|
continue;
|
|
|
|
|
}
|
2015-04-24 17:49:35 -07:00
|
|
|
|
2014-03-16 19:16:18 +01:00
|
|
|
/* skip MMC devices */
|
|
|
|
|
if (!strncmp("mmc", direntry->d_name, 3)) {
|
2014-03-16 18:50:20 +01:00
|
|
|
continue;
|
|
|
|
|
}
|
2015-04-24 17:49:35 -07:00
|
|
|
|
2014-03-16 18:50:20 +01:00
|
|
|
/* skip mavlink */
|
2014-03-16 19:16:18 +01:00
|
|
|
if (!strcmp("mavlink", direntry->d_name)) {
|
|
|
|
|
continue;
|
|
|
|
|
}
|
2015-04-24 17:49:35 -07:00
|
|
|
|
2014-03-16 19:16:18 +01:00
|
|
|
/* skip console */
|
|
|
|
|
if (!strcmp("console", direntry->d_name)) {
|
|
|
|
|
continue;
|
|
|
|
|
}
|
2015-04-24 17:49:35 -07:00
|
|
|
|
2014-03-16 19:16:18 +01:00
|
|
|
/* skip null */
|
|
|
|
|
if (!strcmp("null", direntry->d_name)) {
|
|
|
|
|
continue;
|
|
|
|
|
}
|
2015-04-24 17:49:35 -07:00
|
|
|
|
2014-03-16 19:16:18 +01:00
|
|
|
snprintf(devname, sizeof(devname), "/dev/%s", direntry->d_name);
|
2015-04-24 17:49:35 -07:00
|
|
|
|
2014-03-16 19:16:18 +01:00
|
|
|
int sensfd = ::open(devname, 0);
|
2015-04-24 17:49:35 -07:00
|
|
|
|
2014-03-16 19:16:18 +01:00
|
|
|
if (sensfd < 0) {
|
|
|
|
|
warn("failed opening device %s", devname);
|
2014-03-16 18:50:20 +01:00
|
|
|
continue;
|
|
|
|
|
}
|
2015-04-24 17:49:35 -07:00
|
|
|
|
2014-03-16 18:38:55 +01:00
|
|
|
int block_ret = ::ioctl(sensfd, DEVIOCSPUBBLOCK, 1);
|
2014-01-12 11:47:35 +01:00
|
|
|
close(sensfd);
|
2015-04-24 17:49:35 -07:00
|
|
|
|
2014-03-16 19:16:18 +01:00
|
|
|
printf("Disabling %s: %s\n", devname, (block_ret == OK) ? "OK" : "ERROR");
|
2014-01-12 11:47:35 +01:00
|
|
|
}
|
|
|
|
|
closedir(d);
|
2015-04-24 17:49:35 -07:00
|
|
|
|
2015-06-29 16:24:34 +02:00
|
|
|
ret = TRANSITION_CHANGED;
|
2016-03-15 18:25:02 +00:00
|
|
|
mavlink_and_console_log_critical(mavlink_log_pub, "Switched to ON hil state");
|
2015-04-24 17:49:35 -07:00
|
|
|
|
2015-06-29 16:24:34 +02:00
|
|
|
} else {
|
|
|
|
|
/* failed opening dir */
|
2016-03-15 18:25:02 +00:00
|
|
|
mavlink_log_info(mavlink_log_pub, "FAILED LISTING DEVICE ROOT DIRECTORY");
|
2015-06-29 16:24:34 +02:00
|
|
|
ret = TRANSITION_DENIED;
|
|
|
|
|
}
|
2015-04-24 17:49:35 -07:00
|
|
|
|
2015-06-29 16:24:34 +02:00
|
|
|
#else
|
2015-04-24 17:49:35 -07:00
|
|
|
|
2015-11-16 13:51:39 -08:00
|
|
|
// Handle VDev devices
|
|
|
|
|
const char *devname;
|
|
|
|
|
unsigned int handle = 0;
|
|
|
|
|
for(;;) {
|
|
|
|
|
devname = px4_get_device_names(&handle);
|
|
|
|
|
if (devname == NULL)
|
|
|
|
|
break;
|
|
|
|
|
|
|
|
|
|
/* skip mavlink */
|
|
|
|
|
if (!strcmp("/dev/mavlink", devname)) {
|
|
|
|
|
continue;
|
|
|
|
|
}
|
2015-04-24 17:49:35 -07:00
|
|
|
|
|
|
|
|
|
2015-11-16 13:51:39 -08:00
|
|
|
int sensfd = px4_open(devname, 0);
|
2015-04-24 17:49:35 -07:00
|
|
|
|
2015-11-16 13:51:39 -08:00
|
|
|
if (sensfd < 0) {
|
|
|
|
|
warn("failed opening device %s", devname);
|
|
|
|
|
continue;
|
|
|
|
|
}
|
2015-04-24 17:49:35 -07:00
|
|
|
|
2015-11-16 13:51:39 -08:00
|
|
|
int block_ret = px4_ioctl(sensfd, DEVIOCSPUBBLOCK, 1);
|
|
|
|
|
px4_close(sensfd);
|
|
|
|
|
|
|
|
|
|
printf("Disabling %s: %s\n", devname, (block_ret == OK) ? "OK" : "ERROR");
|
|
|
|
|
}
|
2013-02-22 09:32:49 -08:00
|
|
|
|
2015-11-12 15:31:38 +01:00
|
|
|
|
2015-11-16 13:51:39 -08:00
|
|
|
// Handle DF devices
|
2015-11-19 19:03:10 -08:00
|
|
|
const char *df_dev_path;
|
2015-11-16 13:51:39 -08:00
|
|
|
unsigned int index = 0;
|
|
|
|
|
for(;;) {
|
2015-11-19 19:03:10 -08:00
|
|
|
if (DevMgr::getNextDeviceName(index, &df_dev_path) < 0) {
|
2015-11-16 13:51:39 -08:00
|
|
|
break;
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
DevHandle h;
|
2015-11-19 19:03:10 -08:00
|
|
|
DevMgr::getHandle(df_dev_path, h);
|
2015-11-16 13:51:39 -08:00
|
|
|
|
|
|
|
|
if (!h.isValid()) {
|
2015-11-19 19:03:10 -08:00
|
|
|
warn("failed opening device %s", df_dev_path);
|
2015-11-16 13:51:39 -08:00
|
|
|
continue;
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
int block_ret = h.ioctl(DEVIOCSPUBBLOCK, 1);
|
|
|
|
|
DevMgr::releaseHandle(h);
|
|
|
|
|
|
2015-11-19 19:03:10 -08:00
|
|
|
printf("Disabling %s: %s\n", df_dev_path, (block_ret == OK) ? "OK" : "ERROR");
|
2015-11-16 13:51:39 -08:00
|
|
|
}
|
2015-06-29 16:24:34 +02:00
|
|
|
|
|
|
|
|
ret = TRANSITION_CHANGED;
|
2016-03-15 18:25:02 +00:00
|
|
|
mavlink_and_console_log_critical(mavlink_log_pub, "Switched to ON hil state");
|
2015-06-29 16:24:34 +02:00
|
|
|
#endif
|
|
|
|
|
|
2014-05-27 21:56:32 +02:00
|
|
|
} else {
|
2016-03-15 18:25:02 +00:00
|
|
|
mavlink_and_console_log_critical(mavlink_log_pub, "Not switching to HIL when armed");
|
2014-05-27 21:56:32 +02:00
|
|
|
ret = TRANSITION_DENIED;
|
2013-07-28 23:12:16 +04:00
|
|
|
}
|
|
|
|
|
break;
|
|
|
|
|
|
|
|
|
|
default:
|
2014-05-27 21:56:32 +02:00
|
|
|
warnx("Unknown HIL 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();
|
2013-09-08 21:06:55 +02:00
|
|
|
// XXX also set lockdown here
|
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
|
|
|
}
|
|
|
|
|
return ret;
|
|
|
|
|
}
|
2013-02-20 10:38:06 -08:00
|
|
|
|
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
|
|
|
|
|
*/
|
2016-02-26 15:41:03 +00:00
|
|
|
bool set_nav_state(struct vehicle_status_s *status, struct commander_state_s *internal_state,
|
|
|
|
|
const bool data_link_loss_enabled, const bool mission_finished,
|
2015-11-26 17:45:20 +01:00
|
|
|
const bool stay_in_failsafe, status_flags_s *status_flags, bool landed, const bool rc_loss_enabled,
|
|
|
|
|
const int offb_loss_act, const int offb_loss_rc_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;
|
|
|
|
|
|
2015-01-28 07:58:42 +01:00
|
|
|
bool armed = (status->arming_state == vehicle_status_s::ARMING_STATE_ARMED || status->arming_state == vehicle_status_s::ARMING_STATE_ARMED_ERROR);
|
2016-04-08 13:19:11 +02:00
|
|
|
status->failsafe = false;
|
2014-01-26 11:58:50 +01:00
|
|
|
|
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:
|
|
|
|
|
case commander_state_s::MAIN_STATE_POSCTL:
|
2014-06-16 17:34:21 +02:00
|
|
|
/* require RC for all manual modes */
|
2016-04-23 16:51:10 +02:00
|
|
|
if (rc_loss_enabled && (status->rc_signal_lost || status_flags->rc_signal_lost_cmd) && armed && !landed) {
|
2016-04-08 13:19:11 +02:00
|
|
|
status->failsafe = true;
|
2014-01-26 11:52:33 +01:00
|
|
|
|
2016-02-25 17:00:39 +00:00
|
|
|
if (status_flags->condition_global_position_valid && status_flags->condition_home_position_valid) {
|
2015-01-28 07:58:42 +01:00
|
|
|
status->nav_state = vehicle_status_s::NAVIGATION_STATE_AUTO_RCRECOVER;
|
2016-02-25 17:00:39 +00:00
|
|
|
} else if (status_flags->condition_local_position_valid) {
|
2016-03-13 15:39:35 +01:00
|
|
|
status->nav_state = vehicle_status_s::NAVIGATION_STATE_AUTO_LAND;
|
2016-02-25 17:00:39 +00:00
|
|
|
} else if (status_flags->condition_local_altitude_valid) {
|
2015-01-28 07:58:42 +01:00
|
|
|
status->nav_state = vehicle_status_s::NAVIGATION_STATE_DESCEND;
|
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_TERMINATION;
|
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;
|
|
|
|
|
|
2016-02-26 15:41:03 +00:00
|
|
|
case commander_state_s::MAIN_STATE_POSCTL:
|
2015-01-28 07:58:42 +01:00
|
|
|
status->nav_state = vehicle_status_s::NAVIGATION_STATE_POSCTL;
|
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;
|
|
|
|
|
}
|
|
|
|
|
}
|
|
|
|
|
break;
|
2014-01-26 11:52:33 +01:00
|
|
|
|
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
|
|
|
|
|
|
|
|
/* first look at the commands */
|
2014-08-14 22:38:48 +02:00
|
|
|
if (status->engine_failure_cmd) {
|
2015-01-28 07:58:42 +01:00
|
|
|
status->nav_state = vehicle_status_s::NAVIGATION_STATE_AUTO_LANDENGFAIL;
|
2016-02-26 11:01:12 +00:00
|
|
|
} else if (status_flags->data_link_lost_cmd) {
|
2015-01-28 07:58:42 +01:00
|
|
|
status->nav_state = vehicle_status_s::NAVIGATION_STATE_AUTO_RTGS;
|
2016-02-26 11:01:12 +00:00
|
|
|
} else if (status_flags->gps_failure_cmd) {
|
2015-01-28 07:58:42 +01:00
|
|
|
status->nav_state = vehicle_status_s::NAVIGATION_STATE_AUTO_LANDGPSFAIL;
|
2016-02-26 11:01:12 +00:00
|
|
|
} else if (status_flags->rc_signal_lost_cmd) {
|
2015-01-28 07:58:42 +01:00
|
|
|
status->nav_state = vehicle_status_s::NAVIGATION_STATE_AUTO_RCRECOVER;
|
2016-02-26 11:01:12 +00:00
|
|
|
} else if (status_flags->vtol_transition_failure_cmd) {
|
2016-02-05 13:06:51 +01:00
|
|
|
status->nav_state = vehicle_status_s::NAVIGATION_STATE_AUTO_RTL;
|
2014-11-10 21:40:13 +10:00
|
|
|
|
|
|
|
|
/* finished handling commands which have priority, now handle failures */
|
2016-02-26 11:01:12 +00:00
|
|
|
} else if (status_flags->gps_failure) {
|
2015-01-28 07:58:42 +01:00
|
|
|
status->nav_state = vehicle_status_s::NAVIGATION_STATE_AUTO_LANDGPSFAIL;
|
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-02-26 11:01:12 +00: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-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
|
|
|
|
2014-11-12 09:48:32 +10:00
|
|
|
/* datalink loss enabled:
|
|
|
|
|
* check for datalink lost: this should always trigger RTGS */
|
|
|
|
|
} else if (data_link_loss_enabled && status->data_link_lost) {
|
2016-04-08 13:19:11 +02:00
|
|
|
status->failsafe = true;
|
2013-12-08 16:52:41 +01:00
|
|
|
|
2016-02-25 17:00:39 +00:00
|
|
|
if (status_flags->condition_global_position_valid && status_flags->condition_home_position_valid) {
|
2015-01-28 07:58:42 +01:00
|
|
|
status->nav_state = vehicle_status_s::NAVIGATION_STATE_AUTO_RTGS;
|
2016-02-25 17:00:39 +00:00
|
|
|
} else if (status_flags->condition_local_position_valid) {
|
2016-03-13 15:39:35 +01:00
|
|
|
status->nav_state = vehicle_status_s::NAVIGATION_STATE_AUTO_LAND;
|
2016-02-25 17:00:39 +00:00
|
|
|
} else if (status_flags->condition_local_altitude_valid) {
|
2015-01-28 07:58:42 +01:00
|
|
|
status->nav_state = vehicle_status_s::NAVIGATION_STATE_DESCEND;
|
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_TERMINATION;
|
2014-06-18 19:01:41 +02:00
|
|
|
}
|
|
|
|
|
|
2014-11-12 09:48:32 +10:00
|
|
|
/* datalink loss disabled:
|
|
|
|
|
* check if both, RC and datalink are lost during the mission
|
|
|
|
|
* or RC is lost after the mission is finished: this should always trigger RCRECOVER */
|
|
|
|
|
} else if (!data_link_loss_enabled && ((status->rc_signal_lost && status->data_link_lost) ||
|
|
|
|
|
(status->rc_signal_lost && mission_finished))) {
|
2016-04-08 13:19:11 +02:00
|
|
|
status->failsafe = true;
|
2014-11-10 21:40:13 +10:00
|
|
|
|
2016-02-25 17:00:39 +00:00
|
|
|
if (status_flags->condition_global_position_valid && status_flags->condition_home_position_valid) {
|
2015-01-28 07:58:42 +01:00
|
|
|
status->nav_state = vehicle_status_s::NAVIGATION_STATE_AUTO_RCRECOVER;
|
2016-02-25 17:00:39 +00:00
|
|
|
} else if (status_flags->condition_local_position_valid) {
|
2016-03-13 15:39:35 +01:00
|
|
|
status->nav_state = vehicle_status_s::NAVIGATION_STATE_AUTO_LAND;
|
2016-02-25 17:00:39 +00:00
|
|
|
} else if (status_flags->condition_local_altitude_valid) {
|
2015-01-28 07:58:42 +01:00
|
|
|
status->nav_state = vehicle_status_s::NAVIGATION_STATE_DESCEND;
|
2014-11-10 21:40:13 +10:00
|
|
|
} else {
|
2015-01-28 07:58:42 +01:00
|
|
|
status->nav_state = vehicle_status_s::NAVIGATION_STATE_TERMINATION;
|
2014-06-17 13:19:50 +02:00
|
|
|
}
|
2014-06-18 19:01:41 +02:00
|
|
|
|
2014-11-11 10:28:24 +10:00
|
|
|
/* stay where you are if you should stay in failsafe, otherwise everything is perfect */
|
|
|
|
|
} else if (!stay_in_failsafe){
|
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
|
|
|
}
|
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:
|
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;
|
2014-06-18 19:01:41 +02:00
|
|
|
/* also go into failsafe if just datalink is lost */
|
|
|
|
|
} else if (status->data_link_lost && data_link_loss_enabled) {
|
2016-04-08 13:19:11 +02:00
|
|
|
status->failsafe = true;
|
2013-12-08 16:52:41 +01:00
|
|
|
|
2016-02-25 17:00:39 +00:00
|
|
|
if (status_flags->condition_global_position_valid && status_flags->condition_home_position_valid) {
|
2015-01-28 07:58:42 +01:00
|
|
|
status->nav_state = vehicle_status_s::NAVIGATION_STATE_AUTO_RTGS;
|
2016-02-25 17:00:39 +00:00
|
|
|
} else if (status_flags->condition_local_position_valid) {
|
2016-03-13 15:39:35 +01:00
|
|
|
status->nav_state = vehicle_status_s::NAVIGATION_STATE_AUTO_LAND;
|
2016-02-25 17:00:39 +00:00
|
|
|
} else if (status_flags->condition_local_altitude_valid) {
|
2015-01-28 07:58:42 +01:00
|
|
|
status->nav_state = vehicle_status_s::NAVIGATION_STATE_DESCEND;
|
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_TERMINATION;
|
2014-06-18 19:01:41 +02:00
|
|
|
}
|
|
|
|
|
|
|
|
|
|
/* go into failsafe if RC is lost and datalink loss is not set up */
|
|
|
|
|
} else if (status->rc_signal_lost && !data_link_loss_enabled) {
|
2016-04-08 13:19:11 +02:00
|
|
|
status->failsafe = true;
|
2014-06-18 19:01:41 +02:00
|
|
|
|
2016-02-25 17:00:39 +00:00
|
|
|
if (status_flags->condition_global_position_valid && status_flags->condition_home_position_valid) {
|
2015-01-28 07:58:42 +01:00
|
|
|
status->nav_state = vehicle_status_s::NAVIGATION_STATE_AUTO_RTGS;
|
2016-02-25 17:00:39 +00:00
|
|
|
} else if (status_flags->condition_local_position_valid) {
|
2016-03-13 15:39:35 +01:00
|
|
|
status->nav_state = vehicle_status_s::NAVIGATION_STATE_AUTO_LAND;
|
2016-02-25 17:00:39 +00:00
|
|
|
} else if (status_flags->condition_local_altitude_valid) {
|
2015-01-28 07:58:42 +01:00
|
|
|
status->nav_state = vehicle_status_s::NAVIGATION_STATE_DESCEND;
|
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_TERMINATION;
|
2014-06-18 19:01:41 +02:00
|
|
|
}
|
|
|
|
|
|
|
|
|
|
/* don't bother if RC is lost if datalink is connected */
|
|
|
|
|
} else if (status->rc_signal_lost) {
|
|
|
|
|
|
|
|
|
|
/* 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;
|
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
|
|
|
}
|
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:
|
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-02-25 17:00:39 +00:00
|
|
|
} else if ((!status_flags->condition_global_position_valid ||
|
|
|
|
|
!status_flags->condition_home_position_valid)) {
|
2016-04-08 13:19:11 +02:00
|
|
|
status->failsafe = true;
|
2013-12-08 16:52:41 +01:00
|
|
|
|
2016-02-25 17:00:39 +00:00
|
|
|
if (status_flags->condition_local_position_valid) {
|
2016-03-13 15:39:35 +01:00
|
|
|
status->nav_state = vehicle_status_s::NAVIGATION_STATE_AUTO_LAND;
|
2016-02-25 17:00:39 +00:00
|
|
|
} else if (status_flags->condition_local_altitude_valid) {
|
2015-01-28 07:58:42 +01:00
|
|
|
status->nav_state = vehicle_status_s::NAVIGATION_STATE_DESCEND;
|
2014-06-17 13:19:50 +02:00
|
|
|
} else {
|
2015-01-28 07:58:42 +01:00
|
|
|
status->nav_state = vehicle_status_s::NAVIGATION_STATE_TERMINATION;
|
2014-06-17 13:19:50 +02:00
|
|
|
}
|
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
|
|
|
}
|
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-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-02-26 15:41:03 +00:00
|
|
|
} else if (!status_flags->condition_global_position_valid) {
|
2016-02-18 06:57:01 -08:00
|
|
|
status->failsafe = true;
|
|
|
|
|
|
2016-02-26 15:41:03 +00:00
|
|
|
if (status_flags->condition_local_position_valid) {
|
2016-03-19 20:34:32 -07:00
|
|
|
status->nav_state = vehicle_status_s::NAVIGATION_STATE_AUTO_LAND;
|
2016-02-26 15:41:03 +00:00
|
|
|
} else if (status_flags->condition_local_altitude_valid) {
|
2016-02-18 06:57:01 -08:00
|
|
|
status->nav_state = vehicle_status_s::NAVIGATION_STATE_DESCEND;
|
|
|
|
|
} else {
|
|
|
|
|
status->nav_state = vehicle_status_s::NAVIGATION_STATE_TERMINATION;
|
|
|
|
|
}
|
|
|
|
|
} else {
|
|
|
|
|
status->nav_state = vehicle_status_s::NAVIGATION_STATE_AUTO_FOLLOW_TARGET;
|
|
|
|
|
}
|
|
|
|
|
break;
|
|
|
|
|
|
2016-04-04 13:23:30 +02:00
|
|
|
case commander_state_s::MAIN_STATE_AUTO_TAKEOFF:
|
2015-11-20 11:15:17 +01:00
|
|
|
/* require global position and home */
|
|
|
|
|
|
|
|
|
|
if (status->engine_failure) {
|
|
|
|
|
status->nav_state = vehicle_status_s::NAVIGATION_STATE_AUTO_LANDENGFAIL;
|
2016-02-25 17:00:39 +00:00
|
|
|
} else if ((!status_flags->condition_global_position_valid ||
|
|
|
|
|
!status_flags->condition_home_position_valid)) {
|
2016-04-08 13:19:11 +02:00
|
|
|
status->failsafe = true;
|
2015-11-20 11:15:17 +01:00
|
|
|
|
2016-02-25 17:00:39 +00:00
|
|
|
if (status_flags->condition_local_position_valid) {
|
2016-03-13 15:39:35 +01:00
|
|
|
status->nav_state = vehicle_status_s::NAVIGATION_STATE_AUTO_LAND;
|
2016-02-25 17:00:39 +00:00
|
|
|
} else if (status_flags->condition_local_altitude_valid) {
|
2015-11-20 11:15:17 +01:00
|
|
|
status->nav_state = vehicle_status_s::NAVIGATION_STATE_DESCEND;
|
|
|
|
|
} else {
|
|
|
|
|
status->nav_state = vehicle_status_s::NAVIGATION_STATE_TERMINATION;
|
|
|
|
|
}
|
|
|
|
|
} else {
|
|
|
|
|
status->nav_state = vehicle_status_s::NAVIGATION_STATE_AUTO_TAKEOFF;
|
|
|
|
|
}
|
|
|
|
|
break;
|
|
|
|
|
|
2016-02-26 15:41:03 +00:00
|
|
|
case commander_state_s::MAIN_STATE_AUTO_LAND:
|
2015-12-17 00:11:50 +01:00
|
|
|
/* require global position and home */
|
|
|
|
|
|
|
|
|
|
if (status->engine_failure) {
|
|
|
|
|
status->nav_state = vehicle_status_s::NAVIGATION_STATE_AUTO_LANDENGFAIL;
|
2016-02-25 17:00:39 +00:00
|
|
|
} else if ((!status_flags->condition_global_position_valid ||
|
|
|
|
|
!status_flags->condition_home_position_valid)) {
|
2016-04-08 13:19:11 +02:00
|
|
|
status->failsafe = true;
|
2015-12-17 00:11:50 +01:00
|
|
|
|
2016-02-25 17:00:39 +00:00
|
|
|
if (status_flags->condition_local_altitude_valid) {
|
2015-12-17 00:11:50 +01:00
|
|
|
status->nav_state = vehicle_status_s::NAVIGATION_STATE_DESCEND;
|
|
|
|
|
} else {
|
|
|
|
|
status->nav_state = vehicle_status_s::NAVIGATION_STATE_TERMINATION;
|
|
|
|
|
}
|
|
|
|
|
} 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
|
|
|
}
|
|
|
|
|
break;
|
|
|
|
|
|
2016-02-26 15:41:03 +00:00
|
|
|
case commander_state_s::MAIN_STATE_OFFBOARD:
|
2014-06-21 12:24:37 +02:00
|
|
|
/* require offboard control, otherwise stay where you are */
|
2016-02-26 10:20:52 +00:00
|
|
|
if (status_flags->offboard_control_signal_lost && !status->rc_signal_lost) {
|
2016-04-08 13:19:11 +02:00
|
|
|
status->failsafe = true;
|
2014-06-21 12:24:37 +02:00
|
|
|
|
2015-11-26 17:45:20 +01:00
|
|
|
if (status_flags->offboard_control_loss_timeout && offb_loss_rc_act < 5 && offb_loss_rc_act >= 0) {
|
|
|
|
|
if (status_flags->condition_global_position_valid && status_flags->condition_home_position_valid
|
|
|
|
|
&& offb_loss_rc_act == 3) {
|
|
|
|
|
status->nav_state = vehicle_status_s::NAVIGATION_STATE_AUTO_RTL;
|
|
|
|
|
|
|
|
|
|
} else if (status_flags->condition_global_position_valid && offb_loss_rc_act == 0) {
|
|
|
|
|
status->nav_state = vehicle_status_s::NAVIGATION_STATE_POSCTL;
|
|
|
|
|
|
|
|
|
|
} else if (status_flags->condition_local_altitude_valid && offb_loss_rc_act == 1) {
|
|
|
|
|
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;
|
|
|
|
|
|
|
|
|
|
} else if (status_flags->condition_global_position_valid && offb_loss_rc_act == 4) {
|
|
|
|
|
status->nav_state = vehicle_status_s::NAVIGATION_STATE_AUTO_LAND;
|
|
|
|
|
|
|
|
|
|
} else if (status_flags->condition_local_altitude_valid) {
|
|
|
|
|
status->nav_state = vehicle_status_s::NAVIGATION_STATE_DESCEND;
|
|
|
|
|
|
|
|
|
|
} else {
|
|
|
|
|
status->nav_state = vehicle_status_s::NAVIGATION_STATE_TERMINATION;
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
} else {
|
|
|
|
|
if (status_flags->condition_global_position_valid) {
|
|
|
|
|
status->nav_state = vehicle_status_s::NAVIGATION_STATE_POSCTL;
|
|
|
|
|
|
|
|
|
|
} else if (status_flags->condition_local_altitude_valid) {
|
|
|
|
|
status->nav_state = vehicle_status_s::NAVIGATION_STATE_ALTCTL;
|
|
|
|
|
|
|
|
|
|
} else {
|
|
|
|
|
status->nav_state = vehicle_status_s::NAVIGATION_STATE_TERMINATION;
|
|
|
|
|
}
|
|
|
|
|
}
|
|
|
|
|
|
2016-02-26 10:20:52 +00:00
|
|
|
} else if (status_flags->offboard_control_signal_lost && status->rc_signal_lost) {
|
2016-04-08 13:19:11 +02:00
|
|
|
status->failsafe = true;
|
2014-06-21 12:24:37 +02:00
|
|
|
|
2015-11-26 17:45:20 +01:00
|
|
|
if (status_flags->offboard_control_loss_timeout && offb_loss_act < 3 && offb_loss_act >= 0) {
|
|
|
|
|
if (status_flags->condition_global_position_valid && status_flags->condition_home_position_valid
|
|
|
|
|
&& offb_loss_rc_act == 2) {
|
|
|
|
|
status->nav_state = vehicle_status_s::NAVIGATION_STATE_AUTO_RTL;
|
|
|
|
|
|
|
|
|
|
} else if (status_flags->condition_global_position_valid && offb_loss_rc_act == 1) {
|
|
|
|
|
status->nav_state = vehicle_status_s::NAVIGATION_STATE_AUTO_LOITER;
|
|
|
|
|
|
|
|
|
|
} else if (status_flags->condition_global_position_valid && offb_loss_rc_act == 0) {
|
|
|
|
|
status->nav_state = vehicle_status_s::NAVIGATION_STATE_AUTO_LAND;
|
|
|
|
|
|
|
|
|
|
} else if (status_flags->condition_local_altitude_valid) {
|
|
|
|
|
status->nav_state = vehicle_status_s::NAVIGATION_STATE_DESCEND;
|
|
|
|
|
|
|
|
|
|
} else {
|
|
|
|
|
status->nav_state = vehicle_status_s::NAVIGATION_STATE_TERMINATION;
|
|
|
|
|
}
|
|
|
|
|
|
2014-06-21 12:24:37 +02:00
|
|
|
} else {
|
2015-11-26 17:45:20 +01:00
|
|
|
if (status_flags->condition_global_position_valid) {
|
|
|
|
|
status->nav_state = vehicle_status_s::NAVIGATION_STATE_AUTO_LOITER;
|
|
|
|
|
|
|
|
|
|
} else if (status_flags->condition_local_altitude_valid) {
|
|
|
|
|
status->nav_state = vehicle_status_s::NAVIGATION_STATE_DESCEND;
|
|
|
|
|
|
|
|
|
|
} 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
|
|
|
}
|
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
|
|
|
|
2016-04-07 16:19:20 +02:00
|
|
|
int preflight_check(struct vehicle_status_s *status, orb_advert_t *mavlink_log_pub, bool prearm, bool force_report, status_flags_s *status_flags, battery_status_s *battery)
|
2014-06-26 12:11:39 +02:00
|
|
|
{
|
2016-03-15 18:25:02 +00:00
|
|
|
/*
|
2015-04-19 23:07:32 +02:00
|
|
|
*/
|
2016-02-25 17:00:39 +00:00
|
|
|
bool reportFailures = force_report || (!status_flags->condition_system_prearm_error_reported &&
|
|
|
|
|
status_flags->condition_system_hotplug_timeout);
|
2016-03-15 18:25:02 +00:00
|
|
|
|
2015-04-19 23:07:32 +02:00
|
|
|
bool checkAirspeed = false;
|
2014-07-26 17:48:45 +02:00
|
|
|
/* Perform airspeed check only if circuit breaker is not
|
|
|
|
|
* engaged and it's not a rotary wing */
|
2016-02-25 17:00:39 +00:00
|
|
|
if (!status_flags->circuit_breaker_engaged_airspd_check && (!status->is_rotary_wing || status->is_vtol)) {
|
2015-04-19 23:07:32 +02:00
|
|
|
checkAirspeed = true;
|
2014-06-26 12:11:39 +02:00
|
|
|
}
|
|
|
|
|
|
2016-03-15 18:25:02 +00:00
|
|
|
bool preflight_ok = Commander::preflightCheck(mavlink_log_pub, true, true, true, true,
|
2015-11-20 11:15:17 +01:00
|
|
|
checkAirspeed, (status->rc_input_mode == vehicle_status_s::RC_IN_MODE_DEFAULT),
|
2016-02-25 17:00:39 +00:00
|
|
|
!status_flags->circuit_breaker_engaged_gpsfailure_check, true, reportFailures);
|
2016-03-15 18:25:02 +00:00
|
|
|
|
2016-06-14 15:09:07 -04:00
|
|
|
if (!status_flags->circuit_breaker_engaged_usb_check && status_flags->usb_connected && prearm) {
|
2015-11-10 19:33:14 +05:30
|
|
|
preflight_ok = false;
|
2015-11-19 17:48:39 +01:00
|
|
|
if (reportFailures) {
|
2016-04-10 10:57:38 -07:00
|
|
|
mavlink_and_console_log_critical(mavlink_log_pub, "ARMING DENIED: Flying with USB is not safe");
|
|
|
|
|
}
|
|
|
|
|
}
|
|
|
|
|
|
2016-04-07 16:19:20 +02:00
|
|
|
if (battery->warning == battery_status_s::BATTERY_WARNING_CRITICAL) {
|
2016-04-10 10:57:38 -07:00
|
|
|
preflight_ok = false;
|
|
|
|
|
if (reportFailures) {
|
|
|
|
|
mavlink_and_console_log_critical(mavlink_log_pub, "ARMING DENIED: VERY LOW BATTERY");
|
2015-11-19 17:48:39 +01:00
|
|
|
}
|
|
|
|
|
}
|
2015-10-23 17:47:22 +02:00
|
|
|
|
2015-11-19 17:48:39 +01:00
|
|
|
/* report once, then set the flag */
|
2016-03-15 18:25:02 +00:00
|
|
|
if (reportFailures && !preflight_ok) {
|
2016-02-25 17:00:39 +00:00
|
|
|
status_flags->condition_system_prearm_error_reported = true;
|
2015-10-23 17:47:22 +02:00
|
|
|
}
|
|
|
|
|
|
2015-11-10 19:33:14 +05:30
|
|
|
return !preflight_ok;
|
2014-06-26 12:11:39 +02:00
|
|
|
}
|