mirror of https://github.com/ArduPilot/ardupilot
TradHeli: Drift mode to use heli manual throttle
This commit is contained in:
parent
d441354961
commit
b3d20bb8aa
|
@ -112,6 +112,7 @@
|
|||
# define HELI_ROLL_FF 0
|
||||
# define HELI_YAW_FF 0
|
||||
# define STABILIZE_THR THROTTLE_MANUAL_HELI
|
||||
# define DRIFT_THR THROTTLE_MANUAL_HELI
|
||||
# define MPU6K_FILTER 10
|
||||
# define HELI_STAB_COLLECTIVE_MIN_DEFAULT 0
|
||||
# define HELI_STAB_COLLECTIVE_MAX_DEFAULT 1000
|
||||
|
@ -520,6 +521,11 @@
|
|||
# define ACRO_LEVEL_MAX_ANGLE 3000
|
||||
#endif
|
||||
|
||||
// Drift Mode
|
||||
#ifndef DRIFT_THR
|
||||
# define DRIFT_THR THROTTLE_MANUAL_TILT_COMPENSATED
|
||||
#endif
|
||||
|
||||
// Sport Mode
|
||||
#ifndef SPORT_YAW
|
||||
# define SPORT_YAW YAW_HOLD
|
||||
|
|
|
@ -479,7 +479,7 @@ static bool set_mode(uint8_t mode)
|
|||
set_yaw_mode(YAW_DRIFT);
|
||||
set_roll_pitch_mode(ROLL_PITCH_DRIFT);
|
||||
set_nav_mode(NAV_NONE);
|
||||
set_throttle_mode(THROTTLE_MANUAL_TILT_COMPENSATED);
|
||||
set_throttle_mode(DRIFT_THR);
|
||||
break;
|
||||
|
||||
case SPORT:
|
||||
|
|
Loading…
Reference in New Issue