mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
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
This commit is contained in:
parent
709c874d8b
commit
bed21b43e1
@ -271,8 +271,8 @@ void AP_OAPathPlanner::avoidance_thread()
|
|||||||
// give the main thread the avoidance result
|
// give the main thread the avoidance result
|
||||||
WITH_SEMAPHORE(_rsem);
|
WITH_SEMAPHORE(_rsem);
|
||||||
avoidance_result.destination = avoidance_request2.destination;
|
avoidance_result.destination = avoidance_request2.destination;
|
||||||
avoidance_result.origin_new = res ? origin_new : avoidance_result.origin_new;
|
avoidance_result.origin_new = (res == OA_SUCCESS) ? origin_new : avoidance_result.origin_new;
|
||||||
avoidance_result.destination_new = res ? destination_new : avoidance_result.destination;
|
avoidance_result.destination_new = (res == OA_SUCCESS) ? destination_new : avoidance_result.destination;
|
||||||
avoidance_result.result_time_ms = AP_HAL::millis();
|
avoidance_result.result_time_ms = AP_HAL::millis();
|
||||||
avoidance_result.ret_state = res;
|
avoidance_result.ret_state = res;
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user