mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_HAL_SITL: drop CAN interface alternate mode support
Only "NormalMode" was ever used; the others had rotted or were never implemented.
This commit is contained in:
parent
faf08bd701
commit
d79e48d594
@ -200,12 +200,12 @@ void CANIface::_confirmSentFrame()
|
||||
}
|
||||
}
|
||||
|
||||
bool CANIface::init(const uint32_t bitrate, const uint32_t fdbitrate, const OperatingMode mode)
|
||||
bool CANIface::init(const uint32_t bitrate, const uint32_t fdbitrate)
|
||||
{
|
||||
return init(bitrate, mode);
|
||||
return init(bitrate);
|
||||
}
|
||||
|
||||
bool CANIface::init(const uint32_t bitrate, const OperatingMode mode)
|
||||
bool CANIface::init(const uint32_t bitrate)
|
||||
{
|
||||
const auto *_sitl = AP::sitl();
|
||||
if (_sitl == nullptr) {
|
||||
|
@ -44,8 +44,8 @@ public:
|
||||
~CANIface() { }
|
||||
|
||||
// Initialise CAN Peripheral
|
||||
bool init(const uint32_t bitrate, const uint32_t fdbitrate, const OperatingMode mode) override;
|
||||
bool init(const uint32_t bitrate, const OperatingMode mode) override;
|
||||
bool init(const uint32_t bitrate, const uint32_t fdbitrate) override;
|
||||
bool init(const uint32_t bitrate) override;
|
||||
|
||||
// number of enabled interfaces
|
||||
static uint8_t num_interfaces(void) {
|
||||
|
Loading…
Reference in New Issue
Block a user