diff --git a/libraries/AP_CANManager/AP_CANManager.cpp b/libraries/AP_CANManager/AP_CANManager.cpp index 41de1ffc22..596ba0ae3c 100644 --- a/libraries/AP_CANManager/AP_CANManager.cpp +++ b/libraries/AP_CANManager/AP_CANManager.cpp @@ -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; diff --git a/libraries/AP_CANManager/AP_CANManager.h b/libraries/AP_CANManager/AP_CANManager.h index 32911f5e66..85d4aa31ed 100644 --- a/libraries/AP_CANManager/AP_CANManager.h +++ b/libraries/AP_CANManager/AP_CANManager.h @@ -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