diff --git a/libraries/AP_Motors/AP_MotorsHeli.cpp b/libraries/AP_Motors/AP_MotorsHeli.cpp
index ff8f5740906c009b9dc14f8cb430342d9cd05582..a0755b203ccb671e4d6659fdcd3a3ab30ae2e193 100644
--- a/libraries/AP_Motors/AP_MotorsHeli.cpp
+++ b/libraries/AP_Motors/AP_MotorsHeli.cpp
@@ -204,7 +204,7 @@ const AP_Param::GroupInfo AP_MotorsHeli::var_info[] PROGMEM = {
     // @Units: PWM
     // @Increment: 1
     // @User: Standard
-    AP_GROUPINFO("TAIL_SPEED", 24, AP_MotorsHeli,  _direct_drive_tailspeed, AP_MOTOR_HELI_DIRECTDRIVE_DEFAULT),
+    AP_GROUPINFO("TAIL_SPEED", 24, AP_MotorsHeli,  _direct_drive_tailspeed, AP_MOTOR_HELI_DDTAIL_DEFAULT),
 
     AP_GROUPEND
 };
diff --git a/libraries/AP_Motors/AP_MotorsHeli.h b/libraries/AP_Motors/AP_MotorsHeli.h
index fca13eaf750035f2bfcd723322902e3dfb2deb72..6a7a41b0d38e2359e720c71733e6980f731fcc31 100644
--- a/libraries/AP_Motors/AP_MotorsHeli.h
+++ b/libraries/AP_Motors/AP_MotorsHeli.h
@@ -38,8 +38,8 @@
 #define AP_MOTORS_HELI_SWASH_H1                 1
 
 // default swash min and max angles and positions
-#define AP_MOTORS_HELI_SWASH_ROLL_MAX           4500
-#define AP_MOTORS_HELI_SWASH_PITCH_MAX          4500
+#define AP_MOTORS_HELI_SWASH_ROLL_MAX           2500
+#define AP_MOTORS_HELI_SWASH_PITCH_MAX          2500
 #define AP_MOTORS_HELI_COLLECTIVE_MIN           1250
 #define AP_MOTORS_HELI_COLLECTIVE_MAX           1750
 #define AP_MOTORS_HELI_COLLECTIVE_MID           1500
@@ -61,7 +61,7 @@
 #define AP_MOTORS_HELI_EXT_GYRO_GAIN            350
 
 // minimum outputs for direct drive motors
-#define AP_MOTOR_HELI_DIRECTDRIVE_DEFAULT       500
+#define AP_MOTOR_HELI_DDTAIL_DEFAULT       500
 
 
 // main rotor speed control types (ch8 out)