Skip to content

Commit

Permalink
Tools: create and use AP_PERIPH_MAG_ENABLED
Browse files Browse the repository at this point in the history
  • Loading branch information
shiv-tyagi authored and peterbarker committed Jan 29, 2025
1 parent f18c458 commit 1060d67
Show file tree
Hide file tree
Showing 7 changed files with 13 additions and 13 deletions.
4 changes: 2 additions & 2 deletions Tools/AP_Periph/AP_Periph.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -160,7 +160,7 @@ void AP_Periph_FW::init()
}
#endif // AP_PERIPH_GPS_ENABLED

#ifdef HAL_PERIPH_ENABLE_MAG
#if AP_PERIPH_MAG_ENABLED
compass.init();
#endif

Expand Down Expand Up @@ -425,7 +425,7 @@ void AP_Periph_FW::update()
#if AP_PERIPH_GPS_ENABLED
hal.serial(0)->printf("GPS status: %u\n", (unsigned)gps.status());
#endif
#ifdef HAL_PERIPH_ENABLE_MAG
#if AP_PERIPH_MAG_ENABLED
const Vector3f &field = compass.get_field();
hal.serial(0)->printf("MAG (%d,%d,%d)\n", int(field.x), int(field.y), int(field.z));
#endif
Expand Down
4 changes: 2 additions & 2 deletions Tools/AP_Periph/AP_Periph.h
Original file line number Diff line number Diff line change
Expand Up @@ -227,7 +227,7 @@ class AP_Periph_FW {
AP_NMEA_Output nmea;
#endif

#ifdef HAL_PERIPH_ENABLE_MAG
#if AP_PERIPH_MAG_ENABLED
Compass compass;
#endif

Expand Down Expand Up @@ -449,7 +449,7 @@ class AP_Periph_FW {
#ifdef HAL_PERIPH_ENABLE_EFI
uint32_t last_efi_update_ms;
#endif
#ifdef HAL_PERIPH_ENABLE_MAG
#if AP_PERIPH_MAG_ENABLED
uint32_t last_mag_update_ms;
#endif
#if AP_PERIPH_GPS_ENABLED
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 @@ -263,7 +263,7 @@ const AP_Param::Info AP_Periph_FW::var_info[] = {
GSCALAR(battery_hide_mask, "BATT_HIDE_MASK", HAL_PERIPH_BATT_HIDE_MASK_DEFAULT),
#endif

#ifdef HAL_PERIPH_ENABLE_MAG
#if AP_PERIPH_MAG_ENABLED
// @Group: COMPASS_
// @Path: ../libraries/AP_Compass/AP_Compass.cpp
GOBJECT(compass, "COMPASS_", Compass),
Expand Down
4 changes: 2 additions & 2 deletions Tools/AP_Periph/can.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -352,7 +352,7 @@ void AP_Periph_FW::handle_param_executeopcode(CanardInstance* canard_instance, C
#if AP_PERIPH_BATTERY_ENABLED
AP_Param::setup_object_defaults(&battery, battery_lib.var_info);
#endif
#ifdef HAL_PERIPH_ENABLE_MAG
#if AP_PERIPH_MAG_ENABLED
AP_Param::setup_object_defaults(&compass, compass.var_info);
#endif
#ifdef HAL_PERIPH_ENABLE_BARO
Expand Down Expand Up @@ -1882,7 +1882,7 @@ void AP_Periph_FW::can_update()
if (!hal.run_in_maintenance_mode())
#endif
{
#ifdef HAL_PERIPH_ENABLE_MAG
#if AP_PERIPH_MAG_ENABLED
can_mag_update();
#endif
#if AP_PERIPH_GPS_ENABLED
Expand Down
4 changes: 2 additions & 2 deletions Tools/AP_Periph/compass.cpp
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
#include "AP_Periph.h"

#ifdef HAL_PERIPH_ENABLE_MAG
#if AP_PERIPH_MAG_ENABLED

/*
magnetometer support
Expand Down Expand Up @@ -97,4 +97,4 @@ void AP_Periph_FW::can_mag_update(void)
#endif // AP_PERIPH_MAG_HIRES
}

#endif // HAL_PERIPH_ENABLE_MAG
#endif // AP_PERIPH_MAG_ENABLED
6 changes: 3 additions & 3 deletions Tools/AP_Periph/msp.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -51,7 +51,7 @@ void AP_Periph_FW::msp_sensor_update(void)
#ifdef HAL_PERIPH_ENABLE_BARO
send_msp_baro();
#endif
#ifdef HAL_PERIPH_ENABLE_MAG
#if AP_PERIPH_MAG_ENABLED
send_msp_compass();
#endif
#ifdef HAL_PERIPH_ENABLE_AIRSPEED
Expand Down Expand Up @@ -151,7 +151,7 @@ void AP_Periph_FW::send_msp_baro(void)
}
#endif // HAL_PERIPH_ENABLE_BARO

#ifdef HAL_PERIPH_ENABLE_MAG
#if AP_PERIPH_MAG_ENABLED
/*
send MSP compass packet
*/
Expand All @@ -176,7 +176,7 @@ void AP_Periph_FW::send_msp_compass(void)

send_msp_packet(MSP2_SENSOR_COMPASS, &p, sizeof(p));
}
#endif // HAL_PERIPH_ENABLE_MAG
#endif // AP_PERIPH_MAG_ENABLED

#ifdef HAL_PERIPH_ENABLE_AIRSPEED
/*
Expand Down
2 changes: 1 addition & 1 deletion Tools/ardupilotwaf/boards.py
Original file line number Diff line number Diff line change
Expand Up @@ -954,7 +954,7 @@ def configure_env(self, cfg, env):

AP_PERIPH_GPS_ENABLED = 1,
HAL_PERIPH_ENABLE_AIRSPEED = 1,
HAL_PERIPH_ENABLE_MAG = 1,
AP_PERIPH_MAG_ENABLED = 1,
HAL_PERIPH_ENABLE_BARO = 1,
HAL_PERIPH_ENABLE_IMU = 1,
HAL_PERIPH_ENABLE_RANGEFINDER = 1,
Expand Down

0 comments on commit 1060d67

Please sign in to comment.