From 6b3c10f0e7418cc785fbb6d029610089b4b92dd8 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sun, 6 Oct 2019 16:29:15 +1100 Subject: [PATCH] AP_BoardConfig: cleanup ifdefs for SLCAN enable --- libraries/AP_BoardConfig/AP_BoardConfig_CAN.cpp | 13 +++++++------ libraries/AP_BoardConfig/AP_BoardConfig_CAN.h | 4 ++-- libraries/AP_BoardConfig/canbus_slcan.cpp | 2 +- 3 files changed, 10 insertions(+), 9 deletions(-) diff --git a/libraries/AP_BoardConfig/AP_BoardConfig_CAN.cpp b/libraries/AP_BoardConfig/AP_BoardConfig_CAN.cpp index ce66a7fde3..39441572ce 100644 --- a/libraries/AP_BoardConfig/AP_BoardConfig_CAN.cpp +++ b/libraries/AP_BoardConfig/AP_BoardConfig_CAN.cpp @@ -77,7 +77,7 @@ const AP_Param::GroupInfo AP_BoardConfig_CAN::var_info[] = { AP_SUBGROUPINFO(_drivers[2], "D3_", 6, AP_BoardConfig_CAN, AP_BoardConfig_CAN::Driver), #endif -#if !HAL_MINIMIZE_FEATURES +#if AP_UAVCAN_SLCAN_ENABLED // @Group: SLCAN_ // @Path: ../AP_BoardConfig/canbus_slcan.cpp AP_SUBGROUPINFO(_slcan, "SLCAN_", 7, AP_BoardConfig_CAN, AP_BoardConfig_CAN::SLCAN_Interface), @@ -102,7 +102,7 @@ void AP_BoardConfig_CAN::init() { // Create all drivers that we need bool initret = true; -#if !HAL_MINIMIZE_FEATURES +#if AP_UAVCAN_SLCAN_ENABLED reset_slcan_serial(); #endif for (uint8_t i = 0; i < MAX_NUMBER_OF_CAN_INTERFACES; i++) { @@ -122,12 +122,12 @@ void AP_BoardConfig_CAN::init() // For this now existing driver (manager), start the physical interface if (hal.can_mgr[drv_num - 1] != nullptr) { initret = initret && hal.can_mgr[drv_num - 1]->begin(_interfaces[i]._bitrate, i); - #if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS && !HAL_MINIMIZE_FEATURES +#if AP_UAVCAN_SLCAN_ENABLED if (_slcan._can_port == (i+1) && hal.can_mgr[drv_num - 1] != nullptr ) { ChibiOS_CAN::CanDriver* drv = (ChibiOS_CAN::CanDriver*)hal.can_mgr[drv_num - 1]->get_driver(); ChibiOS_CAN::CanIface::slcan_router().init(drv->getIface(i), drv->getUpdateEvent()); } - #endif +#endif } else { printf("Failed to initialize can interface %d\n\r", i + 1); } @@ -177,7 +177,7 @@ void AP_BoardConfig_CAN::init() } else { continue; } -#if !HAL_MINIMIZE_FEATURES +#if AP_UAVCAN_SLCAN_ENABLED if (_slcan._can_port == 0) { _drivers[i]._driver->init(i, true); } else { @@ -187,7 +187,8 @@ void AP_BoardConfig_CAN::init() } } } -#if !HAL_MINIMIZE_FEATURES + +#if AP_UAVCAN_SLCAN_ENABLED AP_HAL::UARTDriver *AP_BoardConfig_CAN::get_slcan_serial() { if (_slcan._ser_port != -1) { diff --git a/libraries/AP_BoardConfig/AP_BoardConfig_CAN.h b/libraries/AP_BoardConfig/AP_BoardConfig_CAN.h index bff18cfbd5..2407a1ce99 100644 --- a/libraries/AP_BoardConfig/AP_BoardConfig_CAN.h +++ b/libraries/AP_BoardConfig/AP_BoardConfig_CAN.h @@ -87,7 +87,7 @@ public: } static const struct AP_Param::GroupInfo var_info[]; -#if !HAL_MINIMIZE_FEATURES +#if AP_UAVCAN_SLCAN_ENABLED AP_HAL::UARTDriver *get_slcan_serial(); uint8_t get_slcan_timeout() { return _slcan._timeout; } void reset_slcan_serial() { _slcan._ser_port.set_and_save_ifchanged(-1); } @@ -131,7 +131,7 @@ private: AP_HAL::CANProtocol* _tcan; }; -#if !HAL_MINIMIZE_FEATURES +#if AP_UAVCAN_SLCAN_ENABLED class SLCAN_Interface { friend class AP_BoardConfig_CAN; diff --git a/libraries/AP_BoardConfig/canbus_slcan.cpp b/libraries/AP_BoardConfig/canbus_slcan.cpp index f9609604e7..c8811d4ab5 100644 --- a/libraries/AP_BoardConfig/canbus_slcan.cpp +++ b/libraries/AP_BoardConfig/canbus_slcan.cpp @@ -15,7 +15,7 @@ #include -#if HAL_WITH_UAVCAN && !HAL_MINIMIZE_FEATURES +#if AP_UAVCAN_SLCAN_ENABLED #include "AP_BoardConfig_CAN.h" const AP_Param::GroupInfo AP_BoardConfig_CAN::SLCAN_Interface::var_info[] = {