AP_Mission: ensure location options are zero at start of mavlink conversion

This commit is contained in:
Andrew Tridgell 2014-12-03 18:29:43 +11:00
parent f98e283091
commit ede920f293
1 changed files with 1 additions and 0 deletions

View File

@ -460,6 +460,7 @@ bool AP_Mission::mavlink_to_mission_cmd(const mavlink_mission_item_t& packet, AP
// command's position in mission list and mavlink id
cmd.index = packet.seq;
cmd.id = packet.command;
cmd.content.location.options = 0;
// command specific conversions from mavlink packet to mission command
switch (cmd.id) {