Browse Source

AP_Rangefinder: Fix bad subgroup pointer for drivers

copter407
Michael du Breuil 5 years ago committed by Randy Mackay
parent
commit
2c0eee390d
  1. 2
      libraries/AP_RangeFinder/RangeFinder.cpp

2
libraries/AP_RangeFinder/RangeFinder.cpp

@ -86,7 +86,7 @@ const AP_Param::GroupInfo RangeFinder::var_info[] = { @@ -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…
Cancel
Save