2015-05-13 03:09:36 -03:00
|
|
|
#include "Plane.h"
|
|
|
|
|
2021-09-10 03:28:21 -03:00
|
|
|
#include "qautotune.h"
|
|
|
|
|
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 failsafe_check_static()
|
|
|
|
{
|
|
|
|
plane.failsafe_check();
|
|
|
|
}
|
|
|
|
|
|
|
|
void Plane::init_ardupilot()
|
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
|
|
|
|
2017-06-27 02:14:45 -03:00
|
|
|
ins.set_log_raw_bit(MASK_LOG_IMU_RAW);
|
|
|
|
|
2016-08-03 04:17:38 -03:00
|
|
|
// setup any board specific drivers
|
|
|
|
BoardConfig.init();
|
2020-05-31 08:49:22 -03:00
|
|
|
|
|
|
|
#if HAL_MAX_CAN_PROTOCOL_DRIVERS
|
|
|
|
can_mgr.init();
|
2017-05-06 06:12:00 -03:00
|
|
|
#endif
|
2016-02-21 20:06:09 -04:00
|
|
|
|
2021-02-27 06:29:49 -04:00
|
|
|
rollController.convert_pid();
|
|
|
|
pitchController.convert_pid();
|
|
|
|
|
2018-04-26 22:01:37 -03:00
|
|
|
// initialise rc channels including setting mode
|
2021-09-13 21:11:36 -03:00
|
|
|
#if HAL_QUADPLANE_ENABLED
|
2022-08-05 12:08:59 -03:00
|
|
|
rc().convert_options(RC_Channel::AUX_FUNC::ARMDISARM_UNUSED, (quadplane.enabled() && quadplane.option_is_set(QuadPlane::OPTION::AIRMODE_UNUSED) && (rc().find_channel_for_option(RC_Channel::AUX_FUNC::AIRMODE) == nullptr)) ? RC_Channel::AUX_FUNC::ARMDISARM_AIRMODE : RC_Channel::AUX_FUNC::ARMDISARM);
|
2021-09-13 21:11:36 -03:00
|
|
|
#else
|
|
|
|
rc().convert_options(RC_Channel::AUX_FUNC::ARMDISARM_UNUSED, RC_Channel::AUX_FUNC::ARMDISARM);
|
|
|
|
#endif
|
2021-09-20 22:47:33 -03:00
|
|
|
rc().init();
|
2018-04-26 22:01:37 -03:00
|
|
|
|
2023-06-06 05:05:07 -03:00
|
|
|
#if AP_RELAY_ENABLED
|
2017-03-01 03:24:32 -04:00
|
|
|
relay.init();
|
2023-06-06 05:05:07 -03:00
|
|
|
#endif
|
2017-03-01 03:24:32 -04:00
|
|
|
|
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
|
|
|
|
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();
|
|
|
|
|
2020-01-16 01:15:45 -04:00
|
|
|
rssi.init();
|
|
|
|
|
2022-07-21 01:34:31 -03:00
|
|
|
#if AP_RPM_ENABLED
|
2015-09-24 07:58:18 -03:00
|
|
|
rpm_sensor.init();
|
2022-07-21 01:34:31 -03:00
|
|
|
#endif
|
2015-09-24 07:58:18 -03:00
|
|
|
|
2016-05-16 00:33:43 -03:00
|
|
|
// setup telem slots with serial ports
|
2019-06-19 01:24:56 -03:00
|
|
|
gcs().setup_uarts();
|
2015-05-15 01:24:39 -03:00
|
|
|
|
2019-11-06 20:43:07 -04: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
|
|
|
|
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();
|
|
|
|
|
2022-01-02 03:41:27 -04:00
|
|
|
#if AP_AIRSPEED_ENABLED
|
2022-12-06 16:36:30 -04:00
|
|
|
airspeed.set_fixedwing_parameters(&aparm);
|
2022-01-02 03:41:27 -04:00
|
|
|
airspeed.set_log_bit(MASK_LOG_IMU);
|
|
|
|
#endif
|
|
|
|
|
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
|
|
|
|
2020-07-24 14:23:23 -03:00
|
|
|
#if HAL_MOUNT_ENABLED
|
2015-01-08 16:12:08 -04:00
|
|
|
// initialise camera mount
|
2019-08-27 03:24:05 -03:00
|
|
|
camera_mount.init();
|
2015-01-27 09:12:12 -04:00
|
|
|
#endif
|
2015-01-08 16:12:08 -04:00
|
|
|
|
2023-02-14 00:03:56 -04:00
|
|
|
#if AP_CAMERA_ENABLED
|
|
|
|
// initialise camera
|
|
|
|
camera.init();
|
|
|
|
#endif
|
|
|
|
|
2022-10-01 07:21:38 -03:00
|
|
|
#if AP_LANDINGGEAR_ENABLED
|
2018-06-10 03:33:06 -03:00
|
|
|
// initialise landing gear position
|
|
|
|
g2.landing_gear.init();
|
|
|
|
#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
|
|
|
|
2021-09-10 03:28:21 -03:00
|
|
|
#if HAL_QUADPLANE_ENABLED
|
2015-11-24 04:24:04 -04:00
|
|
|
quadplane.setup();
|
2021-09-10 03:28:21 -03:00
|
|
|
#endif
|
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();
|
2021-07-17 05:11:28 -03:00
|
|
|
|
|
|
|
if (g2.oneshot_mask != 0) {
|
|
|
|
hal.rcout->set_output_mode(g2.oneshot_mask, AP_HAL::RCOutput::MODE_PWM_ONESHOT);
|
|
|
|
}
|
|
|
|
|
2020-07-24 14:52:07 -03:00
|
|
|
set_mode_by_number((enum Mode::Number)g.initial_mode.get(), ModeReason::INITIALISED);
|
2011-09-08 22:29:39 -03:00
|
|
|
|
2012-08-21 23:19:51 -03:00
|
|
|
// set the correct flight mode
|
|
|
|
// ---------------------------
|
2022-07-13 22:10:43 -03:00
|
|
|
rc().reset_mode_switch();
|
2014-10-13 04:51:10 -03:00
|
|
|
|
|
|
|
// initialise sensor
|
2021-12-24 04:17:51 -04:00
|
|
|
#if AP_OPTICALFLOW_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
|
2022-09-20 04:37:48 -03:00
|
|
|
#if AP_GRIPPER_ENABLED
|
2018-02-22 05:13:38 -04:00
|
|
|
g2.gripper.init();
|
|
|
|
#endif
|
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
|
|
|
{
|
2020-07-24 14:52:07 -03:00
|
|
|
set_mode(mode_initializing, ModeReason::INITIALISED);
|
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
|
|
|
|
2021-11-15 01:08:34 -04:00
|
|
|
#if AP_SCRIPTING_ENABLED
|
2019-11-26 01:40:44 -04:00
|
|
|
g2.scripting.init();
|
2021-11-15 01:08:34 -04:00
|
|
|
#endif // AP_SCRIPTING_ENABLED
|
2018-09-27 20:03:56 -03:00
|
|
|
|
2012-12-25 17:46:36 -04:00
|
|
|
// reset last heartbeat time, so we don't trigger failsafe on slow
|
|
|
|
// startup
|
2021-02-04 22:28:08 -04:00
|
|
|
gcs().sysid_myggcs_seen(AP_HAL::millis());
|
2011-09-08 22:29:39 -03:00
|
|
|
}
|
|
|
|
|
2014-02-13 18:49:42 -04:00
|
|
|
|
2022-10-23 16:19:09 -03:00
|
|
|
#if AP_FENCE_ENABLED
|
|
|
|
/*
|
|
|
|
return true if a mode reason is an automatic mode change due to
|
|
|
|
landing sequencing.
|
|
|
|
*/
|
|
|
|
static bool mode_reason_is_landing_sequence(const ModeReason reason)
|
|
|
|
{
|
|
|
|
switch (reason) {
|
|
|
|
case ModeReason::RTL_COMPLETE_SWITCHING_TO_FIXEDWING_AUTOLAND:
|
|
|
|
case ModeReason::RTL_COMPLETE_SWITCHING_TO_VTOL_LAND_RTL:
|
|
|
|
case ModeReason::QRTL_INSTEAD_OF_RTL:
|
|
|
|
case ModeReason::QLAND_INSTEAD_OF_RTL:
|
|
|
|
return true;
|
|
|
|
default:
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
#endif // AP_FENCE_ENABLED
|
|
|
|
|
2023-06-18 12:31:10 -03:00
|
|
|
// Check if this mode can be entered from the GCS
|
|
|
|
bool Plane::gcs_mode_enabled(const Mode::Number mode_num) const
|
|
|
|
{
|
|
|
|
// List of modes that can be blocked, index is bit number in parameter bitmask
|
|
|
|
static const uint8_t mode_list [] {
|
|
|
|
(uint8_t)Mode::Number::MANUAL,
|
|
|
|
(uint8_t)Mode::Number::CIRCLE,
|
|
|
|
(uint8_t)Mode::Number::STABILIZE,
|
|
|
|
(uint8_t)Mode::Number::TRAINING,
|
|
|
|
(uint8_t)Mode::Number::ACRO,
|
|
|
|
(uint8_t)Mode::Number::FLY_BY_WIRE_A,
|
|
|
|
(uint8_t)Mode::Number::FLY_BY_WIRE_B,
|
|
|
|
(uint8_t)Mode::Number::CRUISE,
|
|
|
|
(uint8_t)Mode::Number::AUTOTUNE,
|
|
|
|
(uint8_t)Mode::Number::AUTO,
|
|
|
|
(uint8_t)Mode::Number::LOITER,
|
|
|
|
(uint8_t)Mode::Number::TAKEOFF,
|
|
|
|
(uint8_t)Mode::Number::AVOID_ADSB,
|
|
|
|
(uint8_t)Mode::Number::GUIDED,
|
|
|
|
(uint8_t)Mode::Number::THERMAL,
|
|
|
|
#if HAL_QUADPLANE_ENABLED
|
|
|
|
(uint8_t)Mode::Number::QSTABILIZE,
|
|
|
|
(uint8_t)Mode::Number::QHOVER,
|
|
|
|
(uint8_t)Mode::Number::QLOITER,
|
|
|
|
(uint8_t)Mode::Number::QACRO,
|
|
|
|
#if QAUTOTUNE_ENABLED
|
|
|
|
(uint8_t)Mode::Number::QAUTOTUNE
|
|
|
|
#endif
|
|
|
|
#endif
|
|
|
|
};
|
|
|
|
|
|
|
|
return !block_GCS_mode_change((uint8_t)mode_num, mode_list, ARRAY_SIZE(mode_list));
|
|
|
|
}
|
|
|
|
|
2019-10-17 00:49:32 -03:00
|
|
|
bool Plane::set_mode(Mode &new_mode, const ModeReason reason)
|
2011-09-08 22:29:39 -03:00
|
|
|
{
|
2021-08-09 11:07:32 -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.
|
2021-08-09 11:07:32 -03:00
|
|
|
// only make happy noise if using a difent method to switch, this stops beeping for repeated change mode requests from GCS
|
2022-07-08 18:51:21 -03:00
|
|
|
if ((reason != control_mode_reason) && (reason != ModeReason::INITIALISED)) {
|
2021-08-09 11:07:32 -03:00
|
|
|
AP_Notify::events.user_mode_change = 1;
|
|
|
|
}
|
2019-04-01 14:43:12 -03:00
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
2021-09-10 03:28:21 -03:00
|
|
|
#if HAL_QUADPLANE_ENABLED
|
2021-09-04 16:24:10 -03:00
|
|
|
if (new_mode.is_vtol_mode() && !plane.quadplane.available()) {
|
|
|
|
// dont try and switch to a Q mode if quadplane is not enabled and initalized
|
|
|
|
gcs().send_text(MAV_SEVERITY_INFO,"Q_ENABLE 0");
|
|
|
|
// make sad noise
|
|
|
|
if (reason != ModeReason::INITIALISED) {
|
|
|
|
AP_Notify::events.user_mode_change_failed = 1;
|
|
|
|
}
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
2021-09-10 03:28:21 -03:00
|
|
|
#else
|
|
|
|
if (new_mode.is_vtol_mode()) {
|
|
|
|
INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control);
|
|
|
|
gcs().send_text(MAV_SEVERITY_INFO,"HAL_QUADPLANE_ENABLED=0");
|
|
|
|
// make sad noise
|
|
|
|
if (reason != ModeReason::INITIALISED) {
|
|
|
|
AP_Notify::events.user_mode_change_failed = 1;
|
|
|
|
}
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
#endif // HAL_QUADPLANE_ENABLED
|
2018-12-07 03:52:05 -04:00
|
|
|
|
2022-08-12 16:34:31 -03:00
|
|
|
#if AP_FENCE_ENABLED
|
|
|
|
// may not be allowed to change mode if recovering from fence breach
|
2022-10-23 04:00:29 -03:00
|
|
|
if (hal.util->get_soft_armed() &&
|
|
|
|
fence.enabled() &&
|
|
|
|
fence.option_enabled(AC_Fence::OPTIONS::DISABLE_MODE_CHANGE) &&
|
|
|
|
fence.get_breaches() &&
|
|
|
|
in_fence_recovery() &&
|
2022-10-23 16:19:09 -03:00
|
|
|
!mode_reason_is_landing_sequence(reason)) {
|
2022-08-12 16:34:31 -03:00
|
|
|
gcs().send_text(MAV_SEVERITY_NOTICE,"Mode change to %s denied, in fence recovery", new_mode.name());
|
|
|
|
AP_Notify::events.user_mode_change_failed = 1;
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
#endif
|
|
|
|
|
2023-06-18 12:31:10 -03:00
|
|
|
// Check if GCS mode change is disabled via parameter
|
|
|
|
if ((reason == ModeReason::GCS_COMMAND) && !gcs_mode_enabled(new_mode.mode_number())) {
|
|
|
|
gcs().send_text(MAV_SEVERITY_NOTICE,"Mode change to %s denied, GCS entry disabled (FLTMODE_GCSBLOCK)", new_mode.name());
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
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;
|
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;
|
2022-07-08 19:10:01 -03:00
|
|
|
const ModeReason old_previous_mode_reason = previous_mode_reason;
|
|
|
|
previous_mode_reason = control_mode_reason;
|
2016-08-13 04:54:37 -03:00
|
|
|
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;
|
2022-07-08 19:10:01 -03:00
|
|
|
previous_mode_reason = old_previous_mode_reason;
|
2019-04-01 14:54:34 -03:00
|
|
|
|
2021-08-09 11:07:32 -03:00
|
|
|
// make sad noise
|
|
|
|
if (reason != ModeReason::INITIALISED) {
|
|
|
|
AP_Notify::events.user_mode_change_failed = 1;
|
|
|
|
}
|
2019-01-15 13:46:13 -04:00
|
|
|
return false;
|
2012-08-21 23:19:51 -03:00
|
|
|
}
|
|
|
|
|
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
|
|
|
// log and notify mode change
|
|
|
|
logger.Write_Mode(control_mode->mode_number(), control_mode_reason);
|
|
|
|
notify_mode(*control_mode);
|
2019-06-26 15:21:48 -03:00
|
|
|
gcs().send_message(MSG_HEARTBEAT);
|
2017-01-20 06:15:51 -04:00
|
|
|
|
2021-08-09 11:07:32 -03:00
|
|
|
// make happy noise
|
|
|
|
if (reason != ModeReason::INITIALISED) {
|
|
|
|
AP_Notify::events.user_mode_change = 1;
|
|
|
|
}
|
2019-01-15 13:46:13 -04:00
|
|
|
return true;
|
2011-09-08 22:29:39 -03:00
|
|
|
}
|
|
|
|
|
2019-10-17 00:49:32 -03:00
|
|
|
bool Plane::set_mode(const uint8_t new_mode, const ModeReason reason)
|
|
|
|
{
|
|
|
|
static_assert(sizeof(Mode::Number) == sizeof(new_mode), "The new mode can't be mapped to the vehicles mode number");
|
2021-08-24 22:48:08 -03:00
|
|
|
|
|
|
|
return set_mode_by_number(static_cast<Mode::Number>(new_mode), reason);
|
2019-10-17 00:49:32 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
bool Plane::set_mode_by_number(const Mode::Number new_mode_number, const ModeReason 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) {
|
2021-08-24 23:04:50 -03:00
|
|
|
notify_no_such_mode(new_mode_number);
|
2019-01-15 13:46:13 -04:00
|
|
|
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
|
|
|
{
|
2021-02-04 22:28:08 -04:00
|
|
|
const uint32_t gcs_last_seen_ms = gcs().sysid_myggcs_last_seen_time_ms();
|
|
|
|
const uint32_t tnow = millis();
|
2012-08-21 23:19:51 -03:00
|
|
|
// only act on changes
|
|
|
|
// -------------------
|
2022-09-29 20:10:41 -03:00
|
|
|
if (failsafe.state != FAILSAFE_LONG && failsafe.state != FAILSAFE_GCS && flight_stage != AP_FixedWing::FlightStage::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) {
|
2019-10-17 00:49:32 -03:00
|
|
|
failsafe_long_on_event(FAILSAFE_LONG, ModeReason::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 &&
|
2021-02-04 22:28:08 -04:00
|
|
|
gcs_last_seen_ms != 0 &&
|
|
|
|
(tnow - gcs_last_seen_ms) > g.fs_timeout_long*1000) {
|
2019-10-17 00:49:32 -03:00
|
|
|
failsafe_long_on_event(FAILSAFE_GCS, ModeReason::GCS_FAILSAFE);
|
2019-12-03 20:49:13 -04:00
|
|
|
} else if ((g.gcs_heartbeat_fs_enabled == GCS_FAILSAFE_HEARTBEAT ||
|
|
|
|
g.gcs_heartbeat_fs_enabled == GCS_FAILSAFE_HB_RSSI) &&
|
2021-02-04 22:28:08 -04:00
|
|
|
gcs_last_seen_ms != 0 &&
|
|
|
|
(tnow - gcs_last_seen_ms) > g.fs_timeout_long*1000) {
|
2019-10-17 00:49:32 -03:00
|
|
|
failsafe_long_on_event(FAILSAFE_GCS, ModeReason::GCS_FAILSAFE);
|
2013-12-19 20:39:00 -04:00
|
|
|
} else if (g.gcs_heartbeat_fs_enabled == GCS_FAILSAFE_HB_RSSI &&
|
2019-08-05 23:33:36 -03:00
|
|
|
gcs().chan(0) != nullptr &&
|
2020-06-03 23:06:30 -03:00
|
|
|
gcs().chan(0)->last_radio_status_remrssi_ms() != 0 &&
|
|
|
|
(tnow - gcs().chan(0)->last_radio_status_remrssi_ms()) > g.fs_timeout_long*1000) {
|
2019-10-17 00:49:32 -03:00
|
|
|
failsafe_long_on_event(FAILSAFE_GCS, ModeReason::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 &&
|
2021-02-04 22:28:08 -04:00
|
|
|
(tnow - gcs_last_seen_ms) < timeout_seconds*1000) {
|
2019-10-17 00:49:32 -03:00
|
|
|
failsafe_long_off_event(ModeReason::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) {
|
2019-10-17 00:49:32 -03:00
|
|
|
failsafe_long_off_event(ModeReason::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 &&
|
2022-09-29 20:10:41 -03:00
|
|
|
flight_stage != AP_FixedWing::FlightStage::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) {
|
2019-10-17 00:49:32 -03:00
|
|
|
failsafe_short_on_event(FAILSAFE_SHORT, ModeReason::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) {
|
2019-10-17 00:49:32 -03:00
|
|
|
failsafe_short_off_event(ModeReason::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-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);
|
2021-08-11 20:25:34 -03:00
|
|
|
ahrs.set_vehicle_class(AP_AHRS::VehicleClass::FIXED_WING);
|
2021-08-16 23:34:15 -03:00
|
|
|
ahrs.set_wind_estimation_enabled(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
|
|
|
}
|
|
|
|
|
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
|
|
|
{
|
2021-09-10 03:28:21 -03:00
|
|
|
#if HAL_QUADPLANE_ENABLED
|
2021-07-14 17:15:49 -03:00
|
|
|
if (quadplane.in_vtol_mode() && !quadplane.tailsitter.in_vtol_transition()) {
|
2021-09-17 20:27:15 -03:00
|
|
|
return quadplane.motors->get_throttle_out() * 100.0;
|
2016-01-03 06:38:51 -04:00
|
|
|
}
|
2021-09-10 03:28:21 -03:00
|
|
|
#endif
|
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
|
|
|
}
|