AP_InertialNav: added parameter descriptions
This commit is contained in:
parent
bf77a0f2e4
commit
55e6544e64
@ -6,10 +6,23 @@ extern const AP_HAL::HAL& hal;
|
|||||||
|
|
||||||
// table of user settable parameters
|
// table of user settable parameters
|
||||||
const AP_Param::GroupInfo AP_InertialNav::var_info[] PROGMEM = {
|
const AP_Param::GroupInfo AP_InertialNav::var_info[] PROGMEM = {
|
||||||
// @Param: ACORR
|
// @Param: ACORR_X
|
||||||
// @DisplayName: Inertial Nav calculated accelerometer corrections
|
// @DisplayName: Inertial Nav accelerometer offset correction on x-axis
|
||||||
// @Description: calculated accelerometer corrections
|
// @Description: Accelerometer offset correction for the x-axis. Calculated automatically
|
||||||
// @Increment: 1
|
// @Range: -100 100
|
||||||
|
// @Increment: 0.1
|
||||||
|
|
||||||
|
// @Param: ACORR_Y
|
||||||
|
// @DisplayName: Inertial Nav accelerometer correction on y-axis
|
||||||
|
// @Description: Accelerometer offset correction for the y-axis. Calculated automatically
|
||||||
|
// @Range: -100 100
|
||||||
|
// @Increment: 0.1
|
||||||
|
|
||||||
|
// @Param: ACORR_Z
|
||||||
|
// @DisplayName: Inertial Nav accelerometer correction on z-axis
|
||||||
|
// @Description: Accelerometer offset correction for the z-axis. Calculated automatically
|
||||||
|
// @Range: -100 100
|
||||||
|
// @Increment: 0.1
|
||||||
AP_GROUPINFO("ACORR", 0, AP_InertialNav, accel_correction, 0),
|
AP_GROUPINFO("ACORR", 0, AP_InertialNav, accel_correction, 0),
|
||||||
|
|
||||||
// @Param: TC_XY
|
// @Param: TC_XY
|
||||||
|
Loading…
Reference in New Issue
Block a user