2011-09-08 22:29:39 -03:00
|
|
|
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
|
|
|
2015-05-13 03:09:36 -03:00
|
|
|
#include "Plane.h"
|
|
|
|
|
2011-09-08 22:29:39 -03:00
|
|
|
//Function that will read the radio data, limit servos and trigger a failsafe
|
|
|
|
// ----------------------------------------------------------------------------
|
|
|
|
|
2013-06-03 03:42:38 -03:00
|
|
|
/*
|
|
|
|
allow for runtime change of control channel ordering
|
|
|
|
*/
|
2015-05-13 03:09:36 -03:00
|
|
|
void Plane::set_control_channels(void)
|
2013-06-03 03:42:38 -03:00
|
|
|
{
|
2015-04-15 22:16:30 -03:00
|
|
|
if (g.rudder_only) {
|
2015-04-16 10:30:32 -03:00
|
|
|
// in rudder only mode the roll and rudder channels are the
|
|
|
|
// same.
|
2015-04-15 22:16:30 -03:00
|
|
|
channel_roll = RC_Channel::rc_channel(rcmap.yaw()-1);
|
|
|
|
} else {
|
|
|
|
channel_roll = RC_Channel::rc_channel(rcmap.roll()-1);
|
|
|
|
}
|
2013-06-03 03:42:38 -03:00
|
|
|
channel_pitch = RC_Channel::rc_channel(rcmap.pitch()-1);
|
|
|
|
channel_throttle = RC_Channel::rc_channel(rcmap.throttle()-1);
|
|
|
|
channel_rudder = RC_Channel::rc_channel(rcmap.yaw()-1);
|
2011-09-08 22:29:39 -03:00
|
|
|
|
2012-08-21 23:19:50 -03:00
|
|
|
// set rc channel ranges
|
2013-06-03 02:32:08 -03:00
|
|
|
channel_roll->set_angle(SERVO_MAX);
|
|
|
|
channel_pitch->set_angle(SERVO_MAX);
|
|
|
|
channel_rudder->set_angle(SERVO_MAX);
|
2016-01-30 03:22:21 -04:00
|
|
|
if (aparm.throttle_min >= 0) {
|
|
|
|
// normal operation
|
|
|
|
channel_throttle->set_range(0, 100);
|
|
|
|
} else {
|
|
|
|
// reverse thrust
|
|
|
|
channel_throttle->set_angle(100);
|
|
|
|
}
|
2014-01-15 07:28:00 -04:00
|
|
|
|
|
|
|
if (!arming.is_armed() && arming.arming_required() == AP_Arming::YES_MIN_PWM) {
|
2015-09-13 20:42:20 -03:00
|
|
|
hal.rcout->set_safety_pwm(1UL<<(rcmap.throttle()-1), throttle_min());
|
2014-01-15 07:28:00 -04:00
|
|
|
}
|
2014-11-20 03:32:18 -04:00
|
|
|
|
|
|
|
// setup correct scaling for ESCs like the UAVCAN PX4ESC which
|
|
|
|
// take a proportion of speed
|
|
|
|
hal.rcout->set_esc_scaling(channel_throttle->radio_min, channel_throttle->radio_max);
|
2013-06-03 08:20:39 -03:00
|
|
|
}
|
2012-08-21 23:19:50 -03:00
|
|
|
|
2013-06-03 08:20:39 -03:00
|
|
|
/*
|
|
|
|
initialise RC input channels
|
|
|
|
*/
|
2015-05-13 03:09:36 -03:00
|
|
|
void Plane::init_rc_in()
|
2013-06-03 08:20:39 -03:00
|
|
|
{
|
2012-08-21 23:19:50 -03:00
|
|
|
// set rc dead zones
|
2013-07-11 11:12:26 -03:00
|
|
|
channel_roll->set_default_dead_zone(30);
|
|
|
|
channel_pitch->set_default_dead_zone(30);
|
|
|
|
channel_rudder->set_default_dead_zone(30);
|
2013-07-13 00:19:25 -03:00
|
|
|
channel_throttle->set_default_dead_zone(30);
|
2011-09-08 22:29:39 -03:00
|
|
|
}
|
|
|
|
|
2013-06-03 03:42:38 -03:00
|
|
|
/*
|
|
|
|
initialise RC output channels
|
|
|
|
*/
|
2015-05-13 03:09:36 -03:00
|
|
|
void Plane::init_rc_out()
|
2011-09-08 22:29:39 -03:00
|
|
|
{
|
2013-06-03 03:12:41 -03:00
|
|
|
channel_roll->enable_out();
|
|
|
|
channel_pitch->enable_out();
|
2015-09-06 20:17:22 -03:00
|
|
|
|
|
|
|
/*
|
|
|
|
change throttle trim to minimum throttle. This prevents a
|
|
|
|
configuration error where the user sets CH3_TRIM incorrectly and
|
|
|
|
the motor may start on power up
|
|
|
|
*/
|
2015-09-13 20:42:20 -03:00
|
|
|
channel_throttle->radio_trim = throttle_min();
|
2015-09-06 20:17:22 -03:00
|
|
|
|
2013-12-19 20:59:45 -04:00
|
|
|
if (arming.arming_required() != AP_Arming::YES_ZERO_PWM) {
|
|
|
|
channel_throttle->enable_out();
|
|
|
|
}
|
2013-06-03 03:12:41 -03:00
|
|
|
channel_rudder->enable_out();
|
2016-01-04 18:38:02 -04:00
|
|
|
update_aux();
|
2014-02-05 19:12:07 -04:00
|
|
|
RC_Channel_aux::enable_aux_servos();
|
2012-08-04 13:39:20 -03:00
|
|
|
|
2012-09-16 02:51:13 -03:00
|
|
|
// Initialization of servo outputs
|
2014-04-02 22:19:11 -03:00
|
|
|
RC_Channel::output_trim_all();
|
2014-01-15 07:28:00 -04:00
|
|
|
|
2014-04-20 19:37:56 -03:00
|
|
|
// setup PWM values to send if the FMU firmware dies
|
|
|
|
RC_Channel::setup_failsafe_trim_all();
|
|
|
|
|
2014-01-15 07:28:00 -04:00
|
|
|
// setup PX4 to output the min throttle when safety off if arming
|
|
|
|
// is setup for min on disarm
|
|
|
|
if (arming.arming_required() == AP_Arming::YES_MIN_PWM) {
|
2015-09-13 20:42:20 -03:00
|
|
|
hal.rcout->set_safety_pwm(1UL<<(rcmap.throttle()-1), throttle_min());
|
2014-01-15 07:28:00 -04:00
|
|
|
}
|
2011-09-08 22:29:39 -03:00
|
|
|
}
|
|
|
|
|
2015-07-23 08:47:37 -03:00
|
|
|
/*
|
|
|
|
check for pilot input on rudder stick for arming/disarming
|
|
|
|
*/
|
2015-07-16 14:47:08 -03:00
|
|
|
void Plane::rudder_arm_disarm_check()
|
2013-12-11 02:01:37 -04:00
|
|
|
{
|
2015-07-23 08:47:37 -03:00
|
|
|
AP_Arming::ArmingRudder arming_rudder = arming.rudder_arming();
|
2013-11-27 22:19:34 -04:00
|
|
|
|
2015-07-23 08:47:37 -03:00
|
|
|
if (arming_rudder == AP_Arming::ARMING_RUDDER_DISABLED) {
|
2015-07-16 14:47:08 -03:00
|
|
|
//parameter disallows rudder arming/disabling
|
2013-11-27 22:19:34 -04:00
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
2015-07-23 08:47:37 -03:00
|
|
|
// if throttle is not down, then pilot cannot rudder arm/disarm
|
2016-02-11 00:59:00 -04:00
|
|
|
if (channel_throttle->control_in != 0){
|
2013-11-27 22:19:34 -04:00
|
|
|
rudder_arm_timer = 0;
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
2015-07-23 08:47:37 -03:00
|
|
|
// if not in a manual throttle mode then disallow rudder arming/disarming
|
2013-11-27 22:19:34 -04:00
|
|
|
if (auto_throttle_mode ) {
|
|
|
|
rudder_arm_timer = 0;
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
2015-07-16 14:47:08 -03:00
|
|
|
if (!arming.is_armed()) {
|
|
|
|
// when not armed, full right rudder starts arming counter
|
|
|
|
if (channel_rudder->control_in > 4000) {
|
|
|
|
uint32_t now = millis();
|
|
|
|
|
|
|
|
if (rudder_arm_timer == 0 ||
|
|
|
|
now - rudder_arm_timer < 3000) {
|
|
|
|
|
2015-07-23 08:47:37 -03:00
|
|
|
if (rudder_arm_timer == 0) {
|
|
|
|
rudder_arm_timer = now;
|
|
|
|
}
|
2015-07-16 14:47:08 -03:00
|
|
|
} else {
|
|
|
|
//time to arm!
|
|
|
|
arm_motors(AP_Arming::RUDDER);
|
|
|
|
rudder_arm_timer = 0;
|
|
|
|
}
|
|
|
|
} else {
|
|
|
|
// not at full right rudder
|
|
|
|
rudder_arm_timer = 0;
|
|
|
|
}
|
2015-07-23 08:47:37 -03:00
|
|
|
} else if (arming_rudder == AP_Arming::ARMING_RUDDER_ARMDISARM && !is_flying()) {
|
2015-07-16 14:47:08 -03:00
|
|
|
// when armed and not flying, full left rudder starts disarming counter
|
|
|
|
if (channel_rudder->control_in < -4000) {
|
|
|
|
uint32_t now = millis();
|
|
|
|
|
|
|
|
if (rudder_arm_timer == 0 ||
|
|
|
|
now - rudder_arm_timer < 3000) {
|
2015-07-23 08:47:37 -03:00
|
|
|
if (rudder_arm_timer == 0) {
|
|
|
|
rudder_arm_timer = now;
|
|
|
|
}
|
2015-07-16 14:47:08 -03:00
|
|
|
} else {
|
|
|
|
//time to disarm!
|
|
|
|
disarm_motors();
|
|
|
|
rudder_arm_timer = 0;
|
|
|
|
}
|
|
|
|
} else {
|
|
|
|
// not at full left rudder
|
|
|
|
rudder_arm_timer = 0;
|
|
|
|
}
|
|
|
|
}
|
2013-11-27 22:19:34 -04:00
|
|
|
}
|
|
|
|
|
2015-05-13 03:09:36 -03:00
|
|
|
void Plane::read_radio()
|
2011-09-08 22:29:39 -03:00
|
|
|
{
|
2014-03-25 00:41:14 -03:00
|
|
|
if (!hal.rcin->new_input()) {
|
2013-12-19 18:41:15 -04:00
|
|
|
control_failsafe(channel_throttle->radio_in);
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
2015-05-13 19:05:32 -03:00
|
|
|
failsafe.last_valid_rc_ms = millis();
|
2013-12-19 18:41:15 -04:00
|
|
|
|
2013-06-03 03:12:41 -03:00
|
|
|
elevon.ch1_temp = channel_roll->read();
|
|
|
|
elevon.ch2_temp = channel_pitch->read();
|
2012-12-04 02:32:37 -04:00
|
|
|
uint16_t pwm_roll, pwm_pitch;
|
2012-08-21 23:19:50 -03:00
|
|
|
|
2012-12-04 02:32:37 -04:00
|
|
|
if (g.mix_mode == 0) {
|
2013-04-15 01:53:56 -03:00
|
|
|
pwm_roll = elevon.ch1_temp;
|
|
|
|
pwm_pitch = elevon.ch2_temp;
|
2012-08-21 23:19:50 -03:00
|
|
|
}else{
|
2013-04-15 01:53:56 -03:00
|
|
|
pwm_roll = BOOL_TO_SIGN(g.reverse_elevons) * (BOOL_TO_SIGN(g.reverse_ch2_elevon) * int16_t(elevon.ch2_temp - elevon.trim2) - BOOL_TO_SIGN(g.reverse_ch1_elevon) * int16_t(elevon.ch1_temp - elevon.trim1)) / 2 + 1500;
|
|
|
|
pwm_pitch = (BOOL_TO_SIGN(g.reverse_ch2_elevon) * int16_t(elevon.ch2_temp - elevon.trim2) + BOOL_TO_SIGN(g.reverse_ch1_elevon) * int16_t(elevon.ch1_temp - elevon.trim1)) / 2 + 1500;
|
2012-12-04 02:32:37 -04:00
|
|
|
}
|
2014-04-02 22:19:11 -03:00
|
|
|
|
|
|
|
RC_Channel::set_pwm_all();
|
2012-12-04 02:32:37 -04:00
|
|
|
|
|
|
|
if (control_mode == TRAINING) {
|
|
|
|
// in training mode we don't want to use a deadzone, as we
|
|
|
|
// want manual pass through when not exceeding attitude limits
|
2013-06-03 02:32:08 -03:00
|
|
|
channel_roll->set_pwm_no_deadzone(pwm_roll);
|
|
|
|
channel_pitch->set_pwm_no_deadzone(pwm_pitch);
|
2013-06-03 03:12:41 -03:00
|
|
|
channel_throttle->set_pwm_no_deadzone(channel_throttle->read());
|
|
|
|
channel_rudder->set_pwm_no_deadzone(channel_rudder->read());
|
2012-12-04 02:32:37 -04:00
|
|
|
} else {
|
2013-06-03 02:32:08 -03:00
|
|
|
channel_roll->set_pwm(pwm_roll);
|
|
|
|
channel_pitch->set_pwm(pwm_pitch);
|
2012-08-21 23:19:50 -03:00
|
|
|
}
|
|
|
|
|
2013-06-03 02:32:08 -03:00
|
|
|
control_failsafe(channel_throttle->radio_in);
|
2012-08-21 23:19:50 -03:00
|
|
|
|
2013-06-03 02:32:08 -03:00
|
|
|
channel_throttle->servo_out = channel_throttle->control_in;
|
2012-08-21 23:19:50 -03:00
|
|
|
|
2016-02-07 19:59:37 -04:00
|
|
|
if (g.throttle_nudge && channel_throttle->servo_out > 50 && geofence_stickmixing()) {
|
2013-10-11 23:30:27 -03:00
|
|
|
float nudge = (channel_throttle->servo_out - 50) * 0.02f;
|
2015-01-19 20:28:35 -04:00
|
|
|
if (ahrs.airspeed_sensor_enabled()) {
|
2013-07-17 22:58:23 -03:00
|
|
|
airspeed_nudge_cm = (aparm.airspeed_max * 100 - g.airspeed_cruise_cm) * nudge;
|
2012-08-21 23:19:50 -03:00
|
|
|
} else {
|
2013-06-26 07:48:45 -03:00
|
|
|
throttle_nudge = (aparm.throttle_max - aparm.throttle_cruise) * nudge;
|
2012-08-21 23:19:50 -03:00
|
|
|
}
|
|
|
|
} else {
|
|
|
|
airspeed_nudge_cm = 0;
|
|
|
|
throttle_nudge = 0;
|
|
|
|
}
|
2013-11-27 22:19:34 -04:00
|
|
|
|
2015-07-16 14:47:08 -03:00
|
|
|
rudder_arm_disarm_check();
|
2015-04-16 10:30:32 -03:00
|
|
|
|
|
|
|
if (g.rudder_only != 0) {
|
|
|
|
// in rudder only mode we discard rudder input and get target
|
|
|
|
// attitude from the roll channel.
|
|
|
|
rudder_input = 0;
|
|
|
|
} else {
|
|
|
|
rudder_input = channel_rudder->control_in;
|
|
|
|
}
|
2011-09-08 22:29:39 -03:00
|
|
|
}
|
|
|
|
|
2015-05-13 03:09:36 -03:00
|
|
|
void Plane::control_failsafe(uint16_t pwm)
|
2011-09-08 22:29:39 -03:00
|
|
|
{
|
2015-05-13 19:05:32 -03:00
|
|
|
if (millis() - failsafe.last_valid_rc_ms > 1000 || rc_failsafe_active()) {
|
2014-03-08 01:20:09 -04:00
|
|
|
// we do not have valid RC input. Set all primary channel
|
2014-03-08 02:22:24 -04:00
|
|
|
// control inputs to the trim value and throttle to min
|
2014-03-08 01:20:09 -04:00
|
|
|
channel_roll->radio_in = channel_roll->radio_trim;
|
|
|
|
channel_pitch->radio_in = channel_pitch->radio_trim;
|
|
|
|
channel_rudder->radio_in = channel_rudder->radio_trim;
|
2014-04-09 18:43:48 -03:00
|
|
|
|
|
|
|
// note that we don't set channel_throttle->radio_in to radio_trim,
|
|
|
|
// as that would cause throttle failsafe to not activate
|
|
|
|
|
2014-03-08 01:20:09 -04:00
|
|
|
channel_roll->control_in = 0;
|
|
|
|
channel_pitch->control_in = 0;
|
|
|
|
channel_rudder->control_in = 0;
|
|
|
|
channel_throttle->control_in = 0;
|
|
|
|
}
|
|
|
|
|
2012-08-21 23:19:50 -03:00
|
|
|
if(g.throttle_fs_enabled == 0)
|
|
|
|
return;
|
|
|
|
|
ArduPlane failsafes: remove rc_override_active
- rc_override_active is never set anywhere in the ArduPlane code; it's only used for Copter and Rover. Removing it significantly simplifies the failsafe code.
- modified code has been tested in SITL. Heartbeat and RC failures in AUTO, CRUISE, and RTL modes (covering the three cases in the failsafe check functions) have been simulated with FS_LONG_ACTN = 0, 1, and 2, FS_SHORT_ACTN = 0, 1, and 2, and FS_GCS_ENABL = 0, 1, and 2. In all cases the results are identical to those with the original code.
2014-09-16 00:14:40 -03:00
|
|
|
if (g.throttle_fs_enabled) {
|
2014-03-08 01:20:09 -04:00
|
|
|
if (rc_failsafe_active()) {
|
2012-08-21 23:19:50 -03:00
|
|
|
// we detect a failsafe from radio
|
|
|
|
// throttle has dropped below the mark
|
2013-07-19 01:11:16 -03:00
|
|
|
failsafe.ch3_counter++;
|
2013-09-13 21:30:13 -03:00
|
|
|
if (failsafe.ch3_counter == 10) {
|
2015-11-03 23:52:54 -04:00
|
|
|
gcs_send_text_fmt(MAV_SEVERITY_WARNING, "MSG FS ON %u", (unsigned)pwm);
|
2013-07-19 01:11:16 -03:00
|
|
|
failsafe.ch3_failsafe = true;
|
2013-09-17 22:58:54 -03:00
|
|
|
AP_Notify::flags.failsafe_radio = true;
|
2013-09-13 21:30:13 -03:00
|
|
|
}
|
|
|
|
if (failsafe.ch3_counter > 10) {
|
|
|
|
failsafe.ch3_counter = 10;
|
2012-08-21 23:19:50 -03:00
|
|
|
}
|
|
|
|
|
2013-07-19 01:11:16 -03:00
|
|
|
}else if(failsafe.ch3_counter > 0) {
|
2012-08-21 23:19:50 -03:00
|
|
|
// we are no longer in failsafe condition
|
|
|
|
// but we need to recover quickly
|
2013-07-19 01:11:16 -03:00
|
|
|
failsafe.ch3_counter--;
|
|
|
|
if (failsafe.ch3_counter > 3) {
|
|
|
|
failsafe.ch3_counter = 3;
|
2012-08-21 23:19:50 -03:00
|
|
|
}
|
2013-07-19 01:11:16 -03:00
|
|
|
if (failsafe.ch3_counter == 1) {
|
2015-11-03 23:52:54 -04:00
|
|
|
gcs_send_text_fmt(MAV_SEVERITY_WARNING, "MSG FS OFF %u", (unsigned)pwm);
|
2013-07-19 01:11:16 -03:00
|
|
|
} else if(failsafe.ch3_counter == 0) {
|
|
|
|
failsafe.ch3_failsafe = false;
|
2013-09-17 22:58:54 -03:00
|
|
|
AP_Notify::flags.failsafe_radio = false;
|
2012-08-21 23:19:50 -03:00
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|
2011-09-08 22:29:39 -03:00
|
|
|
}
|
|
|
|
|
2015-05-13 03:09:36 -03:00
|
|
|
void Plane::trim_control_surfaces()
|
2011-09-08 22:29:39 -03:00
|
|
|
{
|
2012-08-21 23:19:50 -03:00
|
|
|
read_radio();
|
2013-06-03 02:32:08 -03:00
|
|
|
int16_t trim_roll_range = (channel_roll->radio_max - channel_roll->radio_min)/5;
|
|
|
|
int16_t trim_pitch_range = (channel_pitch->radio_max - channel_pitch->radio_min)/5;
|
|
|
|
if (channel_roll->radio_in < channel_roll->radio_min+trim_roll_range ||
|
|
|
|
channel_roll->radio_in > channel_roll->radio_max-trim_roll_range ||
|
|
|
|
channel_pitch->radio_in < channel_pitch->radio_min+trim_pitch_range ||
|
|
|
|
channel_pitch->radio_in > channel_pitch->radio_max-trim_pitch_range) {
|
2013-04-11 23:47:59 -03:00
|
|
|
// don't trim for extreme values - if we attempt to trim so
|
|
|
|
// there is less than 20 percent range left then assume the
|
|
|
|
// sticks are not properly centered. This also prevents
|
|
|
|
// problems with starting APM with the TX off
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
2012-08-21 23:19:50 -03:00
|
|
|
// Store control surface trim values
|
|
|
|
// ---------------------------------
|
|
|
|
if(g.mix_mode == 0) {
|
2013-06-03 02:32:08 -03:00
|
|
|
if (channel_roll->radio_in != 0) {
|
|
|
|
channel_roll->radio_trim = channel_roll->radio_in;
|
2013-01-24 23:27:44 -04:00
|
|
|
}
|
2013-06-03 02:32:08 -03:00
|
|
|
if (channel_pitch->radio_in != 0) {
|
|
|
|
channel_pitch->radio_trim = channel_pitch->radio_in;
|
2013-01-24 23:27:44 -04:00
|
|
|
}
|
2012-11-20 20:48:46 -04:00
|
|
|
|
2013-02-04 17:57:58 -04:00
|
|
|
// the secondary aileron/elevator is trimmed only if it has a
|
2012-11-20 20:48:46 -04:00
|
|
|
// corresponding transmitter input channel, which k_aileron
|
|
|
|
// doesn't have
|
|
|
|
RC_Channel_aux::set_radio_trim(RC_Channel_aux::k_aileron_with_input);
|
2013-02-04 17:57:58 -04:00
|
|
|
RC_Channel_aux::set_radio_trim(RC_Channel_aux::k_elevator_with_input);
|
2012-09-08 02:13:22 -03:00
|
|
|
} else{
|
2013-04-15 01:53:56 -03:00
|
|
|
if (elevon.ch1_temp != 0) {
|
|
|
|
elevon.trim1 = elevon.ch1_temp;
|
2013-01-24 23:27:44 -04:00
|
|
|
}
|
2013-04-15 01:53:56 -03:00
|
|
|
if (elevon.ch2_temp != 0) {
|
|
|
|
elevon.trim2 = elevon.ch2_temp;
|
2013-01-24 23:27:44 -04:00
|
|
|
}
|
2012-08-21 23:19:50 -03:00
|
|
|
//Recompute values here using new values for elevon1_trim and elevon2_trim
|
|
|
|
//We cannot use radio_in[CH_ROLL] and radio_in[CH_PITCH] values from read_radio() because the elevon trim values have changed
|
|
|
|
uint16_t center = 1500;
|
2013-06-03 02:32:08 -03:00
|
|
|
channel_roll->radio_trim = center;
|
|
|
|
channel_pitch->radio_trim = center;
|
2012-08-21 23:19:50 -03:00
|
|
|
}
|
2013-06-03 02:32:08 -03:00
|
|
|
if (channel_rudder->radio_in != 0) {
|
|
|
|
channel_rudder->radio_trim = channel_rudder->radio_in;
|
2013-01-24 23:27:44 -04:00
|
|
|
}
|
2012-08-21 23:19:50 -03:00
|
|
|
|
|
|
|
// save to eeprom
|
2013-06-03 02:32:08 -03:00
|
|
|
channel_roll->save_eeprom();
|
|
|
|
channel_pitch->save_eeprom();
|
|
|
|
channel_rudder->save_eeprom();
|
2011-09-08 22:29:39 -03:00
|
|
|
}
|
|
|
|
|
2015-05-13 03:09:36 -03:00
|
|
|
void Plane::trim_radio()
|
2011-09-08 22:29:39 -03:00
|
|
|
{
|
2012-09-09 06:38:48 -03:00
|
|
|
for (uint8_t y = 0; y < 30; y++) {
|
2012-08-21 23:19:50 -03:00
|
|
|
read_radio();
|
|
|
|
}
|
|
|
|
|
2012-09-09 06:38:48 -03:00
|
|
|
trim_control_surfaces();
|
2011-09-09 11:18:38 -03:00
|
|
|
}
|
2013-11-17 00:32:36 -04:00
|
|
|
|
|
|
|
/*
|
|
|
|
return true if throttle level is below throttle failsafe threshold
|
2014-03-08 01:20:09 -04:00
|
|
|
or RC input is invalid
|
2013-11-17 00:32:36 -04:00
|
|
|
*/
|
2015-05-13 03:09:36 -03:00
|
|
|
bool Plane::rc_failsafe_active(void)
|
2013-11-17 00:32:36 -04:00
|
|
|
{
|
|
|
|
if (!g.throttle_fs_enabled) {
|
|
|
|
return false;
|
|
|
|
}
|
2015-05-13 19:05:32 -03:00
|
|
|
if (millis() - failsafe.last_valid_rc_ms > 1000) {
|
2014-03-08 01:20:09 -04:00
|
|
|
// we haven't had a valid RC frame for 1 seconds
|
2013-12-19 18:41:15 -04:00
|
|
|
return true;
|
|
|
|
}
|
2013-11-17 00:32:36 -04:00
|
|
|
if (channel_throttle->get_reverse()) {
|
|
|
|
return channel_throttle->radio_in >= g.throttle_fs_value;
|
|
|
|
}
|
|
|
|
return channel_throttle->radio_in <= g.throttle_fs_value;
|
|
|
|
}
|