mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Plane: Address Randy review comments
This commit is contained in:
parent
aae092b88f
commit
fef8b37b11
@ -54,13 +54,16 @@ float Plane::get_speed_scaler(void)
|
||||
*/
|
||||
bool Plane::stick_mixing_enabled(void)
|
||||
{
|
||||
#if AC_FENCE == ENABLED
|
||||
const bool stickmixing = fence_stickmixing();
|
||||
#else
|
||||
const bool stickmixing = true;
|
||||
#endif
|
||||
if (control_mode->does_auto_throttle() && plane.control_mode->does_auto_navigation()) {
|
||||
// we're in an auto mode. Check the stick mixing flag
|
||||
if (g.stick_mixing != STICK_MIXING_DISABLED &&
|
||||
g.stick_mixing != STICK_MIXING_VTOL_YAW &&
|
||||
#if AC_FENCE == ENABLED
|
||||
fence_stickmixing() &&
|
||||
#endif
|
||||
stickmixing &&
|
||||
failsafe.state == FAILSAFE_NONE &&
|
||||
!rc_failsafe_active()) {
|
||||
// we're in an auto mode, and haven't triggered failsafe
|
||||
|
@ -186,13 +186,16 @@ void Plane::read_radio()
|
||||
|
||||
control_failsafe();
|
||||
|
||||
#if AC_FENCE == ENABLED
|
||||
const bool stickmixing = fence_stickmixing();
|
||||
#else
|
||||
const bool stickmixing = true;
|
||||
#endif
|
||||
airspeed_nudge_cm = 0;
|
||||
throttle_nudge = 0;
|
||||
if (g.throttle_nudge && channel_throttle->get_control_in() > 50
|
||||
#if AC_FENCE == ENABLED
|
||||
&& fence_stickmixing()
|
||||
#endif
|
||||
) {
|
||||
if (g.throttle_nudge
|
||||
&& channel_throttle->get_control_in() > 50
|
||||
&& stickmixing) {
|
||||
float nudge = (channel_throttle->get_control_in() - 50) * 0.02f;
|
||||
if (ahrs.airspeed_sensor_enabled()) {
|
||||
airspeed_nudge_cm = (aparm.airspeed_max * 100 - aparm.airspeed_cruise_cm) * nudge;
|
||||
|
Loading…
Reference in New Issue
Block a user