mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
BoardConfig_CAN: return serial port with switch between parameter and passthrough
This commit is contained in:
parent
eabb93f842
commit
fe44384c95
@ -35,7 +35,7 @@
|
|||||||
#include <AP_UAVCAN/AP_UAVCAN.h>
|
#include <AP_UAVCAN/AP_UAVCAN.h>
|
||||||
#include <AP_KDECAN/AP_KDECAN.h>
|
#include <AP_KDECAN/AP_KDECAN.h>
|
||||||
#include <AP_ToshibaCAN/AP_ToshibaCAN.h>
|
#include <AP_ToshibaCAN/AP_ToshibaCAN.h>
|
||||||
|
#include <AP_SerialManager/AP_SerialManager.h>
|
||||||
extern const AP_HAL::HAL& hal;
|
extern const AP_HAL::HAL& hal;
|
||||||
|
|
||||||
// table of user settable parameters
|
// table of user settable parameters
|
||||||
@ -102,7 +102,7 @@ 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
|
#if !HAL_MINIMIZE_FEATURES
|
||||||
reset_slcan_serial();
|
reset_slcan_serial();
|
||||||
#endif
|
#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++) {
|
||||||
@ -187,7 +187,18 @@ void AP_BoardConfig_CAN::init()
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
#if !HAL_MINIMIZE_FEATURES
|
||||||
|
AP_HAL::UARTDriver *AP_BoardConfig_CAN::get_slcan_serial()
|
||||||
|
{
|
||||||
|
if (_slcan._ser_port != -1) {
|
||||||
|
return AP::serialmanager().get_serial_by_id(_slcan._ser_port);
|
||||||
|
}
|
||||||
|
if (AP::serialmanager().find_serial(AP_SerialManager::SerialProtocol_SLCAN, 0)->is_initialized()) {
|
||||||
|
return AP::serialmanager().find_serial(AP_SerialManager::SerialProtocol_SLCAN, 0);
|
||||||
|
}
|
||||||
|
return nullptr;
|
||||||
|
}
|
||||||
|
#endif
|
||||||
AP_BoardConfig_CAN& AP::can() {
|
AP_BoardConfig_CAN& AP::can() {
|
||||||
return *AP_BoardConfig_CAN::get_singleton();
|
return *AP_BoardConfig_CAN::get_singleton();
|
||||||
}
|
}
|
||||||
|
@ -88,7 +88,7 @@ public:
|
|||||||
|
|
||||||
static const struct AP_Param::GroupInfo var_info[];
|
static const struct AP_Param::GroupInfo var_info[];
|
||||||
#if !HAL_MINIMIZE_FEATURES
|
#if !HAL_MINIMIZE_FEATURES
|
||||||
int8_t get_slcan_serial() { return _slcan._ser_port; }
|
AP_HAL::UARTDriver *get_slcan_serial();
|
||||||
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
|
#endif
|
||||||
|
Loading…
Reference in New Issue
Block a user