Browse Source

ACM: Adding Pre-Compiler Define for Stabilize Throttle Mode.

mission-4.1.18
Robert Lefebvre 12 years ago
parent
commit
aa4d4f8c24
  1. 8
      ArduCopter/config.h
  2. 2
      ArduCopter/system.pde

8
ArduCopter/config.h

@ -96,7 +96,8 @@ @@ -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 @@ @@ -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

2
ArduCopter/system.pde

@ -447,7 +447,7 @@ static void set_mode(byte mode) @@ -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…
Cancel
Save