Copter Motors: by default spin motors at 65 when armed

This commit is contained in:
Randy Mackay 2013-07-28 11:28:10 +09:00
parent 9a1a999fba
commit 8d26fb5581

View File

@ -45,7 +45,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_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 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 0 // spin motors when armed disabled by default #define AP_MOTORS_SPIN_WHEN_ARMED 65 // spin motors at this PWM value when armed
// bit mask for recording which limits we have reached when outputting to motors // bit mask for recording which limits we have reached when outputting to motors
#define AP_MOTOR_NO_LIMITS_REACHED 0x00 #define AP_MOTOR_NO_LIMITS_REACHED 0x00