mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-01 21:48:28 -04:00
Copter Motors: increased spin-when-armed to 70
Changed choices to be displayed in ground stations
This commit is contained in:
parent
653a5036ae
commit
0a047ae1c1
@ -49,7 +49,7 @@ const AP_Param::GroupInfo AP_Motors::var_info[] PROGMEM = {
|
||||
// @Param: SPIN_ARMED
|
||||
// @DisplayName: Motors always spin when armed
|
||||
// @Description: Controls whether motors always spin when armed
|
||||
// @Values: 0:Do Not Spin,50:Slow,85:Medium,120:Fast
|
||||
// @Values: 0:Do Not Spin,70:Slow,100:Medium,130:Fast
|
||||
AP_GROUPINFO("SPIN_ARMED", 4, AP_Motors, _spin_when_armed, AP_MOTORS_SPIN_WHEN_ARMED),
|
||||
|
||||
AP_GROUPEND
|
||||
|
@ -46,7 +46,7 @@
|
||||
#define THROTTLE_CURVE_MID_THRUST 52 // throttle which produces 1/2 the maximum thrust. expressed as a percentage of the full throttle range (i.e 0 ~ 100)
|
||||
#define THROTTLE_CURVE_MAX_THRUST 93 // throttle which produces the maximum thrust. expressed as a percentage of the full throttle range (i.e 0 ~ 100)
|
||||
|
||||
#define AP_MOTORS_SPIN_WHEN_ARMED 65 // spin motors at this PWM value when armed
|
||||
#define AP_MOTORS_SPIN_WHEN_ARMED 70 // spin motors at this PWM value when armed
|
||||
|
||||
// bit mask for recording which limits we have reached when outputting to motors
|
||||
#define AP_MOTOR_NO_LIMITS_REACHED 0x00
|
||||
|
Loading…
Reference in New Issue
Block a user