2015-05-29 23:12:49 -03:00
|
|
|
#include "Copter.h"
|
|
|
|
|
|
|
|
|
2012-11-11 09:11:12 -04:00
|
|
|
// Function that will read the radio data, limit servos and trigger a failsafe
|
2011-02-25 01:33:39 -04:00
|
|
|
// ----------------------------------------------------------------------------
|
2012-08-04 13:39:20 -03:00
|
|
|
|
2015-05-29 23:12:49 -03:00
|
|
|
void Copter::default_dead_zones()
|
2011-10-27 15:34:00 -03:00
|
|
|
{
|
2017-05-31 22:10:57 -03:00
|
|
|
channel_roll->set_default_dead_zone(20);
|
|
|
|
channel_pitch->set_default_dead_zone(20);
|
2012-08-16 21:50:02 -03:00
|
|
|
#if FRAME_CONFIG == HELI_FRAME
|
2015-05-11 23:24:13 -03:00
|
|
|
channel_throttle->set_default_dead_zone(10);
|
|
|
|
channel_yaw->set_default_dead_zone(15);
|
2012-08-16 21:50:02 -03:00
|
|
|
#else
|
2015-05-11 23:24:13 -03:00
|
|
|
channel_throttle->set_default_dead_zone(30);
|
2017-05-31 22:10:57 -03:00
|
|
|
channel_yaw->set_default_dead_zone(20);
|
2012-08-16 21:50:02 -03:00
|
|
|
#endif
|
2018-06-04 00:06:32 -03:00
|
|
|
rc().channel(CH_6)->set_default_dead_zone(0);
|
2011-10-27 15:34:00 -03:00
|
|
|
}
|
2011-02-25 01:33:39 -04:00
|
|
|
|
2015-05-29 23:12:49 -03:00
|
|
|
void Copter::init_rc_in()
|
2010-12-19 12:40:33 -04:00
|
|
|
{
|
2018-06-04 00:06:32 -03:00
|
|
|
channel_roll = rc().channel(rcmap.roll()-1);
|
|
|
|
channel_pitch = rc().channel(rcmap.pitch()-1);
|
|
|
|
channel_throttle = rc().channel(rcmap.throttle()-1);
|
|
|
|
channel_yaw = rc().channel(rcmap.yaw()-1);
|
2015-05-11 23:24:13 -03:00
|
|
|
|
2012-08-16 21:50:02 -03:00
|
|
|
// set rc channel ranges
|
2016-10-23 03:59:09 -03:00
|
|
|
channel_roll->set_angle(ROLL_PITCH_YAW_INPUT_MAX);
|
|
|
|
channel_pitch->set_angle(ROLL_PITCH_YAW_INPUT_MAX);
|
|
|
|
channel_yaw->set_angle(ROLL_PITCH_YAW_INPUT_MAX);
|
2017-01-06 21:06:40 -04:00
|
|
|
channel_throttle->set_range(1000);
|
2012-08-16 21:50:02 -03:00
|
|
|
|
2013-07-11 11:15:11 -03:00
|
|
|
// set default dead zones
|
|
|
|
default_dead_zones();
|
2014-10-08 09:52:16 -03:00
|
|
|
|
|
|
|
// initialise throttle_zero flag
|
|
|
|
ap.throttle_zero = true;
|
2010-12-27 19:09:08 -04:00
|
|
|
}
|
|
|
|
|
2019-07-22 00:11:01 -03:00
|
|
|
// init_rc_out -- initialise motors
|
2015-05-29 23:12:49 -03:00
|
|
|
void Copter::init_rc_out()
|
2010-12-27 19:09:08 -04:00
|
|
|
{
|
2017-01-09 03:31:26 -04:00
|
|
|
motors->set_loop_rate(scheduler.get_loop_rate_hz());
|
|
|
|
motors->init((AP_Motors::motor_frame_class)g2.frame_class.get(), (AP_Motors::motor_frame_type)g.frame_type.get());
|
2017-04-17 06:00:26 -03:00
|
|
|
|
|
|
|
// enable aux servos to cope with multiple output channels per motor
|
|
|
|
SRV_Channels::enable_aux_servos();
|
|
|
|
|
|
|
|
// update rate must be set after motors->init() to allow for motor mapping
|
|
|
|
motors->set_update_rate(g.rc_speed);
|
|
|
|
|
2015-07-15 02:35:20 -03:00
|
|
|
#if FRAME_CONFIG != HELI_FRAME
|
2022-05-11 19:04:37 -03:00
|
|
|
if (channel_throttle->configured()) {
|
2021-09-04 14:37:59 -03:00
|
|
|
// throttle inputs setup, use those to set motor PWM min and max if not already configured
|
|
|
|
motors->convert_pwm_min_max_param(channel_throttle->get_radio_min(), channel_throttle->get_radio_max());
|
|
|
|
} else {
|
|
|
|
// throttle inputs default, force set motor PWM min and max to defaults so they will not be over-written by a future change in RC min / max
|
|
|
|
motors->convert_pwm_min_max_param(1000, 2000);
|
|
|
|
}
|
2021-09-04 14:12:23 -03:00
|
|
|
motors->update_throttle_range();
|
2017-02-10 03:35:34 -04:00
|
|
|
#else
|
2019-10-17 03:03:15 -03:00
|
|
|
// setup correct scaling for ESCs like the UAVCAN ESCs which
|
2017-02-10 03:35:34 -04:00
|
|
|
// take a proportion of speed.
|
|
|
|
hal.rcout->set_esc_scaling(channel_throttle->get_radio_min(), channel_throttle->get_radio_max());
|
2015-07-15 02:35:20 -03:00
|
|
|
#endif
|
2012-08-16 21:50:02 -03:00
|
|
|
|
2015-06-10 03:00:18 -03:00
|
|
|
// refresh auxiliary channel to function map
|
2017-01-06 21:06:40 -04:00
|
|
|
SRV_Channels::update_aux_servo_function();
|
2016-10-20 21:53:59 -03:00
|
|
|
|
|
|
|
#if FRAME_CONFIG != HELI_FRAME
|
|
|
|
/*
|
|
|
|
setup a default safety ignore mask, so that servo gimbals can be active while safety is on
|
|
|
|
*/
|
2017-01-09 03:31:26 -04:00
|
|
|
uint16_t safety_ignore_mask = (~copter.motors->get_motor_mask()) & 0x3FFF;
|
2016-10-20 21:53:59 -03:00
|
|
|
BoardConfig.set_default_safety_ignore_mask(safety_ignore_mask);
|
|
|
|
#endif
|
2011-03-26 18:03:20 -03:00
|
|
|
}
|
2011-03-06 20:57:06 -04:00
|
|
|
|
2016-10-20 21:53:59 -03:00
|
|
|
|
2015-04-22 15:59:34 -03:00
|
|
|
// enable_motor_output() - enable and output lowest possible value to motors
|
2015-05-29 23:12:49 -03:00
|
|
|
void Copter::enable_motor_output()
|
2011-03-26 18:03:20 -03:00
|
|
|
{
|
2012-08-16 21:50:02 -03:00
|
|
|
// enable motors
|
2017-01-09 03:31:26 -04:00
|
|
|
motors->output_min();
|
2010-12-19 12:40:33 -04:00
|
|
|
}
|
2012-11-13 05:18:21 -04:00
|
|
|
|
2015-05-29 23:12:49 -03:00
|
|
|
void Copter::read_radio()
|
2010-12-26 01:25:52 -04:00
|
|
|
{
|
2018-08-03 04:23:34 -03:00
|
|
|
const uint32_t tnow_ms = millis();
|
2014-10-07 11:01:15 -03:00
|
|
|
|
2018-06-04 00:06:32 -03:00
|
|
|
if (rc().read_input()) {
|
2013-10-08 03:25:14 -03:00
|
|
|
ap.new_radio_frame = true;
|
2015-05-11 23:24:13 -03:00
|
|
|
|
ArduCopter: 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:46:59 -03:00
|
|
|
set_throttle_and_failsafe(channel_throttle->get_radio_in());
|
|
|
|
set_throttle_zero_flag(channel_throttle->get_control_in());
|
2014-09-23 10:55:19 -03:00
|
|
|
|
2019-09-13 21:56:36 -03:00
|
|
|
// RC receiver must be attached if we've just got input
|
|
|
|
ap.rc_receiver_present = true;
|
2014-04-02 22:19:44 -03:00
|
|
|
|
2016-02-05 21:43:16 -04:00
|
|
|
// pass pilot input through to motors (used to allow wiggling servos while disarmed on heli, single, coax copters)
|
|
|
|
radio_passthrough_to_motors();
|
|
|
|
|
2018-08-04 08:32:31 -03:00
|
|
|
const float dt = (tnow_ms - last_radio_update_ms)*1.0e-3f;
|
2017-01-06 21:06:40 -04:00
|
|
|
rc_throttle_control_in_filter.apply(channel_throttle->get_control_in(), dt);
|
2016-08-16 07:23:27 -03:00
|
|
|
last_radio_update_ms = tnow_ms;
|
2018-08-04 08:32:31 -03:00
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
|
|
|
// No radio input this time
|
|
|
|
if (failsafe.radio) {
|
|
|
|
// already in failsafe!
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
|
|
|
const uint32_t elapsed = tnow_ms - last_radio_update_ms;
|
2021-11-17 10:12:22 -04:00
|
|
|
// turn on throttle failsafe if no update from the RC Radio for 500ms or 1000ms if we are using RC_OVERRIDE
|
2018-08-04 08:32:31 -03:00
|
|
|
const uint32_t timeout = RC_Channels::has_active_overrides() ? FS_RADIO_RC_OVERRIDE_TIMEOUT_MS : FS_RADIO_TIMEOUT_MS;
|
|
|
|
if (elapsed < timeout) {
|
|
|
|
// not timed out yet
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
if (!g.failsafe_throttle) {
|
|
|
|
// throttle failsafe not enabled
|
|
|
|
return;
|
2012-08-16 21:50:02 -03:00
|
|
|
}
|
2018-08-04 08:32:31 -03:00
|
|
|
if (!ap.rc_receiver_present && !motors->armed()) {
|
|
|
|
// we only failsafe if we are armed OR we have ever seen an RC receiver
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
|
|
|
// Nobody ever talks to us. Log an error and enter failsafe.
|
2019-03-24 22:31:46 -03:00
|
|
|
AP::logger().Write_Error(LogErrorSubsystem::RADIO, LogErrorCode::RADIO_LATE_FRAME);
|
2018-08-04 08:32:31 -03:00
|
|
|
set_failsafe_radio(true);
|
2010-12-19 12:40:33 -04:00
|
|
|
}
|
2012-11-11 09:11:12 -04:00
|
|
|
|
2013-09-26 05:54:33 -03:00
|
|
|
#define FS_COUNTER 3 // radio failsafe kicks in after 3 consecutive throttle values below failsafe_throttle_value
|
2015-05-29 23:12:49 -03:00
|
|
|
void Copter::set_throttle_and_failsafe(uint16_t throttle_pwm)
|
2011-02-24 01:56:59 -04:00
|
|
|
{
|
2012-11-11 09:11:12 -04:00
|
|
|
// if failsafe not enabled pass through throttle and exit
|
2012-12-10 10:38:43 -04:00
|
|
|
if(g.failsafe_throttle == FS_THR_DISABLED) {
|
2012-08-16 21:50:02 -03:00
|
|
|
return;
|
2012-11-11 09:11:12 -04:00
|
|
|
}
|
2012-08-16 21:50:02 -03:00
|
|
|
|
2012-11-11 09:11:12 -04:00
|
|
|
//check for low throttle value
|
2012-12-10 10:38:43 -04:00
|
|
|
if (throttle_pwm < (uint16_t)g.failsafe_throttle_value) {
|
2012-11-11 09:11:12 -04:00
|
|
|
|
|
|
|
// if we are already in failsafe or motors not armed pass through throttle and exit
|
2017-01-09 03:31:26 -04:00
|
|
|
if (failsafe.radio || !(ap.rc_receiver_present || motors->armed())) {
|
2012-11-11 09:11:12 -04:00
|
|
|
return;
|
2012-08-16 21:50:02 -03:00
|
|
|
}
|
|
|
|
|
2012-11-11 09:11:12 -04:00
|
|
|
// check for 3 low throttle values
|
2016-05-12 14:24:23 -03:00
|
|
|
// Note: we do not pass through the low throttle until 3 low throttle values are received
|
2013-09-26 05:54:33 -03:00
|
|
|
failsafe.radio_counter++;
|
|
|
|
if( failsafe.radio_counter >= FS_COUNTER ) {
|
|
|
|
failsafe.radio_counter = FS_COUNTER; // check to ensure we don't overflow the counter
|
2013-03-16 05:14:21 -03:00
|
|
|
set_failsafe_radio(true);
|
2012-08-16 21:50:02 -03:00
|
|
|
}
|
2012-11-11 09:11:12 -04:00
|
|
|
}else{
|
|
|
|
// we have a good throttle so reduce failsafe counter
|
2013-09-26 05:54:33 -03:00
|
|
|
failsafe.radio_counter--;
|
|
|
|
if( failsafe.radio_counter <= 0 ) {
|
|
|
|
failsafe.radio_counter = 0; // check to ensure we don't underflow the counter
|
2012-11-11 09:11:12 -04:00
|
|
|
|
|
|
|
// disengage failsafe after three (nearly) consecutive valid throttle values
|
2013-09-26 05:54:33 -03:00
|
|
|
if (failsafe.radio) {
|
2013-03-16 05:14:21 -03:00
|
|
|
set_failsafe_radio(false);
|
2012-11-11 09:11:12 -04:00
|
|
|
}
|
2012-08-16 21:50:02 -03:00
|
|
|
}
|
2012-11-11 09:11:12 -04:00
|
|
|
// pass through throttle
|
2012-08-16 21:50:02 -03:00
|
|
|
}
|
2011-02-24 01:56:59 -04:00
|
|
|
}
|
|
|
|
|
2014-10-08 09:52:16 -03:00
|
|
|
#define THROTTLE_ZERO_DEBOUNCE_TIME_MS 400
|
2015-03-13 16:38:23 -03:00
|
|
|
// set_throttle_zero_flag - set throttle_zero flag from debounced throttle control
|
|
|
|
// throttle_zero is used to determine if the pilot intends to shut down the motors
|
|
|
|
// Basically, this signals when we are not flying. We are either on the ground
|
|
|
|
// or the pilot has shut down the copter in the air and it is free-falling
|
2015-05-29 23:12:49 -03:00
|
|
|
void Copter::set_throttle_zero_flag(int16_t throttle_control)
|
2014-10-08 09:52:16 -03:00
|
|
|
{
|
|
|
|
static uint32_t last_nonzero_throttle_ms = 0;
|
|
|
|
uint32_t tnow_ms = millis();
|
|
|
|
|
2015-03-13 16:38:23 -03:00
|
|
|
// if not using throttle interlock and non-zero throttle and not E-stopped,
|
|
|
|
// or using motor interlock and it's enabled, then motors are running,
|
|
|
|
// and we are flying. Immediately set as non-zero
|
2019-01-25 14:57:36 -04:00
|
|
|
if ((!ap.using_interlock && (throttle_control > 0) && !SRV_Channels::get_emergency_stop()) ||
|
2018-05-27 05:12:00 -03:00
|
|
|
(ap.using_interlock && motors->get_interlock()) ||
|
2021-09-13 21:08:28 -03:00
|
|
|
ap.armed_with_airmode_switch || air_mode == AirMode::AIRMODE_ENABLED) {
|
2014-10-08 09:52:16 -03:00
|
|
|
last_nonzero_throttle_ms = tnow_ms;
|
|
|
|
ap.throttle_zero = false;
|
|
|
|
} else if (tnow_ms - last_nonzero_throttle_ms > THROTTLE_ZERO_DEBOUNCE_TIME_MS) {
|
|
|
|
ap.throttle_zero = true;
|
|
|
|
}
|
2015-03-16 01:35:57 -03:00
|
|
|
}
|
2016-02-05 21:43:16 -04:00
|
|
|
|
|
|
|
// pass pilot's inputs to motors library (used to allow wiggling servos while disarmed on heli, single, coax copters)
|
|
|
|
void Copter::radio_passthrough_to_motors()
|
|
|
|
{
|
2017-09-19 22:10:09 -03:00
|
|
|
motors->set_radio_passthrough(channel_roll->norm_input(),
|
|
|
|
channel_pitch->norm_input(),
|
2019-04-04 02:41:10 -03:00
|
|
|
channel_throttle->get_control_in_zero_dz()*0.001f,
|
2017-09-19 22:10:09 -03:00
|
|
|
channel_yaw->norm_input());
|
2016-02-05 21:43:16 -04:00
|
|
|
}
|
2018-01-18 02:49:20 -04:00
|
|
|
|
|
|
|
/*
|
|
|
|
return the throttle input for mid-stick as a control-in value
|
|
|
|
*/
|
|
|
|
int16_t Copter::get_throttle_mid(void)
|
|
|
|
{
|
|
|
|
#if TOY_MODE_ENABLED == ENABLED
|
|
|
|
if (g2.toy_mode.enabled()) {
|
|
|
|
return g2.toy_mode.get_throttle_mid();
|
|
|
|
}
|
|
|
|
#endif
|
|
|
|
return channel_throttle->get_control_mid();
|
|
|
|
}
|