AP_Mission: Change the magic number to a defined value

This commit is contained in:
muramura 2024-05-02 04:51:52 +09:00 committed by Peter Barker
parent 68bb55841a
commit a9a2696368
1 changed files with 2 additions and 2 deletions

View File

@ -2553,7 +2553,7 @@ bool AP_Mission::distance_to_landing(uint16_t index, float &tot_distance, Locati
}
// run through remainder of mission to approximate a distance to landing
for (uint8_t i=0; i<255; i++) {
for (uint8_t i=0; i<UINT8_MAX; i++) {
// search until the end of the mission command list
for (uint16_t cmd_index = index; cmd_index < (unsigned)_cmd_total; cmd_index++) {
// get next command
@ -2612,7 +2612,7 @@ bool AP_Mission::distance_to_mission_leg(uint16_t start_index, float &rejoin_dis
// run through remainder of mission to approximate a distance to landing
uint16_t index = start_index;
for (uint8_t i=0; i<255; i++) {
for (uint8_t i=0; i<UINT8_MAX; i++) {
// search until the end of the mission command list
for (uint16_t cmd_index = index; cmd_index <= (unsigned)_cmd_total; cmd_index++) {
if (get_next_cmd(cmd_index, temp_cmd, true, false)) {