Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Ensure all peripherals define HAL_PERIPH_ENABLE_GPS to 1 or 0 #28127

Open
wants to merge 3 commits into
base: master
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
4 changes: 2 additions & 2 deletions Tools/AP_Periph/AP_Periph.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -148,7 +148,7 @@ void AP_Periph_FW::init()
serial_options.init();
#endif

#ifdef HAL_PERIPH_ENABLE_GPS
#if HAL_PERIPH_ENABLE_GPS
gps.set_default_type_for_gps1(HAL_GPS1_TYPE_DEFAULT);
if (gps.get_type(0) != AP_GPS::GPS_Type::GPS_TYPE_NONE && g.gps_port >= 0) {
serial_manager.set_protocol_and_baud(g.gps_port, AP_SerialManager::SerialProtocol_GPS, AP_SERIALMANAGER_GPS_BAUD);
Expand Down Expand Up @@ -413,7 +413,7 @@ void AP_Periph_FW::update()
}
#endif
#if 0
#ifdef HAL_PERIPH_ENABLE_GPS
#if HAL_PERIPH_ENABLE_GPS
hal.serial(0)->printf("GPS status: %u\n", (unsigned)gps.status());
#endif
#ifdef HAL_PERIPH_ENABLE_MAG
Expand Down
8 changes: 4 additions & 4 deletions Tools/AP_Periph/AP_Periph.h
Original file line number Diff line number Diff line change
Expand Up @@ -61,7 +61,7 @@
#endif

#include <AP_NMEA_Output/AP_NMEA_Output.h>
#if HAL_NMEA_OUTPUT_ENABLED && !(HAL_GCS_ENABLED && defined(HAL_PERIPH_ENABLE_GPS))
#if HAL_NMEA_OUTPUT_ENABLED && !(HAL_GCS_ENABLED && HAL_PERIPH_ENABLE_GPS)
// Needs SerialManager + (AHRS or GPS)
#error "AP_NMEA_Output requires Serial/GCS and either AHRS or GPS. Needs HAL_GCS_ENABLED and HAL_PERIPH_ENABLE_GPS"
#endif
Expand Down Expand Up @@ -211,7 +211,7 @@ class AP_Periph_FW {
AP_Stats node_stats;
#endif

#ifdef HAL_PERIPH_ENABLE_GPS
#if HAL_PERIPH_ENABLE_GPS
AP_GPS gps;
#if HAL_NUM_CAN_IFACES >= 2
int8_t gps_mb_can_port = -1;
Expand Down Expand Up @@ -443,7 +443,7 @@ class AP_Periph_FW {
#ifdef HAL_PERIPH_ENABLE_MAG
uint32_t last_mag_update_ms;
#endif
#ifdef HAL_PERIPH_ENABLE_GPS
#if HAL_PERIPH_ENABLE_GPS
uint32_t last_gps_update_ms;
uint32_t last_gps_yaw_ms;
#endif
Expand All @@ -454,7 +454,7 @@ class AP_Periph_FW {
#ifdef HAL_PERIPH_ENABLE_AIRSPEED
uint32_t last_airspeed_update_ms;
#endif
#ifdef HAL_PERIPH_ENABLE_GPS
#if HAL_PERIPH_ENABLE_GPS
bool saw_gps_lock_once;
#endif

Expand Down
2 changes: 1 addition & 1 deletion Tools/AP_Periph/Parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -224,7 +224,7 @@ const AP_Param::Info AP_Periph_FW::var_info[] = {
GSCALAR(buzz_volume, "BUZZER_VOLUME", 100),
#endif

#ifdef HAL_PERIPH_ENABLE_GPS
#if HAL_PERIPH_ENABLE_GPS
// GPS driver
// @Group: GPS
// @Path: ../libraries/AP_GPS/AP_GPS.cpp
Expand Down
2 changes: 1 addition & 1 deletion Tools/AP_Periph/Parameters.h
Original file line number Diff line number Diff line change
Expand Up @@ -164,7 +164,7 @@ class Parameters {
AP_Int8 pole_count[ESC_NUMBERS];
#endif

#ifdef HAL_PERIPH_ENABLE_GPS
#if HAL_PERIPH_ENABLE_GPS
AP_Int8 gps_port;
#if GPS_MOVING_BASELINE
AP_Int8 gps_mb_only_can_port;
Expand Down
10 changes: 5 additions & 5 deletions Tools/AP_Periph/can.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -346,7 +346,7 @@ void AP_Periph_FW::handle_param_executeopcode(CanardInstance* canard_instance, C
AP_Param::erase_all();
AP_Param::load_all();
AP_Param::setup_sketch_defaults();
#ifdef HAL_PERIPH_ENABLE_GPS
#if HAL_PERIPH_ENABLE_GPS
AP_Param::setup_object_defaults(&gps, gps.var_info);
#endif
#ifdef HAL_PERIPH_ENABLE_BATTERY
Expand Down Expand Up @@ -474,7 +474,7 @@ void AP_Periph_FW::handle_allocation_response(CanardInstance* canard_instance, C
canardSetLocalNodeID(canard_instance, msg.node_id);
printf("IF%d Node ID allocated: %d\n", dronecan.dna_interface, msg.node_id);

#if defined(HAL_PERIPH_ENABLE_GPS) && (HAL_NUM_CAN_IFACES >= 2) && GPS_MOVING_BASELINE
#if HAL_PERIPH_ENABLE_GPS && (HAL_NUM_CAN_IFACES >= 2) && GPS_MOVING_BASELINE
if (g.gps_mb_only_can_port) {
// we need to assign the unallocated port to be used for Moving Baseline only
gps_mb_can_port = (dronecan.dna_interface+1)%HAL_NUM_CAN_IFACES;
Expand Down Expand Up @@ -832,7 +832,7 @@ void AP_Periph_FW::onTransferReceived(CanardInstance* canard_instance,
handle_arming_status(canard_instance, transfer);
break;

#ifdef HAL_PERIPH_ENABLE_GPS
#if HAL_PERIPH_ENABLE_GPS
case UAVCAN_EQUIPMENT_GNSS_RTCMSTREAM_ID:
handle_RTCMStream(canard_instance, transfer);
break;
Expand Down Expand Up @@ -955,7 +955,7 @@ bool AP_Periph_FW::shouldAcceptTransfer(const CanardInstance* canard_instance,
*out_data_type_signature = UAVCAN_EQUIPMENT_INDICATION_LIGHTSCOMMAND_SIGNATURE;
return true;
#endif
#ifdef HAL_PERIPH_ENABLE_GPS
#if HAL_PERIPH_ENABLE_GPS
case UAVCAN_EQUIPMENT_GNSS_RTCMSTREAM_ID:
*out_data_type_signature = UAVCAN_EQUIPMENT_GNSS_RTCMSTREAM_SIGNATURE;
return true;
Expand Down Expand Up @@ -1877,7 +1877,7 @@ void AP_Periph_FW::can_update()
#ifdef HAL_PERIPH_ENABLE_MAG
can_mag_update();
#endif
#ifdef HAL_PERIPH_ENABLE_GPS
#if HAL_PERIPH_ENABLE_GPS
can_gps_update();
#endif
#if AP_UART_MONITOR_ENABLED
Expand Down
2 changes: 1 addition & 1 deletion Tools/AP_Periph/gps.cpp
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
#include "AP_Periph.h"

#ifdef HAL_PERIPH_ENABLE_GPS
#if HAL_PERIPH_ENABLE_GPS

/*
GPS support
Expand Down
4 changes: 2 additions & 2 deletions Tools/AP_Periph/msp.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -45,7 +45,7 @@ void AP_Periph_FW::msp_sensor_update(void)
if (msp.port.uart == nullptr) {
return;
}
#ifdef HAL_PERIPH_ENABLE_GPS
#if HAL_PERIPH_ENABLE_GPS
send_msp_GPS();
#endif
#ifdef HAL_PERIPH_ENABLE_BARO
Expand All @@ -60,7 +60,7 @@ void AP_Periph_FW::msp_sensor_update(void)
}


#ifdef HAL_PERIPH_ENABLE_GPS
#if HAL_PERIPH_ENABLE_GPS
/*
send MSP GPS packet
*/
Expand Down
2 changes: 1 addition & 1 deletion Tools/AP_Periph/serial_tunnel.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -43,7 +43,7 @@ extern const AP_HAL::HAL &hal;
int8_t AP_Periph_FW::get_default_tunnel_serial_port(void) const
{
int8_t uart_num = -1;
#ifdef HAL_PERIPH_ENABLE_GPS
#if HAL_PERIPH_ENABLE_GPS
if (uart_num == -1) {
uart_num = g.gps_port;
}
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_HAL_ChibiOS/hwdef/ARK_CANNODE/hwdef.dat
Original file line number Diff line number Diff line change
Expand Up @@ -110,7 +110,7 @@ PB9 I2C1_SDA I2C1
define GPS_MAX_RECEIVERS 1
define GPS_MAX_INSTANCES 1
define HAL_COMPASS_MAX_SENSORS 1
define HAL_PERIPH_ENABLE_GPS
define HAL_PERIPH_ENABLE_GPS 1
define HAL_PERIPH_ENABLE_MAG
define HAL_PERIPH_ENABLE_BARO
define HAL_PERIPH_ENABLE_RC_OUT
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_HAL_ChibiOS/hwdef/ARK_GPS/hwdef.dat
Original file line number Diff line number Diff line change
Expand Up @@ -110,7 +110,7 @@ PB15 SAFE_BUTTON INPUT PULLDOWN
define GPS_MAX_RECEIVERS 1
define GPS_MAX_INSTANCES 1
define HAL_COMPASS_MAX_SENSORS 1
define HAL_PERIPH_ENABLE_GPS
define HAL_PERIPH_ENABLE_GPS 1
define HAL_PERIPH_ENABLE_MAG
define HAL_PERIPH_ENABLE_BARO
define HAL_PERIPH_ENABLE_BUZZER
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_HAL_ChibiOS/hwdef/ARK_RTK_GPS/hwdef.dat
Original file line number Diff line number Diff line change
Expand Up @@ -122,7 +122,7 @@ define HAL_CAN_POOL_SIZE 12000
define GPS_MAX_RECEIVERS 1
define GPS_MAX_INSTANCES 1
define HAL_COMPASS_MAX_SENSORS 1
define HAL_PERIPH_ENABLE_GPS
define HAL_PERIPH_ENABLE_GPS 1
define HAL_PERIPH_ENABLE_MAG
define HAL_PERIPH_ENABLE_BARO
define HAL_PERIPH_ENABLE_BUZZER
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_HAL_ChibiOS/hwdef/AeroFox-GNSS_F9P/hwdef.dat
Original file line number Diff line number Diff line change
Expand Up @@ -73,7 +73,7 @@ define HAL_PERIPH_LISTEN_FOR_SERIAL_UART_REBOOT_CMD_PORT 0
env ROMFS_UNCOMPRESSED True

# enable GPS and compass
define HAL_PERIPH_ENABLE_GPS
define HAL_PERIPH_ENABLE_GPS 1
define GPS_MAX_RATE_MS 200
define GPS_MAX_RECEIVERS 1
define GPS_MAX_INSTANCES 1
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_HAL_ChibiOS/hwdef/BirdCANdy/hwdef.dat
Original file line number Diff line number Diff line change
Expand Up @@ -100,7 +100,7 @@ define HAL_COMPASS_MAX_SENSORS 1

# RCOU+GPS+MAG+BARO+Buzzer+NeoPixels
define HAL_PERIPH_ENABLE_RC_OUT
define HAL_PERIPH_ENABLE_GPS
define HAL_PERIPH_ENABLE_GPS 1
define HAL_PERIPH_ENABLE_MAG
define HAL_PERIPH_ENABLE_BARO
define HAL_PERIPH_ENABLE_BUZZER
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_HAL_ChibiOS/hwdef/C-RTK2-HP/hwdef.dat
Original file line number Diff line number Diff line change
Expand Up @@ -98,7 +98,7 @@ define AP_PARAM_MAX_EMBEDDED_PARAM 256
define GPS_MAX_RECEIVERS 1
define GPS_MAX_INSTANCES 1

define HAL_PERIPH_ENABLE_GPS
define HAL_PERIPH_ENABLE_GPS 1
define GPS_MOVING_BASELINE 1

define HAL_PERIPH_ENABLE_MAG
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_HAL_ChibiOS/hwdef/CUAV_GPS/hwdef.dat
Original file line number Diff line number Diff line change
Expand Up @@ -130,7 +130,7 @@ define GPS_MAX_INSTANCES 1
define HAL_COMPASS_MAX_SENSORS 1

# GPS+MAG+BARO+Buzzer+NeoPixels
define HAL_PERIPH_ENABLE_GPS
define HAL_PERIPH_ENABLE_GPS 1
define HAL_PERIPH_ENABLE_MAG
define HAL_PERIPH_ENABLE_BARO

Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_HAL_ChibiOS/hwdef/CarbonixF405/hwdef.dat
Original file line number Diff line number Diff line change
Expand Up @@ -122,7 +122,7 @@ define HAL_SUPPORT_RCOUT_SERIAL 1
define HAL_WITH_ESC_TELEM 1

# enable GPS
define HAL_PERIPH_ENABLE_GPS
define HAL_PERIPH_ENABLE_GPS 1
define HAL_PERIPH_GPS_PORT_DEFAULT 2
#define HAL_PERIPH_ENABLE_NOTIFY
#define HAL_PERIPH_ENABLE_NCP5623_LED_WITHOUT_NOTIFY
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_HAL_ChibiOS/hwdef/CarbonixL496/hwdef.dat
Original file line number Diff line number Diff line change
Expand Up @@ -125,7 +125,7 @@ define HAL_SUPPORT_RCOUT_SERIAL 1
define HAL_WITH_ESC_TELEM 1

# enable GPS
define HAL_PERIPH_ENABLE_GPS
define HAL_PERIPH_ENABLE_GPS 1
define HAL_PERIPH_GPS_PORT_DEFAULT 2
#define HAL_PERIPH_ENABLE_NOTIFY
#define HAL_PERIPH_ENABLE_NCP5623_LED_WITHOUT_NOTIFY
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_HAL_ChibiOS/hwdef/CubeBlack-periph/hwdef.dat
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,7 @@ env AP_PERIPH 1



define HAL_PERIPH_ENABLE_GPS
define HAL_PERIPH_ENABLE_GPS 1
define HAL_PERIPH_ENABLE_MAG
define HAL_PERIPH_ENABLE_BARO
define HAL_PERIPH_ENABLE_RC_OUT
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,7 @@ env AP_PERIPH_HEAVY 1

define AP_CAN_SLCAN_ENABLED 1
define HAL_PERIPH_ENABLE_BATTERY
define HAL_PERIPH_ENABLE_GPS
define HAL_PERIPH_ENABLE_GPS 1
define HAL_PERIPH_ENABLE_MAG
define HAL_PERIPH_ENABLE_BARO
define HAL_PERIPH_ENABLE_RC_OUT
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-periph/hwdef.dat
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,7 @@ env AP_PERIPH 1

define AP_CAN_SLCAN_ENABLED 1
define HAL_PERIPH_ENABLE_BATTERY
define HAL_PERIPH_ENABLE_GPS
define HAL_PERIPH_ENABLE_GPS 1
define HAL_PERIPH_ENABLE_MAG
define HAL_PERIPH_ENABLE_BARO
define HAL_PERIPH_ENABLE_RC_OUT
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_HAL_ChibiOS/hwdef/FreeflyRTK/hwdef.dat
Original file line number Diff line number Diff line change
Expand Up @@ -122,7 +122,7 @@ define GPS_MOVING_BASELINE 1
define HAL_COMPASS_MAX_SENSORS 1

# GPS+MAG+BARO+Buzzer+NeoPixels
define HAL_PERIPH_ENABLE_GPS
define HAL_PERIPH_ENABLE_GPS 1
define HAL_PERIPH_ENABLE_MAG
define HAL_PERIPH_ENABLE_BARO
define HAL_PERIPH_ENABLE_RC_OUT
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_HAL_ChibiOS/hwdef/HitecMosaic/hwdef.dat
Original file line number Diff line number Diff line change
Expand Up @@ -138,7 +138,7 @@ PA7 LED_BUS_I2C OUTPUT LOW
env ROMFS_UNCOMPRESSED True


define HAL_PERIPH_ENABLE_GPS
define HAL_PERIPH_ENABLE_GPS 1
define HAL_PERIPH_ENABLE_MAG
define HAL_PERIPH_ENABLE_BARO

Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_HAL_ChibiOS/hwdef/HolybroG4_GPS/hwdef.dat
Original file line number Diff line number Diff line change
Expand Up @@ -131,7 +131,7 @@ DMA_NOSHARE USART3*
define GPS_MOVING_BASELINE 1

# GPS+MAG+LEDs
define HAL_PERIPH_ENABLE_GPS
define HAL_PERIPH_ENABLE_GPS 1
define HAL_PERIPH_ENABLE_MAG
define HAL_PERIPH_ENABLE_NOTIFY
define HAL_PERIPH_ENABLE_RC_OUT
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_HAL_ChibiOS/hwdef/HolybroGPS/hwdef.dat
Original file line number Diff line number Diff line change
Expand Up @@ -137,7 +137,7 @@ define GPS_MAX_INSTANCES 1
define HAL_COMPASS_MAX_SENSORS 1

# GPS+MAG+BARO+LEDs
define HAL_PERIPH_ENABLE_GPS
define HAL_PERIPH_ENABLE_GPS 1
define HAL_PERIPH_ENABLE_MAG
define HAL_PERIPH_ENABLE_BARO
define HAL_PERIPH_ENABLE_NOTIFY
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_HAL_ChibiOS/hwdef/MatekG474-Periph/hwdef.dat
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
include ../MatekG474/hwdef.inc

# ----------- GPS
define HAL_PERIPH_ENABLE_GPS
define HAL_PERIPH_ENABLE_GPS 1
define GPS_MAX_RATE_MS 200

define GPS_MAX_RECEIVERS 1
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_HAL_ChibiOS/hwdef/MatekH743-periph/hwdef.dat
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,7 @@ env AP_PERIPH 1



define HAL_PERIPH_ENABLE_GPS
define HAL_PERIPH_ENABLE_GPS 1
define HAL_PERIPH_ENABLE_MAG
define HAL_PERIPH_ENABLE_BARO
define HAL_PERIPH_ENABLE_AIRSPEED
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_HAL_ChibiOS/hwdef/MatekL431-GPS/hwdef.dat
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
include ../MatekL431/hwdef.inc

# enable GPS and compass
define HAL_PERIPH_ENABLE_GPS
define HAL_PERIPH_ENABLE_GPS 1
define GPS_MAX_RATE_MS 200

define GPS_MAX_RECEIVERS 1
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_HAL_ChibiOS/hwdef/MatekL431-Periph/hwdef.dat
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@ PA15 TIM2_CH1 TIM2 PWM(5) GPIO(54)
PA6 TIM16_CH1 TIM16 GPIO(32) ALARM

# ----------------------- GPS ----------------------------
define HAL_PERIPH_ENABLE_GPS
define HAL_PERIPH_ENABLE_GPS 1
define GPS_MAX_RATE_MS 200

define GPS_MAX_RECEIVERS 1
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_HAL_ChibiOS/hwdef/Nucleo-L476/hwdef.dat
Original file line number Diff line number Diff line change
Expand Up @@ -89,7 +89,7 @@ PA4 VSENSE ADC1 SCALE(2)

define AP_PARAM_MAX_EMBEDDED_PARAM 512

define HAL_PERIPH_ENABLE_GPS
define HAL_PERIPH_ENABLE_GPS 1
define HAL_PERIPH_GPS_PORT_DEFAULT 0

define HAL_PERIPH_ENABLE_MAG
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_HAL_ChibiOS/hwdef/Nucleo-L496/hwdef.dat
Original file line number Diff line number Diff line change
Expand Up @@ -97,7 +97,7 @@ PA4 VSENSE ADC1 SCALE(2)

define AP_PARAM_MAX_EMBEDDED_PARAM 512

define HAL_PERIPH_ENABLE_GPS
define HAL_PERIPH_ENABLE_GPS 1
define HAL_PERIPH_ENABLE_MAG
define HAL_PERIPH_ENABLE_BARO
define HAL_PERIPH_ENABLE_AIRSPEED
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_HAL_ChibiOS/hwdef/Pixracer-periph/hwdef.dat
Original file line number Diff line number Diff line change
Expand Up @@ -64,7 +64,7 @@ define HAL_PERIPH_ENABLE_AIRSPEED
define HAL_AIRSPEED_BUS_DEFAULT 0
define AIRSPEED_MAX_SENSORS 1

define HAL_PERIPH_ENABLE_GPS
define HAL_PERIPH_ENABLE_GPS 1
define HAL_PERIPH_GPS_PORT_DEFAULT 3

define HAL_PERIPH_ENABLE_MAG
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_HAL_ChibiOS/hwdef/Sierra-F405/hwdef.dat
Original file line number Diff line number Diff line change
Expand Up @@ -80,7 +80,7 @@ PA15 TIM2_CH1 TIM2 PWM(3) GPIO(52)
PB4 TIM3_CH1 TIM3 PWM(4) GPIO(53)

# ----------------------- GPS ----------------------------
define HAL_PERIPH_ENABLE_GPS
define HAL_PERIPH_ENABLE_GPS 1
define HAL_PERIPH_GPS_PORT_DEFAULT 3
define GPS_MAX_RECEIVERS 1
define GPS_MAX_INSTANCES 1
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_HAL_ChibiOS/hwdef/Sierra-F412/hwdef.dat
Original file line number Diff line number Diff line change
Expand Up @@ -103,7 +103,7 @@ define GPS_MAX_INSTANCES 1
define HAL_COMPASS_MAX_SENSORS 1

# GPS+MAG+BARO+Buzzer+NeoPixels
define HAL_PERIPH_ENABLE_GPS
define HAL_PERIPH_ENABLE_GPS 1
define HAL_PERIPH_GPS_PORT_DEFAULT 3
define HAL_PERIPH_ENABLE_MAG
define HAL_PERIPH_ENABLE_BARO
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_HAL_ChibiOS/hwdef/Sierra-F9P/hwdef.dat
Original file line number Diff line number Diff line change
Expand Up @@ -115,7 +115,7 @@ define GPS_MAX_INSTANCES 1
define HAL_COMPASS_MAX_SENSORS 1

# GPS+MAG+BARO+Buzzer+NeoPixels
define HAL_PERIPH_ENABLE_GPS
define HAL_PERIPH_ENABLE_GPS 1
define HAL_PERIPH_ENABLE_MAG
define HAL_PERIPH_ENABLE_BARO
define HAL_PERIPH_ENABLE_RC_OUT
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -108,7 +108,7 @@ define GPS_MAX_INSTANCES 1
define HAL_COMPASS_MAX_SENSORS 1

# GPS+MAG+BARO+NeoPixels
define HAL_PERIPH_ENABLE_GPS
define HAL_PERIPH_ENABLE_GPS 1
define HAL_PERIPH_ENABLE_MAG
define HAL_PERIPH_ENABLE_BARO
define HAL_PERIPH_ENABLE_RC_OUT
Expand Down
Loading
Loading