Browse Source

hwdef: Set the maximum number of barometric pressure sensors to 1

gps-1.3.1
murata 3 years ago committed by Andrew Tridgell
parent
commit
bc0954e124
  1. 1
      libraries/AP_HAL_ChibiOS/hwdef/JHEMCU-GSF405A/hwdef.dat

1
libraries/AP_HAL_ChibiOS/hwdef/JHEMCU-GSF405A/hwdef.dat

@ -170,3 +170,4 @@ define HAL_NMEA_OUTPUT_ENABLED 0 @@ -170,3 +170,4 @@ define HAL_NMEA_OUTPUT_ENABLED 0
define HAL_BUTTON_ENABLED 0
define HAL_OREO_LED_ENABLED 0
define HAL_PICCOLO_CAN_ENABLE 0
define BARO_MAX_INSTANCES 1

Loading…
Cancel
Save