Skip to content

Commit

Permalink
AP_Mission: Change the magic number to a defined value
Browse files Browse the repository at this point in the history
  • Loading branch information
muramura authored and peterbarker committed Sep 11, 2024
1 parent 6495936 commit 2568887
Showing 1 changed file with 2 additions and 2 deletions.
4 changes: 2 additions & 2 deletions libraries/AP_Mission/AP_Mission.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down Expand Up @@ -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)) {
Expand Down

0 comments on commit 2568887

Please sign in to comment.