Browse Source

Copter: reduce ANGLE_MAX default to 30deg

c415-sdk
Randy Mackay 4 years ago
parent
commit
64289d436a
  1. 2
      ArduCopter/config.h

2
ArduCopter/config.h

@ -559,7 +559,7 @@ @@ -559,7 +559,7 @@
# define ROLL_PITCH_YAW_INPUT_MAX 4500 // roll, pitch and yaw input range
#endif
#ifndef DEFAULT_ANGLE_MAX
# define DEFAULT_ANGLE_MAX 4500 // ANGLE_MAX parameters default value
# define DEFAULT_ANGLE_MAX 3000 // ANGLE_MAX parameters default value
#endif
#ifndef ANGLE_RATE_MAX
# define ANGLE_RATE_MAX 18000 // default maximum rotation rate in roll/pitch axis requested by angle controller used in stabilize, loiter, rtl, auto flight modes

Loading…
Cancel
Save