2015-05-13 03:09:36 -03:00
|
|
|
#include "Plane.h"
|
2019-04-04 08:06:47 -03:00
|
|
|
#include <AP_Common/AP_FWVersion.h>
|
2015-05-13 03:09:36 -03:00
|
|
|
|
2011-09-08 22:29:39 -03:00
|
|
|
/*****************************************************************************
|
2012-08-21 23:19:51 -03:00
|
|
|
* The init_ardupilot function processes everything we need for an in - air restart
|
|
|
|
* We will determine later if we are actually on the ground and process a
|
|
|
|
* ground start in that case.
|
|
|
|
*
|
2011-09-08 22:29:39 -03:00
|
|
|
*****************************************************************************/
|
|
|
|
|
2015-05-13 03:09:36 -03:00
|
|
|
static void mavlink_delay_cb_static()
|
|
|
|
{
|
|
|
|
plane.mavlink_delay_cb();
|
|
|
|
}
|
|
|
|
|
|
|
|
static void failsafe_check_static()
|
|
|
|
{
|
|
|
|
plane.failsafe_check();
|
|
|
|
}
|
|
|
|
|
|
|
|
void Plane::init_ardupilot()
|
2011-09-08 22:29:39 -03:00
|
|
|
{
|
2015-01-23 09:45:24 -04:00
|
|
|
// initialise serial port
|
|
|
|
serial_manager.init_console();
|
2011-09-08 22:29:39 -03:00
|
|
|
|
2017-08-19 06:50:44 -03:00
|
|
|
hal.console->printf("\n\nInit %s"
|
2017-08-11 01:31:18 -03:00
|
|
|
"\n\nFree RAM: %u\n",
|
2018-06-13 08:12:16 -03:00
|
|
|
AP::fwversion().fw_string,
|
2017-08-11 01:31:18 -03:00
|
|
|
(unsigned)hal.util->available_memory());
|
2011-09-08 22:29:39 -03:00
|
|
|
|
2011-11-13 00:10:30 -04:00
|
|
|
//
|
2012-12-04 18:22:21 -04:00
|
|
|
// Check the EEPROM format version before loading any parameters from EEPROM
|
2012-08-21 23:19:51 -03:00
|
|
|
//
|
2012-02-12 04:20:56 -04:00
|
|
|
load_parameters();
|
2011-09-08 22:29:39 -03:00
|
|
|
|
2018-02-28 08:22:16 -04:00
|
|
|
#if STATS_ENABLED == ENABLED
|
2016-10-25 22:24:41 -03:00
|
|
|
// initialise stats module
|
|
|
|
g2.stats.init();
|
2018-02-28 08:22:16 -04:00
|
|
|
#endif
|
2016-10-25 22:24:41 -03:00
|
|
|
|
2015-07-13 03:07:40 -03:00
|
|
|
#if HIL_SUPPORT
|
2015-03-13 08:33:48 -03:00
|
|
|
if (g.hil_mode == 1) {
|
|
|
|
// set sensors to HIL mode
|
|
|
|
ins.set_hil_mode();
|
|
|
|
compass.set_hil_mode();
|
|
|
|
barometer.set_hil_mode();
|
|
|
|
}
|
2015-07-13 03:07:40 -03:00
|
|
|
#endif
|
2015-03-13 08:33:48 -03:00
|
|
|
|
2017-06-27 02:14:45 -03:00
|
|
|
ins.set_log_raw_bit(MASK_LOG_IMU_RAW);
|
|
|
|
|
2016-06-30 03:48:30 -03:00
|
|
|
set_control_channels();
|
2014-11-05 06:18:04 -04:00
|
|
|
|
2016-10-16 19:20:55 -03:00
|
|
|
mavlink_system.sysid = g.sysid_this_mav;
|
|
|
|
|
2015-01-23 09:45:24 -04:00
|
|
|
// initialise serial ports
|
|
|
|
serial_manager.init();
|
2016-08-25 04:48:27 -03:00
|
|
|
gcs().chan(0).setup_uart(serial_manager, AP_SerialManager::SerialProtocol_MAVLink, 0);
|
2015-01-23 09:45:24 -04:00
|
|
|
|
2017-02-14 08:07:54 -04:00
|
|
|
|
2016-08-03 04:17:38 -03:00
|
|
|
// Register mavlink_delay_cb, which will run anytime you have
|
|
|
|
// more than 5ms remaining in your call to hal.scheduler->delay
|
|
|
|
hal.scheduler->register_delay_callback(mavlink_delay_cb_static, 5);
|
|
|
|
|
|
|
|
// setup any board specific drivers
|
|
|
|
BoardConfig.init();
|
2017-05-06 06:12:00 -03:00
|
|
|
#if HAL_WITH_UAVCAN
|
|
|
|
BoardConfig_CAN.init();
|
|
|
|
#endif
|
2016-02-21 20:06:09 -04:00
|
|
|
|
2018-04-26 22:01:37 -03:00
|
|
|
// initialise rc channels including setting mode
|
|
|
|
rc().init();
|
|
|
|
|
2017-03-01 03:24:32 -04:00
|
|
|
relay.init();
|
|
|
|
|
2017-01-21 02:16:27 -04:00
|
|
|
// initialise notify system
|
2018-07-25 22:10:33 -03:00
|
|
|
notify.init();
|
2019-01-15 13:46:13 -04:00
|
|
|
notify_mode(*control_mode);
|
2017-01-21 02:16:27 -04:00
|
|
|
|
2016-11-12 23:55:35 -04:00
|
|
|
init_rc_out_main();
|
|
|
|
|
2011-09-08 22:29:39 -03:00
|
|
|
// keep a record of how many resets have happened. This can be
|
|
|
|
// used to detect in-flight resets
|
|
|
|
g.num_resets.set_and_save(g.num_resets+1);
|
|
|
|
|
2017-08-11 01:31:18 -03:00
|
|
|
// init baro
|
2013-05-05 21:57:57 -03:00
|
|
|
barometer.init();
|
|
|
|
|
2014-08-26 08:17:47 -03:00
|
|
|
// initialise rangefinder
|
2019-04-05 06:20:05 -03:00
|
|
|
rangefinder.set_log_rfnd_bit(MASK_LOG_SONAR);
|
2019-04-05 06:14:50 -03:00
|
|
|
rangefinder.init(ROTATION_PITCH_270);
|
2013-10-30 19:23:21 -03:00
|
|
|
|
2014-08-08 23:29:20 -03:00
|
|
|
// initialise battery monitoring
|
|
|
|
battery.init();
|
|
|
|
|
2015-09-24 07:58:18 -03:00
|
|
|
rpm_sensor.init();
|
|
|
|
|
2016-05-16 00:33:43 -03:00
|
|
|
// setup telem slots with serial ports
|
2016-08-25 04:48:27 -03:00
|
|
|
gcs().setup_uarts(serial_manager);
|
2015-05-15 01:24:39 -03:00
|
|
|
|
2018-06-23 04:11:05 -03:00
|
|
|
#if OSD_ENABLED == ENABLED
|
2018-06-23 04:35:28 -03:00
|
|
|
osd.init();
|
2018-06-23 04:11:05 -03:00
|
|
|
#endif
|
|
|
|
|
2011-12-21 08:29:22 -04:00
|
|
|
#if LOGGING_ENABLED == ENABLED
|
2015-05-13 03:09:36 -03:00
|
|
|
log_init();
|
2011-12-21 08:29:22 -04:00
|
|
|
#endif
|
2011-09-08 22:29:39 -03:00
|
|
|
|
2013-06-02 22:40:44 -03:00
|
|
|
// initialise airspeed sensor
|
|
|
|
airspeed.init();
|
|
|
|
|
2019-03-25 09:43:04 -03:00
|
|
|
AP::compass().set_log_bit(MASK_LOG_COMPASS);
|
2019-03-24 00:27:03 -03:00
|
|
|
AP::compass().init();
|
|
|
|
|
2015-07-10 01:50:35 -03:00
|
|
|
#if OPTFLOW == ENABLED
|
2015-01-02 20:09:02 -04:00
|
|
|
// make optflow available to libraries
|
2016-07-11 19:44:04 -03:00
|
|
|
if (optflow.enabled()) {
|
|
|
|
ahrs.set_optflow(&optflow);
|
|
|
|
}
|
2015-07-10 01:50:35 -03:00
|
|
|
#endif
|
2011-09-08 22:29:39 -03:00
|
|
|
|
2012-08-10 19:57:44 -03:00
|
|
|
// give AHRS the airspeed sensor
|
|
|
|
ahrs.set_airspeed(&airspeed);
|
|
|
|
|
2012-06-10 03:36:18 -03:00
|
|
|
// GPS Initialization
|
2017-06-27 05:13:24 -03:00
|
|
|
gps.set_log_gps_bit(MASK_LOG_GPS);
|
|
|
|
gps.init(serial_manager);
|
2013-12-21 07:27:15 -04:00
|
|
|
|
2012-08-21 23:19:51 -03:00
|
|
|
init_rc_in(); // sets up rc channels from radio
|
2011-09-08 22:29:39 -03:00
|
|
|
|
2015-01-27 09:12:12 -04:00
|
|
|
#if MOUNT == ENABLED
|
2015-01-08 16:12:08 -04:00
|
|
|
// initialise camera mount
|
2017-08-23 21:59:47 -03:00
|
|
|
camera_mount.init(serial_manager);
|
2015-01-27 09:12:12 -04:00
|
|
|
#endif
|
2015-01-08 16:12:08 -04:00
|
|
|
|
2018-06-10 03:33:06 -03:00
|
|
|
#if LANDING_GEAR_ENABLED == ENABLED
|
|
|
|
// initialise landing gear position
|
|
|
|
g2.landing_gear.init();
|
|
|
|
gear.last_auto_cmd = -1;
|
|
|
|
gear.last_cmd = -1;
|
|
|
|
#endif
|
|
|
|
|
2011-12-16 15:28:25 -04:00
|
|
|
#if FENCE_TRIGGERED_PIN > 0
|
2014-06-01 20:28:27 -03:00
|
|
|
hal.gpio->pinMode(FENCE_TRIGGERED_PIN, HAL_GPIO_OUTPUT);
|
|
|
|
hal.gpio->write(FENCE_TRIGGERED_PIN, 0);
|
2011-12-16 15:28:25 -04:00
|
|
|
#endif
|
|
|
|
|
2011-12-22 20:11:59 -04:00
|
|
|
/*
|
2012-08-21 23:19:51 -03:00
|
|
|
* setup the 'main loop is dead' check. Note that this relies on
|
|
|
|
* the RC library being initialised.
|
2011-12-22 20:11:59 -04:00
|
|
|
*/
|
2015-05-13 03:09:36 -03:00
|
|
|
hal.scheduler->register_timer_failsafe(failsafe_check_static, 1000);
|
2011-12-22 20:11:59 -04:00
|
|
|
|
2015-11-24 04:24:04 -04:00
|
|
|
quadplane.setup();
|
2016-01-04 18:38:02 -04:00
|
|
|
|
2018-06-26 12:54:36 -03:00
|
|
|
AP_Param::reload_defaults_file(true);
|
2017-01-09 05:52:49 -04:00
|
|
|
|
2016-04-02 17:49:38 -03:00
|
|
|
startup_ground();
|
|
|
|
|
2016-06-30 03:48:30 -03:00
|
|
|
// don't initialise aux rc output until after quadplane is setup as
|
2016-01-04 18:38:02 -04:00
|
|
|
// that can change initial values of channels
|
2016-06-30 03:48:30 -03:00
|
|
|
init_rc_out_aux();
|
2015-11-24 04:24:04 -04:00
|
|
|
|
2013-04-11 21:25:46 -03:00
|
|
|
// choose the nav controller
|
|
|
|
set_nav_controller();
|
|
|
|
|
2019-01-15 13:46:13 -04:00
|
|
|
set_mode_by_number((enum Mode::Number)g.initial_mode.get(), MODE_REASON_UNKNOWN);
|
2011-09-08 22:29:39 -03:00
|
|
|
|
2012-08-21 23:19:51 -03:00
|
|
|
// set the correct flight mode
|
|
|
|
// ---------------------------
|
|
|
|
reset_control_switch();
|
2014-10-13 04:51:10 -03:00
|
|
|
|
|
|
|
// initialise sensor
|
2014-11-03 03:33:56 -04:00
|
|
|
#if OPTFLOW == ENABLED
|
2016-07-11 19:44:04 -03:00
|
|
|
if (optflow.enabled()) {
|
2018-09-02 09:26:19 -03:00
|
|
|
optflow.init(-1);
|
2016-07-11 17:46:16 -03:00
|
|
|
}
|
2014-11-03 03:33:56 -04:00
|
|
|
#endif
|
|
|
|
|
2018-02-22 05:13:38 -04:00
|
|
|
// init cargo gripper
|
|
|
|
#if GRIPPER_ENABLED == ENABLED
|
|
|
|
g2.gripper.init();
|
|
|
|
#endif
|
|
|
|
|
2017-04-29 21:48:01 -03:00
|
|
|
// disable safety if requested
|
|
|
|
BoardConfig.init_safety();
|
2011-09-08 22:29:39 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
//********************************************************************************
|
|
|
|
//This function does all the calibrations, etc. that we need during a ground start
|
|
|
|
//********************************************************************************
|
2015-05-13 03:09:36 -03:00
|
|
|
void Plane::startup_ground(void)
|
2011-09-08 22:29:39 -03:00
|
|
|
{
|
2019-01-15 13:46:13 -04:00
|
|
|
set_mode(mode_initializing, MODE_REASON_UNKNOWN);
|
2011-09-08 22:29:39 -03:00
|
|
|
|
2012-08-21 23:19:51 -03:00
|
|
|
#if (GROUND_START_DELAY > 0)
|
2017-07-08 22:15:58 -03:00
|
|
|
gcs().send_text(MAV_SEVERITY_NOTICE,"Ground start with delay");
|
2012-08-21 23:19:51 -03:00
|
|
|
delay(GROUND_START_DELAY * 1000);
|
2017-03-04 04:31:24 -04:00
|
|
|
#else
|
2017-07-08 22:15:58 -03:00
|
|
|
gcs().send_text(MAV_SEVERITY_INFO,"Ground start");
|
2012-08-21 23:19:51 -03:00
|
|
|
#endif
|
2011-09-08 22:29:39 -03:00
|
|
|
|
2012-11-05 00:32:13 -04:00
|
|
|
//INS ground start
|
2012-08-21 23:19:51 -03:00
|
|
|
//------------------------
|
2011-09-08 22:29:39 -03:00
|
|
|
//
|
2015-03-10 20:16:59 -03:00
|
|
|
startup_INS_ground();
|
2011-09-08 22:29:39 -03:00
|
|
|
|
2012-08-21 23:19:51 -03:00
|
|
|
// Save the settings for in-air restart
|
|
|
|
// ------------------------------------
|
|
|
|
//save_EEPROM_groundstart();
|
2011-09-08 22:29:39 -03:00
|
|
|
|
2014-03-11 01:06:45 -03:00
|
|
|
// initialise mission library
|
|
|
|
mission.init();
|
|
|
|
|
2019-01-18 00:23:42 -04:00
|
|
|
// initialise AP_Logger library
|
2018-04-20 03:42:37 -03:00
|
|
|
#if LOGGING_ENABLED == ENABLED
|
2019-01-18 00:24:08 -04:00
|
|
|
logger.setVehicle_Startup_Writer(
|
2017-05-01 03:08:35 -03:00
|
|
|
FUNCTOR_BIND(&plane, &Plane::Log_Write_Vehicle_Startup_Messages, void)
|
|
|
|
);
|
2018-04-20 03:42:37 -03:00
|
|
|
#endif
|
2017-05-01 03:08:35 -03:00
|
|
|
|
2018-09-27 20:03:56 -03:00
|
|
|
#ifdef ENABLE_SCRIPTING
|
|
|
|
if (!g2.scripting.init()) {
|
|
|
|
gcs().send_text(MAV_SEVERITY_ERROR, "Scripting failed to start");
|
|
|
|
}
|
|
|
|
#endif // ENABLE_SCRIPTING
|
|
|
|
|
2012-12-25 17:46:36 -04:00
|
|
|
// reset last heartbeat time, so we don't trigger failsafe on slow
|
|
|
|
// startup
|
2015-05-13 19:05:32 -03:00
|
|
|
failsafe.last_heartbeat_ms = millis();
|
2012-12-25 17:46:36 -04:00
|
|
|
|
2012-03-30 03:06:03 -03:00
|
|
|
// we don't want writes to the serial port to cause us to pause
|
|
|
|
// mid-flight, so set the serial ports non-blocking once we are
|
|
|
|
// ready to fly
|
2015-01-23 09:45:24 -04:00
|
|
|
serial_manager.set_blocking_writes_all(false);
|
2012-03-30 03:06:03 -03:00
|
|
|
|
2017-07-08 22:15:58 -03:00
|
|
|
gcs().send_text(MAV_SEVERITY_INFO,"Ground start complete");
|
2011-09-08 22:29:39 -03:00
|
|
|
}
|
|
|
|
|
2014-02-13 18:49:42 -04:00
|
|
|
|
2019-01-15 13:46:13 -04:00
|
|
|
bool Plane::set_mode(Mode &new_mode, const mode_reason_t reason)
|
2011-09-08 22:29:39 -03:00
|
|
|
{
|
2019-04-01 14:43:12 -03:00
|
|
|
if (control_mode == &new_mode) {
|
|
|
|
// don't switch modes if we are already in the correct mode.
|
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
2018-12-07 03:52:05 -04:00
|
|
|
#if !QAUTOTUNE_ENABLED
|
2019-04-07 18:56:08 -03:00
|
|
|
if (&new_mode == &plane.mode_qautotune) {
|
2018-12-07 03:52:05 -04:00
|
|
|
gcs().send_text(MAV_SEVERITY_INFO,"QAUTOTUNE disabled");
|
2019-04-07 18:56:08 -03:00
|
|
|
set_mode(plane.mode_qhover, MODE_REASON_UNAVAILABLE);
|
|
|
|
return false;
|
2018-12-07 03:52:05 -04:00
|
|
|
}
|
|
|
|
#endif
|
|
|
|
|
2019-01-15 13:46:13 -04:00
|
|
|
// backup current control_mode and previous_mode
|
|
|
|
Mode &old_previous_mode = *previous_mode;
|
|
|
|
Mode &old_mode = *control_mode;
|
2019-04-01 14:54:34 -03:00
|
|
|
const mode_reason_t previous_mode_reason_backup = previous_mode_reason;
|
2015-06-03 16:22:24 -03:00
|
|
|
|
2019-01-15 13:46:13 -04:00
|
|
|
// update control_mode assuming success
|
|
|
|
// TODO: move these to be after enter() once start_command_callback() no longer checks control_mode
|
2014-02-13 18:49:42 -04:00
|
|
|
previous_mode = control_mode;
|
2019-01-15 13:46:13 -04:00
|
|
|
control_mode = &new_mode;
|
2016-08-13 04:54:37 -03:00
|
|
|
previous_mode_reason = control_mode_reason;
|
|
|
|
control_mode_reason = reason;
|
2012-08-21 23:19:51 -03:00
|
|
|
|
2019-01-15 13:46:13 -04:00
|
|
|
// attempt to enter new mode
|
|
|
|
if (!new_mode.enter()) {
|
|
|
|
// Log error that we failed to enter desired flight mode
|
|
|
|
gcs().send_text(MAV_SEVERITY_WARNING, "Flight mode change failed");
|
2018-07-29 19:57:55 -03:00
|
|
|
|
2019-01-15 13:46:13 -04:00
|
|
|
// we failed entering new mode, roll back to old
|
|
|
|
previous_mode = &old_previous_mode;
|
|
|
|
control_mode = &old_mode;
|
2019-04-01 14:54:34 -03:00
|
|
|
|
|
|
|
control_mode_reason = previous_mode_reason;
|
|
|
|
previous_mode_reason = previous_mode_reason_backup;
|
|
|
|
|
|
|
|
// currently, only Q modes can fail enter(). This will likely change in the future and all modes
|
|
|
|
// should be changed to check dependencies and fail early before depending on changes in Mode::set_mode()
|
|
|
|
if (control_mode->is_vtol_mode()) {
|
|
|
|
// ignore result because if we fail we risk looping at the qautotune check above
|
|
|
|
control_mode->enter();
|
|
|
|
}
|
2019-01-15 13:46:13 -04:00
|
|
|
return false;
|
2012-08-21 23:19:51 -03:00
|
|
|
}
|
|
|
|
|
2019-04-01 14:43:12 -03:00
|
|
|
if (previous_mode == &mode_autotune) {
|
|
|
|
// restore last gains
|
|
|
|
autotune_restore();
|
|
|
|
}
|
|
|
|
|
2019-01-15 13:46:13 -04:00
|
|
|
// exit previous mode
|
|
|
|
old_mode.exit();
|
2016-07-10 21:23:08 -03:00
|
|
|
|
2019-01-15 13:46:13 -04:00
|
|
|
// record reasons
|
|
|
|
previous_mode_reason = control_mode_reason;
|
|
|
|
control_mode_reason = reason;
|
2013-06-01 09:29:28 -03:00
|
|
|
|
2019-01-15 13:46:13 -04:00
|
|
|
// log and notify mode change
|
|
|
|
logger.Write_Mode(control_mode->mode_number(), control_mode_reason);
|
|
|
|
notify_mode(*control_mode);
|
2017-01-20 06:15:51 -04:00
|
|
|
|
2019-01-15 13:46:13 -04:00
|
|
|
return true;
|
2011-09-08 22:29:39 -03:00
|
|
|
}
|
|
|
|
|
2019-01-15 13:46:13 -04:00
|
|
|
bool Plane::set_mode_by_number(const Mode::Number new_mode_number, const mode_reason_t reason)
|
2014-03-14 09:40:47 -03:00
|
|
|
{
|
2019-01-15 13:46:13 -04:00
|
|
|
Mode *new_mode = plane.mode_from_mode_num(new_mode_number);
|
|
|
|
if (new_mode == nullptr) {
|
|
|
|
gcs().send_text(MAV_SEVERITY_INFO, "Error: invalid mode number: %d", new_mode_number);
|
|
|
|
return false;
|
2014-03-14 09:40:47 -03:00
|
|
|
}
|
2019-01-15 13:46:13 -04:00
|
|
|
return set_mode(*new_mode, reason);
|
2014-03-14 09:40:47 -03:00
|
|
|
}
|
|
|
|
|
2015-05-13 03:09:36 -03:00
|
|
|
void Plane::check_long_failsafe()
|
2011-09-08 22:29:39 -03:00
|
|
|
{
|
2015-05-13 19:05:32 -03:00
|
|
|
uint32_t tnow = millis();
|
2012-08-21 23:19:51 -03:00
|
|
|
// only act on changes
|
|
|
|
// -------------------
|
2017-01-11 01:29:03 -04:00
|
|
|
if (failsafe.state != FAILSAFE_LONG && failsafe.state != FAILSAFE_GCS && flight_stage != AP_Vehicle::FixedWing::FLIGHT_LAND) {
|
2017-09-21 03:53:15 -03:00
|
|
|
uint32_t radio_timeout_ms = failsafe.last_valid_rc_ms;
|
2017-09-24 23:04:01 -03:00
|
|
|
if (failsafe.state == FAILSAFE_SHORT) {
|
2017-09-21 03:53:15 -03:00
|
|
|
// time is relative to when short failsafe enabled
|
2017-10-27 17:21:28 -03:00
|
|
|
radio_timeout_ms = failsafe.short_timer_ms;
|
2017-09-21 03:53:15 -03:00
|
|
|
}
|
2017-10-27 17:21:28 -03:00
|
|
|
if (failsafe.rc_failsafe &&
|
2017-12-06 19:02:11 -04:00
|
|
|
(tnow - radio_timeout_ms) > g.fs_timeout_long*1000) {
|
2016-08-13 04:54:37 -03:00
|
|
|
failsafe_long_on_event(FAILSAFE_LONG, MODE_REASON_RADIO_FAILSAFE);
|
2019-01-15 13:46:13 -04:00
|
|
|
} else if (g.gcs_heartbeat_fs_enabled == GCS_FAILSAFE_HB_AUTO && control_mode == &mode_auto &&
|
2015-05-09 07:51:24 -03:00
|
|
|
failsafe.last_heartbeat_ms != 0 &&
|
2017-12-06 19:02:11 -04:00
|
|
|
(tnow - failsafe.last_heartbeat_ms) > g.fs_timeout_long*1000) {
|
2016-08-13 04:54:37 -03:00
|
|
|
failsafe_long_on_event(FAILSAFE_GCS, MODE_REASON_GCS_FAILSAFE);
|
2015-05-09 07:51:24 -03:00
|
|
|
} else if (g.gcs_heartbeat_fs_enabled == GCS_FAILSAFE_HEARTBEAT &&
|
2013-12-19 20:39:00 -04:00
|
|
|
failsafe.last_heartbeat_ms != 0 &&
|
2017-12-06 19:02:11 -04:00
|
|
|
(tnow - failsafe.last_heartbeat_ms) > g.fs_timeout_long*1000) {
|
2016-08-13 04:54:37 -03:00
|
|
|
failsafe_long_on_event(FAILSAFE_GCS, MODE_REASON_GCS_FAILSAFE);
|
2013-12-19 20:39:00 -04:00
|
|
|
} else if (g.gcs_heartbeat_fs_enabled == GCS_FAILSAFE_HB_RSSI &&
|
2016-08-25 04:48:27 -03:00
|
|
|
gcs().chan(0).last_radio_status_remrssi_ms != 0 &&
|
2017-12-06 19:02:11 -04:00
|
|
|
(tnow - gcs().chan(0).last_radio_status_remrssi_ms) > g.fs_timeout_long*1000) {
|
2016-08-13 04:54:37 -03:00
|
|
|
failsafe_long_on_event(FAILSAFE_GCS, MODE_REASON_GCS_FAILSAFE);
|
2012-08-21 23:19:51 -03:00
|
|
|
}
|
|
|
|
} else {
|
2017-12-06 19:02:11 -04:00
|
|
|
uint32_t timeout_seconds = g.fs_timeout_long;
|
|
|
|
if (g.fs_action_short != FS_ACTION_SHORT_DISABLED) {
|
2017-09-21 03:53:15 -03:00
|
|
|
// avoid dropping back into short timeout
|
2017-12-06 19:02:11 -04:00
|
|
|
timeout_seconds = g.fs_timeout_short;
|
2017-09-21 03:53:15 -03:00
|
|
|
}
|
2012-08-21 23:19:51 -03:00
|
|
|
// We do not change state but allow for user to change mode
|
2013-07-19 01:11:16 -03:00
|
|
|
if (failsafe.state == FAILSAFE_GCS &&
|
2017-09-21 03:53:15 -03:00
|
|
|
(tnow - failsafe.last_heartbeat_ms) < timeout_seconds*1000) {
|
2017-09-22 00:31:44 -03:00
|
|
|
failsafe_long_off_event(MODE_REASON_GCS_FAILSAFE);
|
2013-07-19 01:11:16 -03:00
|
|
|
} else if (failsafe.state == FAILSAFE_LONG &&
|
2017-10-27 17:21:28 -03:00
|
|
|
!failsafe.rc_failsafe) {
|
2017-09-22 00:31:44 -03:00
|
|
|
failsafe_long_off_event(MODE_REASON_RADIO_FAILSAFE);
|
2013-07-11 22:56:04 -03:00
|
|
|
}
|
2012-08-21 23:19:51 -03:00
|
|
|
}
|
2011-09-08 22:29:39 -03:00
|
|
|
}
|
|
|
|
|
2015-05-13 03:09:36 -03:00
|
|
|
void Plane::check_short_failsafe()
|
2011-09-08 22:29:39 -03:00
|
|
|
{
|
2012-08-21 23:19:51 -03:00
|
|
|
// only act on changes
|
|
|
|
// -------------------
|
2017-12-06 19:02:11 -04:00
|
|
|
if (g.fs_action_short != FS_ACTION_SHORT_DISABLED &&
|
2017-09-21 03:53:15 -03:00
|
|
|
failsafe.state == FAILSAFE_NONE &&
|
|
|
|
flight_stage != AP_Vehicle::FixedWing::FLIGHT_LAND) {
|
2017-10-27 17:21:28 -03:00
|
|
|
// The condition is checked and the flag rc_failsafe is set in radio.cpp
|
|
|
|
if(failsafe.rc_failsafe) {
|
2016-08-13 04:54:37 -03:00
|
|
|
failsafe_short_on_event(FAILSAFE_SHORT, MODE_REASON_RADIO_FAILSAFE);
|
2012-08-21 23:19:51 -03:00
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2013-07-19 01:11:16 -03:00
|
|
|
if(failsafe.state == FAILSAFE_SHORT) {
|
2017-12-06 19:02:11 -04:00
|
|
|
if(!failsafe.rc_failsafe || g.fs_action_short == FS_ACTION_SHORT_DISABLED) {
|
2016-08-13 04:54:37 -03:00
|
|
|
failsafe_short_off_event(MODE_REASON_RADIO_FAILSAFE);
|
2012-08-21 23:19:51 -03:00
|
|
|
}
|
|
|
|
}
|
2011-09-08 22:29:39 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
|
2015-05-13 03:09:36 -03:00
|
|
|
void Plane::startup_INS_ground(void)
|
2011-09-08 22:29:39 -03:00
|
|
|
{
|
2015-07-13 03:07:40 -03:00
|
|
|
#if HIL_SUPPORT
|
2015-03-13 08:33:48 -03:00
|
|
|
if (g.hil_mode == 1) {
|
|
|
|
while (barometer.get_last_update() == 0) {
|
|
|
|
// the barometer begins updating when we get the first
|
|
|
|
// HIL_STATE message
|
2017-07-08 22:15:58 -03:00
|
|
|
gcs().send_text(MAV_SEVERITY_WARNING, "Waiting for first HIL_STATE message");
|
2015-03-13 08:33:48 -03:00
|
|
|
hal.scheduler->delay(1000);
|
|
|
|
}
|
2013-01-03 20:29:19 -04:00
|
|
|
}
|
2015-07-13 03:07:40 -03:00
|
|
|
#endif
|
2013-01-03 20:29:19 -04:00
|
|
|
|
2015-09-17 09:32:06 -03:00
|
|
|
if (ins.gyro_calibration_timing() != AP_InertialSensor::GYRO_CAL_NEVER) {
|
2017-07-08 22:15:58 -03:00
|
|
|
gcs().send_text(MAV_SEVERITY_ALERT, "Beginning INS calibration. Do not move plane");
|
2019-04-11 06:51:43 -03:00
|
|
|
} else {
|
|
|
|
gcs().send_text(MAV_SEVERITY_ALERT, "Skipping INS calibration");
|
2013-07-19 22:33:09 -03:00
|
|
|
}
|
2011-09-08 22:29:39 -03:00
|
|
|
|
2013-01-13 01:04:18 -04:00
|
|
|
ahrs.init();
|
|
|
|
ahrs.set_fly_forward(true);
|
2014-04-21 04:12:24 -03:00
|
|
|
ahrs.set_vehicle_class(AHRS_VEHICLE_FIXED_WING);
|
2013-05-23 22:21:32 -03:00
|
|
|
ahrs.set_wind_estimation(true);
|
2013-01-13 01:04:18 -04:00
|
|
|
|
2015-12-25 23:12:39 -04:00
|
|
|
ins.init(scheduler.get_loop_rate_hz());
|
2012-03-11 05:13:31 -03:00
|
|
|
ahrs.reset();
|
2011-09-08 22:29:39 -03:00
|
|
|
|
2012-08-21 23:19:51 -03:00
|
|
|
// read Baro pressure at ground
|
|
|
|
//-----------------------------
|
2018-04-11 09:48:34 -03:00
|
|
|
barometer.set_log_baro_bit(MASK_LOG_IMU);
|
2018-03-18 01:22:12 -03:00
|
|
|
barometer.calibrate();
|
2011-09-08 22:29:39 -03:00
|
|
|
|
2012-07-15 22:21:50 -03:00
|
|
|
if (airspeed.enabled()) {
|
2011-11-20 21:05:43 -04:00
|
|
|
// initialize airspeed sensor
|
|
|
|
// --------------------------
|
2018-03-27 23:29:46 -03:00
|
|
|
airspeed.calibrate(true);
|
2011-11-20 21:05:43 -04:00
|
|
|
} else {
|
2017-07-08 22:15:58 -03:00
|
|
|
gcs().send_text(MAV_SEVERITY_WARNING,"No airspeed");
|
2011-11-20 21:05:43 -04:00
|
|
|
}
|
2011-09-08 22:29:39 -03:00
|
|
|
}
|
|
|
|
|
2017-01-20 06:15:51 -04:00
|
|
|
// sets notify object flight mode information
|
2019-01-15 13:46:13 -04:00
|
|
|
void Plane::notify_mode(const Mode& mode)
|
2017-01-20 06:15:51 -04:00
|
|
|
{
|
2019-01-15 13:46:13 -04:00
|
|
|
notify.flags.flight_mode = mode.mode_number();
|
|
|
|
notify.set_flight_mode_str(mode.name4());
|
2017-01-20 06:15:51 -04:00
|
|
|
}
|
|
|
|
|
2014-01-13 22:07:43 -04:00
|
|
|
/*
|
|
|
|
should we log a message type now?
|
|
|
|
*/
|
2015-05-13 03:09:36 -03:00
|
|
|
bool Plane::should_log(uint32_t mask)
|
2014-01-13 22:07:43 -04:00
|
|
|
{
|
2015-08-06 10:25:22 -03:00
|
|
|
#if LOGGING_ENABLED == ENABLED
|
2019-01-18 00:23:42 -04:00
|
|
|
return logger.should_log(mask);
|
2015-08-06 10:25:22 -03:00
|
|
|
#else
|
|
|
|
return false;
|
|
|
|
#endif
|
2014-01-13 22:07:43 -04:00
|
|
|
}
|
2014-07-29 08:38:15 -03:00
|
|
|
|
2014-08-03 04:16:51 -03:00
|
|
|
/*
|
2016-01-30 02:38:31 -04:00
|
|
|
return throttle percentage from 0 to 100 for normal use and -100 to 100 when using reverse thrust
|
2014-08-03 04:16:51 -03:00
|
|
|
*/
|
2016-01-30 02:38:31 -04:00
|
|
|
int8_t Plane::throttle_percentage(void)
|
2014-08-03 04:16:51 -03:00
|
|
|
{
|
2016-05-11 02:14:43 -03:00
|
|
|
if (quadplane.in_vtol_mode()) {
|
2016-01-03 06:38:51 -04:00
|
|
|
return quadplane.throttle_percentage();
|
|
|
|
}
|
2018-05-21 00:40:41 -03:00
|
|
|
float throttle = SRV_Channels::get_output_scaled(SRV_Channel::k_throttle);
|
2018-11-09 18:38:43 -04:00
|
|
|
if (!have_reverse_thrust()) {
|
2018-05-21 00:40:41 -03:00
|
|
|
return constrain_int16(throttle, 0, 100);
|
2016-02-09 01:46:56 -04:00
|
|
|
}
|
2018-05-21 00:40:41 -03:00
|
|
|
return constrain_int16(throttle, -100, 100);
|
2014-08-03 04:16:51 -03:00
|
|
|
}
|
2015-02-22 04:39:58 -04:00
|
|
|
|
|
|
|
/*
|
|
|
|
update AHRS soft arm state and log as needed
|
|
|
|
*/
|
2015-05-13 03:09:36 -03:00
|
|
|
void Plane::change_arm_state(void)
|
2015-02-22 04:39:58 -04:00
|
|
|
{
|
|
|
|
Log_Arm_Disarm();
|
2016-07-28 03:37:28 -03:00
|
|
|
update_soft_armed();
|
2015-11-24 04:24:04 -04:00
|
|
|
quadplane.set_armed(hal.util->get_soft_armed());
|
2015-02-22 04:39:58 -04:00
|
|
|
}
|
2015-03-16 20:09:37 -03:00
|
|
|
|
|
|
|
/*
|
|
|
|
arm motors
|
|
|
|
*/
|
2019-03-06 23:12:56 -04:00
|
|
|
bool Plane::arm_motors(const AP_Arming::Method method, const bool do_arming_checks)
|
2015-03-16 20:09:37 -03:00
|
|
|
{
|
2016-09-26 10:03:06 -03:00
|
|
|
if (!arming.arm(method, do_arming_checks)) {
|
2015-03-16 20:09:37 -03:00
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
|
|
|
change_arm_state();
|
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
|
|
|
/*
|
|
|
|
disarm motors
|
|
|
|
*/
|
2015-05-13 03:09:36 -03:00
|
|
|
bool Plane::disarm_motors(void)
|
2015-03-16 20:09:37 -03:00
|
|
|
{
|
|
|
|
if (!arming.disarm()) {
|
|
|
|
return false;
|
|
|
|
}
|
2019-01-15 13:46:13 -04:00
|
|
|
if (control_mode != &mode_auto) {
|
2015-03-16 20:09:37 -03:00
|
|
|
// reset the mission on disarm if we are not in auto
|
|
|
|
mission.reset();
|
|
|
|
}
|
|
|
|
|
|
|
|
// suppress the throttle in auto-throttle modes
|
|
|
|
throttle_suppressed = auto_throttle_mode;
|
|
|
|
|
|
|
|
//only log if disarming was successful
|
|
|
|
change_arm_state();
|
|
|
|
|
2016-04-27 01:36:13 -03:00
|
|
|
// reload target airspeed which could have been modified by a mission
|
2016-11-17 21:07:10 -04:00
|
|
|
plane.aparm.airspeed_cruise_cm.load();
|
2016-04-27 01:36:13 -03:00
|
|
|
|
2018-12-07 03:52:05 -04:00
|
|
|
#if QAUTOTUNE_ENABLED
|
|
|
|
//save qautotune gains if enabled and success
|
|
|
|
quadplane.qautotune.save_tuning_gains();
|
|
|
|
#endif
|
|
|
|
|
2015-03-16 20:09:37 -03:00
|
|
|
return true;
|
2016-01-19 01:26:14 -04:00
|
|
|
}
|