AP_CANManager: handle CAN_FORWARD as both command_INT and COMMAND_LONG

This commit is contained in:
Peter Barker 2023-09-19 16:46:08 +10:00 committed by Andrew Tridgell
parent 712237ec3a
commit 3c93fd3c5f
2 changed files with 2 additions and 2 deletions

View File

@ -385,7 +385,7 @@ void AP_CANManager::log_retrieve(ExpandingString &str) const
/*
handle MAV_CMD_CAN_FORWARD mavlink long command
*/
bool AP_CANManager::handle_can_forward(mavlink_channel_t chan, const mavlink_command_long_t &packet, const mavlink_message_t &msg)
bool AP_CANManager::handle_can_forward(mavlink_channel_t chan, const mavlink_command_int_t &packet, const mavlink_message_t &msg)
{
WITH_SEMAPHORE(can_forward.sem);
const int8_t bus = int8_t(packet.param1)-1;

View File

@ -101,7 +101,7 @@ public:
static const struct AP_Param::GroupInfo var_info[];
#if HAL_GCS_ENABLED
bool handle_can_forward(mavlink_channel_t chan, const mavlink_command_long_t &packet, const mavlink_message_t &msg);
bool handle_can_forward(mavlink_channel_t chan, const mavlink_command_int_t &packet, const mavlink_message_t &msg);
void handle_can_frame(const mavlink_message_t &msg);
void handle_can_filter_modify(const mavlink_message_t &msg);
#endif