mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 09:58:28 -04:00
AP_ToshibaCAN: send aborts on error
avoids flooding the bus when trying to send to ESCs that are not connected
This commit is contained in:
parent
d8959b3400
commit
73850f7a06
@ -243,7 +243,7 @@ bool AP_ToshibaCAN::write_frame(uavcan::CanFrame &out_frame, uavcan::MonotonicTi
|
|||||||
} while (!inout_mask.write);
|
} while (!inout_mask.write);
|
||||||
|
|
||||||
// send frame and return success
|
// send frame and return success
|
||||||
return (_can_driver->getIface(CAN_IFACE_INDEX)->send(out_frame, timeout, 0) == 1);
|
return (_can_driver->getIface(CAN_IFACE_INDEX)->send(out_frame, timeout, uavcan::CanIOFlagAbortOnError) == 1);
|
||||||
}
|
}
|
||||||
|
|
||||||
// called from SRV_Channels
|
// called from SRV_Channels
|
||||||
|
Loading…
Reference in New Issue
Block a user