mirror of https://github.com/ArduPilot/ardupilot
AP_Mission: correct off-by-one check when fetching mission items
This commit is contained in:
parent
53d1585ebf
commit
591bb32496
|
@ -429,7 +429,7 @@ bool AP_Mission::set_current_cmd(uint16_t index)
|
|||
bool AP_Mission::read_cmd_from_storage(uint16_t index, Mission_Command& cmd) const
|
||||
{
|
||||
// exit immediately if index is beyond last command but we always let cmd #0 (i.e. home) be read
|
||||
if (index > (unsigned)_cmd_total && index != 0) {
|
||||
if (index >= (unsigned)_cmd_total && index != 0) {
|
||||
return false;
|
||||
}
|
||||
|
||||
|
|
|
@ -294,6 +294,7 @@ public:
|
|||
mission_state state() const { return _flags.state; }
|
||||
|
||||
/// num_commands - returns total number of commands in the mission
|
||||
/// this number includes offset 0, the home location
|
||||
uint16_t num_commands() const { return _cmd_total; }
|
||||
|
||||
/// num_commands_max - returns maximum number of commands that can be stored
|
||||
|
|
Loading…
Reference in New Issue