From 048b907c98b03504e9f2525a4813e2e10347d7ae Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 17 Sep 2024 15:26:43 +1000 Subject: [PATCH] AP_Periph: ensure all peripherals define HAL_PERIPH_ENABLE_GPS to 1 or 0 --- Tools/AP_Periph/AP_Periph.cpp | 4 ++-- Tools/AP_Periph/AP_Periph.h | 8 ++++---- Tools/AP_Periph/Parameters.cpp | 2 +- Tools/AP_Periph/Parameters.h | 2 +- Tools/AP_Periph/can.cpp | 10 +++++----- Tools/AP_Periph/gps.cpp | 2 +- Tools/AP_Periph/msp.cpp | 4 ++-- Tools/AP_Periph/serial_tunnel.cpp | 2 +- 8 files changed, 17 insertions(+), 17 deletions(-) diff --git a/Tools/AP_Periph/AP_Periph.cpp b/Tools/AP_Periph/AP_Periph.cpp index b952d7ae24..7c1e92eb41 100644 --- a/Tools/AP_Periph/AP_Periph.cpp +++ b/Tools/AP_Periph/AP_Periph.cpp @@ -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); @@ -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 diff --git a/Tools/AP_Periph/AP_Periph.h b/Tools/AP_Periph/AP_Periph.h index dc3f6754e4..e0c234a569 100644 --- a/Tools/AP_Periph/AP_Periph.h +++ b/Tools/AP_Periph/AP_Periph.h @@ -61,7 +61,7 @@ #endif #include -#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 @@ -211,7 +211,7 @@ public: 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; @@ -443,7 +443,7 @@ public: #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 @@ -454,7 +454,7 @@ public: #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 diff --git a/Tools/AP_Periph/Parameters.cpp b/Tools/AP_Periph/Parameters.cpp index e0196045a9..12118fadd5 100644 --- a/Tools/AP_Periph/Parameters.cpp +++ b/Tools/AP_Periph/Parameters.cpp @@ -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 diff --git a/Tools/AP_Periph/Parameters.h b/Tools/AP_Periph/Parameters.h index 6479b51168..dff03cec2f 100644 --- a/Tools/AP_Periph/Parameters.h +++ b/Tools/AP_Periph/Parameters.h @@ -164,7 +164,7 @@ public: 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; diff --git a/Tools/AP_Periph/can.cpp b/Tools/AP_Periph/can.cpp index 55ceefc9d8..19ac6d999e 100644 --- a/Tools/AP_Periph/can.cpp +++ b/Tools/AP_Periph/can.cpp @@ -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 @@ -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; @@ -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; @@ -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; @@ -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 diff --git a/Tools/AP_Periph/gps.cpp b/Tools/AP_Periph/gps.cpp index 3eced2d6e1..ebafc52481 100644 --- a/Tools/AP_Periph/gps.cpp +++ b/Tools/AP_Periph/gps.cpp @@ -1,6 +1,6 @@ #include "AP_Periph.h" -#ifdef HAL_PERIPH_ENABLE_GPS +#if HAL_PERIPH_ENABLE_GPS /* GPS support diff --git a/Tools/AP_Periph/msp.cpp b/Tools/AP_Periph/msp.cpp index 8c3858fbe0..3372a791f3 100644 --- a/Tools/AP_Periph/msp.cpp +++ b/Tools/AP_Periph/msp.cpp @@ -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 @@ -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 */ diff --git a/Tools/AP_Periph/serial_tunnel.cpp b/Tools/AP_Periph/serial_tunnel.cpp index a4e13d9ab9..51d74940a4 100644 --- a/Tools/AP_Periph/serial_tunnel.cpp +++ b/Tools/AP_Periph/serial_tunnel.cpp @@ -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; }