Browse Source

Plane: change default slewrate to 100%/second

master
Andrew Tridgell 12 years ago
parent
commit
b8fa83ff54
  1. 4
      ArduPlane/Parameters.pde
  2. 6
      ArduPlane/config.h

4
ArduPlane/Parameters.pde

@ -304,12 +304,12 @@ const AP_Param::Info var_info[] PROGMEM = { @@ -304,12 +304,12 @@ const AP_Param::Info var_info[] PROGMEM = {
// @Param: THR_SLEWRATE
// @DisplayName: Throttle slew rate
// @Description: maximum percentage change in throttle per second. A setting of 10 means to not change the throttle by more than 10% of the full throttle range in one second
// @Description: maximum percentage change in throttle per second. A setting of 10 means to not change the throttle by more than 10% of the full throttle range in one second.
// @Units: Percent
// @Range: 0 100
// @Increment: 1
// @User: Standard
ASCALAR(throttle_slewrate, "THR_SLEWRATE", THROTTLE_SLEW_LIMIT),
ASCALAR(throttle_slewrate, "THR_SLEWRATE", 100),
// @Param: THR_SUPP_MAN
// @DisplayName: Throttle suppress manual passthru

6
ArduPlane/config.h

@ -503,9 +503,6 @@ @@ -503,9 +503,6 @@
# define SERVO_ROLL_INT_MAX 5
#endif
#define SERVO_ROLL_INT_MAX_CENTIDEGREE SERVO_ROLL_INT_MAX*100
#ifndef ROLL_SLEW_LIMIT
# define ROLL_SLEW_LIMIT 0
#endif
#ifndef SERVO_PITCH_P
# define SERVO_PITCH_P 0.6
#endif
@ -598,9 +595,6 @@ @@ -598,9 +595,6 @@
#ifndef THROTTLE_TE_INT_MAX
# define THROTTLE_TE_INT_MAX 20
#endif
#ifndef THROTTLE_SLEW_LIMIT
# define THROTTLE_SLEW_LIMIT 0
#endif
#ifndef PITCH_TARGET
# define PITCH_TARGET 0
#endif

Loading…
Cancel
Save