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
|
|
|
|
2012-09-11 00:01:36 -03:00
|
|
|
/*
|
|
|
|
get a speed scaling number for control surfaces. This is applied to
|
|
|
|
PIDs to change the scaling of the PID with speed. At high speed we
|
|
|
|
move the surfaces less, and at low speeds we move them more.
|
|
|
|
*/
|
2015-05-13 03:09:36 -03:00
|
|
|
float Plane::get_speed_scaler(void)
|
2012-09-11 00:01:36 -03:00
|
|
|
{
|
|
|
|
float aspeed, speed_scaler;
|
2012-08-24 09:03:03 -03:00
|
|
|
if (ahrs.airspeed_estimate(&aspeed)) {
|
2014-05-21 07:21:19 -03:00
|
|
|
if (aspeed > auto_state.highest_airspeed) {
|
|
|
|
auto_state.highest_airspeed = aspeed;
|
|
|
|
}
|
2016-06-04 06:20:18 -03:00
|
|
|
if (aspeed > 0.0001f) {
|
2012-08-21 23:19:50 -03:00
|
|
|
speed_scaler = g.scaling_speed / aspeed;
|
2012-07-15 22:21:50 -03:00
|
|
|
} else {
|
2012-08-21 23:19:50 -03:00
|
|
|
speed_scaler = 2.0;
|
2012-07-15 22:21:50 -03:00
|
|
|
}
|
2015-04-11 06:43:13 -03:00
|
|
|
speed_scaler = constrain_float(speed_scaler, 0.5f, 2.0f);
|
2012-08-21 23:19:50 -03:00
|
|
|
} else {
|
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_servo_out() > 0) {
|
|
|
|
speed_scaler = 0.5f + ((float)THROTTLE_CRUISE / channel_throttle->get_servo_out() / 2.0f); // First order taylor expansion of square root
|
2016-01-30 03:22:21 -04:00
|
|
|
// Should maybe be to the 2/7 power, but we aren't going to implement that...
|
2012-08-21 23:19:50 -03:00
|
|
|
}else{
|
2014-04-02 22:48:06 -03:00
|
|
|
speed_scaler = 1.67f;
|
2012-08-21 23:19:50 -03:00
|
|
|
}
|
2012-08-24 09:03:03 -03:00
|
|
|
// This case is constrained tighter as we don't have real speed info
|
2015-04-11 06:43:13 -03:00
|
|
|
speed_scaler = constrain_float(speed_scaler, 0.6f, 1.67f);
|
2012-08-21 23:19:50 -03:00
|
|
|
}
|
2012-09-11 00:01:36 -03:00
|
|
|
return speed_scaler;
|
|
|
|
}
|
|
|
|
|
2012-09-22 20:33:17 -03:00
|
|
|
/*
|
|
|
|
return true if the current settings and mode should allow for stick mixing
|
|
|
|
*/
|
2015-05-13 03:09:36 -03:00
|
|
|
bool Plane::stick_mixing_enabled(void)
|
2012-09-22 20:33:17 -03:00
|
|
|
{
|
2016-07-04 23:52:13 -03:00
|
|
|
if (auto_throttle_mode && auto_navigation_mode) {
|
2012-09-23 18:13:57 -03:00
|
|
|
// we're in an auto mode. Check the stick mixing flag
|
2013-04-01 18:52:56 -03:00
|
|
|
if (g.stick_mixing != STICK_MIXING_DISABLED &&
|
2012-09-23 18:13:57 -03:00
|
|
|
geofence_stickmixing() &&
|
2013-07-19 01:11:16 -03:00
|
|
|
failsafe.state == FAILSAFE_NONE &&
|
2014-03-08 01:20:09 -04:00
|
|
|
!rc_failsafe_active()) {
|
2012-09-23 18:13:57 -03:00
|
|
|
// we're in an auto mode, and haven't triggered failsafe
|
|
|
|
return true;
|
|
|
|
} else {
|
|
|
|
return false;
|
|
|
|
}
|
2012-09-22 20:33:17 -03:00
|
|
|
}
|
2013-09-13 21:30:13 -03:00
|
|
|
|
|
|
|
if (failsafe.ch3_failsafe && g.short_fs_action == 2) {
|
|
|
|
// don't do stick mixing in FBWA glide mode
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
2012-09-23 18:13:57 -03:00
|
|
|
// non-auto mode. Always do stick mixing
|
|
|
|
return true;
|
2012-09-22 20:33:17 -03:00
|
|
|
}
|
|
|
|
|
2012-09-11 00:01:36 -03:00
|
|
|
|
2012-12-04 02:32:37 -04:00
|
|
|
/*
|
|
|
|
this is the main roll stabilization function. It takes the
|
|
|
|
previously set nav_roll calculates roll servo_out to try to
|
|
|
|
stabilize the plane at the given roll
|
|
|
|
*/
|
2015-05-13 03:09:36 -03:00
|
|
|
void Plane::stabilize_roll(float speed_scaler)
|
2012-09-11 00:01:36 -03:00
|
|
|
{
|
2014-06-05 03:12:10 -03:00
|
|
|
if (fly_inverted()) {
|
2011-09-09 11:18:38 -03:00
|
|
|
// we want to fly upside down. We need to cope with wrap of
|
|
|
|
// the roll_sensor interfering with wrap of nav_roll, which
|
|
|
|
// would really confuse the PID code. The easiest way to
|
|
|
|
// handle this is to ensure both go in the same direction from
|
|
|
|
// zero
|
2012-08-07 03:05:51 -03:00
|
|
|
nav_roll_cd += 18000;
|
|
|
|
if (ahrs.roll_sensor < 0) nav_roll_cd -= 36000;
|
2011-09-09 11:18:38 -03:00
|
|
|
}
|
|
|
|
|
2013-08-02 08:55:34 -03:00
|
|
|
bool disable_integrator = false;
|
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 (control_mode == STABILIZE && channel_roll->get_control_in() != 0) {
|
2013-08-02 08:55:34 -03:00
|
|
|
disable_integrator = true;
|
|
|
|
}
|
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_servo_out(rollController.get_servo_out(nav_roll_cd - ahrs.roll_sensor,
|
2013-08-14 01:57:41 -03:00
|
|
|
speed_scaler,
|
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
|
|
|
disable_integrator));
|
2012-12-04 02:32:37 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
/*
|
|
|
|
this is the main pitch stabilization function. It takes the
|
|
|
|
previously set nav_pitch and calculates servo_out values to try to
|
|
|
|
stabilize the plane at the given attitude.
|
|
|
|
*/
|
2015-05-13 03:09:36 -03:00
|
|
|
void Plane::stabilize_pitch(float speed_scaler)
|
2012-12-04 02:32:37 -04:00
|
|
|
{
|
2014-05-21 07:21:19 -03:00
|
|
|
int8_t force_elevator = takeoff_tail_hold();
|
|
|
|
if (force_elevator != 0) {
|
2016-01-30 03:22:21 -04:00
|
|
|
// we are holding the tail down during takeoff. Just convert
|
2014-05-21 07:21:19 -03:00
|
|
|
// from a percentage to a -4500..4500 centidegree angle
|
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_pitch->set_servo_out(45*force_elevator);
|
2014-05-21 07:21:19 -03:00
|
|
|
return;
|
|
|
|
}
|
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
|
|
|
int32_t demanded_pitch = nav_pitch_cd + g.pitch_trim_cd + channel_throttle->get_servo_out() * g.kff_throttle_to_pitch;
|
2013-08-02 08:55:34 -03:00
|
|
|
bool disable_integrator = false;
|
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 (control_mode == STABILIZE && channel_pitch->get_control_in() != 0) {
|
2013-08-02 08:55:34 -03:00
|
|
|
disable_integrator = true;
|
|
|
|
}
|
2016-05-09 07:21:00 -03:00
|
|
|
channel_pitch->set_servo_out(pitchController.get_servo_out(demanded_pitch - ahrs.pitch_sensor,
|
2013-08-14 01:57:41 -03:00
|
|
|
speed_scaler,
|
2016-05-09 07:21:00 -03:00
|
|
|
disable_integrator));
|
2012-12-04 02:32:37 -04:00
|
|
|
}
|
2011-09-08 22:29:39 -03:00
|
|
|
|
2013-10-03 09:51:43 -03:00
|
|
|
/*
|
|
|
|
perform stick mixing on one channel
|
|
|
|
This type of stick mixing reduces the influence of the auto
|
|
|
|
controller as it increases the influence of the users stick input,
|
|
|
|
allowing the user full deflection if needed
|
|
|
|
*/
|
2015-05-13 03:09:36 -03:00
|
|
|
void Plane::stick_mix_channel(RC_Channel *channel, int16_t &servo_out)
|
2013-10-03 09:51:43 -03:00
|
|
|
{
|
|
|
|
float ch_inf;
|
|
|
|
|
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
|
|
|
ch_inf = (float)channel->get_radio_in() - (float)channel->get_radio_trim();
|
2013-10-03 09:51:43 -03:00
|
|
|
ch_inf = fabsf(ch_inf);
|
2015-11-27 13:11:58 -04:00
|
|
|
ch_inf = MIN(ch_inf, 400.0f);
|
2014-07-08 07:26:07 -03:00
|
|
|
ch_inf = ((400.0f - ch_inf) / 400.0f);
|
2014-03-04 21:13:19 -04:00
|
|
|
servo_out *= ch_inf;
|
|
|
|
servo_out += channel->pwm_to_angle();
|
2013-10-03 09:51:43 -03:00
|
|
|
}
|
|
|
|
|
2016-05-09 07:21:00 -03:00
|
|
|
/*
|
|
|
|
One argument version for when the servo out in the rc channel
|
|
|
|
is the target
|
|
|
|
*/
|
|
|
|
void Plane::stick_mix_channel(RC_Channel * channel)
|
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
|
|
|
{
|
2016-05-09 07:21:00 -03:00
|
|
|
int16_t servo_out = channel->get_servo_out();
|
|
|
|
stick_mix_channel(channel,servo_out);
|
|
|
|
channel->set_servo_out(servo_out);
|
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
|
|
|
}
|
|
|
|
|
2012-12-04 02:32:37 -04:00
|
|
|
/*
|
|
|
|
this gives the user control of the aircraft in stabilization modes
|
|
|
|
*/
|
2015-05-13 03:09:36 -03:00
|
|
|
void Plane::stabilize_stick_mixing_direct()
|
2012-12-04 02:32:37 -04:00
|
|
|
{
|
|
|
|
if (!stick_mixing_enabled() ||
|
2013-07-10 10:25:38 -03:00
|
|
|
control_mode == ACRO ||
|
2012-12-04 02:32:37 -04:00
|
|
|
control_mode == FLY_BY_WIRE_A ||
|
2014-04-12 01:12:14 -03:00
|
|
|
control_mode == AUTOTUNE ||
|
2012-12-04 02:32:37 -04:00
|
|
|
control_mode == FLY_BY_WIRE_B ||
|
2013-07-13 07:05:53 -03:00
|
|
|
control_mode == CRUISE ||
|
2015-12-26 03:45:42 -04:00
|
|
|
control_mode == QSTABILIZE ||
|
|
|
|
control_mode == QHOVER ||
|
2015-12-26 04:51:05 -04:00
|
|
|
control_mode == QLOITER ||
|
2016-03-09 03:20:41 -04:00
|
|
|
control_mode == QLAND ||
|
2016-04-29 02:31:08 -03:00
|
|
|
control_mode == QRTL ||
|
2012-12-04 02:32:37 -04:00
|
|
|
control_mode == TRAINING) {
|
|
|
|
return;
|
|
|
|
}
|
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
|
|
|
stick_mix_channel(channel_roll);
|
|
|
|
stick_mix_channel(channel_pitch);
|
2012-12-04 02:32:37 -04:00
|
|
|
}
|
|
|
|
|
2013-04-01 18:52:56 -03:00
|
|
|
/*
|
|
|
|
this gives the user control of the aircraft in stabilization modes
|
|
|
|
using FBW style controls
|
|
|
|
*/
|
2015-05-13 03:09:36 -03:00
|
|
|
void Plane::stabilize_stick_mixing_fbw()
|
2013-04-01 18:52:56 -03:00
|
|
|
{
|
|
|
|
if (!stick_mixing_enabled() ||
|
2013-07-10 10:25:38 -03:00
|
|
|
control_mode == ACRO ||
|
2013-04-01 18:52:56 -03:00
|
|
|
control_mode == FLY_BY_WIRE_A ||
|
2014-04-12 01:12:14 -03:00
|
|
|
control_mode == AUTOTUNE ||
|
2013-04-01 18:52:56 -03:00
|
|
|
control_mode == FLY_BY_WIRE_B ||
|
2013-07-13 07:05:53 -03:00
|
|
|
control_mode == CRUISE ||
|
2015-12-26 03:45:42 -04:00
|
|
|
control_mode == QSTABILIZE ||
|
|
|
|
control_mode == QHOVER ||
|
2015-12-26 04:51:05 -04:00
|
|
|
control_mode == QLOITER ||
|
2016-03-09 03:20:41 -04:00
|
|
|
control_mode == QLAND ||
|
2016-04-29 02:31:08 -03:00
|
|
|
control_mode == QRTL ||
|
2013-09-19 23:31:35 -03:00
|
|
|
control_mode == TRAINING ||
|
2016-04-05 18:58:23 -03:00
|
|
|
(control_mode == AUTO && g.auto_fbw_steer == 42)) {
|
2013-04-01 18:52:56 -03:00
|
|
|
return;
|
|
|
|
}
|
|
|
|
// do FBW style stick mixing. We don't treat it linearly
|
|
|
|
// however. For inputs up to half the maximum, we use linear
|
|
|
|
// addition to the nav_roll and nav_pitch. Above that it goes
|
|
|
|
// non-linear and ends up as 2x the maximum, to ensure that
|
|
|
|
// the user can direct the plane in any direction with stick
|
|
|
|
// mixing.
|
2013-06-03 02:32:08 -03:00
|
|
|
float roll_input = channel_roll->norm_input();
|
2013-05-26 19:24:35 -03:00
|
|
|
if (roll_input > 0.5f) {
|
2013-04-01 18:52:56 -03:00
|
|
|
roll_input = (3*roll_input - 1);
|
2013-05-26 19:24:35 -03:00
|
|
|
} else if (roll_input < -0.5f) {
|
|
|
|
roll_input = (3*roll_input + 1);
|
2013-04-01 18:52:56 -03:00
|
|
|
}
|
2013-11-04 04:48:22 -04:00
|
|
|
nav_roll_cd += roll_input * roll_limit_cd;
|
|
|
|
nav_roll_cd = constrain_int32(nav_roll_cd, -roll_limit_cd, roll_limit_cd);
|
2013-04-01 18:52:56 -03:00
|
|
|
|
2013-06-03 02:32:08 -03:00
|
|
|
float pitch_input = channel_pitch->norm_input();
|
2016-06-01 19:07:55 -03:00
|
|
|
if (pitch_input > 0.5f) {
|
2013-04-01 18:52:56 -03:00
|
|
|
pitch_input = (3*pitch_input - 1);
|
2016-06-01 19:07:55 -03:00
|
|
|
} else if (pitch_input < -0.5f) {
|
|
|
|
pitch_input = (3*pitch_input + 1);
|
2013-04-01 18:52:56 -03:00
|
|
|
}
|
2014-06-05 03:12:10 -03:00
|
|
|
if (fly_inverted()) {
|
2013-04-01 18:52:56 -03:00
|
|
|
pitch_input = -pitch_input;
|
|
|
|
}
|
|
|
|
if (pitch_input > 0) {
|
2013-06-26 07:48:45 -03:00
|
|
|
nav_pitch_cd += pitch_input * aparm.pitch_limit_max_cd;
|
2013-04-01 18:52:56 -03:00
|
|
|
} else {
|
2013-11-04 04:48:22 -04:00
|
|
|
nav_pitch_cd += -(pitch_input * pitch_limit_min_cd);
|
2013-04-01 18:52:56 -03:00
|
|
|
}
|
2013-11-04 04:48:22 -04:00
|
|
|
nav_pitch_cd = constrain_int32(nav_pitch_cd, pitch_limit_min_cd, aparm.pitch_limit_max_cd.get());
|
2013-04-01 18:52:56 -03:00
|
|
|
}
|
|
|
|
|
2012-08-21 23:19:50 -03:00
|
|
|
|
2012-12-04 02:32:37 -04:00
|
|
|
/*
|
2013-10-03 09:01:43 -03:00
|
|
|
stabilize the yaw axis. There are 3 modes of operation:
|
|
|
|
|
|
|
|
- hold a specific heading with ground steering
|
|
|
|
- rate controlled with ground steering
|
|
|
|
- yaw control for coordinated flight
|
2012-12-04 02:32:37 -04:00
|
|
|
*/
|
2015-05-13 03:09:36 -03:00
|
|
|
void Plane::stabilize_yaw(float speed_scaler)
|
2012-12-04 02:32:37 -04:00
|
|
|
{
|
2014-08-26 06:37:36 -03:00
|
|
|
if (control_mode == AUTO && flight_stage == AP_SpdHgtControl::FLIGHT_LAND_FINAL) {
|
|
|
|
// in land final setup for ground steering
|
|
|
|
steering_control.ground_steering = true;
|
|
|
|
} else {
|
|
|
|
// otherwise use ground steering when no input control and we
|
|
|
|
// are below the GROUND_STEER_ALT
|
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
|
|
|
steering_control.ground_steering = (channel_roll->get_control_in() == 0 &&
|
2014-08-26 06:37:36 -03:00
|
|
|
fabsf(relative_altitude()) < g.ground_steer_alt);
|
2016-01-30 02:32:42 -04:00
|
|
|
if (control_mode == AUTO &&
|
|
|
|
(flight_stage == AP_SpdHgtControl::FLIGHT_LAND_APPROACH ||
|
|
|
|
flight_stage == AP_SpdHgtControl::FLIGHT_LAND_PREFLARE)) {
|
2014-08-28 22:36:09 -03:00
|
|
|
// don't use ground steering on landing approach
|
|
|
|
steering_control.ground_steering = false;
|
|
|
|
}
|
2014-08-26 06:37:36 -03:00
|
|
|
}
|
|
|
|
|
2012-12-04 02:32:37 -04:00
|
|
|
|
2014-03-04 21:13:19 -04:00
|
|
|
/*
|
2014-08-26 06:37:36 -03:00
|
|
|
first calculate steering_control.steering for a nose or tail
|
|
|
|
wheel.
|
|
|
|
We use "course hold" mode for the rudder when either in the
|
|
|
|
final stage of landing (when the wings are help level) or when
|
|
|
|
in course hold in FBWA mode (when we are below GROUND_STEER_ALT)
|
2014-03-04 21:13:19 -04:00
|
|
|
*/
|
2014-08-26 06:37:36 -03:00
|
|
|
if ((control_mode == AUTO && flight_stage == AP_SpdHgtControl::FLIGHT_LAND_FINAL) ||
|
|
|
|
(steer_state.hold_course_cd != -1 && steering_control.ground_steering)) {
|
2013-10-03 09:01:43 -03:00
|
|
|
calc_nav_yaw_course();
|
2014-03-04 21:13:19 -04:00
|
|
|
} else if (steering_control.ground_steering) {
|
2013-10-03 09:01:43 -03:00
|
|
|
calc_nav_yaw_ground();
|
|
|
|
}
|
2014-03-04 21:13:19 -04:00
|
|
|
|
|
|
|
/*
|
|
|
|
now calculate steering_control.rudder for the rudder
|
|
|
|
*/
|
|
|
|
calc_nav_yaw_coordinated(speed_scaler);
|
2011-09-08 22:29:39 -03:00
|
|
|
}
|
|
|
|
|
2012-12-04 02:32:37 -04:00
|
|
|
|
|
|
|
/*
|
|
|
|
a special stabilization function for training mode
|
|
|
|
*/
|
2015-05-13 03:09:36 -03:00
|
|
|
void Plane::stabilize_training(float speed_scaler)
|
2012-12-04 02:32:37 -04:00
|
|
|
{
|
|
|
|
if (training_manual_roll) {
|
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_servo_out(channel_roll->get_control_in());
|
2012-12-04 02:32:37 -04:00
|
|
|
} else {
|
|
|
|
// calculate what is needed to hold
|
|
|
|
stabilize_roll(speed_scaler);
|
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 ((nav_roll_cd > 0 && channel_roll->get_control_in() < channel_roll->get_servo_out()) ||
|
|
|
|
(nav_roll_cd < 0 && channel_roll->get_control_in() > channel_roll->get_servo_out())) {
|
2012-12-04 02:32:37 -04:00
|
|
|
// allow user to get out of the roll
|
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_servo_out(channel_roll->get_control_in());
|
2012-12-04 02:32:37 -04:00
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
if (training_manual_pitch) {
|
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_pitch->set_servo_out(channel_pitch->get_control_in());
|
2012-12-04 02:32:37 -04:00
|
|
|
} else {
|
|
|
|
stabilize_pitch(speed_scaler);
|
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 ((nav_pitch_cd > 0 && channel_pitch->get_control_in() < channel_pitch->get_servo_out()) ||
|
|
|
|
(nav_pitch_cd < 0 && channel_pitch->get_control_in() > channel_pitch->get_servo_out())) {
|
2012-12-04 02:32:37 -04:00
|
|
|
// allow user to get back to level
|
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_pitch->set_servo_out(channel_pitch->get_control_in());
|
2012-12-04 02:32:37 -04:00
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
stabilize_yaw(speed_scaler);
|
|
|
|
}
|
|
|
|
|
|
|
|
|
2013-07-10 10:25:38 -03:00
|
|
|
/*
|
|
|
|
this is the ACRO mode stabilization function. It does rate
|
|
|
|
stabilization on roll and pitch axes
|
|
|
|
*/
|
2015-05-13 03:09:36 -03:00
|
|
|
void Plane::stabilize_acro(float speed_scaler)
|
2013-07-10 10:25:38 -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
|
|
|
float roll_rate = (channel_roll->get_control_in()/4500.0f) * g.acro_roll_rate;
|
|
|
|
float pitch_rate = (channel_pitch->get_control_in()/4500.0f) * g.acro_pitch_rate;
|
2013-07-10 10:25:38 -03:00
|
|
|
|
2013-07-10 19:05:25 -03:00
|
|
|
/*
|
|
|
|
check for special roll handling near the pitch poles
|
|
|
|
*/
|
2015-05-04 23:34:27 -03:00
|
|
|
if (g.acro_locking && is_zero(roll_rate)) {
|
2013-07-10 19:05:25 -03:00
|
|
|
/*
|
|
|
|
we have no roll stick input, so we will enter "roll locked"
|
|
|
|
mode, and hold the roll we had when the stick was released
|
|
|
|
*/
|
2013-07-10 10:25:38 -03:00
|
|
|
if (!acro_state.locked_roll) {
|
|
|
|
acro_state.locked_roll = true;
|
2013-07-13 08:06:45 -03:00
|
|
|
acro_state.locked_roll_err = 0;
|
|
|
|
} else {
|
2013-10-11 23:30:27 -03:00
|
|
|
acro_state.locked_roll_err += ahrs.get_gyro().x * G_Dt;
|
2013-07-10 10:25:38 -03:00
|
|
|
}
|
2013-07-13 08:06:45 -03:00
|
|
|
int32_t roll_error_cd = -ToDeg(acro_state.locked_roll_err)*100;
|
|
|
|
nav_roll_cd = ahrs.roll_sensor + roll_error_cd;
|
|
|
|
// try to reduce the integrated angular error to zero. We set
|
|
|
|
// 'stabilze' to true, which disables the roll integrator
|
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_servo_out(rollController.get_servo_out(roll_error_cd,
|
2013-08-14 01:57:41 -03:00
|
|
|
speed_scaler,
|
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
|
|
|
true));
|
2013-07-10 10:25:38 -03:00
|
|
|
} else {
|
2013-07-10 19:05:25 -03:00
|
|
|
/*
|
|
|
|
aileron stick is non-zero, use pure rate control until the
|
|
|
|
user releases the stick
|
|
|
|
*/
|
2013-07-10 10:25:38 -03:00
|
|
|
acro_state.locked_roll = false;
|
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_servo_out(rollController.get_rate_out(roll_rate, speed_scaler));
|
2013-07-10 10:25:38 -03:00
|
|
|
}
|
|
|
|
|
2015-05-04 23:34:27 -03:00
|
|
|
if (g.acro_locking && is_zero(pitch_rate)) {
|
2013-07-10 19:05:25 -03:00
|
|
|
/*
|
|
|
|
user has zero pitch stick input, so we lock pitch at the
|
|
|
|
point they release the stick
|
|
|
|
*/
|
2013-07-10 10:25:38 -03:00
|
|
|
if (!acro_state.locked_pitch) {
|
|
|
|
acro_state.locked_pitch = true;
|
|
|
|
acro_state.locked_pitch_cd = ahrs.pitch_sensor;
|
|
|
|
}
|
2013-07-13 08:06:45 -03:00
|
|
|
// try to hold the locked pitch. Note that we have the pitch
|
|
|
|
// integrator enabled, which helps with inverted flight
|
2013-07-10 10:25:38 -03:00
|
|
|
nav_pitch_cd = acro_state.locked_pitch_cd;
|
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_pitch->set_servo_out(pitchController.get_servo_out(nav_pitch_cd - ahrs.pitch_sensor,
|
2013-08-14 01:57:41 -03:00
|
|
|
speed_scaler,
|
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
|
|
|
false));
|
2013-07-10 10:25:38 -03:00
|
|
|
} else {
|
2013-07-10 19:05:25 -03:00
|
|
|
/*
|
|
|
|
user has non-zero pitch input, use a pure rate controller
|
|
|
|
*/
|
2013-07-10 10:25:38 -03:00
|
|
|
acro_state.locked_pitch = false;
|
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_pitch->set_servo_out( pitchController.get_rate_out(pitch_rate, speed_scaler));
|
2013-07-10 10:25:38 -03:00
|
|
|
}
|
|
|
|
|
2013-07-10 19:05:25 -03:00
|
|
|
/*
|
2013-10-04 09:15:53 -03:00
|
|
|
manual rudder for now
|
2013-07-10 19:05:25 -03:00
|
|
|
*/
|
2015-04-16 10:30:32 -03:00
|
|
|
steering_control.steering = steering_control.rudder = rudder_input;
|
2013-07-10 10:25:38 -03:00
|
|
|
}
|
|
|
|
|
2012-12-04 02:32:37 -04:00
|
|
|
/*
|
|
|
|
main stabilization function for all 3 axes
|
|
|
|
*/
|
2015-05-13 03:09:36 -03:00
|
|
|
void Plane::stabilize()
|
2012-12-04 02:32:37 -04:00
|
|
|
{
|
2013-07-05 05:05:27 -03:00
|
|
|
if (control_mode == MANUAL) {
|
|
|
|
// nothing to do
|
|
|
|
return;
|
|
|
|
}
|
2012-12-04 02:32:37 -04:00
|
|
|
float speed_scaler = get_speed_scaler();
|
|
|
|
|
|
|
|
if (control_mode == TRAINING) {
|
|
|
|
stabilize_training(speed_scaler);
|
2013-07-10 10:25:38 -03:00
|
|
|
} else if (control_mode == ACRO) {
|
|
|
|
stabilize_acro(speed_scaler);
|
2015-12-26 06:40:40 -04:00
|
|
|
} else if (control_mode == QSTABILIZE ||
|
|
|
|
control_mode == QHOVER ||
|
2016-03-09 03:20:41 -04:00
|
|
|
control_mode == QLOITER ||
|
2016-04-29 02:31:08 -03:00
|
|
|
control_mode == QLAND ||
|
|
|
|
control_mode == QRTL) {
|
2015-12-26 06:40:40 -04:00
|
|
|
quadplane.control_run();
|
2012-12-04 02:32:37 -04:00
|
|
|
} else {
|
2013-04-01 18:52:56 -03:00
|
|
|
if (g.stick_mixing == STICK_MIXING_FBW && control_mode != STABILIZE) {
|
|
|
|
stabilize_stick_mixing_fbw();
|
|
|
|
}
|
2012-12-04 02:32:37 -04:00
|
|
|
stabilize_roll(speed_scaler);
|
|
|
|
stabilize_pitch(speed_scaler);
|
2013-04-01 18:52:56 -03:00
|
|
|
if (g.stick_mixing == STICK_MIXING_DIRECT || control_mode == STABILIZE) {
|
|
|
|
stabilize_stick_mixing_direct();
|
|
|
|
}
|
2012-12-04 02:32:37 -04:00
|
|
|
stabilize_yaw(speed_scaler);
|
|
|
|
}
|
2013-06-01 04:34:40 -03:00
|
|
|
|
|
|
|
/*
|
|
|
|
see if we should zero the attitude controller integrators.
|
|
|
|
*/
|
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-07-10 00:40:13 -03:00
|
|
|
relative_altitude_abs_cm() < 500 &&
|
2014-07-08 07:26:07 -03:00
|
|
|
fabsf(barometer.get_climb_rate()) < 0.5f &&
|
2014-03-28 16:52:48 -03:00
|
|
|
gps.ground_speed() < 3) {
|
2013-06-01 04:34:40 -03:00
|
|
|
// we are low, with no climb rate, and zero throttle, and very
|
|
|
|
// low ground speed. Zero the attitude controller
|
|
|
|
// integrators. This prevents integrator buildup pre-takeoff.
|
2013-08-14 01:57:41 -03:00
|
|
|
rollController.reset_I();
|
|
|
|
pitchController.reset_I();
|
|
|
|
yawController.reset_I();
|
2014-08-24 19:20:37 -03:00
|
|
|
|
|
|
|
// if moving very slowly also zero the steering integrator
|
|
|
|
if (gps.ground_speed() < 1) {
|
|
|
|
steerController.reset_I();
|
|
|
|
}
|
2013-06-01 04:34:40 -03:00
|
|
|
}
|
2012-12-04 02:32:37 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
|
2015-05-13 03:09:36 -03:00
|
|
|
void Plane::calc_throttle()
|
2011-09-08 22:29:39 -03:00
|
|
|
{
|
2013-06-26 07:48:45 -03:00
|
|
|
if (aparm.throttle_cruise <= 1) {
|
2013-03-07 23:59:19 -04:00
|
|
|
// user has asked for zero throttle - this may be done by a
|
|
|
|
// mission which wants to turn off the engine for a parachute
|
|
|
|
// landing
|
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_throttle->set_servo_out(0);
|
2013-03-07 23:59:19 -04:00
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
2016-06-30 12:50:17 -03:00
|
|
|
int32_t commanded_throttle = SpdHgt_Controller->get_throttle_demand();
|
|
|
|
|
|
|
|
// Received an external msg that guides throttle in the last 3 seconds?
|
|
|
|
if (control_mode == GUIDED &&
|
|
|
|
plane.guided_state.last_forced_throttle_ms > 0 &&
|
|
|
|
millis() - plane.guided_state.last_forced_throttle_ms < 3000) {
|
|
|
|
commanded_throttle = plane.guided_state.forced_throttle;
|
|
|
|
}
|
|
|
|
|
|
|
|
channel_throttle->set_servo_out(commanded_throttle);
|
2011-09-08 22:29:39 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
/*****************************************
|
2012-08-21 23:19:50 -03:00
|
|
|
* Calculate desired roll/pitch/yaw angles (in medium freq loop)
|
|
|
|
*****************************************/
|
2011-09-08 22:29:39 -03:00
|
|
|
|
2013-10-03 09:01:43 -03:00
|
|
|
/*
|
|
|
|
calculate yaw control for coordinated flight
|
|
|
|
*/
|
2015-05-13 03:09:36 -03:00
|
|
|
void Plane::calc_nav_yaw_coordinated(float speed_scaler)
|
2011-09-08 22:29:39 -03:00
|
|
|
{
|
2013-08-02 08:55:34 -03:00
|
|
|
bool disable_integrator = false;
|
2015-04-16 10:30:32 -03:00
|
|
|
if (control_mode == STABILIZE && rudder_input != 0) {
|
2013-08-02 08:55:34 -03:00
|
|
|
disable_integrator = true;
|
|
|
|
}
|
2012-08-14 22:19:12 -03:00
|
|
|
|
2016-06-30 12:50:17 -03:00
|
|
|
int16_t commanded_rudder;
|
|
|
|
|
|
|
|
// Received an external msg that guides yaw in the last 3 seconds?
|
|
|
|
if (control_mode == GUIDED &&
|
|
|
|
plane.guided_state.last_forced_rpy_ms.z > 0 &&
|
|
|
|
millis() - plane.guided_state.last_forced_rpy_ms.z < 3000) {
|
|
|
|
commanded_rudder = plane.guided_state.forced_rpy_cd.z;
|
|
|
|
} else {
|
|
|
|
commanded_rudder = yawController.get_servo_out(speed_scaler, disable_integrator);
|
|
|
|
|
|
|
|
// add in rudder mixing from roll
|
|
|
|
commanded_rudder += channel_roll->get_servo_out() * g.kff_rudder_mix;
|
|
|
|
commanded_rudder += rudder_input;
|
|
|
|
}
|
|
|
|
|
|
|
|
steering_control.rudder = constrain_int16(commanded_rudder, -4500, 4500);
|
2011-09-08 22:29:39 -03:00
|
|
|
}
|
|
|
|
|
2013-10-03 09:01:43 -03:00
|
|
|
/*
|
|
|
|
calculate yaw control for ground steering with specific course
|
|
|
|
*/
|
2015-05-13 03:09:36 -03:00
|
|
|
void Plane::calc_nav_yaw_course(void)
|
2013-10-03 09:01:43 -03:00
|
|
|
{
|
|
|
|
// holding a specific navigation course on the ground. Used in
|
|
|
|
// auto-takeoff and landing
|
|
|
|
int32_t bearing_error_cd = nav_controller->bearing_error_cd();
|
2014-03-04 21:13:19 -04:00
|
|
|
steering_control.steering = steerController.get_steering_out_angle_error(bearing_error_cd);
|
2013-10-03 09:01:43 -03:00
|
|
|
if (stick_mixing_enabled()) {
|
2014-03-04 21:13:19 -04:00
|
|
|
stick_mix_channel(channel_rudder, steering_control.steering);
|
2013-10-03 09:01:43 -03:00
|
|
|
}
|
2014-03-04 21:13:19 -04:00
|
|
|
steering_control.steering = constrain_int16(steering_control.steering, -4500, 4500);
|
2013-10-03 09:01:43 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
/*
|
|
|
|
calculate yaw control for ground steering
|
|
|
|
*/
|
2015-05-13 03:09:36 -03:00
|
|
|
void Plane::calc_nav_yaw_ground(void)
|
2013-10-03 09:01:43 -03:00
|
|
|
{
|
2014-03-28 16:52:48 -03:00
|
|
|
if (gps.ground_speed() < 1 &&
|
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_throttle->get_control_in() == 0 &&
|
2015-05-09 13:36:40 -03:00
|
|
|
flight_stage != AP_SpdHgtControl::FLIGHT_TAKEOFF &&
|
|
|
|
flight_stage != AP_SpdHgtControl::FLIGHT_LAND_ABORT) {
|
2013-10-03 09:16:09 -03:00
|
|
|
// manual rudder control while still
|
|
|
|
steer_state.locked_course = false;
|
|
|
|
steer_state.locked_course_err = 0;
|
2015-04-16 10:30:32 -03:00
|
|
|
steering_control.steering = rudder_input;
|
2013-10-03 09:16:09 -03:00
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
2015-04-16 10:30:32 -03:00
|
|
|
float steer_rate = (rudder_input/4500.0f) * g.ground_steer_dps;
|
2015-05-09 13:36:40 -03:00
|
|
|
if (flight_stage == AP_SpdHgtControl::FLIGHT_TAKEOFF ||
|
|
|
|
flight_stage == AP_SpdHgtControl::FLIGHT_LAND_ABORT) {
|
2014-10-06 17:17:33 -03:00
|
|
|
steer_rate = 0;
|
|
|
|
}
|
2015-05-04 23:34:27 -03:00
|
|
|
if (!is_zero(steer_rate)) {
|
2013-10-03 09:01:43 -03:00
|
|
|
// pilot is giving rudder input
|
|
|
|
steer_state.locked_course = false;
|
2013-10-03 09:16:09 -03:00
|
|
|
} else if (!steer_state.locked_course) {
|
2013-10-03 09:01:43 -03:00
|
|
|
// pilot has released the rudder stick or we are still - lock the course
|
|
|
|
steer_state.locked_course = true;
|
2015-05-09 13:36:40 -03:00
|
|
|
if (flight_stage != AP_SpdHgtControl::FLIGHT_TAKEOFF &&
|
|
|
|
flight_stage != AP_SpdHgtControl::FLIGHT_LAND_ABORT) {
|
2014-10-06 17:17:33 -03:00
|
|
|
steer_state.locked_course_err = 0;
|
|
|
|
}
|
2013-10-03 09:01:43 -03:00
|
|
|
}
|
|
|
|
if (!steer_state.locked_course) {
|
2013-10-03 09:51:43 -03:00
|
|
|
// use a rate controller at the pilot specified rate
|
2014-03-04 21:13:19 -04:00
|
|
|
steering_control.steering = steerController.get_steering_out_rate(steer_rate);
|
2013-10-03 09:01:43 -03:00
|
|
|
} else {
|
2013-10-03 09:51:43 -03:00
|
|
|
// use a error controller on the summed error
|
2013-10-03 09:01:43 -03:00
|
|
|
int32_t yaw_error_cd = -ToDeg(steer_state.locked_course_err)*100;
|
2014-03-04 21:13:19 -04:00
|
|
|
steering_control.steering = steerController.get_steering_out_angle_error(yaw_error_cd);
|
2013-10-03 09:01:43 -03:00
|
|
|
}
|
2014-03-04 21:13:19 -04:00
|
|
|
steering_control.steering = constrain_int16(steering_control.steering, -4500, 4500);
|
2013-10-03 09:01:43 -03:00
|
|
|
}
|
|
|
|
|
2011-09-08 22:29:39 -03:00
|
|
|
|
2014-11-11 22:35:34 -04:00
|
|
|
/*
|
|
|
|
calculate a new nav_pitch_cd from the speed height controller
|
|
|
|
*/
|
2015-05-13 03:09:36 -03:00
|
|
|
void Plane::calc_nav_pitch()
|
2011-09-08 22:29:39 -03:00
|
|
|
{
|
2012-08-21 23:19:50 -03:00
|
|
|
// Calculate the Pitch of the plane
|
|
|
|
// --------------------------------
|
2016-06-30 12:50:17 -03:00
|
|
|
int32_t commanded_pitch = SpdHgt_Controller->get_pitch_demand();
|
|
|
|
|
|
|
|
// Received an external msg that guides roll in the last 3 seconds?
|
|
|
|
if (control_mode == GUIDED &&
|
|
|
|
plane.guided_state.last_forced_rpy_ms.y > 0 &&
|
|
|
|
millis() - plane.guided_state.last_forced_rpy_ms.y < 3000) {
|
|
|
|
commanded_pitch = plane.guided_state.forced_rpy_cd.y;
|
|
|
|
}
|
|
|
|
|
|
|
|
nav_pitch_cd = constrain_int32(commanded_pitch, pitch_limit_min_cd, aparm.pitch_limit_max_cd.get());
|
2011-09-08 22:29:39 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
|
2014-11-11 22:35:34 -04:00
|
|
|
/*
|
|
|
|
calculate a new nav_roll_cd from the navigation controller
|
|
|
|
*/
|
2015-05-13 03:09:36 -03:00
|
|
|
void Plane::calc_nav_roll()
|
2011-09-08 22:29:39 -03:00
|
|
|
{
|
2016-05-09 11:34:11 -03:00
|
|
|
int32_t commanded_roll = nav_controller->nav_roll_cd();
|
|
|
|
|
2016-06-30 11:48:37 -03:00
|
|
|
// Received an external msg that guides roll in the last 3 seconds?
|
2016-06-30 12:50:17 -03:00
|
|
|
if (control_mode == GUIDED &&
|
|
|
|
plane.guided_state.last_forced_rpy_ms.x > 0 &&
|
|
|
|
millis() - plane.guided_state.last_forced_rpy_ms.x < 3000) {
|
|
|
|
commanded_roll = plane.guided_state.forced_rpy_cd.x;
|
2016-05-09 11:34:11 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
nav_roll_cd = constrain_int32(commanded_roll, -roll_limit_cd, roll_limit_cd);
|
2014-11-11 22:35:34 -04:00
|
|
|
update_load_factor();
|
2011-09-08 22:29:39 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
|
|
|
|
/*****************************************
|
2012-08-21 23:19:50 -03:00
|
|
|
* Throttle slew limit
|
|
|
|
*****************************************/
|
2015-05-13 03:09:36 -03:00
|
|
|
void Plane::throttle_slew_limit(int16_t last_throttle)
|
2011-09-08 22:29:39 -03:00
|
|
|
{
|
2014-05-21 07:21:19 -03:00
|
|
|
uint8_t slewrate = aparm.throttle_slewrate;
|
2016-02-23 18:46:00 -04:00
|
|
|
if (control_mode==AUTO) {
|
|
|
|
if (auto_state.takeoff_complete == false && g.takeoff_throttle_slewrate != 0) {
|
|
|
|
slewrate = g.takeoff_throttle_slewrate;
|
|
|
|
} else if (g.land_throttle_slewrate != 0 &&
|
|
|
|
(flight_stage == AP_SpdHgtControl::FLIGHT_LAND_APPROACH || flight_stage == AP_SpdHgtControl::FLIGHT_LAND_FINAL || flight_stage == AP_SpdHgtControl::FLIGHT_LAND_PREFLARE)) {
|
|
|
|
slewrate = g.land_throttle_slewrate;
|
|
|
|
}
|
2014-05-21 07:21:19 -03:00
|
|
|
}
|
2012-11-27 20:42:05 -04:00
|
|
|
// if slew limit rate is set to zero then do not slew limit
|
2014-05-31 03:47:45 -03:00
|
|
|
if (slewrate) {
|
2012-11-27 20:42:05 -04:00
|
|
|
// limit throttle change by the given percentage per second
|
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
|
|
|
float temp = slewrate * G_Dt * 0.01f * fabsf(channel_throttle->get_radio_max() - channel_throttle->get_radio_min());
|
2012-11-27 21:13:09 -04:00
|
|
|
// allow a minimum change of 1 PWM per cycle
|
|
|
|
if (temp < 1) {
|
|
|
|
temp = 1;
|
|
|
|
}
|
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_throttle->set_radio_out(constrain_int16(channel_throttle->get_radio_out(), last_throttle - temp, last_throttle + temp));
|
2012-08-21 23:19:50 -03:00
|
|
|
}
|
2011-09-08 22:29:39 -03:00
|
|
|
}
|
2011-09-09 11:18:38 -03:00
|
|
|
|
2014-08-29 07:30:41 -03:00
|
|
|
/*****************************************
|
|
|
|
Flap slew limit
|
|
|
|
*****************************************/
|
2015-05-13 03:09:36 -03:00
|
|
|
void Plane::flap_slew_limit(int8_t &last_value, int8_t &new_value)
|
2014-08-29 07:30:41 -03:00
|
|
|
{
|
|
|
|
uint8_t slewrate = g.flap_slewrate;
|
|
|
|
// if slew limit rate is set to zero then do not slew limit
|
|
|
|
if (slewrate) {
|
|
|
|
// limit flap change by the given percentage per second
|
|
|
|
float temp = slewrate * G_Dt;
|
|
|
|
// allow a minimum change of 1% per cycle. This means the
|
|
|
|
// slowest flaps we can do is full change over 2 seconds
|
|
|
|
if (temp < 1) {
|
|
|
|
temp = 1;
|
|
|
|
}
|
|
|
|
new_value = constrain_int16(new_value, last_value - temp, last_value + temp);
|
|
|
|
}
|
|
|
|
last_value = new_value;
|
|
|
|
}
|
|
|
|
|
2015-02-17 04:21:42 -04:00
|
|
|
/* We want to suppress the throttle if we think we are on the ground and in an autopilot controlled throttle mode.
|
2012-08-27 03:26:53 -03:00
|
|
|
|
|
|
|
Disable throttle if following conditions are met:
|
|
|
|
* 1 - We are in Circle mode (which we use for short term failsafe), or in FBW-B or higher
|
|
|
|
* AND
|
|
|
|
* 2 - Our reported altitude is within 10 meters of the home altitude.
|
|
|
|
* 3 - Our reported speed is under 5 meters per second.
|
2013-03-08 23:41:04 -04:00
|
|
|
* 4 - We are not performing a takeoff in Auto mode or takeoff speed/accel not yet reached
|
2012-08-27 03:26:53 -03:00
|
|
|
* OR
|
|
|
|
* 5 - Home location is not set
|
|
|
|
*/
|
2015-05-13 03:09:36 -03:00
|
|
|
bool Plane::suppress_throttle(void)
|
2012-08-27 03:26:53 -03:00
|
|
|
{
|
2016-06-01 21:24:45 -03:00
|
|
|
#if PARACHUTE == ENABLED
|
2016-04-05 04:39:55 -03:00
|
|
|
if (auto_throttle_mode && parachute.release_initiated()) {
|
|
|
|
// throttle always suppressed in auto-throttle modes after parachute release initiated
|
2015-10-26 20:36:25 -03:00
|
|
|
throttle_suppressed = true;
|
|
|
|
return true;
|
|
|
|
}
|
2016-06-01 21:24:45 -03:00
|
|
|
#endif
|
2016-04-05 04:39:55 -03:00
|
|
|
|
2012-08-27 03:26:53 -03:00
|
|
|
if (!throttle_suppressed) {
|
|
|
|
// we've previously met a condition for unsupressing the throttle
|
|
|
|
return false;
|
|
|
|
}
|
2013-07-05 01:55:22 -03:00
|
|
|
if (!auto_throttle_mode) {
|
2012-08-27 03:26:53 -03:00
|
|
|
// the user controls the throttle
|
|
|
|
throttle_suppressed = false;
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
2016-04-05 18:58:23 -03:00
|
|
|
if (control_mode==AUTO && g.auto_fbw_steer == 42) {
|
2013-09-19 23:38:46 -03:00
|
|
|
// user has throttle control
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
2015-09-08 20:24:54 -03:00
|
|
|
bool gps_movement = (gps.status() >= AP_GPS::GPS_OK_FIX_2D && gps.ground_speed() >= 5);
|
|
|
|
|
2014-04-23 08:57:51 -03:00
|
|
|
if (control_mode==AUTO &&
|
2015-02-24 22:09:30 -04:00
|
|
|
auto_state.takeoff_complete == false) {
|
2015-08-29 18:04:45 -03:00
|
|
|
|
2015-09-01 12:32:52 -03:00
|
|
|
uint32_t launch_duration_ms = ((int32_t)g.takeoff_throttle_delay)*100 + 2000;
|
2015-08-29 18:04:45 -03:00
|
|
|
if (is_flying() &&
|
2015-11-30 13:34:25 -04:00
|
|
|
millis() - started_flying_ms > MAX(launch_duration_ms, 5000U) && // been flying >5s in any mode
|
2015-09-08 20:24:54 -03:00
|
|
|
adjusted_relative_altitude_cm() > 500 && // are >5m above AGL/home
|
|
|
|
labs(ahrs.pitch_sensor) < 3000 && // not high pitch, which happens when held before launch
|
2016-05-12 14:10:49 -03:00
|
|
|
gps_movement) { // definite gps movement
|
2015-08-29 18:04:45 -03:00
|
|
|
// we're already flying, do not suppress the throttle. We can get
|
|
|
|
// stuck in this condition if we reset a mission and cmd 1 is takeoff
|
2015-09-01 12:32:52 -03:00
|
|
|
// but we're currently flying around below the takeoff altitude
|
2015-08-29 18:04:45 -03:00
|
|
|
throttle_suppressed = false;
|
|
|
|
return false;
|
|
|
|
}
|
2015-02-24 22:09:30 -04:00
|
|
|
if (auto_takeoff_check()) {
|
|
|
|
// we're in auto takeoff
|
|
|
|
throttle_suppressed = false;
|
2015-09-17 02:35:37 -03:00
|
|
|
auto_state.baro_takeoff_alt = barometer.get_altitude();
|
2015-02-24 22:09:30 -04:00
|
|
|
return false;
|
|
|
|
}
|
|
|
|
// keep throttle suppressed
|
|
|
|
return true;
|
2012-08-27 03:26:53 -03:00
|
|
|
}
|
|
|
|
|
2013-07-10 00:40:13 -03:00
|
|
|
if (relative_altitude_abs_cm() >= 1000) {
|
2012-08-27 03:26:53 -03:00
|
|
|
// we're more than 10m from the home altitude
|
|
|
|
throttle_suppressed = false;
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
2015-09-08 20:24:54 -03:00
|
|
|
if (gps_movement) {
|
2013-04-25 07:01:59 -03:00
|
|
|
// if we have an airspeed sensor, then check it too, and
|
|
|
|
// require 5m/s. This prevents throttle up due to spiky GPS
|
|
|
|
// groundspeed with bad GPS reception
|
2015-01-19 20:28:35 -04:00
|
|
|
if ((!ahrs.airspeed_sensor_enabled()) || airspeed.get_airspeed() >= 5) {
|
2013-04-25 07:01:59 -03:00
|
|
|
// we're moving at more than 5 m/s
|
|
|
|
throttle_suppressed = false;
|
|
|
|
return false;
|
|
|
|
}
|
2012-08-27 03:26:53 -03:00
|
|
|
}
|
|
|
|
|
2016-01-01 06:39:36 -04:00
|
|
|
if (quadplane.is_flying()) {
|
|
|
|
throttle_suppressed = false;
|
|
|
|
}
|
|
|
|
|
2012-08-27 03:26:53 -03:00
|
|
|
// throttle remains suppressed
|
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
2013-04-05 01:22:00 -03:00
|
|
|
/*
|
2013-04-28 07:49:53 -03:00
|
|
|
implement a software VTail or elevon mixer. There are 4 different mixing modes
|
2013-04-05 01:22:00 -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
|
|
|
void Plane::channel_output_mixer(uint8_t mixing_type, int16_t & chan1_out, int16_t & chan2_out)const
|
2013-04-05 01:22:00 -03:00
|
|
|
{
|
2013-04-28 07:49:53 -03:00
|
|
|
int16_t c1, c2;
|
2013-04-05 01:47:35 -03:00
|
|
|
int16_t v1, v2;
|
2013-04-05 01:22:00 -03:00
|
|
|
|
2013-04-05 01:47:35 -03:00
|
|
|
// first get desired elevator and rudder as -500..500 values
|
2013-04-28 07:49:53 -03:00
|
|
|
c1 = chan1_out - 1500;
|
|
|
|
c2 = chan2_out - 1500;
|
2013-04-05 01:22:00 -03:00
|
|
|
|
2015-10-04 03:22:07 -03:00
|
|
|
// apply MIXING_OFFSET to input channels using long-integer version
|
|
|
|
// of formula: x = x * (g.mixing_offset/100.0 + 1.0)
|
|
|
|
// -100 => 2x on 'c1', 100 => 2x on 'c2'
|
|
|
|
if (g.mixing_offset < 0) {
|
|
|
|
c1 = (int16_t)(((int32_t)c1) * (-g.mixing_offset+100) / 100);
|
|
|
|
} else if (g.mixing_offset > 0) {
|
|
|
|
c2 = (int16_t)(((int32_t)c2) * (g.mixing_offset+100) / 100);
|
|
|
|
}
|
|
|
|
|
2013-05-25 05:27:57 -03:00
|
|
|
v1 = (c1 - c2) * g.mixing_gain;
|
|
|
|
v2 = (c1 + c2) * g.mixing_gain;
|
2013-04-05 01:22:00 -03:00
|
|
|
|
2013-04-28 07:49:53 -03:00
|
|
|
// now map to mixed output
|
|
|
|
switch (mixing_type) {
|
|
|
|
case MIXING_DISABLED:
|
2013-04-05 01:22:00 -03:00
|
|
|
return;
|
|
|
|
|
2013-04-28 07:49:53 -03:00
|
|
|
case MIXING_UPUP:
|
2013-04-05 01:22:00 -03:00
|
|
|
break;
|
|
|
|
|
2013-04-28 07:49:53 -03:00
|
|
|
case MIXING_UPDN:
|
2013-04-05 01:22:00 -03:00
|
|
|
v2 = -v2;
|
|
|
|
break;
|
|
|
|
|
2013-04-28 07:49:53 -03:00
|
|
|
case MIXING_DNUP:
|
2013-04-05 01:22:00 -03:00
|
|
|
v1 = -v1;
|
|
|
|
break;
|
|
|
|
|
2013-04-28 07:49:53 -03:00
|
|
|
case MIXING_DNDN:
|
2013-04-05 01:22:00 -03:00
|
|
|
v1 = -v1;
|
|
|
|
v2 = -v2;
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
|
2013-05-25 05:27:57 -03:00
|
|
|
// scale for a 1500 center and 900..2100 range, symmetric
|
|
|
|
v1 = constrain_int16(v1, -600, 600);
|
|
|
|
v2 = constrain_int16(v2, -600, 600);
|
2013-04-05 01:22:00 -03:00
|
|
|
|
2013-04-28 07:49:53 -03:00
|
|
|
chan1_out = 1500 + v1;
|
|
|
|
chan2_out = 1500 + v2;
|
2013-04-05 01:22:00 -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
|
|
|
void Plane::channel_output_mixer(uint8_t mixing_type, RC_Channel* chan1, RC_Channel* chan2)const
|
|
|
|
{
|
|
|
|
int16_t ch1 = chan1->get_radio_out();
|
|
|
|
int16_t ch2 = chan2->get_radio_out();
|
|
|
|
|
|
|
|
channel_output_mixer(mixing_type,ch1,ch2);
|
|
|
|
|
|
|
|
chan1->set_radio_out(ch1);
|
|
|
|
chan2->set_radio_out(ch2);
|
|
|
|
}
|
|
|
|
|
2014-02-05 21:38:59 -04:00
|
|
|
/*
|
|
|
|
setup flaperon output channels
|
|
|
|
*/
|
2015-05-13 03:09:36 -03:00
|
|
|
void Plane::flaperon_update(int8_t flap_percent)
|
2014-02-05 21:38:59 -04:00
|
|
|
{
|
|
|
|
if (!RC_Channel_aux::function_assigned(RC_Channel_aux::k_flaperon1) ||
|
|
|
|
!RC_Channel_aux::function_assigned(RC_Channel_aux::k_flaperon2)) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
int16_t ch1, ch2;
|
|
|
|
/*
|
|
|
|
flaperons are implemented as a mixer between aileron and a
|
|
|
|
percentage of flaps. Flap input can come from a manual channel
|
2014-11-13 20:29:33 -04:00
|
|
|
or from auto flaps.
|
2014-11-13 20:27:50 -04:00
|
|
|
|
2014-11-24 17:20:10 -04:00
|
|
|
Use k_flaperon1 and k_flaperon2 channel trims to center servos.
|
|
|
|
Then adjust aileron trim for level flight (note that aileron trim is affected
|
|
|
|
by mixing gain). flapin_channel's trim is not used.
|
|
|
|
*/
|
|
|
|
|
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
|
|
|
ch1 = channel_roll->get_radio_out();
|
2014-11-24 17:20:10 -04:00
|
|
|
// The *5 is to take a percentage to a value from -500 to 500 for the mixer
|
2014-02-05 23:09:49 -04:00
|
|
|
ch2 = 1500 - flap_percent * 5;
|
2014-02-05 21:38:59 -04:00
|
|
|
channel_output_mixer(g.flaperon_output, ch1, ch2);
|
2014-11-24 17:20:10 -04:00
|
|
|
RC_Channel_aux::set_radio_trimmed(RC_Channel_aux::k_flaperon1, ch1);
|
|
|
|
RC_Channel_aux::set_radio_trimmed(RC_Channel_aux::k_flaperon2, ch2);
|
2014-02-05 21:38:59 -04:00
|
|
|
}
|
|
|
|
|
2015-06-13 06:12:54 -03:00
|
|
|
/*
|
|
|
|
setup servos for idle mode
|
|
|
|
Idle mode is used during balloon launch to keep servos still, apart
|
|
|
|
from occasional wiggle to prevent freezing up
|
|
|
|
*/
|
|
|
|
void Plane::set_servos_idle(void)
|
|
|
|
{
|
|
|
|
RC_Channel_aux::output_ch_all();
|
|
|
|
if (auto_state.idle_wiggle_stage == 0) {
|
|
|
|
RC_Channel::output_trim_all();
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
int16_t servo_value = 0;
|
|
|
|
// move over full range for 2 seconds
|
|
|
|
auto_state.idle_wiggle_stage += 2;
|
|
|
|
if (auto_state.idle_wiggle_stage < 50) {
|
|
|
|
servo_value = auto_state.idle_wiggle_stage * (4500 / 50);
|
|
|
|
} else if (auto_state.idle_wiggle_stage < 100) {
|
|
|
|
servo_value = (100 - auto_state.idle_wiggle_stage) * (4500 / 50);
|
|
|
|
} else if (auto_state.idle_wiggle_stage < 150) {
|
|
|
|
servo_value = (100 - auto_state.idle_wiggle_stage) * (4500 / 50);
|
|
|
|
} else if (auto_state.idle_wiggle_stage < 200) {
|
|
|
|
servo_value = (auto_state.idle_wiggle_stage-200) * (4500 / 50);
|
|
|
|
} else {
|
|
|
|
auto_state.idle_wiggle_stage = 0;
|
|
|
|
}
|
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_servo_out(servo_value);
|
|
|
|
channel_pitch->set_servo_out(servo_value);
|
|
|
|
channel_rudder->set_servo_out(servo_value);
|
2015-06-13 06:12:54 -03:00
|
|
|
channel_roll->calc_pwm();
|
|
|
|
channel_pitch->calc_pwm();
|
|
|
|
channel_rudder->calc_pwm();
|
|
|
|
channel_roll->output();
|
|
|
|
channel_pitch->output();
|
|
|
|
channel_throttle->output();
|
|
|
|
channel_rudder->output();
|
|
|
|
channel_throttle->output_trim();
|
|
|
|
}
|
|
|
|
|
2015-09-13 20:42:20 -03:00
|
|
|
/*
|
2016-01-30 03:22:21 -04:00
|
|
|
return minimum throttle PWM value, taking account of throttle reversal. For reverse thrust you get the throttle off position
|
2015-09-13 20:42:20 -03:00
|
|
|
*/
|
|
|
|
uint16_t Plane::throttle_min(void) const
|
|
|
|
{
|
2016-01-30 03:22:21 -04:00
|
|
|
if (aparm.throttle_min < 0) {
|
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_trim();
|
2016-01-30 03:22:21 -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_reverse() ? channel_throttle->get_radio_max() : channel_throttle->get_radio_min();
|
2015-09-13 20:42:20 -03:00
|
|
|
};
|
|
|
|
|
2014-11-24 17:20:10 -04:00
|
|
|
|
2011-09-08 22:29:39 -03:00
|
|
|
/*****************************************
|
|
|
|
* Set the flight control servos based on the current calculated values
|
|
|
|
*****************************************/
|
2015-05-13 03:09:36 -03:00
|
|
|
void Plane::set_servos(void)
|
2011-09-08 22:29:39 -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
|
|
|
int16_t last_throttle = channel_throttle->get_radio_out();
|
2012-08-21 23:19:50 -03:00
|
|
|
|
2015-11-24 04:24:04 -04:00
|
|
|
// do any transition updates for quadplane
|
|
|
|
quadplane.update();
|
|
|
|
|
2015-06-13 06:12:54 -03:00
|
|
|
if (control_mode == AUTO && auto_state.idle_mode) {
|
|
|
|
// special handling for balloon launch
|
|
|
|
set_servos_idle();
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
2014-03-04 21:13:19 -04:00
|
|
|
/*
|
|
|
|
see if we are doing ground steering.
|
|
|
|
*/
|
|
|
|
if (!steering_control.ground_steering) {
|
|
|
|
// we are not at an altitude for ground steering. Set the nose
|
|
|
|
// wheel to the rudder just in case the barometer has drifted
|
|
|
|
// a lot
|
|
|
|
steering_control.steering = steering_control.rudder;
|
|
|
|
} else if (!RC_Channel_aux::function_assigned(RC_Channel_aux::k_steering)) {
|
|
|
|
// we are within the ground steering altitude but don't have a
|
|
|
|
// dedicated steering channel. Set the rudder to the ground
|
|
|
|
// steering output
|
|
|
|
steering_control.rudder = steering_control.steering;
|
|
|
|
}
|
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_rudder->set_servo_out(steering_control.rudder);
|
2014-03-04 21:13:19 -04:00
|
|
|
|
|
|
|
// clear ground_steering to ensure manual control if the yaw stabilizer doesn't run
|
|
|
|
steering_control.ground_steering = false;
|
|
|
|
|
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
|
|
|
RC_Channel_aux::set_servo_out_for(RC_Channel_aux::k_rudder, steering_control.rudder);
|
|
|
|
RC_Channel_aux::set_servo_out_for(RC_Channel_aux::k_steering, steering_control.steering);
|
2014-03-04 21:13:19 -04:00
|
|
|
|
2012-12-04 02:32:37 -04:00
|
|
|
if (control_mode == MANUAL) {
|
2012-08-21 23:19:50 -03:00
|
|
|
// do a direct pass through of radio values
|
2013-04-28 07:49:53 -03:00
|
|
|
if (g.mix_mode == 0 || g.elevon_output != MIXING_DISABLED) {
|
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_out(channel_roll->get_radio_in());
|
|
|
|
channel_pitch->set_radio_out(channel_pitch->get_radio_in());
|
2012-08-21 23:19:50 -03:00
|
|
|
} else {
|
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_out(channel_roll->read());
|
|
|
|
channel_pitch->set_radio_out(channel_pitch->read());
|
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
|
|
|
channel_throttle->set_radio_out(channel_throttle->get_radio_in());
|
|
|
|
channel_rudder->set_radio_out(channel_rudder->get_radio_in());
|
2012-10-30 22:39:03 -03:00
|
|
|
|
2013-06-28 21:14:57 -03:00
|
|
|
// setup extra channels. We want this to come from the
|
|
|
|
// main input channel, but using the 2nd channels dead
|
2012-11-05 08:37:58 -04:00
|
|
|
// zone, reverse and min/max settings. We need to use
|
|
|
|
// pwm_to_angle_dz() to ensure we don't trim the value for the
|
|
|
|
// deadzone of the main aileron channel, otherwise the 2nd
|
|
|
|
// aileron won't quite follow the first one
|
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
|
|
|
RC_Channel_aux::set_servo_out_for(RC_Channel_aux::k_aileron, channel_roll->pwm_to_angle_dz(0));
|
|
|
|
RC_Channel_aux::set_servo_out_for(RC_Channel_aux::k_elevator, channel_pitch->pwm_to_angle_dz(0));
|
2012-11-05 08:37:58 -04:00
|
|
|
|
2013-06-28 21:14:57 -03:00
|
|
|
// this variant assumes you have the corresponding
|
2012-11-20 20:48:46 -04:00
|
|
|
// input channel setup in your transmitter for manual control
|
|
|
|
// of the 2nd aileron
|
|
|
|
RC_Channel_aux::copy_radio_in_out(RC_Channel_aux::k_aileron_with_input);
|
2013-02-04 17:57:58 -04:00
|
|
|
RC_Channel_aux::copy_radio_in_out(RC_Channel_aux::k_elevator_with_input);
|
2012-10-30 22:39:45 -03:00
|
|
|
|
2012-08-21 23:19:50 -03:00
|
|
|
} else {
|
|
|
|
if (g.mix_mode == 0) {
|
2012-11-20 20:48:46 -04:00
|
|
|
// both types of secondary aileron are slaved to the roll servo out
|
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
|
|
|
RC_Channel_aux::set_servo_out_for(RC_Channel_aux::k_aileron, channel_roll->get_servo_out());
|
|
|
|
RC_Channel_aux::set_servo_out_for(RC_Channel_aux::k_aileron_with_input, channel_roll->get_servo_out());
|
2013-02-04 17:57:58 -04:00
|
|
|
|
|
|
|
// both types of secondary elevator are slaved to the pitch servo out
|
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
|
|
|
RC_Channel_aux::set_servo_out_for(RC_Channel_aux::k_elevator, channel_pitch->get_servo_out());
|
|
|
|
RC_Channel_aux::set_servo_out_for(RC_Channel_aux::k_elevator_with_input, channel_pitch->get_servo_out());
|
2012-08-21 23:19:50 -03:00
|
|
|
}else{
|
|
|
|
/*Elevon mode*/
|
|
|
|
float ch1;
|
|
|
|
float ch2;
|
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
|
|
|
ch1 = channel_pitch->get_servo_out() - (BOOL_TO_SIGN(g.reverse_elevons) * channel_roll->get_servo_out());
|
|
|
|
ch2 = channel_pitch->get_servo_out() + (BOOL_TO_SIGN(g.reverse_elevons) * channel_roll->get_servo_out());
|
2012-10-30 22:39:45 -03:00
|
|
|
|
|
|
|
/* Differential Spoilers
|
|
|
|
If differential spoilers are setup, then we translate
|
|
|
|
rudder control into splitting of the two ailerons on
|
|
|
|
the side of the aircraft where we want to induce
|
|
|
|
additional drag.
|
|
|
|
*/
|
|
|
|
if (RC_Channel_aux::function_assigned(RC_Channel_aux::k_dspoiler1) && RC_Channel_aux::function_assigned(RC_Channel_aux::k_dspoiler2)) {
|
2012-10-02 23:40:45 -03:00
|
|
|
float ch3 = ch1;
|
|
|
|
float ch4 = ch2;
|
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 ( BOOL_TO_SIGN(g.reverse_elevons) * channel_rudder->get_servo_out() < 0) {
|
|
|
|
ch1 += abs(channel_rudder->get_servo_out());
|
|
|
|
ch3 -= abs(channel_rudder->get_servo_out());
|
2012-10-02 23:40:45 -03:00
|
|
|
} else {
|
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
|
|
|
ch2 += abs(channel_rudder->get_servo_out());
|
|
|
|
ch4 -= abs(channel_rudder->get_servo_out());
|
2012-10-02 23:40:45 -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
|
|
|
RC_Channel_aux::set_servo_out_for(RC_Channel_aux::k_dspoiler1, ch3);
|
|
|
|
RC_Channel_aux::set_servo_out_for(RC_Channel_aux::k_dspoiler2, ch4);
|
2012-10-30 22:39:45 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
// directly set the radio_out values for elevon mode
|
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_out(elevon.trim1 + (BOOL_TO_SIGN(g.reverse_ch1_elevon) * (ch1 * 500.0f/ SERVO_MAX)));
|
|
|
|
channel_pitch->set_radio_out(elevon.trim2 + (BOOL_TO_SIGN(g.reverse_ch2_elevon) * (ch2 * 500.0f/ SERVO_MAX)));
|
2012-08-21 23:19:50 -03:00
|
|
|
}
|
|
|
|
|
2012-08-28 02:51:32 -03:00
|
|
|
// push out the PWM values
|
2012-09-12 23:01:40 -03:00
|
|
|
if (g.mix_mode == 0) {
|
2013-06-03 02:32:08 -03:00
|
|
|
channel_roll->calc_pwm();
|
|
|
|
channel_pitch->calc_pwm();
|
2012-09-12 23:01:40 -03:00
|
|
|
}
|
2013-06-03 02:32:08 -03:00
|
|
|
channel_rudder->calc_pwm();
|
2012-09-22 03:17:38 -03:00
|
|
|
|
|
|
|
#if THROTTLE_OUT == 0
|
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_throttle->set_servo_out(0);
|
2012-09-22 03:17:38 -03:00
|
|
|
#else
|
2016-01-30 03:22:21 -04:00
|
|
|
// convert 0 to 100% (or -100 to +100) into PWM
|
|
|
|
int8_t min_throttle = aparm.throttle_min.get();
|
|
|
|
int8_t max_throttle = aparm.throttle_max.get();
|
|
|
|
|
|
|
|
if (min_throttle < 0 && !allow_reverse_thrust()) {
|
|
|
|
// reverse thrust is available but inhibited.
|
|
|
|
min_throttle = 0;
|
2014-08-29 16:15:25 -03:00
|
|
|
}
|
2016-01-30 03:22:21 -04:00
|
|
|
|
|
|
|
if (control_mode == AUTO) {
|
|
|
|
if (flight_stage == AP_SpdHgtControl::FLIGHT_LAND_FINAL) {
|
|
|
|
min_throttle = 0;
|
|
|
|
}
|
|
|
|
|
|
|
|
if (flight_stage == AP_SpdHgtControl::FLIGHT_TAKEOFF || flight_stage == AP_SpdHgtControl::FLIGHT_LAND_ABORT) {
|
|
|
|
if(aparm.takeoff_throttle_max != 0) {
|
|
|
|
max_throttle = aparm.takeoff_throttle_max;
|
|
|
|
} else {
|
|
|
|
max_throttle = aparm.throttle_max;
|
|
|
|
}
|
2015-04-15 19:54:06 -03:00
|
|
|
}
|
2014-11-12 20:35:28 -04:00
|
|
|
}
|
2016-01-05 19:34:21 -04:00
|
|
|
|
|
|
|
uint32_t now = millis();
|
|
|
|
if (battery.overpower_detected()) {
|
|
|
|
// overpower detected, cut back on the throttle if we're maxing it out by calculating a limiter value
|
|
|
|
// throttle limit will attack by 10% per second
|
|
|
|
|
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_servo_out() > 0 && // demanding too much positive thrust
|
2016-01-05 19:34:21 -04:00
|
|
|
throttle_watt_limit_max < max_throttle - 25 &&
|
|
|
|
now - throttle_watt_limit_timer_ms >= 1) {
|
|
|
|
// always allow for 25% throttle available regardless of battery status
|
|
|
|
throttle_watt_limit_timer_ms = now;
|
|
|
|
throttle_watt_limit_max++;
|
|
|
|
|
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
|
|
|
} else if (channel_throttle->get_servo_out() < 0 &&
|
2016-01-05 19:34:21 -04:00
|
|
|
min_throttle < 0 && // reverse thrust is available
|
|
|
|
throttle_watt_limit_min < -(min_throttle) - 25 &&
|
|
|
|
now - throttle_watt_limit_timer_ms >= 1) {
|
|
|
|
// always allow for 25% throttle available regardless of battery status
|
|
|
|
throttle_watt_limit_timer_ms = now;
|
|
|
|
throttle_watt_limit_min++;
|
|
|
|
}
|
|
|
|
|
|
|
|
} else if (now - throttle_watt_limit_timer_ms >= 1000) {
|
|
|
|
// it has been 1 second since last over-current, check if we can resume higher throttle.
|
|
|
|
// this throttle release is needed to allow raising the max_throttle as the battery voltage drains down
|
|
|
|
// throttle limit will release by 1% per second
|
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_servo_out() > throttle_watt_limit_max && // demanding max forward thrust
|
2016-01-05 19:34:21 -04:00
|
|
|
throttle_watt_limit_max > 0) { // and we're currently limiting it
|
|
|
|
throttle_watt_limit_timer_ms = now;
|
|
|
|
throttle_watt_limit_max--;
|
|
|
|
|
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
|
|
|
} else if (channel_throttle->get_servo_out() < throttle_watt_limit_min && // demanding max negative thrust
|
2016-01-05 19:34:21 -04:00
|
|
|
throttle_watt_limit_min > 0) { // and we're limiting it
|
|
|
|
throttle_watt_limit_timer_ms = now;
|
|
|
|
throttle_watt_limit_min--;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
max_throttle = constrain_int16(max_throttle, 0, max_throttle - throttle_watt_limit_max);
|
|
|
|
if (min_throttle < 0) {
|
|
|
|
min_throttle = constrain_int16(min_throttle, min_throttle + throttle_watt_limit_min, 0);
|
|
|
|
}
|
|
|
|
|
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_throttle->set_servo_out(constrain_int16(channel_throttle->get_servo_out(),
|
2014-08-29 16:15:25 -03:00
|
|
|
min_throttle,
|
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
|
|
|
max_throttle));
|
2012-09-22 03:17:38 -03:00
|
|
|
|
2015-01-28 19:30:00 -04:00
|
|
|
if (!hal.util->get_soft_armed()) {
|
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_throttle->set_servo_out(0);
|
2015-02-03 01:42:31 -04:00
|
|
|
channel_throttle->calc_pwm();
|
|
|
|
} else if (suppress_throttle()) {
|
2012-11-26 08:29:00 -04:00
|
|
|
// throttle is suppressed in auto mode
|
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_throttle->set_servo_out(0);
|
2012-09-22 03:17:38 -03:00
|
|
|
if (g.throttle_suppress_manual) {
|
|
|
|
// manual pass through of throttle while throttle is suppressed
|
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_throttle->set_radio_out(channel_throttle->get_radio_in());
|
2012-09-22 03:17:38 -03:00
|
|
|
} else {
|
2013-06-03 02:32:08 -03:00
|
|
|
channel_throttle->calc_pwm();
|
2012-09-22 03:17:38 -03:00
|
|
|
}
|
2012-11-26 08:29:00 -04:00
|
|
|
} else if (g.throttle_passthru_stabilize &&
|
2012-12-04 02:32:37 -04:00
|
|
|
(control_mode == STABILIZE ||
|
|
|
|
control_mode == TRAINING ||
|
2013-07-10 10:25:38 -03:00
|
|
|
control_mode == ACRO ||
|
2014-04-12 01:12:14 -03:00
|
|
|
control_mode == FLY_BY_WIRE_A ||
|
2016-05-20 07:14:48 -03:00
|
|
|
control_mode == AUTOTUNE) &&
|
|
|
|
!failsafe.ch3_counter) {
|
2012-11-26 08:29:00 -04:00
|
|
|
// manual pass through of throttle while in FBWA or
|
|
|
|
// STABILIZE mode with THR_PASS_STAB set
|
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_throttle->set_radio_out(channel_throttle->get_radio_in());
|
2013-09-07 18:31:10 -03:00
|
|
|
} else if (control_mode == GUIDED &&
|
|
|
|
guided_throttle_passthru) {
|
|
|
|
// manual pass through of throttle while in GUIDED
|
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_throttle->set_radio_out(channel_throttle->get_radio_in());
|
2016-03-09 03:20:41 -04:00
|
|
|
} else if (quadplane.in_vtol_mode()) {
|
2016-04-20 02:13:20 -03:00
|
|
|
// ask quadplane code for forward throttle
|
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_throttle->set_servo_out(quadplane.forward_throttle_pct());
|
2015-11-24 04:24:04 -04:00
|
|
|
channel_throttle->calc_pwm();
|
2012-09-22 03:17:38 -03:00
|
|
|
} else {
|
2012-11-26 08:29:00 -04:00
|
|
|
// normal throttle calculation based on servo_out
|
2013-06-03 02:32:08 -03:00
|
|
|
channel_throttle->calc_pwm();
|
2012-09-22 03:17:38 -03:00
|
|
|
}
|
|
|
|
#endif
|
2012-08-21 23:19:50 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
// Auto flap deployment
|
2014-08-29 07:30:41 -03:00
|
|
|
int8_t auto_flap_percent = 0;
|
2014-02-05 23:09:49 -04:00
|
|
|
int8_t manual_flap_percent = 0;
|
2014-08-29 07:30:41 -03:00
|
|
|
static int8_t last_auto_flap;
|
|
|
|
static int8_t last_manual_flap;
|
2014-02-05 23:09:49 -04:00
|
|
|
|
|
|
|
// work out any manual flap input
|
|
|
|
RC_Channel *flapin = RC_Channel::rc_channel(g.flapin_channel-1);
|
|
|
|
if (flapin != NULL && !failsafe.ch3_failsafe && failsafe.ch3_counter == 0) {
|
|
|
|
flapin->input();
|
2014-03-04 18:16:28 -04:00
|
|
|
manual_flap_percent = flapin->percent_input();
|
2014-02-05 23:09:49 -04:00
|
|
|
}
|
2014-02-05 21:38:59 -04:00
|
|
|
|
2014-02-05 23:09:49 -04:00
|
|
|
if (auto_throttle_mode) {
|
2012-12-04 02:32:37 -04:00
|
|
|
int16_t flapSpeedSource = 0;
|
2015-01-19 20:28:35 -04:00
|
|
|
if (ahrs.airspeed_sensor_enabled()) {
|
2014-02-05 21:38:59 -04:00
|
|
|
flapSpeedSource = target_airspeed_cm * 0.01f;
|
2012-09-08 02:13:22 -03:00
|
|
|
} else {
|
2013-06-26 07:48:45 -03:00
|
|
|
flapSpeedSource = aparm.throttle_cruise;
|
2012-09-08 02:13:22 -03:00
|
|
|
}
|
2015-07-19 19:01:11 -03:00
|
|
|
if (g.flap_2_speed != 0 && flapSpeedSource <= g.flap_2_speed) {
|
2014-02-05 21:38:59 -04:00
|
|
|
auto_flap_percent = g.flap_2_percent;
|
2015-07-19 19:01:11 -03:00
|
|
|
} else if ( g.flap_1_speed != 0 && flapSpeedSource <= g.flap_1_speed) {
|
2014-02-05 21:38:59 -04:00
|
|
|
auto_flap_percent = g.flap_1_percent;
|
2015-07-19 19:01:11 -03:00
|
|
|
} //else flaps stay at default zero deflection
|
2014-08-29 07:10:44 -03:00
|
|
|
|
|
|
|
/*
|
|
|
|
special flap levels for takeoff and landing. This works
|
|
|
|
better than speed based flaps as it leads to less
|
|
|
|
possibility of oscillation
|
|
|
|
*/
|
|
|
|
if (control_mode == AUTO) {
|
|
|
|
switch (flight_stage) {
|
|
|
|
case AP_SpdHgtControl::FLIGHT_TAKEOFF:
|
2015-05-09 13:36:40 -03:00
|
|
|
case AP_SpdHgtControl::FLIGHT_LAND_ABORT:
|
2014-08-29 16:16:42 -03:00
|
|
|
if (g.takeoff_flap_percent != 0) {
|
|
|
|
auto_flap_percent = g.takeoff_flap_percent;
|
|
|
|
}
|
2014-08-29 07:10:44 -03:00
|
|
|
break;
|
2016-06-06 18:51:24 -03:00
|
|
|
case AP_SpdHgtControl::FLIGHT_NORMAL:
|
|
|
|
if (auto_flap_percent != 0 && in_preLaunch_flight_stage()) {
|
|
|
|
// TODO: move this to a new FLIGHT_PRE_TAKEOFF stage
|
|
|
|
auto_flap_percent = g.takeoff_flap_percent;
|
|
|
|
}
|
|
|
|
break;
|
2014-08-29 07:10:44 -03:00
|
|
|
case AP_SpdHgtControl::FLIGHT_LAND_APPROACH:
|
2016-01-30 02:32:42 -04:00
|
|
|
case AP_SpdHgtControl::FLIGHT_LAND_PREFLARE:
|
2014-08-29 07:10:44 -03:00
|
|
|
case AP_SpdHgtControl::FLIGHT_LAND_FINAL:
|
2014-08-29 16:16:42 -03:00
|
|
|
if (g.land_flap_percent != 0) {
|
|
|
|
auto_flap_percent = g.land_flap_percent;
|
|
|
|
}
|
2014-08-29 07:10:44 -03:00
|
|
|
break;
|
|
|
|
default:
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
}
|
2012-08-21 23:19:50 -03:00
|
|
|
}
|
2011-10-09 10:25:20 -03:00
|
|
|
|
2014-02-05 23:09:49 -04:00
|
|
|
// manual flap input overrides auto flap input
|
|
|
|
if (abs(manual_flap_percent) > auto_flap_percent) {
|
|
|
|
auto_flap_percent = manual_flap_percent;
|
|
|
|
}
|
|
|
|
|
2014-08-29 07:30:41 -03:00
|
|
|
flap_slew_limit(last_auto_flap, auto_flap_percent);
|
|
|
|
flap_slew_limit(last_manual_flap, manual_flap_percent);
|
|
|
|
|
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
|
|
|
RC_Channel_aux::set_servo_out_for(RC_Channel_aux::k_flap_auto, auto_flap_percent);
|
|
|
|
RC_Channel_aux::set_servo_out_for(RC_Channel_aux::k_flap, manual_flap_percent);
|
2014-02-05 23:09:49 -04:00
|
|
|
|
2016-02-12 20:36:26 -04:00
|
|
|
if (control_mode >= FLY_BY_WIRE_B ||
|
2016-04-20 02:13:20 -03:00
|
|
|
quadplane.in_assisted_flight() ||
|
|
|
|
quadplane.in_vtol_mode()) {
|
2012-11-27 21:13:09 -04:00
|
|
|
/* only do throttle slew limiting in modes where throttle
|
|
|
|
* control is automatic */
|
|
|
|
throttle_slew_limit(last_throttle);
|
|
|
|
}
|
|
|
|
|
2013-04-05 05:38:43 -03:00
|
|
|
if (control_mode == TRAINING) {
|
|
|
|
// copy rudder in training mode
|
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_rudder->set_radio_out(channel_rudder->get_radio_in());
|
2013-04-05 05:38:43 -03:00
|
|
|
}
|
|
|
|
|
2014-02-05 21:38:59 -04:00
|
|
|
if (g.flaperon_output != MIXING_DISABLED && g.elevon_output == MIXING_DISABLED && g.mix_mode == 0) {
|
|
|
|
flaperon_update(auto_flap_percent);
|
|
|
|
}
|
2013-04-28 07:49:53 -03:00
|
|
|
if (g.vtail_output != MIXING_DISABLED) {
|
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_output_mixer(g.vtail_output, channel_pitch, channel_rudder);
|
2013-04-28 07:49:53 -03:00
|
|
|
} else if (g.elevon_output != MIXING_DISABLED) {
|
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_output_mixer(g.elevon_output, channel_pitch, channel_roll);
|
2015-10-04 03:22:07 -03:00
|
|
|
// if (both) differential spoilers setup then apply rudder
|
|
|
|
// control into splitting the two elevons on the side of
|
|
|
|
// the aircraft where we want to induce additional drag:
|
|
|
|
if (RC_Channel_aux::function_assigned(RC_Channel_aux::k_dspoiler1) &&
|
|
|
|
RC_Channel_aux::function_assigned(RC_Channel_aux::k_dspoiler2)) {
|
|
|
|
int16_t ch3 = channel_roll->get_radio_out(); //diff spoiler 1
|
|
|
|
int16_t ch4 = channel_pitch->get_radio_out(); //diff spoiler 2
|
|
|
|
// convert rudder-servo output (-4500 to 4500) to PWM offset
|
|
|
|
// value (-500 to 500) and multiply by DSPOILR_RUD_RATE/100
|
|
|
|
// (rudder->servo_out * 500 / SERVO_MAX * dspoiler_rud_rate/100):
|
|
|
|
int16_t ruddVal = (int16_t)((int32_t)(channel_rudder->get_servo_out()) *
|
|
|
|
g.dspoiler_rud_rate / (SERVO_MAX/5));
|
|
|
|
if (ruddVal != 0) { //if nonzero rudder then apply to spoilers
|
|
|
|
int16_t ch1 = ch3; //elevon 1
|
|
|
|
int16_t ch2 = ch4; //elevon 2
|
|
|
|
if (ruddVal > 0) { //apply rudder to right or left side
|
|
|
|
ch1 += ruddVal;
|
|
|
|
ch3 -= ruddVal;
|
|
|
|
} else {
|
|
|
|
ch2 += ruddVal;
|
|
|
|
ch4 -= ruddVal;
|
|
|
|
}
|
|
|
|
// change elevon 1 & 2 positions; constrain min/max:
|
|
|
|
channel_roll->set_radio_out(constrain_int16(ch1, 900, 2100));
|
|
|
|
channel_pitch->set_radio_out(constrain_int16(ch2, 900, 2100));
|
|
|
|
// constrain min/max for intermediate dspoiler positions:
|
|
|
|
ch3 = constrain_int16(ch3, 900, 2100);
|
|
|
|
ch4 = constrain_int16(ch4, 900, 2100);
|
|
|
|
}
|
|
|
|
// set positions of differential spoilers (convert PWM
|
|
|
|
// 900-2100 range to servo output (-4500 to 4500)
|
|
|
|
// and use function that supports rev/min/max/trim):
|
|
|
|
RC_Channel_aux::set_servo_out_for(RC_Channel_aux::k_dspoiler1,
|
|
|
|
(ch3-(int16_t)1500) * (int16_t)(SERVO_MAX/300) / (int16_t)2);
|
|
|
|
RC_Channel_aux::set_servo_out_for(RC_Channel_aux::k_dspoiler2,
|
|
|
|
(ch4-(int16_t)1500) * (int16_t)(SERVO_MAX/300) / (int16_t)2);
|
|
|
|
}
|
2013-04-05 01:22:00 -03:00
|
|
|
}
|
|
|
|
|
2013-11-27 22:19:34 -04:00
|
|
|
if (!arming.is_armed()) {
|
|
|
|
//Some ESCs get noisy (beep error msgs) if PWM == 0.
|
|
|
|
//This little segment aims to avoid this.
|
|
|
|
switch (arming.arming_required()) {
|
2015-09-13 20:35:53 -03:00
|
|
|
case AP_Arming::NO:
|
|
|
|
//keep existing behavior: do nothing to radio_out
|
|
|
|
//(don't disarm throttle channel even if AP_Arming class is)
|
2013-11-27 22:19:34 -04:00
|
|
|
break;
|
2015-09-13 20:35:53 -03:00
|
|
|
|
|
|
|
case AP_Arming::YES_ZERO_PWM:
|
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_throttle->set_radio_out(0);
|
2013-11-27 22:19:34 -04:00
|
|
|
break;
|
2015-09-13 20:35:53 -03:00
|
|
|
|
|
|
|
case AP_Arming::YES_MIN_PWM:
|
|
|
|
default:
|
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_throttle->set_radio_out(throttle_min());
|
2013-11-27 22:19:34 -04:00
|
|
|
break;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2014-04-20 21:36:00 -03:00
|
|
|
#if OBC_FAILSAFE == ENABLED
|
|
|
|
// this is to allow the failsafe module to deliberately crash
|
|
|
|
// the plane. Only used in extreme circumstances to meet the
|
|
|
|
// OBC rules
|
|
|
|
obc.check_crash_plane();
|
|
|
|
#endif
|
2014-07-26 03:58:13 -03:00
|
|
|
|
2015-07-13 03:07:40 -03:00
|
|
|
#if HIL_SUPPORT
|
2015-03-13 08:33:48 -03:00
|
|
|
if (g.hil_mode == 1) {
|
|
|
|
// get the servos to the GCS immediately for HIL
|
2016-04-05 01:10:30 -03:00
|
|
|
if (HAVE_PAYLOAD_SPACE(MAVLINK_COMM_0, RC_CHANNELS_SCALED)) {
|
2015-03-13 08:33:48 -03:00
|
|
|
send_servo_out(MAVLINK_COMM_0);
|
|
|
|
}
|
|
|
|
if (!g.hil_servos) {
|
|
|
|
return;
|
|
|
|
}
|
2014-01-20 04:40:11 -04:00
|
|
|
}
|
2015-07-13 03:07:40 -03:00
|
|
|
#endif
|
2014-01-20 04:40:11 -04:00
|
|
|
|
2016-02-24 22:16:00 -04:00
|
|
|
if (g.land_then_servos_neutral > 0 &&
|
|
|
|
control_mode == AUTO &&
|
2016-02-17 03:17:55 -04:00
|
|
|
g.land_disarm_delay > 0 &&
|
|
|
|
auto_state.land_complete &&
|
|
|
|
!arming.is_armed()) {
|
|
|
|
// after an auto land and auto disarm, set the servos to be neutral just
|
|
|
|
// in case we're upside down or some crazy angle and straining the servos.
|
2016-02-24 22:16:00 -04:00
|
|
|
if (g.land_then_servos_neutral == 1) {
|
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_out(channel_roll->get_radio_trim());
|
|
|
|
channel_pitch->set_radio_out(channel_pitch->get_radio_trim());
|
|
|
|
channel_rudder->set_radio_out(channel_rudder->get_radio_trim());
|
2016-02-24 22:16:00 -04:00
|
|
|
} else if (g.land_then_servos_neutral == 2) {
|
|
|
|
channel_roll->disable_out();
|
|
|
|
channel_pitch->disable_out();
|
|
|
|
channel_rudder->disable_out();
|
|
|
|
}
|
2016-02-17 03:17:55 -04:00
|
|
|
}
|
|
|
|
|
2016-07-23 04:37:42 -03:00
|
|
|
uint8_t override_pct;
|
|
|
|
if (g2.ice_control.throttle_override(override_pct)) {
|
|
|
|
// the ICE controller wants to override the throttle for starting
|
|
|
|
channel_throttle->set_servo_out(override_pct);
|
|
|
|
channel_throttle->calc_pwm();
|
|
|
|
}
|
|
|
|
|
2012-08-21 23:19:50 -03:00
|
|
|
// send values to the PWM timers for output
|
|
|
|
// ----------------------------------------
|
2015-04-15 22:16:30 -03:00
|
|
|
if (g.rudder_only == 0) {
|
2015-04-16 10:30:32 -03:00
|
|
|
// when we RUDDER_ONLY mode we don't send the channel_roll
|
|
|
|
// output and instead rely on KFF_RDDRMIX. That allows the yaw
|
|
|
|
// damper to operate.
|
2015-04-15 22:16:30 -03:00
|
|
|
channel_roll->output();
|
|
|
|
}
|
2013-06-03 03:12:41 -03:00
|
|
|
channel_pitch->output();
|
|
|
|
channel_throttle->output();
|
|
|
|
channel_rudder->output();
|
2014-04-02 22:19:11 -03:00
|
|
|
RC_Channel_aux::output_ch_all();
|
2011-10-09 10:25:20 -03:00
|
|
|
}
|
2011-09-08 22:29:39 -03:00
|
|
|
|
2016-01-30 03:22:21 -04:00
|
|
|
bool Plane::allow_reverse_thrust(void)
|
|
|
|
{
|
|
|
|
// check if we should allow reverse thrust
|
|
|
|
bool allow = false;
|
|
|
|
|
|
|
|
if (g.use_reverse_thrust == USE_REVERSE_THRUST_NEVER) {
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
|
|
|
switch (control_mode) {
|
|
|
|
case AUTO:
|
|
|
|
{
|
2016-04-22 04:59:00 -03:00
|
|
|
uint16_t nav_cmd = mission.get_current_nav_cmd().id;
|
2016-01-30 03:22:21 -04:00
|
|
|
|
|
|
|
// never allow reverse thrust during takeoff
|
|
|
|
if (nav_cmd == MAV_CMD_NAV_TAKEOFF) {
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
|
|
|
// always allow regardless of mission item
|
|
|
|
allow |= (g.use_reverse_thrust & USE_REVERSE_THRUST_AUTO_ALWAYS);
|
|
|
|
|
|
|
|
// landing
|
|
|
|
allow |= (g.use_reverse_thrust & USE_REVERSE_THRUST_AUTO_LAND_APPROACH) &&
|
|
|
|
(nav_cmd == MAV_CMD_NAV_LAND);
|
|
|
|
|
|
|
|
// LOITER_TO_ALT
|
|
|
|
allow |= (g.use_reverse_thrust & USE_REVERSE_THRUST_AUTO_LOITER_TO_ALT) &&
|
|
|
|
(nav_cmd == MAV_CMD_NAV_LOITER_TO_ALT);
|
|
|
|
|
|
|
|
// any Loiter (including LOITER_TO_ALT)
|
|
|
|
allow |= (g.use_reverse_thrust & USE_REVERSE_THRUST_AUTO_LOITER_ALL) &&
|
|
|
|
(nav_cmd == MAV_CMD_NAV_LOITER_TIME ||
|
|
|
|
nav_cmd == MAV_CMD_NAV_LOITER_TO_ALT ||
|
|
|
|
nav_cmd == MAV_CMD_NAV_LOITER_TURNS ||
|
|
|
|
nav_cmd == MAV_CMD_NAV_LOITER_UNLIM);
|
|
|
|
|
|
|
|
// waypoints
|
|
|
|
allow |= (g.use_reverse_thrust & USE_REVERSE_THRUST_AUTO_WAYPOINT) &&
|
|
|
|
(nav_cmd == MAV_CMD_NAV_WAYPOINT ||
|
|
|
|
nav_cmd == MAV_CMD_NAV_SPLINE_WAYPOINT);
|
|
|
|
}
|
|
|
|
break;
|
|
|
|
|
|
|
|
case LOITER:
|
|
|
|
allow |= (g.use_reverse_thrust & USE_REVERSE_THRUST_LOITER);
|
|
|
|
break;
|
|
|
|
case RTL:
|
|
|
|
allow |= (g.use_reverse_thrust & USE_REVERSE_THRUST_RTL);
|
|
|
|
break;
|
|
|
|
case CIRCLE:
|
|
|
|
allow |= (g.use_reverse_thrust & USE_REVERSE_THRUST_CIRCLE);
|
|
|
|
break;
|
|
|
|
case CRUISE:
|
|
|
|
allow |= (g.use_reverse_thrust & USE_REVERSE_THRUST_CRUISE);
|
|
|
|
break;
|
|
|
|
case FLY_BY_WIRE_B:
|
|
|
|
allow |= (g.use_reverse_thrust & USE_REVERSE_THRUST_FBWB);
|
|
|
|
break;
|
|
|
|
case GUIDED:
|
|
|
|
allow |= (g.use_reverse_thrust & USE_REVERSE_THRUST_GUIDED);
|
|
|
|
break;
|
|
|
|
default:
|
|
|
|
// all other control_modes are auto_throttle_mode=false.
|
|
|
|
// If we are not controlling throttle, don't limit it.
|
|
|
|
allow = true;
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
|
|
|
|
return allow;
|
|
|
|
}
|
|
|
|
|
2014-08-03 04:16:51 -03:00
|
|
|
/*
|
|
|
|
adjust nav_pitch_cd for STAB_PITCH_DOWN_CD. This is used to make
|
|
|
|
keeping up good airspeed in FBWA mode easier, as the plane will
|
|
|
|
automatically pitch down a little when at low throttle. It makes
|
|
|
|
FBWA landings without stalling much easier.
|
|
|
|
*/
|
2015-05-13 03:09:36 -03:00
|
|
|
void Plane::adjust_nav_pitch_throttle(void)
|
2014-08-03 04:16:51 -03:00
|
|
|
{
|
2016-01-30 02:38:31 -04:00
|
|
|
int8_t throttle = throttle_percentage();
|
2016-02-09 01:46:56 -04:00
|
|
|
if (throttle >= 0 && throttle < aparm.throttle_cruise && flight_stage != AP_SpdHgtControl::FLIGHT_VTOL) {
|
2014-08-03 04:16:51 -03:00
|
|
|
float p = (aparm.throttle_cruise - throttle) / (float)aparm.throttle_cruise;
|
2014-08-05 22:46:40 -03:00
|
|
|
nav_pitch_cd -= g.stab_pitch_down * 100.0f * p;
|
2014-08-03 04:16:51 -03:00
|
|
|
}
|
|
|
|
}
|
2014-11-11 22:35:34 -04:00
|
|
|
|
|
|
|
|
|
|
|
/*
|
|
|
|
calculate a new aerodynamic_load_factor and limit nav_roll_cd to
|
|
|
|
ensure that the load factor does not take us below the sustainable
|
|
|
|
airspeed
|
|
|
|
*/
|
2015-05-13 03:09:36 -03:00
|
|
|
void Plane::update_load_factor(void)
|
2014-11-11 22:35:34 -04:00
|
|
|
{
|
|
|
|
float demanded_roll = fabsf(nav_roll_cd*0.01f);
|
|
|
|
if (demanded_roll > 85) {
|
|
|
|
// limit to 85 degrees to prevent numerical errors
|
|
|
|
demanded_roll = 85;
|
|
|
|
}
|
2015-05-15 12:54:46 -03:00
|
|
|
aerodynamic_load_factor = 1.0f / safe_sqrt(cosf(radians(demanded_roll)));
|
2014-11-11 22:35:34 -04:00
|
|
|
|
2014-11-12 23:06:00 -04:00
|
|
|
if (!aparm.stall_prevention) {
|
|
|
|
// stall prevention is disabled
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
if (fly_inverted()) {
|
|
|
|
// no roll limits when inverted
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
2016-05-28 12:07:07 -03:00
|
|
|
float max_load_factor = smoothed_airspeed / airspeed.get_airspeed_min();
|
2014-11-11 22:35:34 -04:00
|
|
|
if (max_load_factor <= 1) {
|
|
|
|
// our airspeed is below the minimum airspeed. Limit roll to
|
|
|
|
// 25 degrees
|
|
|
|
nav_roll_cd = constrain_int32(nav_roll_cd, -2500, 2500);
|
2015-08-14 00:31:59 -03:00
|
|
|
roll_limit_cd = constrain_int32(roll_limit_cd, -2500, 2500);
|
2014-11-11 22:35:34 -04:00
|
|
|
} else if (max_load_factor < aerodynamic_load_factor) {
|
|
|
|
// the demanded nav_roll would take us past the aerodymamic
|
|
|
|
// load limit. Limit our roll to a bank angle that will keep
|
|
|
|
// the load within what the airframe can handle. We always
|
|
|
|
// allow at least 25 degrees of roll however, to ensure the
|
|
|
|
// aircraft can be maneuvered with a bad airspeed estimate. At
|
|
|
|
// 25 degrees the load factor is 1.1 (10%)
|
|
|
|
int32_t roll_limit = degrees(acosf(sq(1.0f / max_load_factor)))*100;
|
|
|
|
if (roll_limit < 2500) {
|
|
|
|
roll_limit = 2500;
|
|
|
|
}
|
|
|
|
nav_roll_cd = constrain_int32(nav_roll_cd, -roll_limit, roll_limit);
|
2015-08-14 00:31:59 -03:00
|
|
|
roll_limit_cd = constrain_int32(roll_limit_cd, -roll_limit, roll_limit);
|
2014-11-11 22:35:34 -04:00
|
|
|
}
|
|
|
|
}
|