Skip to content

Commit

Permalink
Tools: use new AP_PERIPH_SERIAL_OPTIONS_ENABLED define
Browse files Browse the repository at this point in the history
  • Loading branch information
shiv-tyagi committed Feb 20, 2025
1 parent 0197220 commit 7490b07
Show file tree
Hide file tree
Showing 7 changed files with 12 additions and 10 deletions.
2 changes: 1 addition & 1 deletion Tools/AP_Periph/AP_Periph.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -144,7 +144,7 @@ void AP_Periph_FW::init()
node_stats.init();
#endif

#ifdef HAL_PERIPH_ENABLE_SERIAL_OPTIONS
#if AP_PERIPH_SERIAL_OPTIONS_ENABLED
serial_options.init();
#endif

Expand Down
2 changes: 1 addition & 1 deletion Tools/AP_Periph/AP_Periph.h
Original file line number Diff line number Diff line change
Expand Up @@ -384,7 +384,7 @@ class AP_Periph_FW {
BattBalance battery_balance;
#endif

#ifdef HAL_PERIPH_ENABLE_SERIAL_OPTIONS
#if AP_PERIPH_SERIAL_OPTIONS_ENABLED
SerialOptions serial_options;
#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 @@ -643,7 +643,7 @@ const AP_Param::Info AP_Periph_FW::var_info[] = {
GOBJECT(battery_balance, "BAL", BattBalance),
#endif

#ifdef HAL_PERIPH_ENABLE_SERIAL_OPTIONS
#if AP_PERIPH_SERIAL_OPTIONS_ENABLED
// @Group: UART
// @Path: serial_options.cpp
GOBJECT(serial_options, "UART", SerialOptions),
Expand Down
4 changes: 2 additions & 2 deletions Tools/AP_Periph/serial_options.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@

#include "AP_Periph.h"

#ifdef HAL_PERIPH_ENABLE_SERIAL_OPTIONS
#if AP_PERIPH_SERIAL_OPTIONS_ENABLED

#include "serial_options.h"
#include <AP_SerialManager/AP_SerialManager_config.h>
Expand Down Expand Up @@ -107,4 +107,4 @@ void SerialOptions::init(void)
}
}

#endif // HAL_PERIPH_ENABLE_SERIAL_OPTIONS
#endif // AP_PERIPH_SERIAL_OPTIONS_ENABLED
4 changes: 2 additions & 2 deletions Tools/AP_Periph/serial_options.h
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
#pragma once

#ifdef HAL_PERIPH_ENABLE_SERIAL_OPTIONS
#if AP_PERIPH_SERIAL_OPTIONS_ENABLED

#ifndef HAL_UART_NUM_SERIAL_PORTS
#define HAL_UART_NUM_SERIAL_PORTS AP_HAL::HAL::num_serial
Expand All @@ -27,4 +27,4 @@ class SerialOptions {
};


#endif // HAL_PERIPH_ENABLE_SERIAL_OPTIONS
#endif // AP_PERIPH_SERIAL_OPTIONS_ENABLED
4 changes: 2 additions & 2 deletions Tools/AP_Periph/serial_options_dev.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@

#include "AP_Periph.h"

#ifdef HAL_PERIPH_ENABLE_SERIAL_OPTIONS
#if AP_PERIPH_SERIAL_OPTIONS_ENABLED

#include "serial_options.h"

Expand All @@ -44,4 +44,4 @@ const AP_Param::GroupInfo SerialOptionsDev::var_info[] {
AP_GROUPEND
};

#endif // HAL_PERIPH_ENABLE_SERIAL_OPTIONS
#endif // AP_PERIPH_SERIAL_OPTIONS_ENABLED
4 changes: 3 additions & 1 deletion Tools/ardupilotwaf/boards.py
Original file line number Diff line number Diff line change
Expand Up @@ -966,7 +966,7 @@ def configure_env(self, cfg, env):
AP_RPM_STREAM_ENABLED = 1,
HAL_PERIPH_ENABLE_RC_OUT = 1,
AP_PERIPH_ADSB_ENABLED = 1,
HAL_PERIPH_ENABLE_SERIAL_OPTIONS = 1,
AP_PERIPH_SERIAL_OPTIONS_ENABLED = 1,
AP_AIRSPEED_ENABLED = 1,
AP_BATTERY_ESC_ENABLED = 1,
HAL_PWM_COUNT = 32,
Expand All @@ -991,6 +991,7 @@ def configure_env(self, cfg, env):
APJ_BOARD_ID = 101,

AP_PERIPH_BATTERY_ENABLED = 0,
AP_PERIPH_SERIAL_OPTIONS_ENABLED = 0,
AP_PERIPH_ADSB_ENABLED = 0,
AP_PERIPH_GPS_ENABLED = 1,
AP_PERIPH_IMU_ENABLED = 0,
Expand Down Expand Up @@ -1019,6 +1020,7 @@ def configure_env(self, cfg, env):
APJ_BOARD_ID = 101,

AP_PERIPH_BATTERY_ENABLED = 1,
AP_PERIPH_SERIAL_OPTIONS_ENABLED = 0,
AP_PERIPH_BATTERY_BALANCE_ENABLED = 0,
AP_PERIPH_ADSB_ENABLED = 0,
AP_PERIPH_BARO_ENABLED = 0,
Expand Down

0 comments on commit 7490b07

Please sign in to comment.