mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-07 16:38:30 -04:00
AP_Periph: correct paths to libraries
These were a mixture. This allows param_parse.py to function appropriately.
This commit is contained in:
parent
f847066596
commit
725e36b381
@ -69,7 +69,7 @@ const AP_Param::Info AP_Periph_FW::var_info[] = {
|
|||||||
#ifdef HAL_PERIPH_ENABLE_GPS
|
#ifdef HAL_PERIPH_ENABLE_GPS
|
||||||
// GPS driver
|
// GPS driver
|
||||||
// @Group: GPS
|
// @Group: GPS
|
||||||
// @Path: ../../libraries/AP_GPS/AP_GPS.cpp
|
// @Path: ../libraries/AP_GPS/AP_GPS.cpp
|
||||||
GOBJECT(gps, "GPS", AP_GPS),
|
GOBJECT(gps, "GPS", AP_GPS),
|
||||||
|
|
||||||
// @Param: GPS_PORT
|
// @Param: GPS_PORT
|
||||||
@ -90,14 +90,14 @@ const AP_Param::Info AP_Periph_FW::var_info[] = {
|
|||||||
|
|
||||||
#ifdef HAL_PERIPH_ENABLE_MAG
|
#ifdef HAL_PERIPH_ENABLE_MAG
|
||||||
// @Group: COMPASS_
|
// @Group: COMPASS_
|
||||||
// @Path: ../../libraries/AP_Compass/AP_Compass.cpp
|
// @Path: ../libraries/AP_Compass/AP_Compass.cpp
|
||||||
GOBJECT(compass, "COMPASS_", Compass),
|
GOBJECT(compass, "COMPASS_", Compass),
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef HAL_PERIPH_ENABLE_BARO
|
#ifdef HAL_PERIPH_ENABLE_BARO
|
||||||
// Baro driver
|
// Baro driver
|
||||||
// @Group: BARO
|
// @Group: BARO
|
||||||
// @Path: ../../libraries/AP_Baro/AP_Baro.cpp
|
// @Path: ../libraries/AP_Baro/AP_Baro.cpp
|
||||||
GOBJECT(baro, "BARO", AP_Baro),
|
GOBJECT(baro, "BARO", AP_Baro),
|
||||||
GSCALAR(baro_enable, "BARO_ENABLE", 1),
|
GSCALAR(baro_enable, "BARO_ENABLE", 1),
|
||||||
#endif
|
#endif
|
||||||
@ -109,7 +109,7 @@ const AP_Param::Info AP_Periph_FW::var_info[] = {
|
|||||||
#ifdef HAL_PERIPH_ENABLE_AIRSPEED
|
#ifdef HAL_PERIPH_ENABLE_AIRSPEED
|
||||||
// Airspeed driver
|
// Airspeed driver
|
||||||
// @Group: ARSP
|
// @Group: ARSP
|
||||||
// @Path: ../../libraries/AP_Airspeed/AP_Airspeed.cpp
|
// @Path: ../libraries/AP_Airspeed/AP_Airspeed.cpp
|
||||||
GOBJECT(airspeed, "ARSP", AP_Airspeed),
|
GOBJECT(airspeed, "ARSP", AP_Airspeed),
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
@ -119,7 +119,7 @@ const AP_Param::Info AP_Periph_FW::var_info[] = {
|
|||||||
|
|
||||||
// Rangefinder driver
|
// Rangefinder driver
|
||||||
// @Group: RNGFND
|
// @Group: RNGFND
|
||||||
// @Path: ../../libraries/AP_RangeFinder/Rangefinder.cpp
|
// @Path: ../libraries/AP_RangeFinder/AP_RangeFinder.cpp
|
||||||
GOBJECT(rangefinder, "RNGFND", RangeFinder),
|
GOBJECT(rangefinder, "RNGFND", RangeFinder),
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user