mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-26 01:33:56 -04:00
Plane: moved some default values to Parameters.pde
This commit is contained in:
parent
6251d0510a
commit
9c6f80c42b
@ -64,7 +64,7 @@ const AP_Param::Info var_info[] PROGMEM = {
|
|||||||
// @Range: 0 5
|
// @Range: 0 5
|
||||||
// @Increment: 0.01
|
// @Increment: 0.01
|
||||||
// @User: Advanced
|
// @User: Advanced
|
||||||
GSCALAR(kff_pitch_to_throttle, "KFF_PTCH2THR", P_TO_T),
|
GSCALAR(kff_pitch_to_throttle, "KFF_PTCH2THR", 0),
|
||||||
|
|
||||||
// @Param: KFF_THR2PTCH
|
// @Param: KFF_THR2PTCH
|
||||||
// @DisplayName: Throttle to Pitch Mix
|
// @DisplayName: Throttle to Pitch Mix
|
||||||
@ -72,7 +72,7 @@ const AP_Param::Info var_info[] PROGMEM = {
|
|||||||
// @Range: 0 5
|
// @Range: 0 5
|
||||||
// @Increment: 0.01
|
// @Increment: 0.01
|
||||||
// @User: Advanced
|
// @User: Advanced
|
||||||
GSCALAR(kff_throttle_to_pitch, "KFF_THR2PTCH", T_TO_P),
|
GSCALAR(kff_throttle_to_pitch, "KFF_THR2PTCH", 0),
|
||||||
|
|
||||||
// @Param: STICK_MIXING
|
// @Param: STICK_MIXING
|
||||||
// @DisplayName: Stick Mixing
|
// @DisplayName: Stick Mixing
|
||||||
|
@ -655,12 +655,6 @@
|
|||||||
#ifndef THROTTLE_SLEW_LIMIT
|
#ifndef THROTTLE_SLEW_LIMIT
|
||||||
# define THROTTLE_SLEW_LIMIT 0
|
# define THROTTLE_SLEW_LIMIT 0
|
||||||
#endif
|
#endif
|
||||||
#ifndef P_TO_T
|
|
||||||
# define P_TO_T 0
|
|
||||||
#endif
|
|
||||||
#ifndef T_TO_P
|
|
||||||
# define T_TO_P 0
|
|
||||||
#endif
|
|
||||||
#ifndef PITCH_TARGET
|
#ifndef PITCH_TARGET
|
||||||
# define PITCH_TARGET 0
|
# define PITCH_TARGET 0
|
||||||
#endif
|
#endif
|
||||||
|
Loading…
Reference in New Issue
Block a user