mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 09:58:28 -04:00
ACM: Adding Pre-Compiler Define for Stabilize Throttle Mode.
This commit is contained in:
parent
083c451ec6
commit
39013a33bc
@ -96,7 +96,8 @@
|
||||
# define HELI_ROLL_FF 0
|
||||
# define HELI_YAW_FF 0
|
||||
# define RC_FAST_SPEED 125
|
||||
#endif
|
||||
# define STABILIZE_THROTTLE THROTTLE_MANUAL
|
||||
#endif
|
||||
|
||||
|
||||
// optical flow doesn't work in SITL yet
|
||||
@ -534,6 +535,11 @@
|
||||
#define EARTH_FRAME 0
|
||||
#define BODY_FRAME 1
|
||||
|
||||
// Stabilize Mode
|
||||
#ifndef STABILIZE_THROTTLE
|
||||
# define STABILIZE_THROTTLE THROTTLE_MANUAL_TILT_COMPENSATED
|
||||
#endif
|
||||
|
||||
// Alt Hold Mode
|
||||
#ifndef ALT_HOLD_YAW
|
||||
# define ALT_HOLD_YAW YAW_HOLD
|
||||
|
@ -447,7 +447,7 @@ static void set_mode(byte mode)
|
||||
ap.manual_attitude = true;
|
||||
set_yaw_mode(YAW_HOLD);
|
||||
set_roll_pitch_mode(ROLL_PITCH_STABLE);
|
||||
set_throttle_mode(THROTTLE_MANUAL_TILT_COMPENSATED);
|
||||
set_throttle_mode(STABILIZE_THROTTLE);
|
||||
break;
|
||||
|
||||
case ALT_HOLD:
|
||||
|
Loading…
Reference in New Issue
Block a user