mirror of https://github.com/ArduPilot/ardupilot
AP_Rangefinder: Fix bad subgroup pointer for drivers
This commit is contained in:
parent
2a1735192a
commit
2c0eee390d
|
@ -86,7 +86,7 @@ const AP_Param::GroupInfo RangeFinder::var_info[] = {
|
|||
|
||||
// @Group: 4_
|
||||
// @Path: AP_RangeFinder_Wasp.cpp
|
||||
AP_SUBGROUPVARPTR(drivers[0], "4_", 60, RangeFinder, backend_var_info[3]),
|
||||
AP_SUBGROUPVARPTR(drivers[3], "4_", 60, RangeFinder, backend_var_info[3]),
|
||||
#endif
|
||||
|
||||
#if RANGEFINDER_MAX_INSTANCES > 4
|
||||
|
|
Loading…
Reference in New Issue