From 8d26fb5581b5442716ef68acccad7a23bbd8d90c Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Sun, 28 Jul 2013 11:28:10 +0900 Subject: [PATCH] Copter Motors: by default spin motors at 65 when armed --- libraries/AP_Motors/AP_Motors_Class.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_Motors/AP_Motors_Class.h b/libraries/AP_Motors/AP_Motors_Class.h index 89234309a8..3812e5d444 100644 --- a/libraries/AP_Motors/AP_Motors_Class.h +++ b/libraries/AP_Motors/AP_Motors_Class.h @@ -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_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 #define AP_MOTOR_NO_LIMITS_REACHED 0x00