We read every piece of feedback, and take your input very seriously.
To see all available qualifiers, see our documentation.
There was an error while loading. Please reload this page.
1 parent 3798d6f commit a313c2aCopy full SHA for a313c2a
Tools/AP_Periph/AP_Periph.cpp
@@ -273,7 +273,7 @@ void AP_Periph_FW::init()
273
hwesc_telem.init(hal.serial(HAL_PERIPH_HWESC_SERIAL_PORT));
274
#endif
275
276
-#ifdef HAL_PERIPH_ENABLE_ESC_APD
+#if AP_PERIPH_ESC_APD_ENABLED
277
for (uint8_t i = 0; i < ESC_NUMBERS; i++) {
278
const uint8_t port = g.esc_serial_port[i];
279
if (port < SERIALMANAGER_NUM_PORTS) { // skip bad ports
Tools/AP_Periph/AP_Periph.h
@@ -335,7 +335,7 @@ class AP_Periph_FW {
335
AP_KDECAN kdecan;
336
337
338
339
ESC_APD_Telem *apd_esc_telem[APD_ESC_INSTANCES];
340
void apd_esc_telem_update();
341
Tools/AP_Periph/Parameters.cpp
@@ -392,7 +392,7 @@ const AP_Param::Info AP_Periph_FW::var_info[] = {
392
GSCALAR(hardpoint_rate, "HARDPOINT_RATE", 100),
393
394
395
-#if AP_PERIPH_HOBBYWING_ESC_ENABLED || defined(HAL_PERIPH_ENABLE_ESC_APD)
+#if AP_PERIPH_HOBBYWING_ESC_ENABLED || AP_PERIPH_ESC_APD_ENABLED
396
// @Param: ESC_NUMBER
397
// @DisplayName: ESC number
398
// @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[] = {
589
GOBJECT(kdecan, "KDE_", AP_KDECAN),
590
591
592
-#if defined(HAL_PERIPH_ENABLE_ESC_APD)
593
GARRAY(pole_count, 0, "ESC_NUM_POLES", 22),
594
595
596
597
// @Param: ESC_APD_SERIAL_1
598
// @DisplayName: ESC APD Serial 1
599
// @Description: Which serial port to use for APD ESC data
Tools/AP_Periph/Parameters.h
@@ -149,7 +149,7 @@ class Parameters {
149
AP_Int8 hardpoint_rate;
150
151
152
153
#if defined ESC_NUMBERS
154
#error "ESC_NUMBERS should not have been previously defined"
155
Tools/AP_Periph/can.cpp
@@ -1839,7 +1839,7 @@ void AP_Periph_FW::esc_telem_extended_update(const uint32_t &now_ms)
1839
}
1840
1841
1842
1843
void AP_Periph_FW::apd_esc_telem_update()
1844
{
1845
for(uint8_t i = 0; i < ARRAY_SIZE(apd_esc_telem); i++) {
@@ -1872,7 +1872,7 @@ void AP_Periph_FW::apd_esc_telem_update()
1872
1873
1874
1875
-#endif // HAL_PERIPH_ENABLE_ESC_APD
+#endif // AP_PERIPH_ESC_APD_ENABLED
1876
#endif // AP_PERIPH_RC_OUT_ENABLED
1877
1878
void AP_Periph_FW::can_update()
@@ -1951,7 +1951,7 @@ void AP_Periph_FW::can_update()
1951
#if AP_PERIPH_HOBBYWING_ESC_ENABLED
1952
hwesc_telem_update();
1953
1954
1955
apd_esc_telem_update();
1956
1957
#if AP_PERIPH_MSP_ENABLED
Tools/AP_Periph/esc_apd_telem.cpp
@@ -9,7 +9,7 @@
9
#include <AP_Math/definitions.h>
10
#include <string.h>
11
12
13
14
extern const AP_HAL::HAL& hal;
15
@@ -95,4 +95,4 @@ float ESC_APD_Telem::convert_temperature(uint16_t raw) const {
95
return temperature;
96
97
98
Tools/AP_Periph/esc_apd_telem.h
@@ -6,7 +6,7 @@
6
7
#include <AP_HAL/AP_HAL.h>
8
class ESC_APD_Telem {
public:
@@ -58,4 +58,4 @@ class ESC_APD_Telem {
58
void shift_buffer(void);
59
};
60
61
Tools/ardupilotwaf/boards.py
@@ -984,6 +984,7 @@ def configure_env(self, cfg, env):
984
AP_PERIPH_NETWORKING_ENABLED = 0,
985
AP_PERIPH_NOTIFY_ENABLED = 0,
986
AP_PERIPH_PWM_HARDPOINT_ENABLED = 0,
987
+ AP_PERIPH_ESC_APD_ENABLED = 0,
988
)
989
990
class sitl_periph_gps(sitl_periph):
@@ -1019,7 +1020,8 @@ def configure_env(self, cfg, env):
1019
1020
AP_PERIPH_HOBBYWING_ESC_ENABLED = 0,
1021
1022
- AP_PERIPH_PWM_HARDPOINT_ENABLED =0,
1023
+ AP_PERIPH_PWM_HARDPOINT_ENABLED = 0,
1024
1025
1026
1027
class sitl_periph_battmon(sitl_periph):
@@ -1056,6 +1058,7 @@ def configure_env(self, cfg, env):
1056
1058
1057
1059
1060
1061
1062
1063
1064
class esp32(Board):
0 commit comments