Skip to content

Commit a313c2a

Browse files
shiv-tyagipeterbarker
authored andcommitted
Tools: use new AP_PERIPH_ESC_APD_ENABLED define
1 parent 3798d6f commit a313c2a

File tree

8 files changed

+17
-14
lines changed

8 files changed

+17
-14
lines changed

Tools/AP_Periph/AP_Periph.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -273,7 +273,7 @@ void AP_Periph_FW::init()
273273
hwesc_telem.init(hal.serial(HAL_PERIPH_HWESC_SERIAL_PORT));
274274
#endif
275275

276-
#ifdef HAL_PERIPH_ENABLE_ESC_APD
276+
#if AP_PERIPH_ESC_APD_ENABLED
277277
for (uint8_t i = 0; i < ESC_NUMBERS; i++) {
278278
const uint8_t port = g.esc_serial_port[i];
279279
if (port < SERIALMANAGER_NUM_PORTS) { // skip bad ports

Tools/AP_Periph/AP_Periph.h

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -335,7 +335,7 @@ class AP_Periph_FW {
335335
AP_KDECAN kdecan;
336336
#endif
337337

338-
#ifdef HAL_PERIPH_ENABLE_ESC_APD
338+
#if AP_PERIPH_ESC_APD_ENABLED
339339
ESC_APD_Telem *apd_esc_telem[APD_ESC_INSTANCES];
340340
void apd_esc_telem_update();
341341
#endif

Tools/AP_Periph/Parameters.cpp

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -392,7 +392,7 @@ const AP_Param::Info AP_Periph_FW::var_info[] = {
392392
GSCALAR(hardpoint_rate, "HARDPOINT_RATE", 100),
393393
#endif
394394

395-
#if AP_PERIPH_HOBBYWING_ESC_ENABLED || defined(HAL_PERIPH_ENABLE_ESC_APD)
395+
#if AP_PERIPH_HOBBYWING_ESC_ENABLED || AP_PERIPH_ESC_APD_ENABLED
396396
// @Param: ESC_NUMBER
397397
// @DisplayName: ESC number
398398
// @Description: This is the ESC number to report as in UAVCAN ESC telemetry feedback packets.
@@ -589,11 +589,11 @@ const AP_Param::Info AP_Periph_FW::var_info[] = {
589589
GOBJECT(kdecan, "KDE_", AP_KDECAN),
590590
#endif
591591

592-
#if defined(HAL_PERIPH_ENABLE_ESC_APD)
592+
#if AP_PERIPH_ESC_APD_ENABLED
593593
GARRAY(pole_count, 0, "ESC_NUM_POLES", 22),
594594
#endif
595595

596-
#if defined(HAL_PERIPH_ENABLE_ESC_APD)
596+
#if AP_PERIPH_ESC_APD_ENABLED
597597
// @Param: ESC_APD_SERIAL_1
598598
// @DisplayName: ESC APD Serial 1
599599
// @Description: Which serial port to use for APD ESC data

Tools/AP_Periph/Parameters.h

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -149,7 +149,7 @@ class Parameters {
149149
AP_Int8 hardpoint_rate;
150150
#endif
151151

152-
#if AP_PERIPH_HOBBYWING_ESC_ENABLED || defined(HAL_PERIPH_ENABLE_ESC_APD)
152+
#if AP_PERIPH_HOBBYWING_ESC_ENABLED || AP_PERIPH_ESC_APD_ENABLED
153153
#if defined ESC_NUMBERS
154154
#error "ESC_NUMBERS should not have been previously defined"
155155
#endif

Tools/AP_Periph/can.cpp

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -1839,7 +1839,7 @@ void AP_Periph_FW::esc_telem_extended_update(const uint32_t &now_ms)
18391839
}
18401840
#endif
18411841

1842-
#ifdef HAL_PERIPH_ENABLE_ESC_APD
1842+
#if AP_PERIPH_ESC_APD_ENABLED
18431843
void AP_Periph_FW::apd_esc_telem_update()
18441844
{
18451845
for(uint8_t i = 0; i < ARRAY_SIZE(apd_esc_telem); i++) {
@@ -1872,7 +1872,7 @@ void AP_Periph_FW::apd_esc_telem_update()
18721872
}
18731873

18741874
}
1875-
#endif // HAL_PERIPH_ENABLE_ESC_APD
1875+
#endif // AP_PERIPH_ESC_APD_ENABLED
18761876
#endif // AP_PERIPH_RC_OUT_ENABLED
18771877

18781878
void AP_Periph_FW::can_update()
@@ -1951,7 +1951,7 @@ void AP_Periph_FW::can_update()
19511951
#if AP_PERIPH_HOBBYWING_ESC_ENABLED
19521952
hwesc_telem_update();
19531953
#endif
1954-
#ifdef HAL_PERIPH_ENABLE_ESC_APD
1954+
#if AP_PERIPH_ESC_APD_ENABLED
19551955
apd_esc_telem_update();
19561956
#endif
19571957
#if AP_PERIPH_MSP_ENABLED

Tools/AP_Periph/esc_apd_telem.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -9,7 +9,7 @@
99
#include <AP_Math/definitions.h>
1010
#include <string.h>
1111

12-
#ifdef HAL_PERIPH_ENABLE_ESC_APD
12+
#if AP_PERIPH_ESC_APD_ENABLED
1313

1414
extern const AP_HAL::HAL& hal;
1515

@@ -95,4 +95,4 @@ float ESC_APD_Telem::convert_temperature(uint16_t raw) const {
9595
return temperature;
9696
}
9797

98-
#endif // HAL_PERIPH_ENABLE_ESC_APD
98+
#endif // AP_PERIPH_ESC_APD_ENABLED

Tools/AP_Periph/esc_apd_telem.h

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -6,7 +6,7 @@
66

77
#include <AP_HAL/AP_HAL.h>
88

9-
#ifdef HAL_PERIPH_ENABLE_ESC_APD
9+
#if AP_PERIPH_ESC_APD_ENABLED
1010

1111
class ESC_APD_Telem {
1212
public:
@@ -58,4 +58,4 @@ class ESC_APD_Telem {
5858
void shift_buffer(void);
5959
};
6060

61-
#endif // HAL_PERIPH_ENABLE_ESC_APD
61+
#endif // AP_PERIPH_ESC_APD_ENABLED

Tools/ardupilotwaf/boards.py

Lines changed: 4 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -984,6 +984,7 @@ def configure_env(self, cfg, env):
984984
AP_PERIPH_NETWORKING_ENABLED = 0,
985985
AP_PERIPH_NOTIFY_ENABLED = 0,
986986
AP_PERIPH_PWM_HARDPOINT_ENABLED = 0,
987+
AP_PERIPH_ESC_APD_ENABLED = 0,
987988
)
988989

989990
class sitl_periph_gps(sitl_periph):
@@ -1019,7 +1020,8 @@ def configure_env(self, cfg, env):
10191020
AP_PERIPH_HOBBYWING_ESC_ENABLED = 0,
10201021
AP_PERIPH_NETWORKING_ENABLED = 0,
10211022
AP_PERIPH_NOTIFY_ENABLED = 0,
1022-
AP_PERIPH_PWM_HARDPOINT_ENABLED =0,
1023+
AP_PERIPH_PWM_HARDPOINT_ENABLED = 0,
1024+
AP_PERIPH_ESC_APD_ENABLED = 0,
10231025
)
10241026

10251027
class sitl_periph_battmon(sitl_periph):
@@ -1056,6 +1058,7 @@ def configure_env(self, cfg, env):
10561058
AP_PERIPH_NETWORKING_ENABLED = 0,
10571059
AP_PERIPH_NOTIFY_ENABLED = 0,
10581060
AP_PERIPH_PWM_HARDPOINT_ENABLED = 0,
1061+
AP_PERIPH_ESC_APD_ENABLED = 0,
10591062
)
10601063

10611064
class esp32(Board):

0 commit comments

Comments
 (0)