AP_CANManager: add and use option to compile SLCAN support out of code

This commit is contained in:
Peter Barker 2023-03-11 11:46:34 +11:00 committed by Peter Barker
parent 5121cb4a70
commit c1c8158687
5 changed files with 27 additions and 5 deletions

View File

@ -87,9 +87,11 @@ const AP_Param::GroupInfo AP_CANManager::var_info[] = {
AP_SUBGROUPINFO(_drv_param[2], "D3_", 6, AP_CANManager, AP_CANManager::CANDriver_Params),
#endif
#if AP_CAN_SLCAN_ENABLED
// @Group: SLCAN_
// @Path: ../AP_CANManager/AP_SLCANIface.cpp
AP_SUBGROUPINFO(_slcan_interface, "SLCAN_", 7, AP_CANManager, SLCAN::CANIface),
#endif
// @Param: LOGLEVEL
// @DisplayName: Loglevel
@ -134,8 +136,10 @@ void AP_CANManager::init()
_log_pos = 0;
}
#if AP_CAN_SLCAN_ENABLED
//Reset all SLCAN related params that needs resetting at boot
_slcan_interface.reset_params();
#endif
Driver_Type drv_type[HAL_MAX_CAN_PROTOCOL_DRIVERS] = {};
// loop through interfaces and allocate and initialise Iface,
@ -165,11 +169,15 @@ void AP_CANManager::init()
bool can_initialised = false;
// Check if this interface need hooking up to slcan passthrough
// instead of a driver
#if AP_CAN_SLCAN_ENABLED
if (_slcan_interface.init_passthrough(i)) {
// we have slcan bridge setup pass that on as can iface
can_initialised = hal.can[i]->init(_interfaces[i]._bitrate, _interfaces[i]._fdbitrate*1000000, AP_HAL::CANIface::NormalMode);
iface = &_slcan_interface;
} else {
#else
if (true) {
#endif
can_initialised = hal.can[i]->init(_interfaces[i]._bitrate, _interfaces[i]._fdbitrate*1000000, AP_HAL::CANIface::NormalMode);
}

View File

@ -17,6 +17,8 @@
#pragma once
#include "AP_CANManager_config.h"
#include <AP_HAL/AP_HAL.h>
#if HAL_MAX_CAN_PROTOCOL_DRIVERS
@ -166,7 +168,10 @@ private:
AP_Int8 _loglevel;
uint8_t _num_drivers;
#if AP_CAN_SLCAN_ENABLED
SLCAN::CANIface _slcan_interface;
#endif
static AP_CANManager *_singleton;
char* _log_buf;

View File

@ -0,0 +1,7 @@
#pragma once
#include <AP_HAL/AP_HAL_Boards.h>
#ifndef AP_CAN_SLCAN_ENABLED
#define AP_CAN_SLCAN_ENABLED HAL_MAX_CAN_PROTOCOL_DRIVERS
#endif

View File

@ -19,7 +19,7 @@
#include "AP_SLCANIface.h"
#if HAL_MAX_CAN_PROTOCOL_DRIVERS
#if AP_CAN_SLCAN_ENABLED
#include <AP_HAL/AP_HAL.h>
#include <AP_Common/AP_Common.h>
@ -770,4 +770,4 @@ void SLCAN::CANIface::reset_params()
{
_slcan_ser_port.set_and_save(-1);
}
#endif
#endif // AP_CAN_SLCAN_ENABLED

View File

@ -17,9 +17,11 @@
#pragma once
#include <AP_HAL/AP_HAL.h>
#include "AP_CANManager_config.h"
#if HAL_MAX_CAN_PROTOCOL_DRIVERS
#if AP_CAN_SLCAN_ENABLED
#include <AP_HAL/AP_HAL.h>
#include "AP_HAL/utility/RingBuffer.h"
#include <AP_Param/AP_Param.h>
@ -139,4 +141,4 @@ protected:
}
#endif
#endif // AP_CAN_SLCAN_ENABLED