AP_Compass: Use SI units conventions in parameter units

Follow the rules from:
http://physics.nist.gov/cuu/Units/units.html
http://physics.nist.gov/cuu/Units/outside.html
and
http://physics.nist.gov/cuu/Units/checklist.html
one further constrain is that only printable (7bit) ASCII characters are allowed
This commit is contained in:
Dr.-Ing. Amilcar Do Carmo Lucas 2017-05-02 15:42:55 +02:00 committed by Andrew Tridgell
parent 41a9402175
commit 4c45b1c7ca

View File

@ -41,7 +41,7 @@ const AP_Param::GroupInfo Compass::var_info[] = {
// @DisplayName: Compass offsets in milligauss on the X axis
// @Description: Offset to be added to the compass x-axis values to compensate for metal in the frame
// @Range: -400 400
// @Units: milligauss
// @Units: mGauss
// @Increment: 1
// @User: Advanced
@ -49,7 +49,7 @@ const AP_Param::GroupInfo Compass::var_info[] = {
// @DisplayName: Compass offsets in milligauss on the Y axis
// @Description: Offset to be added to the compass y-axis values to compensate for metal in the frame
// @Range: -400 400
// @Units: milligauss
// @Units: mGauss
// @Increment: 1
// @User: Advanced
@ -57,7 +57,7 @@ const AP_Param::GroupInfo Compass::var_info[] = {
// @DisplayName: Compass offsets in milligauss on the Z axis
// @Description: Offset to be added to the compass z-axis values to compensate for metal in the frame
// @Range: -400 400
// @Units: milligauss
// @Units: mGauss
// @Increment: 1
// @User: Advanced
AP_GROUPINFO("OFS", 1, Compass, _state[0].offset, 0),
@ -66,7 +66,7 @@ const AP_Param::GroupInfo Compass::var_info[] = {
// @DisplayName: Compass declination
// @Description: An angle to compensate between the true north and magnetic north
// @Range: -3.142 3.142
// @Units: Radians
// @Units: rad
// @Increment: 0.01
// @User: Standard
AP_GROUPINFO("DEC", 2, Compass, _declination, 0),
@ -101,25 +101,25 @@ const AP_Param::GroupInfo Compass::var_info[] = {
// @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
// @Description: Multiplied by the current throttle and added to the compass's x-axis values to compensate for motor interference (Offset per Amp or at Full Throttle)
// @Range: -1000 1000
// @Units: Offset per Amp or at Full Throttle
// @Units: mGauss/A
// @Increment: 1
// @User: Advanced
// @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
// @Description: Multiplied by the current throttle and added to the compass's y-axis values to compensate for motor interference (Offset per Amp or at Full Throttle)
// @Range: -1000 1000
// @Units: Offset per Amp or at Full Throttle
// @Units: mGauss/A
// @Increment: 1
// @User: Advanced
// @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
// @Description: Multiplied by the current throttle and added to the compass's z-axis values to compensate for motor interference (Offset per Amp or at Full Throttle)
// @Range: -1000 1000
// @Units: Offset per Amp or at Full Throttle
// @Units: mGauss/A
// @Increment: 1
// @User: Advanced
AP_GROUPINFO("MOT", 7, Compass, _state[0].motor_compensation, 0),
@ -142,7 +142,7 @@ const AP_Param::GroupInfo Compass::var_info[] = {
// @DisplayName: Compass2 offsets in milligauss on the X axis
// @Description: Offset to be added to compass2's x-axis values to compensate for metal in the frame
// @Range: -400 400
// @Units: milligauss
// @Units: mGauss
// @Increment: 1
// @User: Advanced
@ -150,7 +150,7 @@ const AP_Param::GroupInfo Compass::var_info[] = {
// @DisplayName: Compass2 offsets in milligauss on the Y axis
// @Description: Offset to be added to compass2's y-axis values to compensate for metal in the frame
// @Range: -400 400
// @Units: milligauss
// @Units: mGauss
// @Increment: 1
// @User: Advanced
@ -158,32 +158,32 @@ const AP_Param::GroupInfo Compass::var_info[] = {
// @DisplayName: Compass2 offsets in milligauss on the Z axis
// @Description: Offset to be added to compass2's z-axis values to compensate for metal in the frame
// @Range: -400 400
// @Units: milligauss
// @Units: mGauss
// @Increment: 1
// @User: Advanced
AP_GROUPINFO("OFS2", 10, Compass, _state[1].offset, 0),
// @Param: MOT2_X
// @DisplayName: Motor interference compensation to compass2 for body frame X axis
// @Description: Multiplied by the current throttle and added to compass2's x-axis values to compensate for motor interference
// @Description: Multiplied by the current throttle and added to compass2's x-axis values to compensate for motor interference (Offset per Amp or at Full Throttle)
// @Range: -1000 1000
// @Units: Offset per Amp or at Full Throttle
// @Units: mGauss/A
// @Increment: 1
// @User: Advanced
// @Param: MOT2_Y
// @DisplayName: Motor interference compensation to compass2 for body frame Y axis
// @Description: Multiplied by the current throttle and added to compass2's y-axis values to compensate for motor interference
// @Description: Multiplied by the current throttle and added to compass2's y-axis values to compensate for motor interference (Offset per Amp or at Full Throttle)
// @Range: -1000 1000
// @Units: Offset per Amp or at Full Throttle
// @Units: mGauss/A
// @Increment: 1
// @User: Advanced
// @Param: MOT2_Z
// @DisplayName: Motor interference compensation to compass2 for body frame Z axis
// @Description: Multiplied by the current throttle and added to compass2's z-axis values to compensate for motor interference
// @Description: Multiplied by the current throttle and added to compass2's z-axis values to compensate for motor interference (Offset per Amp or at Full Throttle)
// @Range: -1000 1000
// @Units: Offset per Amp or at Full Throttle
// @Units: mGauss/A
// @Increment: 1
// @User: Advanced
AP_GROUPINFO("MOT2", 11, Compass, _state[1].motor_compensation, 0),
@ -199,7 +199,7 @@ const AP_Param::GroupInfo Compass::var_info[] = {
// @DisplayName: Compass3 offsets in milligauss on the X axis
// @Description: Offset to be added to compass3's x-axis values to compensate for metal in the frame
// @Range: -400 400
// @Units: milligauss
// @Units: mGauss
// @Increment: 1
// @User: Advanced
@ -207,7 +207,7 @@ const AP_Param::GroupInfo Compass::var_info[] = {
// @DisplayName: Compass3 offsets in milligauss on the Y axis
// @Description: Offset to be added to compass3's y-axis values to compensate for metal in the frame
// @Range: -400 400
// @Units: milligauss
// @Units: mGauss
// @Increment: 1
// @User: Advanced
@ -215,32 +215,32 @@ const AP_Param::GroupInfo Compass::var_info[] = {
// @DisplayName: Compass3 offsets in milligauss on the Z axis
// @Description: Offset to be added to compass3's z-axis values to compensate for metal in the frame
// @Range: -400 400
// @Units: milligauss
// @Units: mGauss
// @Increment: 1
// @User: Advanced
AP_GROUPINFO("OFS3", 13, Compass, _state[2].offset, 0),
// @Param: MOT3_X
// @DisplayName: Motor interference compensation to compass3 for body frame X axis
// @Description: Multiplied by the current throttle and added to compass3's x-axis values to compensate for motor interference
// @Description: Multiplied by the current throttle and added to compass3's x-axis values to compensate for motor interference (Offset per Amp or at Full Throttle)
// @Range: -1000 1000
// @Units: Offset per Amp or at Full Throttle
// @Units: mGauss/A
// @Increment: 1
// @User: Advanced
// @Param: MOT3_Y
// @DisplayName: Motor interference compensation to compass3 for body frame Y axis
// @Description: Multiplied by the current throttle and added to compass3's y-axis values to compensate for motor interference
// @Description: Multiplied by the current throttle and added to compass3's y-axis values to compensate for motor interference (Offset per Amp or at Full Throttle)
// @Range: -1000 1000
// @Units: Offset per Amp or at Full Throttle
// @Units: mGauss/A
// @Increment: 1
// @User: Advanced
// @Param: MOT3_Z
// @DisplayName: Motor interference compensation to compass3 for body frame Z axis
// @Description: Multiplied by the current throttle and added to compass3's z-axis values to compensate for motor interference
// @Description: Multiplied by the current throttle and added to compass3's z-axis values to compensate for motor interference (Offset per Amp or at Full Throttle)
// @Range: -1000 1000
// @Units: Offset per Amp or at Full Throttle
// @Units: mGauss/A
// @Increment: 1
// @User: Advanced
AP_GROUPINFO("MOT3", 14, Compass, _state[2].motor_compensation, 0),