Skip to content
Snippets Groups Projects
Commit 80bd458f authored by Randy Mackay's avatar Randy Mackay
Browse files

Compass: update parameter description

We do not want people modifying the COMPASS_MOTCT manually
parent ad656c7e
No related branches found
No related tags found
No related merge requests found
...@@ -58,7 +58,7 @@ const AP_Param::GroupInfo Compass::var_info[] PROGMEM = { ...@@ -58,7 +58,7 @@ const AP_Param::GroupInfo Compass::var_info[] PROGMEM = {
// @Param: MOTCT // @Param: MOTCT
// @DisplayName: Motor interference compensation type // @DisplayName: Motor interference compensation type
// @Description: Set motor interference compensation type to disabled, throttle or current // @Description: Set motor interference compensation type to disabled, throttle or current. Do not change manually.
// @Values: 0:Disabled,1:Use Throttle,2:Use Current // @Values: 0:Disabled,1:Use Throttle,2:Use Current
// @Increment: 1 // @Increment: 1
AP_GROUPINFO("MOTCT", 6, Compass, _motor_comp_type, AP_COMPASS_MOT_COMP_DISABLED), AP_GROUPINFO("MOTCT", 6, Compass, _motor_comp_type, AP_COMPASS_MOT_COMP_DISABLED),
...@@ -67,18 +67,21 @@ const AP_Param::GroupInfo Compass::var_info[] PROGMEM = { ...@@ -67,18 +67,21 @@ const AP_Param::GroupInfo Compass::var_info[] PROGMEM = {
// @DisplayName: Motor interference compensation for body frame X axis // @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 // @Description: Multiplied by the current throttle and added to the compass's x-axis values to compensate for motor interference
// @Range: -1000 1000 // @Range: -1000 1000
// @Units: Offset per Amp or at Full Throttle
// @Increment: 1 // @Increment: 1
// @Param: MOT_Y // @Param: MOT_Y
// @DisplayName: Motor interference compensation for body frame Y axis // @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 // @Description: Multiplied by the current throttle and added to the compass's y-axis values to compensate for motor interference
// @Range: -1000 1000 // @Range: -1000 1000
// @Units: Offset per Amp or at Full Throttle
// @Increment: 1 // @Increment: 1
// @Param: MOT_Z // @Param: MOT_Z
// @DisplayName: Motor interference compensation for body frame Z axis // @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 // @Description: Multiplied by the current throttle and added to the compass's z-axis values to compensate for motor interference
// @Range: -1000 1000 // @Range: -1000 1000
// @Units: Offset per Amp or at Full Throttle
// @Increment: 1 // @Increment: 1
AP_GROUPINFO("MOT", 7, Compass, _motor_compensation, 0), AP_GROUPINFO("MOT", 7, Compass, _motor_compensation, 0),
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment