AP_Mission: do not adjust ret_packet on get_item failure

do not modify the return packet value at all upon failure, rather than indicating invalidity with a flag value.  We return boolean for a reason.
This commit is contained in:
Peter Barker 2024-09-04 14:41:47 +10:00 committed by Peter Barker
parent 18e95c7979
commit 94062fce5c

View File

@ -701,46 +701,42 @@ bool AP_Mission::set_item(uint16_t index, mavlink_mission_item_int_t& src_packet
bool AP_Mission::get_item(uint16_t index, mavlink_mission_item_int_t& ret_packet) const bool AP_Mission::get_item(uint16_t index, mavlink_mission_item_int_t& ret_packet) const
{ {
// setting ret_packet.command = -1 and/or returning false mavlink_mission_item_int_t tmp;
// means it contains invalid data after it leaves here.
// this is the on-storage format
AP_Mission::Mission_Command cmd {};
// can't handle request for anything bigger than the mission size... // can't handle request for anything bigger than the mission size...
if (index >= num_commands()) { if (index >= num_commands()) {
ret_packet.command = -1;
return false; return false;
} }
// minimal placeholder values during read-from-storage // minimal placeholder values during read-from-storage
ret_packet.target_system = 1; // unused sysid tmp.target_system = 1; // unused sysid
ret_packet.target_component = 1; // unused compid tmp.target_component = 1; // unused compid
// 0=home, higher number/s = mission item number. // 0=home, higher number/s = mission item number.
ret_packet.seq = index; tmp.seq = index;
// retrieve mission from eeprom // retrieve mission from eeprom
if (!read_cmd_from_storage(ret_packet.seq, cmd)) { AP_Mission::Mission_Command cmd {};
ret_packet.command = -1; if (!read_cmd_from_storage(tmp.seq, cmd)) {
return false; return false;
} }
// convert into mavlink-ish format for lua and friends. // convert into mavlink-ish format for lua and friends.
if (!mission_cmd_to_mavlink_int(cmd, ret_packet)) { if (!mission_cmd_to_mavlink_int(cmd, tmp)) {
ret_packet.command = -1;
return false; return false;
} }
// set packet's current field to 1 if this is the command being executed // set packet's current field to 1 if this is the command being executed
if (cmd.id == (uint16_t)get_current_nav_cmd().index) { if (cmd.id == (uint16_t)get_current_nav_cmd().index) {
ret_packet.current = 1; tmp.current = 1;
} else { } else {
ret_packet.current = 0; tmp.current = 0;
} }
// set auto continue to 1, becasue that's what's done elsewhere. // set auto continue to 1, becasue that's what's done elsewhere.
ret_packet.autocontinue = 1; // 1 (true), 0 (false) tmp.autocontinue = 1; // 1 (true), 0 (false)
ret_packet.command = cmd.id; tmp.command = cmd.id;
ret_packet = tmp;
return true; return true;
} }