Browse Source

AP_OAPathPlanner: minor fix to return original origin and dest upon failure

this has no functional effect because the consumers are not using the origin_new and destination_new unless the ret_state was OA_SUCCESS
master
Randy Mackay 6 years ago
parent
commit
bed21b43e1
  1. 4
      libraries/AC_Avoidance/AP_OAPathPlanner.cpp

4
libraries/AC_Avoidance/AP_OAPathPlanner.cpp

@ -271,8 +271,8 @@ void AP_OAPathPlanner::avoidance_thread() @@ -271,8 +271,8 @@ void AP_OAPathPlanner::avoidance_thread()
// give the main thread the avoidance result
WITH_SEMAPHORE(_rsem);
avoidance_result.destination = avoidance_request2.destination;
avoidance_result.origin_new = res ? origin_new : avoidance_result.origin_new;
avoidance_result.destination_new = res ? destination_new : avoidance_result.destination;
avoidance_result.origin_new = (res == OA_SUCCESS) ? origin_new : avoidance_result.origin_new;
avoidance_result.destination_new = (res == OA_SUCCESS) ? destination_new : avoidance_result.destination;
avoidance_result.result_time_ms = AP_HAL::millis();
avoidance_result.ret_state = res;
}

Loading…
Cancel
Save