From d3fcfe669d9c099bdf4837cce2da62ac3a9a0b72 Mon Sep 17 00:00:00 2001 From: Randy Mackay <rmackay9@yahoo.com> Date: Wed, 18 Sep 2013 13:28:01 +0900 Subject: [PATCH] Copter Motors: increase MOT_SPIN_ARMED to int16 --- libraries/AP_Motors/AP_Motors_Class.cpp | 6 +++--- libraries/AP_Motors/AP_Motors_Class.h | 4 ++-- 2 files changed, 5 insertions(+), 5 deletions(-) diff --git a/libraries/AP_Motors/AP_Motors_Class.cpp b/libraries/AP_Motors/AP_Motors_Class.cpp index 5924ee44e..f19e4b7c6 100644 --- a/libraries/AP_Motors/AP_Motors_Class.cpp +++ b/libraries/AP_Motors/AP_Motors_Class.cpp @@ -48,9 +48,9 @@ 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,70:Slow,100:Medium,130:Fast - AP_GROUPINFO("SPIN_ARMED", 4, AP_Motors, _spin_when_armed, AP_MOTORS_SPIN_WHEN_ARMED), + // @Description: Controls whether motors always spin when armed (must be below THR_MIN) + // @Values: 0:Do Not Spin,70:VerySlow,100:Slow,130:Medium,150:Fast + AP_GROUPINFO("SPIN_ARMED", 5, 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 e7c2d030d..1a2bcd884 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 70 // spin motors at this PWM value when armed +#define AP_MOTORS_SPIN_WHEN_ARMED 100 // 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 @@ -157,7 +157,7 @@ protected: AP_Int8 _throttle_curve_enabled; // enable throttle curve AP_Int8 _throttle_curve_mid; // throttle which produces 1/2 the maximum thrust. expressed as a percentage (i.e. 0 ~ 100 ) of the full throttle range AP_Int8 _throttle_curve_max; // throttle which produces the maximum thrust. expressed as a percentage (i.e. 0 ~ 100 ) of the full throttle range - AP_Int8 _spin_when_armed; // used to control whether the motors always spin when armed. pwm value above radio_min + AP_Int16 _spin_when_armed; // used to control whether the motors always spin when armed. pwm value above radio_min // internal variables RC_Channel* _rc_roll, *_rc_pitch, *_rc_throttle, *_rc_yaw; // input in from users -- GitLab