From 886725291c7dab3c2584bc4791bc8dfc9d61eff5 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Fri, 1 Mar 2013 23:59:53 +0900 Subject: [PATCH] Compass: enable motor compensation for 1280 Expand motor compenstion vector's range limit --- libraries/AP_Compass/Compass.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/libraries/AP_Compass/Compass.cpp b/libraries/AP_Compass/Compass.cpp index 2b87e9aea6..04b64f18d0 100644 --- a/libraries/AP_Compass/Compass.cpp +++ b/libraries/AP_Compass/Compass.cpp @@ -54,26 +54,26 @@ const AP_Param::GroupInfo Compass::var_info[] PROGMEM = { // @Values: 0:Disabled,1:Enabled // @User: Advanced AP_GROUPINFO("AUTODEC",5, Compass, _auto_declination, 1), +#endif // @Param: MOT_X // @DisplayName: Motor interference compensation for body frame X axis // @Description: Multiplied by the current throttle and added to the compass's x-axis values to compensate for motor interference - // @Range: -400 400 + // @Range: -1000 1000 // @Increment: 1 // @Param: MOT_Y // @DisplayName: Motor interference compensation for body frame Y axis // @Description: Multiplied by the current throttle and added to the compass's y-axis values to compensate for motor interference - // @Range: -400 400 + // @Range: -1000 1000 // @Increment: 1 // @Param: MOT_Z // @DisplayName: Motor interference compensation for body frame Z axis // @Description: Multiplied by the current throttle and added to the compass's z-axis values to compensate for motor interference - // @Range: -400 400 + // @Range: -1000 1000 // @Increment: 1 AP_GROUPINFO("MOT", 6, Compass, _motor_compensation, 0), -#endif AP_GROUPEND };