mirror of https://github.com/ArduPilot/ardupilot
AP_Mount: document point-at-home default mode option
This commit is contained in:
parent
2b03c49b49
commit
1f4ebb49b5
|
@ -27,7 +27,7 @@ const AP_Param::GroupInfo AP_Mount::var_info[] = {
|
|||
// @Param: _DEFLT_MODE
|
||||
// @DisplayName: Mount default operating mode
|
||||
// @Description: Mount default operating mode on startup and after control is returned from autopilot
|
||||
// @Values: 0:Retracted,1:Neutral,2:MavLink Targeting,3:RC Targeting,4:GPS Point
|
||||
// @Values: 0:Retracted,1:Neutral,2:MavLink Targeting,3:RC Targeting,4:GPS Point,6:Home Location
|
||||
// @User: Standard
|
||||
AP_GROUPINFO("_DEFLT_MODE", 0, AP_Mount, state[0]._default_mode, MAV_MOUNT_MODE_RC_TARGETING),
|
||||
|
||||
|
@ -222,7 +222,7 @@ const AP_Param::GroupInfo AP_Mount::var_info[] = {
|
|||
// @Param: 2_DEFLT_MODE
|
||||
// @DisplayName: Mount default operating mode
|
||||
// @Description: Mount default operating mode on startup and after control is returned from autopilot
|
||||
// @Values: 0:Retracted,1:Neutral,2:MavLink Targeting,3:RC Targeting,4:GPS Point
|
||||
// @Values: 0:Retracted,1:Neutral,2:MavLink Targeting,3:RC Targeting,4:GPS Point,6:Home Location
|
||||
// @User: Standard
|
||||
AP_GROUPINFO("2_DEFLT_MODE", 25, AP_Mount, state[1]._default_mode, MAV_MOUNT_MODE_RC_TARGETING),
|
||||
|
||||
|
|
Loading…
Reference in New Issue