Browse Source

Mission handling: Use default acceptance radius in case its set to zero

sbg
Lorenz Meier 9 years ago
parent
commit
daee5eeefa
  1. 9
      src/modules/navigator/mission_block.cpp

9
src/modules/navigator/mission_block.cpp

@ -143,7 +143,14 @@ MissionBlock::is_mission_item_reached() @@ -143,7 +143,14 @@ MissionBlock::is_mission_item_reached()
}
} else {
/* for normal mission items used their acceptance radius */
if (dist >= 0.0f && dist <= _navigator->get_acceptance_radius(_mission_item.acceptance_radius)) {
float mission_acceptance_radius = _navigator->get_acceptance_radius(_mission_item.acceptance_radius);
/* if set to zero use the default instead */
if (mission_acceptance_radius < 0.001f) {
mission_acceptance_radius = _navigator->get_acceptance_radius();
}
if (dist >= 0.0f && dist <= mission_acceptance_radius) {
_waypoint_position_reached = true;
}
}

Loading…
Cancel
Save