Skip to content

Commit

Permalink
Tools: create AP_PERIPH_GPS_ENABLED
Browse files Browse the repository at this point in the history
  • Loading branch information
peterbarker committed Jan 14, 2025
1 parent e44e3c5 commit 47894ef
Show file tree
Hide file tree
Showing 9 changed files with 25 additions and 25 deletions.
6 changes: 3 additions & 3 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 AP_PERIPH_GPS_ENABLED
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 All @@ -158,7 +158,7 @@ void AP_Periph_FW::init()
#endif
gps.init();
}
#endif
#endif // AP_PERIPH_GPS_ENABLED

#ifdef HAL_PERIPH_ENABLE_MAG
compass.init();
Expand Down Expand Up @@ -422,7 +422,7 @@ void AP_Periph_FW::update()
}
#endif
#if 0
#ifdef HAL_PERIPH_ENABLE_GPS
#if AP_PERIPH_GPS_ENABLED
hal.serial(0)->printf("GPS status: %u\n", (unsigned)gps.status());
#endif
#ifdef HAL_PERIPH_ENABLE_MAG
Expand Down
10 changes: 5 additions & 5 deletions Tools/AP_Periph/AP_Periph.h
Original file line number Diff line number Diff line change
Expand Up @@ -62,9 +62,9 @@
#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 && AP_PERIPH_GPS_ENABLED)
// 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"
#error "AP_NMEA_Output requires Serial/GCS and either AHRS or GPS. Needs HAL_GCS_ENABLED and AP_PERIPH_GPS_ENABLED"
#endif

#if HAL_GCS_ENABLED
Expand Down Expand Up @@ -216,7 +216,7 @@ class AP_Periph_FW {
AP_Stats node_stats;
#endif

#ifdef HAL_PERIPH_ENABLE_GPS
#if AP_GPS_ENABLED
AP_GPS gps;
#if HAL_NUM_CAN_IFACES >= 2
int8_t gps_mb_can_port = -1;
Expand Down Expand Up @@ -452,7 +452,7 @@ class AP_Periph_FW {
#ifdef HAL_PERIPH_ENABLE_MAG
uint32_t last_mag_update_ms;
#endif
#ifdef HAL_PERIPH_ENABLE_GPS
#if AP_PERIPH_GPS_ENABLED
uint32_t last_gps_update_ms;
uint32_t last_gps_yaw_ms;
#endif
Expand All @@ -463,7 +463,7 @@ class AP_Periph_FW {
#ifdef HAL_PERIPH_ENABLE_AIRSPEED
uint32_t last_airspeed_update_ms;
#endif
#ifdef HAL_PERIPH_ENABLE_GPS
#if AP_PERIPH_GPS_ENABLED
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 AP_PERIPH_GPS_ENABLED
// 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 @@ -166,7 +166,7 @@ class Parameters {
AP_Int8 pole_count[ESC_NUMBERS];
#endif

#ifdef HAL_PERIPH_ENABLE_GPS
#if AP_PERIPH_GPS_ENABLED
AP_Int8 gps_port;
#if GPS_MOVING_BASELINE
AP_Int8 gps_mb_only_can_port;
Expand Down
14 changes: 7 additions & 7 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 AP_PERIPH_GPS_ENABLED
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 AP_PERIPH_GPS_ENABLED && (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 AP_PERIPH_GPS_ENABLED
case UAVCAN_EQUIPMENT_GNSS_RTCMSTREAM_ID:
handle_RTCMStream(canard_instance, transfer);
break;
Expand All @@ -842,7 +842,7 @@ void AP_Periph_FW::onTransferReceived(CanardInstance* canard_instance,
handle_MovingBaselineData(canard_instance, transfer);
break;
#endif
#endif // HAL_PERIPH_ENABLE_GPS
#endif // AP_PERIPH_GPS_ENABLED

#if AP_UART_MONITOR_ENABLED
case UAVCAN_TUNNEL_TARGETTED_ID:
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 AP_PERIPH_GPS_ENABLED
case UAVCAN_EQUIPMENT_GNSS_RTCMSTREAM_ID:
*out_data_type_signature = UAVCAN_EQUIPMENT_GNSS_RTCMSTREAM_SIGNATURE;
return true;
Expand All @@ -965,7 +965,7 @@ bool AP_Periph_FW::shouldAcceptTransfer(const CanardInstance* canard_instance,
*out_data_type_signature = ARDUPILOT_GNSS_MOVINGBASELINEDATA_SIGNATURE;
return true;
#endif
#endif // HAL_PERIPH_ENABLE_GPS
#endif // AP_PERIPH_GPS_ENABLED

#if AP_UART_MONITOR_ENABLED
case UAVCAN_TUNNEL_TARGETTED_ID:
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 AP_PERIPH_GPS_ENABLED
can_gps_update();
#endif
#if AP_UART_MONITOR_ENABLED
Expand Down
4 changes: 2 additions & 2 deletions 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 AP_PERIPH_GPS_ENABLED

/*
GPS support
Expand Down Expand Up @@ -317,4 +317,4 @@ void AP_Periph_FW::send_relposheading_msg() {
#endif // GPS_MOVING_BASELINE
}

#endif // HAL_PERIPH_ENABLE_GPS
#endif // AP_PERIPH_GPS_ENABLED
6 changes: 3 additions & 3 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 AP_PERIPH_GPS_ENABLED
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 AP_PERIPH_GPS_ENABLED
/*
send MSP GPS packet
*/
Expand Down Expand Up @@ -122,7 +122,7 @@ void AP_Periph_FW::send_msp_GPS(void)

send_msp_packet(MSP2_SENSOR_GPS, &p, sizeof(p));
}
#endif // HAL_PERIPH_ENABLE_GPS
#endif // AP_PERIPH_GPS_ENABLED


#ifdef HAL_PERIPH_ENABLE_BARO
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 AP_PERIPH_GPS_ENABLED
if (uart_num == -1) {
uart_num = g.gps_port;
}
Expand Down
4 changes: 2 additions & 2 deletions Tools/ardupilotwaf/boards.py
Original file line number Diff line number Diff line change
Expand Up @@ -945,7 +945,7 @@ def configure_env(self, cfg, env):
CAN_APP_NODE_NAME = '"org.ardupilot.ap_periph_universal"',
APJ_BOARD_ID = 100,

HAL_PERIPH_ENABLE_GPS = 1,
AP_PERIPH_GPS_ENABLED = 1,
HAL_PERIPH_ENABLE_AIRSPEED = 1,
HAL_PERIPH_ENABLE_MAG = 1,
HAL_PERIPH_ENABLE_BARO = 1,
Expand Down Expand Up @@ -977,7 +977,7 @@ def configure_env(self, cfg, env):
CAN_APP_NODE_NAME = '"org.ardupilot.ap_periph_gps"',
APJ_BOARD_ID = 101,

HAL_PERIPH_ENABLE_GPS = 1,
AP_PERIPH_GPS_ENABLED = 1,
)

class sitl_periph_battmon(sitl_periph):
Expand Down

0 comments on commit 47894ef

Please sign in to comment.