Copter: shorten precision landing param prefix
This commit is contained in:
parent
1155b1f557
commit
cfff57257e
@ -1062,7 +1062,7 @@ const AP_Param::Info Copter::var_info[] = {
|
|||||||
#if PRECISION_LANDING == ENABLED
|
#if PRECISION_LANDING == ENABLED
|
||||||
// @Group: PRECLAND_
|
// @Group: PRECLAND_
|
||||||
// @Path: ../libraries/AC_PrecLand/AC_PrecLand.cpp
|
// @Path: ../libraries/AC_PrecLand/AC_PrecLand.cpp
|
||||||
GOBJECT(precland, "PLAND_", AC_PrecLand),
|
GOBJECT(precland, "PLND_", AC_PrecLand),
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// @Group: RPM
|
// @Group: RPM
|
||||||
|
Loading…
Reference in New Issue
Block a user