AP_Mission: zero frame field when filling mavlink_int from mavlink_cmd

Callers should be filling their bits in after calling this.
This commit is contained in:
Peter Barker 2022-09-25 08:12:12 +10:00 committed by Andrew Tridgell
parent 636557d391
commit 3a690ccfc4

View File

@ -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