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.
|
2016-10-22 07:27:57 -03:00
|
|
|
channel_roll = RC_Channels::rc_channel(rcmap.yaw()-1);
|
2015-04-15 22:16:30 -03:00
|
|
|
} else {
|
2016-10-22 07:27:57 -03:00
|
|
|
channel_roll = RC_Channels::rc_channel(rcmap.roll()-1);
|
2015-04-15 22:16:30 -03:00
|
|
|
}
|
2016-10-22 07:27:57 -03:00
|
|
|
channel_pitch = RC_Channels::rc_channel(rcmap.pitch()-1);
|
|
|
|
channel_throttle = RC_Channels::rc_channel(rcmap.throttle()-1);
|
|
|
|
channel_rudder = RC_Channels::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
|
2016-10-22 07:27:57 -03:00
|
|
|
channel_throttle->set_range(100);
|
2016-01-30 03:22:21 -04:00
|
|
|
} else {
|
|
|
|
// reverse thrust
|
|
|
|
channel_throttle->set_angle(100);
|
2017-02-12 21:03:22 -04:00
|
|
|
SRV_Channels::set_angle(SRV_Channel::k_throttle, 100);
|
|
|
|
SRV_Channels::set_angle(SRV_Channel::k_throttleLeft, 100);
|
|
|
|
SRV_Channels::set_angle(SRV_Channel::k_throttleRight, 100);
|
2016-01-30 03:22:21 -04:00
|
|
|
}
|
2014-01-15 07:28:00 -04:00
|
|
|
|
|
|
|
if (!arming.is_armed() && arming.arming_required() == AP_Arming::YES_MIN_PWM) {
|
2016-10-22 07:27:57 -03:00
|
|
|
SRV_Channels::set_safety_limit(SRV_Channel::k_throttle, aparm.throttle_min<0?SRV_Channel::SRV_CHANNEL_LIMIT_TRIM:SRV_Channel::SRV_CHANNEL_LIMIT_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
|
2016-10-22 07:27:57 -03:00
|
|
|
g2.servo_channels.set_esc_scaling_for(SRV_Channel::k_throttle);
|
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
|
|
|
/*
|
2016-06-30 03:48:30 -03:00
|
|
|
initialise RC output for main channels. This is done early to allow
|
|
|
|
for BRD_SAFETYENABLE=0 and early servo control
|
2013-06-03 03:42:38 -03:00
|
|
|
*/
|
2016-06-30 03:48:30 -03:00
|
|
|
void Plane::init_rc_out_main()
|
2011-09-08 22:29:39 -03:00
|
|
|
{
|
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
|
|
|
|
*/
|
2016-10-22 07:27:57 -03:00
|
|
|
if (aparm.throttle_min >= 0) {
|
|
|
|
SRV_Channels::set_trim_to_min_for(SRV_Channel::k_throttle);
|
2013-12-19 20:59:45 -04:00
|
|
|
}
|
2016-06-30 03:48:30 -03:00
|
|
|
|
2016-10-22 07:27:57 -03:00
|
|
|
SRV_Channels::set_failsafe_limit(SRV_Channel::k_aileron, SRV_Channel::SRV_CHANNEL_LIMIT_TRIM);
|
|
|
|
SRV_Channels::set_failsafe_limit(SRV_Channel::k_elevator, SRV_Channel::SRV_CHANNEL_LIMIT_TRIM);
|
|
|
|
SRV_Channels::set_failsafe_limit(SRV_Channel::k_throttle, SRV_Channel::SRV_CHANNEL_LIMIT_TRIM);
|
|
|
|
SRV_Channels::set_failsafe_limit(SRV_Channel::k_rudder, SRV_Channel::SRV_CHANNEL_LIMIT_TRIM);
|
|
|
|
|
2016-06-30 03:48:30 -03: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) {
|
2016-10-22 07:27:57 -03:00
|
|
|
SRV_Channels::set_safety_limit(SRV_Channel::k_throttle, aparm.throttle_min<0?SRV_Channel::SRV_CHANNEL_LIMIT_TRIM:SRV_Channel::SRV_CHANNEL_LIMIT_MIN);
|
2016-06-30 03:48:30 -03:00
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
/*
|
|
|
|
initialise RC output channels for aux channels
|
|
|
|
*/
|
|
|
|
void Plane::init_rc_out_aux()
|
|
|
|
{
|
2016-01-04 18:38:02 -04:00
|
|
|
update_aux();
|
2016-10-22 07:27:57 -03:00
|
|
|
SRV_Channels::enable_aux_servos();
|
2012-08-04 13:39:20 -03:00
|
|
|
|
2016-10-11 19:29:37 -03:00
|
|
|
hal.rcout->cork();
|
|
|
|
|
2012-09-16 02:51:13 -03:00
|
|
|
// Initialization of servo outputs
|
2016-10-22 07:27:57 -03:00
|
|
|
SRV_Channels::output_trim_all();
|
2014-01-15 07:28:00 -04:00
|
|
|
|
2016-10-11 19:29:37 -03:00
|
|
|
servos_output();
|
|
|
|
|
2014-04-20 19:37:56 -03:00
|
|
|
// setup PWM values to send if the FMU firmware dies
|
2016-10-22 07:27:57 -03:00
|
|
|
SRV_Channels::setup_failsafe_trim_all();
|
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
|
|
|
{
|
2017-01-09 04:00:21 -04:00
|
|
|
AP_Arming_Plane::ArmingRudder arming_rudder = arming.rudder_arming();
|
2013-11-27 22:19:34 -04:00
|
|
|
|
2017-01-09 04:00:21 -04:00
|
|
|
if (arming_rudder == AP_Arming_Plane::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
|
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
|
|
|
if (channel_throttle->get_control_in() != 0){
|
2013-11-27 22:19:34 -04:00
|
|
|
rudder_arm_timer = 0;
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
2016-10-07 18:01:25 -03:00
|
|
|
// if not in a manual throttle mode and not in CRUISE or FBWB
|
|
|
|
// modes then disallow rudder arming/disarming
|
|
|
|
if (auto_throttle_mode &&
|
|
|
|
(control_mode != CRUISE && control_mode != FLY_BY_WIRE_B)) {
|
2013-11-27 22:19:34 -04:00
|
|
|
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
|
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
|
|
|
if (channel_rudder->get_control_in() > 4000) {
|
2015-07-16 14:47:08 -03:00
|
|
|
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;
|
|
|
|
}
|
2017-01-09 04:00:21 -04:00
|
|
|
} else if (arming_rudder == AP_Arming_Plane::ARMING_RUDDER_ARMDISARM && !is_flying()) {
|
2015-07-16 14:47:08 -03:00
|
|
|
// when armed and not flying, full left rudder starts disarming counter
|
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
|
|
|
if (channel_rudder->get_control_in() < -4000) {
|
2015-07-16 14:47:08 -03:00
|
|
|
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()) {
|
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
|
|
|
control_failsafe(channel_throttle->get_radio_in());
|
2013-12-19 18:41:15 -04:00
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
2016-03-24 16:17:41 -03:00
|
|
|
if(!failsafe.ch3_failsafe)
|
|
|
|
{
|
|
|
|
failsafe.AFS_last_valid_rc_ms = millis();
|
|
|
|
}
|
|
|
|
|
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
|
|
|
|
2017-07-01 08:14:46 -03:00
|
|
|
pwm_roll = elevon.ch1_temp;
|
|
|
|
pwm_pitch = elevon.ch2_temp;
|
2014-04-02 22:19:11 -03:00
|
|
|
|
2016-10-22 07:27:57 -03:00
|
|
|
RC_Channels::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
|
|
|
}
|
|
|
|
|
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
|
|
|
control_failsafe(channel_throttle->get_radio_in());
|
2012-08-21 23:19:50 -03:00
|
|
|
|
2016-10-22 07:27:57 -03:00
|
|
|
SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, channel_throttle->get_control_in());
|
2012-08-21 23:19:50 -03:00
|
|
|
|
2016-10-22 07:27:57 -03:00
|
|
|
if (g.throttle_nudge && SRV_Channels::get_output_scaled(SRV_Channel::k_throttle) > 50 && geofence_stickmixing()) {
|
|
|
|
float nudge = (SRV_Channels::get_output_scaled(SRV_Channel::k_throttle) - 50) * 0.02f;
|
2015-01-19 20:28:35 -04:00
|
|
|
if (ahrs.airspeed_sensor_enabled()) {
|
2016-11-17 21:07:10 -04:00
|
|
|
airspeed_nudge_cm = (aparm.airspeed_max * 100 - aparm.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;
|
2016-07-04 23:52:13 -03:00
|
|
|
} else if (stick_mixing_enabled()) {
|
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
|
|
|
rudder_input = channel_rudder->get_control_in();
|
2016-07-04 23:52:13 -03:00
|
|
|
} else {
|
|
|
|
// no stick mixing
|
|
|
|
rudder_input = 0;
|
2015-04-16 10:30:32 -03:00
|
|
|
}
|
2016-04-16 07:26:43 -03:00
|
|
|
|
2017-02-24 01:47:09 -04:00
|
|
|
// potentially swap inputs for tailsitters
|
|
|
|
quadplane.tailsitter_check_input();
|
|
|
|
|
2016-05-06 01:43:39 -03:00
|
|
|
// check for transmitter tuning changes
|
|
|
|
tuning.check_input(control_mode);
|
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
|
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
|
|
|
channel_roll->set_radio_in(channel_roll->get_radio_trim());
|
|
|
|
channel_pitch->set_radio_in(channel_pitch->get_radio_trim());
|
|
|
|
channel_rudder->set_radio_in(channel_rudder->get_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
|
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
|
|
|
channel_roll->set_control_in(0);
|
|
|
|
channel_pitch->set_control_in(0);
|
|
|
|
channel_rudder->set_control_in(0);
|
|
|
|
channel_throttle->set_control_in(0);
|
2014-03-08 01:20:09 -04:00
|
|
|
}
|
|
|
|
|
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) {
|
2017-07-08 22:15:58 -03:00
|
|
|
gcs().send_text(MAV_SEVERITY_WARNING, "Throttle failsafe 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) {
|
2017-07-08 22:15:58 -03:00
|
|
|
gcs().send_text(MAV_SEVERITY_WARNING, "Throttle failsafe 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();
|
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
|
|
|
int16_t trim_roll_range = (channel_roll->get_radio_max() - channel_roll->get_radio_min())/5;
|
|
|
|
int16_t trim_pitch_range = (channel_pitch->get_radio_max() - channel_pitch->get_radio_min())/5;
|
|
|
|
if (channel_roll->get_radio_in() < channel_roll->get_radio_min()+trim_roll_range ||
|
|
|
|
channel_roll->get_radio_in() > channel_roll->get_radio_max()-trim_roll_range ||
|
|
|
|
channel_pitch->get_radio_in() < channel_pitch->get_radio_min()+trim_pitch_range ||
|
|
|
|
channel_pitch->get_radio_in() > channel_pitch->get_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;
|
|
|
|
}
|
|
|
|
|
2017-07-01 07:05:17 -03:00
|
|
|
// trim ailerons if not used as old elevons
|
|
|
|
if (g.elevon_output == MIXING_DISABLED) {
|
|
|
|
SRV_Channels::set_trim_to_servo_out_for(SRV_Channel::k_aileron);
|
|
|
|
}
|
2012-11-20 20:48:46 -04:00
|
|
|
|
2017-07-01 07:05:17 -03:00
|
|
|
// trim elevator if not used as old elevons or vtail
|
|
|
|
if (g.elevon_output == MIXING_DISABLED && g.vtail_output == MIXING_DISABLED) {
|
|
|
|
SRV_Channels::set_trim_to_servo_out_for(SRV_Channel::k_elevator);
|
|
|
|
}
|
|
|
|
|
|
|
|
// trim rudder if not used as old vtail
|
|
|
|
if (g.vtail_output == MIXING_DISABLED) {
|
|
|
|
SRV_Channels::set_trim_to_servo_out_for(SRV_Channel::k_rudder);
|
2012-08-21 23:19:50 -03:00
|
|
|
}
|
2017-07-01 07:05:17 -03:00
|
|
|
|
|
|
|
SRV_Channels::set_trim_to_servo_out_for(SRV_Channel::k_aileron_with_input);
|
|
|
|
SRV_Channels::set_trim_to_servo_out_for(SRV_Channel::k_elevator_with_input);
|
|
|
|
|
|
|
|
// trim elevons
|
|
|
|
SRV_Channels::set_trim_to_servo_out_for(SRV_Channel::k_elevon_left);
|
|
|
|
SRV_Channels::set_trim_to_servo_out_for(SRV_Channel::k_elevon_right);
|
|
|
|
|
|
|
|
// trim vtail
|
|
|
|
SRV_Channels::set_trim_to_servo_out_for(SRV_Channel::k_vtail_left);
|
|
|
|
SRV_Channels::set_trim_to_servo_out_for(SRV_Channel::k_vtail_right);
|
|
|
|
|
|
|
|
if (SRV_Channels::get_output_scaled(SRV_Channel::k_rudder) == 0) {
|
|
|
|
// trim differential spoilers if no rudder input
|
|
|
|
SRV_Channels::set_trim_to_servo_out_for(SRV_Channel::k_dspoilerLeft1);
|
|
|
|
SRV_Channels::set_trim_to_servo_out_for(SRV_Channel::k_dspoilerLeft2);
|
|
|
|
SRV_Channels::set_trim_to_servo_out_for(SRV_Channel::k_dspoilerRight1);
|
|
|
|
SRV_Channels::set_trim_to_servo_out_for(SRV_Channel::k_dspoilerRight1);
|
|
|
|
}
|
|
|
|
|
|
|
|
if (SRV_Channels::get_output_scaled(SRV_Channel::k_flap_auto) == 0 &&
|
|
|
|
SRV_Channels::get_output_scaled(SRV_Channel::k_flap) == 0) {
|
|
|
|
// trim flaperons if no flap input
|
|
|
|
SRV_Channels::set_trim_to_servo_out_for(SRV_Channel::k_flaperon_left);
|
|
|
|
SRV_Channels::set_trim_to_servo_out_for(SRV_Channel::k_flaperon_right);
|
2013-01-24 23:27:44 -04:00
|
|
|
}
|
2012-08-21 23:19:50 -03:00
|
|
|
|
2017-07-01 07:05:17 -03:00
|
|
|
// now save input trims, as these have been moved to the outputs
|
|
|
|
channel_roll->set_and_save_trim();
|
|
|
|
channel_pitch->set_and_save_trim();
|
|
|
|
channel_rudder->set_and_save_trim();
|
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()) {
|
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
|
|
|
return channel_throttle->get_radio_in() >= g.throttle_fs_value;
|
2013-11-17 00:32:36 -04:00
|
|
|
}
|
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
|
|
|
return channel_throttle->get_radio_in() <= g.throttle_fs_value;
|
2013-11-17 00:32:36 -04:00
|
|
|
}
|