AP_HAL: moved CAN_FRAME timeout handling to AP_CANManager

This commit is contained in:
Andrew Tridgell 2022-02-14 09:04:54 +11:00
parent cce89099c5
commit d9f79f42c8
2 changed files with 0 additions and 13 deletions

View File

@ -71,16 +71,6 @@ int16_t AP_HAL::CANIface::send(const CANFrame& frame, uint64_t tx_deadline, CanI
{
if (frame_callback) {
if ((flags & IsMAVCAN) == 0) {
if (frame_counter++ == 100) {
// check every 100 frames for disabling CAN_FRAME send
// we stop sending after 5s if the client stops
// sending MAV_CMD_CAN_FORWARD requests
if (AP_HAL::millis() - last_callback_enable_ms > 5000) {
frame_callback = nullptr;
return 1;
}
frame_counter = 0;
}
frame_callback(get_iface_num(), frame);
} else {
CanRxItem rx_item;
@ -98,7 +88,6 @@ int16_t AP_HAL::CANIface::send(const CANFrame& frame, uint64_t tx_deadline, CanI
*/
bool AP_HAL::CANIface::register_frame_callback(FrameCb cb)
{
last_callback_enable_ms = AP_HAL::millis();
frame_callback = cb;
return true;
}

View File

@ -225,8 +225,6 @@ protected:
virtual bool add_to_rx_queue(const CanRxItem &rx_item) = 0;
FrameCb frame_callback;
uint8_t frame_counter;
uint32_t last_callback_enable_ms;
uint32_t bitrate_;
OperatingMode mode_;
};