mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 16:23:56 -04:00
AP_Limit: small fixes to make parameter descriptions appear in mission planner
This commit is contained in:
parent
ac028cca74
commit
45b6dbf580
@ -18,7 +18,7 @@ const AP_Param::GroupInfo AP_Limit_Altitude::var_info[] PROGMEM = {
|
||||
// @User: Standard
|
||||
AP_GROUPINFO("ALT_ON", 0, AP_Limit_Altitude, _enabled, 0),
|
||||
|
||||
// @Param: ALT_REQD
|
||||
// @Param: ALT_REQ
|
||||
// @DisplayName: Require altitude
|
||||
// @Description: Setting this to Enabled(1) will make being inside the altitude a required check before arming the vehicle.
|
||||
// @Values: 0:Disabled,1:Enabled
|
||||
|
@ -43,6 +43,11 @@ const AP_Param::GroupInfo AP_Limit_Geofence::var_info[] PROGMEM = {
|
||||
// @User: Standard
|
||||
AP_GROUPINFO("FNC_RAD", 3, AP_Limit_Geofence, _radius, 0),
|
||||
|
||||
// @Param: FNC_TOT
|
||||
// @DisplayName: Total number of geofence points
|
||||
// @Description: Total number of geofence points. This parameter should not be updated manually
|
||||
// @Range: 0 6
|
||||
// @Increment: 1
|
||||
AP_GROUPINFO("FNC_TOT", 4, AP_Limit_Geofence, _fence_total, 0),
|
||||
AP_GROUPEND
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user