From 5f1388f366fc9a5e5b555e05ff76c2aae26f32b1 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Sun, 25 Sep 2022 08:12:12 +1000 Subject: [PATCH] AP_Mission: zero frame field when filling mavlink_int from mavlink_cmd Callers should be filling their bits in after calling this. --- libraries/AP_Mission/AP_Mission.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/libraries/AP_Mission/AP_Mission.cpp b/libraries/AP_Mission/AP_Mission.cpp index 19dc4ad403..71427453e7 100644 --- a/libraries/AP_Mission/AP_Mission.cpp +++ b/libraries/AP_Mission/AP_Mission.cpp @@ -1391,6 +1391,7 @@ MAV_MISSION_RESULT AP_Mission::mavlink_cmd_long_to_mission_cmd(const mavlink_com // mission_cmd_to_mavlink_int - converts an AP_Mission::Mission_Command object to a mavlink message which can be sent to the GCS // return true on success, false on failure +// NOTE: callers to this method current fill parts of "packet" in before calling this method, so do NOT attempt to zero the entire packet in here bool AP_Mission::mission_cmd_to_mavlink_int(const AP_Mission::Mission_Command& cmd, mavlink_mission_item_int_t& packet) { // command's position in mission list and mavlink id @@ -1403,6 +1404,7 @@ bool AP_Mission::mission_cmd_to_mavlink_int(const AP_Mission::Mission_Command& c packet.param2 = 0; packet.param3 = 0; packet.param4 = 0; + packet.frame = 0; packet.autocontinue = 1; // command specific conversions from mission command to mavlink packet