From 0a047ae1c11f9964322e4c9439cade1520db8bd7 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Thu, 12 Sep 2013 22:36:04 +0900 Subject: [PATCH] Copter Motors: increased spin-when-armed to 70 Changed choices to be displayed in ground stations --- libraries/AP_Motors/AP_Motors_Class.cpp | 2 +- libraries/AP_Motors/AP_Motors_Class.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_Motors/AP_Motors_Class.cpp b/libraries/AP_Motors/AP_Motors_Class.cpp index d0b2a7ddc2..5924ee44e3 100644 --- a/libraries/AP_Motors/AP_Motors_Class.cpp +++ b/libraries/AP_Motors/AP_Motors_Class.cpp @@ -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 diff --git a/libraries/AP_Motors/AP_Motors_Class.h b/libraries/AP_Motors/AP_Motors_Class.h index a5eb4313a5..e7c2d030d8 100644 --- a/libraries/AP_Motors/AP_Motors_Class.h +++ b/libraries/AP_Motors/AP_Motors_Class.h @@ -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