AP_CANManager: use updated frame callback types

also change to IsForwardedFrame from IsMAVCAN
This commit is contained in:
bugobliterator 2025-01-30 11:58:40 +11:00 committed by Randy Mackay
parent ed1dd41b46
commit fcff2e6f57
2 changed files with 7 additions and 7 deletions

View File

@ -466,7 +466,7 @@ bool AP_CANManager::handle_can_forward(mavlink_channel_t chan, const mavlink_com
if (can_forward.callback_id == 0 && if (can_forward.callback_id == 0 &&
!hal.can[bus]->register_frame_callback( !hal.can[bus]->register_frame_callback(
FUNCTOR_BIND_MEMBER(&AP_CANManager::can_frame_callback, void, uint8_t, const AP_HAL::CANFrame &), can_forward.callback_id)) { FUNCTOR_BIND_MEMBER(&AP_CANManager::can_frame_callback, void, uint8_t, const AP_HAL::CANFrame &, AP_HAL::CANIface::CanIOFlags), can_forward.callback_id)) {
// failed to register the callback // failed to register the callback
return false; return false;
} }
@ -558,7 +558,7 @@ void AP_CANManager::process_frame_buffer(void)
} }
const int16_t retcode = hal.can[frame.bus]->send(frame.frame, const int16_t retcode = hal.can[frame.bus]->send(frame.frame,
AP_HAL::micros64() + timeout_us, AP_HAL::micros64() + timeout_us,
AP_HAL::CANIface::IsMAVCAN); AP_HAL::CANIface::IsForwardedFrame);
if (retcode == 0) { if (retcode == 0) {
// no space in the CAN output slots, try again later // no space in the CAN output slots, try again later
break; break;
@ -662,7 +662,7 @@ void AP_CANManager::handle_can_filter_modify(const mavlink_message_t &msg)
handler for CAN frames from the registered callback, sending frames handler for CAN frames from the registered callback, sending frames
out as CAN_FRAME or CANFD_FRAME messages out as CAN_FRAME or CANFD_FRAME messages
*/ */
void AP_CANManager::can_frame_callback(uint8_t bus, const AP_HAL::CANFrame &frame) void AP_CANManager::can_frame_callback(uint8_t bus, const AP_HAL::CANFrame &frame, AP_HAL::CANIface::CanIOFlags flags)
{ {
WITH_SEMAPHORE(can_forward.sem); WITH_SEMAPHORE(can_forward.sem);
if (bus != can_forward.callback_bus) { if (bus != can_forward.callback_bus) {
@ -721,7 +721,7 @@ void AP_CANManager::can_frame_callback(uint8_t bus, const AP_HAL::CANFrame &fram
/* /*
handler for CAN frames for frame logging handler for CAN frames for frame logging
*/ */
void AP_CANManager::can_logging_callback(uint8_t bus, const AP_HAL::CANFrame &frame) void AP_CANManager::can_logging_callback(uint8_t bus, const AP_HAL::CANFrame &frame, AP_HAL::CANIface::CanIOFlags flags)
{ {
#if HAL_CANFD_SUPPORTED #if HAL_CANFD_SUPPORTED
if (frame.canfd) { if (frame.canfd) {
@ -762,7 +762,7 @@ void AP_CANManager::check_logging_enable(void)
} }
if (enabled && logging_id == 0) { if (enabled && logging_id == 0) {
can->register_frame_callback( can->register_frame_callback(
FUNCTOR_BIND_MEMBER(&AP_CANManager::can_logging_callback, void, uint8_t, const AP_HAL::CANFrame &), FUNCTOR_BIND_MEMBER(&AP_CANManager::can_logging_callback, void, uint8_t, const AP_HAL::CANFrame &, AP_HAL::CANIface::CanIOFlags),
logging_id); logging_id);
} else if (!enabled && logging_id != 0) { } else if (!enabled && logging_id != 0) {
can->unregister_frame_callback(logging_id); can->unregister_frame_callback(logging_id);

View File

@ -187,7 +187,7 @@ private:
handler for CAN frames from the registered callback, sending frames handler for CAN frames from the registered callback, sending frames
out as CAN_FRAME messages out as CAN_FRAME messages
*/ */
void can_frame_callback(uint8_t bus, const AP_HAL::CANFrame &frame); void can_frame_callback(uint8_t bus, const AP_HAL::CANFrame &frame, AP_HAL::CANIface::CanIOFlags flags);
struct { struct {
mavlink_channel_t chan; mavlink_channel_t chan;
@ -216,7 +216,7 @@ private:
/* /*
handler for CAN frames for logging handler for CAN frames for logging
*/ */
void can_logging_callback(uint8_t bus, const AP_HAL::CANFrame &frame); void can_logging_callback(uint8_t bus, const AP_HAL::CANFrame &frame, AP_HAL::CANIface::CanIOFlags flags);
void check_logging_enable(void); void check_logging_enable(void);
#endif #endif
}; };