mirror of https://github.com/ArduPilot/ardupilot
BoardConfig: disable SLCAN for minimized features
This commit is contained in:
parent
ef699367d5
commit
3255d793c0
|
@ -84,8 +84,9 @@ const AP_Param::GroupInfo AP_BoardConfig_CAN::var_info[] = {
|
||||||
AP_SUBGROUPINFO(_drivers[2], "D3_", 6, AP_BoardConfig_CAN, AP_BoardConfig_CAN::Driver),
|
AP_SUBGROUPINFO(_drivers[2], "D3_", 6, AP_BoardConfig_CAN, AP_BoardConfig_CAN::Driver),
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#if !HAL_MINIMIZE_FEATURES
|
||||||
AP_SUBGROUPINFO(_slcan, "SLCAN_", 7, AP_BoardConfig_CAN, AP_BoardConfig_CAN::SLCAN_Interface),
|
AP_SUBGROUPINFO(_slcan, "SLCAN_", 7, AP_BoardConfig_CAN, AP_BoardConfig_CAN::SLCAN_Interface),
|
||||||
|
#endif
|
||||||
AP_GROUPEND
|
AP_GROUPEND
|
||||||
};
|
};
|
||||||
|
|
||||||
|
@ -106,7 +107,9 @@ void AP_BoardConfig_CAN::init()
|
||||||
{
|
{
|
||||||
// Create all drivers that we need
|
// Create all drivers that we need
|
||||||
bool initret = true;
|
bool initret = true;
|
||||||
|
#if !HAL_MINIMIZE_FEATURES
|
||||||
reset_slcan_serial();
|
reset_slcan_serial();
|
||||||
|
#endif
|
||||||
for (uint8_t i = 0; i < MAX_NUMBER_OF_CAN_INTERFACES; i++) {
|
for (uint8_t i = 0; i < MAX_NUMBER_OF_CAN_INTERFACES; i++) {
|
||||||
// Check the driver number assigned to this physical interface
|
// Check the driver number assigned to this physical interface
|
||||||
uint8_t drv_num = _interfaces[i]._driver_number_cache = _interfaces[i]._driver_number;
|
uint8_t drv_num = _interfaces[i]._driver_number_cache = _interfaces[i]._driver_number;
|
||||||
|
@ -126,7 +129,7 @@ void AP_BoardConfig_CAN::init()
|
||||||
// For this now existing driver (manager), start the physical interface
|
// For this now existing driver (manager), start the physical interface
|
||||||
if (hal.can_mgr[drv_num - 1] != nullptr) {
|
if (hal.can_mgr[drv_num - 1] != nullptr) {
|
||||||
initret = initret && hal.can_mgr[drv_num - 1]->begin(_interfaces[i]._bitrate, i);
|
initret = initret && hal.can_mgr[drv_num - 1]->begin(_interfaces[i]._bitrate, i);
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
|
#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS && !HAL_MINIMIZE_FEATURES
|
||||||
if (_slcan._can_port == (i+1) && hal.can_mgr[drv_num - 1] != nullptr ) {
|
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::CanDriver* drv = (ChibiOS_CAN::CanDriver*)hal.can_mgr[drv_num - 1]->get_driver();
|
||||||
slcan_router().init(drv->getIface(i), drv->getUpdateEvent());
|
slcan_router().init(drv->getIface(i), drv->getUpdateEvent());
|
||||||
|
@ -181,11 +184,13 @@ void AP_BoardConfig_CAN::init()
|
||||||
} else {
|
} else {
|
||||||
continue;
|
continue;
|
||||||
}
|
}
|
||||||
|
#if !HAL_MINIMIZE_FEATURES
|
||||||
if (_slcan._can_port == 0) {
|
if (_slcan._can_port == 0) {
|
||||||
_drivers[i]._driver->init(i, true);
|
_drivers[i]._driver->init(i, true);
|
||||||
} else {
|
} else {
|
||||||
_drivers[i]._driver->init(i, false);
|
_drivers[i]._driver->init(i, false);
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
|
@ -87,10 +87,11 @@ public:
|
||||||
}
|
}
|
||||||
|
|
||||||
static const struct AP_Param::GroupInfo var_info[];
|
static const struct AP_Param::GroupInfo var_info[];
|
||||||
|
#if !HAL_MINIMIZE_FEATURES
|
||||||
int8_t get_slcan_serial() { return _slcan._ser_port; }
|
int8_t get_slcan_serial() { return _slcan._ser_port; }
|
||||||
uint8_t get_slcan_timeout() { return _slcan._timeout; }
|
uint8_t get_slcan_timeout() { return _slcan._timeout; }
|
||||||
void reset_slcan_serial() { _slcan._ser_port.set_and_save_ifchanged(-1); }
|
void reset_slcan_serial() { _slcan._ser_port.set_and_save_ifchanged(-1); }
|
||||||
|
#endif
|
||||||
private:
|
private:
|
||||||
class Interface {
|
class Interface {
|
||||||
friend class AP_BoardConfig_CAN;
|
friend class AP_BoardConfig_CAN;
|
||||||
|
@ -130,6 +131,7 @@ private:
|
||||||
AP_HAL::CANProtocol* _tcan;
|
AP_HAL::CANProtocol* _tcan;
|
||||||
};
|
};
|
||||||
|
|
||||||
|
#if !HAL_MINIMIZE_FEATURES
|
||||||
class SLCAN_Interface {
|
class SLCAN_Interface {
|
||||||
friend class AP_BoardConfig_CAN;
|
friend class AP_BoardConfig_CAN;
|
||||||
|
|
||||||
|
@ -145,10 +147,10 @@ private:
|
||||||
AP_Int8 _ser_port;
|
AP_Int8 _ser_port;
|
||||||
AP_Int16 _timeout;
|
AP_Int16 _timeout;
|
||||||
};
|
};
|
||||||
|
SLCAN_Interface _slcan;
|
||||||
|
#endif
|
||||||
Interface _interfaces[MAX_NUMBER_OF_CAN_INTERFACES];
|
Interface _interfaces[MAX_NUMBER_OF_CAN_INTERFACES];
|
||||||
Driver _drivers[MAX_NUMBER_OF_CAN_DRIVERS];
|
Driver _drivers[MAX_NUMBER_OF_CAN_DRIVERS];
|
||||||
SLCAN_Interface _slcan;
|
|
||||||
uint8_t _num_drivers;
|
uint8_t _num_drivers;
|
||||||
static AP_BoardConfig_CAN *_singleton;
|
static AP_BoardConfig_CAN *_singleton;
|
||||||
};
|
};
|
||||||
|
|
|
@ -15,7 +15,7 @@
|
||||||
|
|
||||||
#include <AP_HAL/AP_HAL.h>
|
#include <AP_HAL/AP_HAL.h>
|
||||||
|
|
||||||
#if HAL_WITH_UAVCAN
|
#if HAL_WITH_UAVCAN && !HAL_MINIMIZE_FEATURES
|
||||||
#include "AP_BoardConfig_CAN.h"
|
#include "AP_BoardConfig_CAN.h"
|
||||||
|
|
||||||
const AP_Param::GroupInfo AP_BoardConfig_CAN::SLCAN_Interface::var_info[] = {
|
const AP_Param::GroupInfo AP_BoardConfig_CAN::SLCAN_Interface::var_info[] = {
|
||||||
|
|
Loading…
Reference in New Issue