GCS_MAVLink: tidy CAN message handling

This commit is contained in:
Peter Barker 2023-10-25 15:06:23 +11:00 committed by Peter Barker
parent 0f6718b23d
commit c1f0c9e70a
1 changed files with 3 additions and 3 deletions

View File

@ -3766,17 +3766,15 @@ MAV_RESULT GCS_MAVLINK::handle_can_forward(const mavlink_command_int_t &packet,
{
return AP::can().handle_can_forward(chan, packet, msg) ? MAV_RESULT_ACCEPTED : MAV_RESULT_FAILED;
}
#endif
/*
handle CAN_FRAME messages
*/
void GCS_MAVLINK::handle_can_frame(const mavlink_message_t &msg) const
{
#if HAL_CANMANAGER_ENABLED
AP::can().handle_can_frame(msg);
#endif
}
#endif // HAL_CANMANAGER_ENABLED
void GCS_MAVLINK::handle_distance_sensor(const mavlink_message_t &msg)
{
@ -4107,10 +4105,12 @@ void GCS_MAVLINK::handle_common_message(const mavlink_message_t &msg)
handle_named_value(msg);
break;
#if HAL_CANMANAGER_ENABLED
case MAVLINK_MSG_ID_CAN_FRAME:
case MAVLINK_MSG_ID_CANFD_FRAME:
handle_can_frame(msg);
break;
#endif
case MAVLINK_MSG_ID_CAN_FILTER_MODIFY:
#if HAL_CANMANAGER_ENABLED