diff --git a/Rover/GCS_Mavlink.cpp b/Rover/GCS_Mavlink.cpp index 2a1d6f6a90..3a7d31ae12 100644 --- a/Rover/GCS_Mavlink.cpp +++ b/Rover/GCS_Mavlink.cpp @@ -637,7 +637,7 @@ bool GCS_MAVLINK_Rover::set_home(const Location& loc, bool _lock) { return rover.set_home(loc, _lock); } -MAV_RESULT GCS_MAVLINK_Rover::handle_command_int_packet(const mavlink_command_int_t &packet) +MAV_RESULT GCS_MAVLINK_Rover::handle_command_int_packet(const mavlink_command_int_t &packet, const mavlink_message_t &msg) { switch (packet.command) { @@ -658,11 +658,11 @@ MAV_RESULT GCS_MAVLINK_Rover::handle_command_int_packet(const mavlink_command_in return MAV_RESULT_ACCEPTED; default: - return GCS_MAVLINK::handle_command_int_packet(packet); + return GCS_MAVLINK::handle_command_int_packet(packet, msg); } } -MAV_RESULT GCS_MAVLINK_Rover::handle_command_long_packet(const mavlink_command_long_t &packet) +MAV_RESULT GCS_MAVLINK_Rover::handle_command_long_packet(const mavlink_command_long_t &packet, const mavlink_message_t &msg) { switch (packet.command) { @@ -725,7 +725,7 @@ MAV_RESULT GCS_MAVLINK_Rover::handle_command_long_packet(const mavlink_command_l packet.param4); default: - return GCS_MAVLINK::handle_command_long_packet(packet); + return GCS_MAVLINK::handle_command_long_packet(packet, msg); } } diff --git a/Rover/GCS_Mavlink.h b/Rover/GCS_Mavlink.h index 028c92f497..3e7ccacc31 100644 --- a/Rover/GCS_Mavlink.h +++ b/Rover/GCS_Mavlink.h @@ -16,8 +16,8 @@ protected: bool sysid_enforce() const override; MAV_RESULT _handle_command_preflight_calibration(const mavlink_command_long_t &packet, const mavlink_message_t &msg) override; - MAV_RESULT handle_command_int_packet(const mavlink_command_int_t &packet) override; - MAV_RESULT handle_command_long_packet(const mavlink_command_long_t &packet) override; + MAV_RESULT handle_command_int_packet(const mavlink_command_int_t &packet, const mavlink_message_t &msg) override; + MAV_RESULT handle_command_long_packet(const mavlink_command_long_t &packet, const mavlink_message_t &msg) override; MAV_RESULT handle_command_int_do_reposition(const mavlink_command_int_t &packet); void send_position_target_global_int() override;