2015-06-04 00:13:34 -03:00
|
|
|
/*
|
|
|
|
additional arming checks for plane
|
|
|
|
*/
|
2017-01-09 03:56:56 -04:00
|
|
|
#include "AP_Arming.h"
|
2015-06-04 00:13:34 -03:00
|
|
|
#include "Plane.h"
|
|
|
|
|
2020-06-16 15:52:26 -03:00
|
|
|
constexpr uint32_t AP_ARMING_DELAY_MS = 2000; // delay from arming to start of motor spoolup
|
|
|
|
|
2015-10-25 14:03:46 -03:00
|
|
|
const AP_Param::GroupInfo AP_Arming_Plane::var_info[] = {
|
2015-08-24 00:53:15 -03:00
|
|
|
// variables from parent vehicle
|
|
|
|
AP_NESTEDGROUPINFO(AP_Arming, 0),
|
|
|
|
|
2018-09-08 00:35:18 -03:00
|
|
|
// index 3 was RUDDER and should not be used
|
2015-08-24 00:53:15 -03:00
|
|
|
|
|
|
|
AP_GROUPEND
|
|
|
|
};
|
|
|
|
|
2015-06-04 00:13:34 -03:00
|
|
|
/*
|
|
|
|
additional arming checks for plane
|
2016-11-05 20:23:32 -03:00
|
|
|
|
2015-06-04 00:13:34 -03:00
|
|
|
*/
|
2017-08-09 08:22:15 -03:00
|
|
|
bool AP_Arming_Plane::pre_arm_checks(bool display_failure)
|
2015-06-04 00:13:34 -03:00
|
|
|
{
|
2019-05-05 22:16:41 -03:00
|
|
|
//are arming checks disabled?
|
2019-10-04 18:51:32 -03:00
|
|
|
if (checks_to_perform == 0) {
|
2019-05-05 22:16:41 -03:00
|
|
|
return true;
|
|
|
|
}
|
2019-04-21 22:12:12 -03:00
|
|
|
if (hal.util->was_watchdog_armed()) {
|
|
|
|
// on watchdog reset bypass arming checks to allow for
|
|
|
|
// in-flight arming if we were armed before the reset. This
|
|
|
|
// allows a reset on a BVLOS flight to return home if the
|
|
|
|
// operator can command arming over telemetry
|
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
2015-06-04 00:13:34 -03:00
|
|
|
// call parent class checks
|
2017-08-09 08:22:15 -03:00
|
|
|
bool ret = AP_Arming::pre_arm_checks(display_failure);
|
2015-06-04 00:13:34 -03:00
|
|
|
|
2015-08-24 00:53:15 -03:00
|
|
|
// Check airspeed sensor
|
2017-08-09 08:22:15 -03:00
|
|
|
ret &= AP_Arming::airspeed_checks(display_failure);
|
2015-08-24 00:53:15 -03:00
|
|
|
|
2017-12-06 19:02:11 -04:00
|
|
|
if (plane.g.fs_timeout_long < plane.g.fs_timeout_short && plane.g.fs_action_short != FS_ACTION_SHORT_DISABLED) {
|
2019-10-04 18:51:32 -03:00
|
|
|
check_failed(display_failure, "FS_LONG_TIMEOUT < FS_SHORT_TIMEOUT");
|
2017-09-19 23:18:37 -03:00
|
|
|
ret = false;
|
|
|
|
}
|
|
|
|
|
2016-06-23 09:40:13 -03:00
|
|
|
if (plane.aparm.roll_limit_cd < 300) {
|
2019-10-04 18:51:32 -03:00
|
|
|
check_failed(display_failure, "LIM_ROLL_CD too small (%u)", (unsigned)plane.aparm.roll_limit_cd);
|
2017-08-09 08:22:15 -03:00
|
|
|
ret = false;
|
2015-06-04 00:13:34 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
if (plane.aparm.pitch_limit_max_cd < 300) {
|
2019-10-04 18:51:32 -03:00
|
|
|
check_failed(display_failure, "LIM_PITCH_MAX too small (%u)", (unsigned)plane.aparm.pitch_limit_max_cd);
|
2017-08-09 08:22:15 -03:00
|
|
|
ret = false;
|
2015-06-04 00:13:34 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
if (plane.aparm.pitch_limit_min_cd > -300) {
|
2019-10-04 18:51:32 -03:00
|
|
|
check_failed(display_failure, "LIM_PITCH_MIN too large (%u)", (unsigned)plane.aparm.pitch_limit_min_cd);
|
2017-08-09 08:22:15 -03:00
|
|
|
ret = false;
|
2015-06-04 00:13:34 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
if (plane.channel_throttle->get_reverse() &&
|
2020-07-31 05:47:39 -03:00
|
|
|
Plane::ThrFailsafe(plane.g.throttle_fs_enabled.get()) != Plane::ThrFailsafe::Disabled &&
|
2015-06-04 00:13:34 -03:00
|
|
|
plane.g.throttle_fs_value <
|
ArduPlane: Fix up after refactoring RC_Channel class
Further to refactor of RC_Channel class which included
adding get_xx set_xx methods, change reads and writes to the public members
to calls to get and set functionsss
old public member(int16_t) get function -> int16_t set function (int16_t)
(expression where c is an object of type RC_Channel)
c.radio_in c.get_radio_in() c.set_radio_in(v)
c.control_in c.get_control_in() c.set_control_in(v)
c.servo_out c.get_servo_out() c.set_servo_out(v)
c.pwm_out c.get_pwm_out() // use existing
c.radio_out c.get_radio_out() c.set_radio_out(v)
c.radio_max c.get_radio_max() c.set_radio_max(v)
c.radio_min c.get_radio_min() c.set_radio_min(v)
c.radio_trim c.get_radio_trim() c.set_radio_trim(v);
c.min_max_configured() // return true if min and max are configured
Because data members of RC_Channels are now private and so cannot be written directly
some overloads are provided in the Plane classes to provide the old functionality
new overload Plane::stick_mix_channel(RC_Channel *channel)
which forwards to the previously existing
void stick_mix_channel(RC_Channel *channel, int16_t &servo_out);
new overload Plane::channel_output_mixer(Rc_Channel* , RC_Channel*)const
which forwards to
(uint8_t mixing_type, int16_t & chan1, int16_t & chan2)const;
Rename functions
RC_Channel_aux::set_radio_trim(Aux_servo_function_t function)
to RC_Channel_aux::set_trim_to_radio_in_for(Aux_servo_function_t function)
RC_Channel_aux::set_servo_out(Aux_servo_function_t function, int16_t value)
to RC_Channel_aux::set_servo_out_for(Aux_servo_function_t function, int16_t value)
Rationale:
RC_Channel is a complicated class, which combines
several functionalities dealing with stick inputs
in pwm and logical units, logical and actual actuator
outputs, unit conversion etc, etc
The intent of this PR is to clarify existing use of
the class. At the basic level it should now be possible
to grep all places where private variable is set by
searching for the set_xx function.
(The wider purpose is to provide a more generic and
logically simpler method of output mixing. This is a small step)
2016-05-08 05:33:02 -03:00
|
|
|
plane.channel_throttle->get_radio_max()) {
|
2019-10-04 18:51:32 -03:00
|
|
|
check_failed(display_failure, "Invalid THR_FS_VALUE for rev throttle");
|
2015-06-04 00:13:34 -03:00
|
|
|
ret = false;
|
|
|
|
}
|
|
|
|
|
2018-12-24 05:06:22 -04:00
|
|
|
if (plane.quadplane.enabled() && !plane.quadplane.available()) {
|
2019-10-04 18:51:32 -03:00
|
|
|
check_failed(display_failure, "Quadplane enabled but not running");
|
2018-12-24 05:06:22 -04:00
|
|
|
ret = false;
|
|
|
|
}
|
|
|
|
|
2016-02-20 05:02:52 -04:00
|
|
|
if (plane.quadplane.available() && plane.scheduler.get_loop_rate_hz() < 100) {
|
2019-10-04 18:51:32 -03:00
|
|
|
check_failed(display_failure, "quadplane needs SCHED_LOOP_RATE >= 100");
|
2016-02-20 05:02:52 -04:00
|
|
|
ret = false;
|
|
|
|
}
|
|
|
|
|
2020-09-17 18:08:54 -03:00
|
|
|
if (plane.quadplane.available() && !plane.quadplane.motors->initialised_ok()) {
|
|
|
|
check_failed(display_failure, "Quadplane: check motor setup");
|
|
|
|
ret = false;
|
|
|
|
}
|
|
|
|
|
2019-03-04 23:51:44 -04:00
|
|
|
if (plane.quadplane.enabled() && plane.quadplane.available()) {
|
|
|
|
// ensure controllers are OK with us arming:
|
|
|
|
char failure_msg[50];
|
|
|
|
if (!plane.quadplane.pos_control->pre_arm_checks("PSC", failure_msg, ARRAY_SIZE(failure_msg))) {
|
|
|
|
check_failed(ARMING_CHECK_PARAMETERS, display_failure, "Bad parameter: %s", failure_msg);
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
if (!plane.quadplane.attitude_control->pre_arm_checks("ATC", failure_msg, ARRAY_SIZE(failure_msg))) {
|
|
|
|
check_failed(ARMING_CHECK_PARAMETERS, display_failure, "Bad parameter: %s", failure_msg);
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2019-01-15 13:46:13 -04:00
|
|
|
if (plane.control_mode == &plane.mode_auto && plane.mission.num_commands() <= 1) {
|
2019-10-04 18:51:32 -03:00
|
|
|
check_failed(display_failure, "No mission loaded");
|
2016-02-21 12:06:43 -04:00
|
|
|
ret = false;
|
|
|
|
}
|
|
|
|
|
2016-08-12 17:02:31 -03:00
|
|
|
// check adsb avoidance failsafe
|
|
|
|
if (plane.failsafe.adsb) {
|
2019-10-04 18:51:32 -03:00
|
|
|
check_failed(display_failure, "ADSB threat detected");
|
2016-08-12 17:02:31 -03:00
|
|
|
ret = false;
|
|
|
|
}
|
|
|
|
|
2019-02-25 20:25:11 -04:00
|
|
|
if (SRV_Channels::get_emergency_stop()) {
|
2019-10-04 18:51:32 -03:00
|
|
|
check_failed(display_failure,"Motors Emergency Stopped");
|
2019-02-25 20:25:11 -04:00
|
|
|
ret = false;
|
|
|
|
}
|
|
|
|
|
2015-06-04 00:13:34 -03:00
|
|
|
return ret;
|
|
|
|
}
|
2015-10-16 00:52:57 -03:00
|
|
|
|
2017-08-09 08:22:15 -03:00
|
|
|
bool AP_Arming_Plane::ins_checks(bool display_failure)
|
2015-10-16 00:52:57 -03:00
|
|
|
{
|
|
|
|
// call parent class checks
|
2017-08-09 08:22:15 -03:00
|
|
|
if (!AP_Arming::ins_checks(display_failure)) {
|
2015-10-16 00:52:57 -03:00
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
|
|
|
// additional plane specific checks
|
|
|
|
if ((checks_to_perform & ARMING_CHECK_ALL) ||
|
|
|
|
(checks_to_perform & ARMING_CHECK_INS)) {
|
2020-08-11 02:04:10 -03:00
|
|
|
char failure_msg[50] = {};
|
2021-01-21 02:24:01 -04:00
|
|
|
if (!AP::ahrs().pre_arm_check(true, failure_msg, sizeof(failure_msg))) {
|
2020-10-06 02:21:20 -03:00
|
|
|
check_failed(ARMING_CHECK_INS, display_failure, "AHRS: %s", failure_msg);
|
2015-10-16 00:52:57 -03:00
|
|
|
return false;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
return true;
|
|
|
|
}
|
2019-04-21 22:12:12 -03:00
|
|
|
|
|
|
|
bool AP_Arming_Plane::arm_checks(AP_Arming::Method method)
|
|
|
|
{
|
2020-12-06 19:47:39 -04:00
|
|
|
if (method == AP_Arming::Method::RUDDER) {
|
|
|
|
const AP_Arming::RudderArming arming_rudder = get_rudder_arming_type();
|
|
|
|
|
|
|
|
if (arming_rudder == AP_Arming::RudderArming::IS_DISABLED) {
|
|
|
|
//parameter disallows rudder arming/disabling
|
|
|
|
|
|
|
|
// if we emit a message here then someone doing surface
|
|
|
|
// checks may be bothered by the message being emitted.
|
|
|
|
// check_failed(true, "Rudder arming disabled");
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
|
|
|
// if throttle is not down, then pilot cannot rudder arm/disarm
|
|
|
|
if (plane.get_throttle_input() != 0){
|
|
|
|
check_failed(true, "Non-zero throttle");
|
|
|
|
return false;
|
|
|
|
}
|
2021-01-21 19:28:26 -04:00
|
|
|
}
|
2020-12-06 19:47:39 -04:00
|
|
|
|
2021-01-21 19:28:26 -04:00
|
|
|
if (!plane.control_mode->allows_arming()) {
|
|
|
|
check_failed(true, "Mode does not allow arming");
|
|
|
|
return false;
|
2020-12-06 19:47:39 -04:00
|
|
|
}
|
|
|
|
|
2019-05-05 22:16:41 -03:00
|
|
|
//are arming checks disabled?
|
2019-10-04 18:51:32 -03:00
|
|
|
if (checks_to_perform == 0) {
|
2019-05-05 22:16:41 -03:00
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
2019-04-21 22:12:12 -03:00
|
|
|
if (hal.util->was_watchdog_armed()) {
|
|
|
|
// on watchdog reset bypass arming checks to allow for
|
|
|
|
// in-flight arming if we were armed before the reset. This
|
|
|
|
// allows a reset on a BVLOS flight to return home if the
|
|
|
|
// operator can command arming over telemetry
|
|
|
|
gcs().send_text(MAV_SEVERITY_WARNING, "watchdog: Bypassing arming checks");
|
|
|
|
return true;
|
|
|
|
}
|
2019-05-04 02:44:24 -03:00
|
|
|
|
2019-04-21 22:12:12 -03:00
|
|
|
// call parent class checks
|
|
|
|
return AP_Arming::arm_checks(method);
|
|
|
|
}
|
2019-05-29 20:37:41 -03:00
|
|
|
|
|
|
|
/*
|
2019-10-04 19:42:02 -03:00
|
|
|
update HAL soft arm state
|
2019-05-29 20:37:41 -03:00
|
|
|
*/
|
|
|
|
void AP_Arming_Plane::change_arm_state(void)
|
|
|
|
{
|
|
|
|
update_soft_armed();
|
|
|
|
plane.quadplane.set_armed(hal.util->get_soft_armed());
|
|
|
|
}
|
|
|
|
|
|
|
|
bool AP_Arming_Plane::arm(const AP_Arming::Method method, const bool do_arming_checks)
|
|
|
|
{
|
|
|
|
if (!AP_Arming::arm(method, do_arming_checks)) {
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
2020-07-07 21:22:56 -03:00
|
|
|
if ((method == Method::AUXSWITCH) && (plane.quadplane.options & QuadPlane::OPTION_AIRMODE)) {
|
|
|
|
// if no airmode switch assigned, honour the QuadPlane option bit:
|
|
|
|
if (rc().find_channel_for_option(RC_Channel::AUX_FUNC::AIRMODE) == nullptr) {
|
|
|
|
plane.quadplane.air_mode = AirMode::ON;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2019-05-29 20:37:41 -03:00
|
|
|
change_arm_state();
|
2020-06-16 15:52:26 -03:00
|
|
|
|
|
|
|
// rising edge of delay_arming oneshot
|
|
|
|
delay_arming = true;
|
2019-05-29 20:37:41 -03:00
|
|
|
|
|
|
|
gcs().send_text(MAV_SEVERITY_INFO, "Throttle armed");
|
|
|
|
|
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
|
|
|
/*
|
|
|
|
disarm motors
|
|
|
|
*/
|
2021-01-05 20:15:48 -04:00
|
|
|
bool AP_Arming_Plane::disarm(const AP_Arming::Method method, bool do_disarm_checks)
|
2019-05-29 20:37:41 -03:00
|
|
|
{
|
2021-01-05 20:15:48 -04:00
|
|
|
if (do_disarm_checks &&
|
|
|
|
method == AP_Arming::Method::RUDDER) {
|
2020-12-06 19:47:39 -04:00
|
|
|
// don't allow rudder-disarming in flight:
|
|
|
|
if (plane.is_flying()) {
|
|
|
|
// obviously this could happen in-flight so we can't warn about it
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
// option must be enabled:
|
|
|
|
if (get_rudder_arming_type() != AP_Arming::RudderArming::ARMDISARM) {
|
|
|
|
gcs().send_text(MAV_SEVERITY_INFO, "Rudder disarm: disabled");
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2021-01-05 20:15:48 -04:00
|
|
|
if (!AP_Arming::disarm(method, do_disarm_checks)) {
|
2019-05-29 20:37:41 -03:00
|
|
|
return false;
|
|
|
|
}
|
|
|
|
if (plane.control_mode != &plane.mode_auto) {
|
|
|
|
// reset the mission on disarm if we are not in auto
|
|
|
|
plane.mission.reset();
|
|
|
|
}
|
|
|
|
|
|
|
|
// suppress the throttle in auto-throttle modes
|
2020-12-23 01:25:35 -04:00
|
|
|
plane.throttle_suppressed = plane.control_mode->does_auto_throttle();
|
2019-05-29 20:37:41 -03:00
|
|
|
|
2020-07-07 21:22:56 -03:00
|
|
|
// if no airmode switch assigned, ensure airmode is off:
|
|
|
|
if (rc().find_channel_for_option(RC_Channel::AUX_FUNC::AIRMODE) == nullptr) {
|
|
|
|
plane.quadplane.air_mode = AirMode::OFF;
|
|
|
|
}
|
|
|
|
|
2019-05-29 20:37:41 -03:00
|
|
|
//only log if disarming was successful
|
|
|
|
change_arm_state();
|
|
|
|
|
|
|
|
#if QAUTOTUNE_ENABLED
|
|
|
|
//save qautotune gains if enabled and success
|
|
|
|
if (plane.control_mode == &plane.mode_qautotune) {
|
|
|
|
plane.quadplane.qautotune.save_tuning_gains();
|
|
|
|
} else {
|
|
|
|
plane.quadplane.qautotune.reset();
|
|
|
|
}
|
|
|
|
#endif
|
|
|
|
|
|
|
|
gcs().send_text(MAV_SEVERITY_INFO, "Throttle disarmed");
|
|
|
|
|
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
|
|
|
void AP_Arming_Plane::update_soft_armed()
|
|
|
|
{
|
|
|
|
hal.util->set_soft_armed(is_armed() &&
|
|
|
|
hal.util->safety_switch_state() != AP_HAL::Util::SAFETY_DISARMED);
|
|
|
|
AP::logger().set_vehicle_armed(hal.util->get_soft_armed());
|
2020-06-16 15:52:26 -03:00
|
|
|
|
|
|
|
// update delay_arming oneshot
|
|
|
|
if (delay_arming &&
|
|
|
|
(AP_HAL::millis() - hal.util->get_last_armed_change() >= AP_ARMING_DELAY_MS)) {
|
|
|
|
|
|
|
|
delay_arming = false;
|
|
|
|
}
|
2019-05-29 20:37:41 -03:00
|
|
|
}
|
|
|
|
|