mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-26 18:48:30 -04:00
AP_BoardConfig: cleanup ifdefs for SLCAN enable
This commit is contained in:
parent
4a42a3a23a
commit
6b3c10f0e7
@ -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) {
|
||||
|
@ -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;
|
||||
|
||||
|
@ -15,7 +15,7 @@
|
||||
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
|
||||
#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[] = {
|
||||
|
Loading…
Reference in New Issue
Block a user