mirror of https://github.com/ArduPilot/ardupilot
Tools: 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
d79e48d594
commit
8c9ef538f7
|
@ -818,7 +818,7 @@ void can_start()
|
|||
canStart(&CAND1, &cancfg);
|
||||
#else
|
||||
for (uint8_t i=0; i<HAL_NUM_CAN_IFACES; i++) {
|
||||
can_iface[i].init(baudrate, AP_HAL::CANIface::NormalMode);
|
||||
can_iface[i].init(baudrate);
|
||||
}
|
||||
#endif
|
||||
canardInit(&canard, (uint8_t *)canard_memory_pool, sizeof(canard_memory_pool),
|
||||
|
|
|
@ -1637,9 +1637,9 @@ void AP_Periph_FW::can_start()
|
|||
#endif
|
||||
if (can_iface_periph[i] != nullptr) {
|
||||
#if HAL_CANFD_SUPPORTED
|
||||
can_iface_periph[i]->init(g.can_baudrate[i], g.can_fdbaudrate[i]*1000000U, AP_HAL::CANIface::NormalMode);
|
||||
can_iface_periph[i]->init(g.can_baudrate[i], g.can_fdbaudrate[i]*1000000U);
|
||||
#else
|
||||
can_iface_periph[i]->init(g.can_baudrate[i], AP_HAL::CANIface::NormalMode);
|
||||
can_iface_periph[i]->init(g.can_baudrate[i]);
|
||||
#endif
|
||||
}
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue