AP_Avoidance: reorder avoiding and sending GCS notification

handling the avoidance updates the state which indicates what the
vehicle is actually doing, which is what we send to the GCS
This commit is contained in:
Peter Barker 2019-11-06 12:51:48 +11:00 committed by Peter Barker
parent 7e81aa8f64
commit da3bef36fa

View File

@ -524,11 +524,11 @@ void AP_Avoidance::update()
check_for_threats(); check_for_threats();
// notify GCS of most serious thread
handle_threat_gcs_notify(most_serious_threat());
// avoid object (if necessary) // avoid object (if necessary)
handle_avoidance_local(most_serious_threat()); handle_avoidance_local(most_serious_threat());
// notify GCS of most serious thread
handle_threat_gcs_notify(most_serious_threat());
} }
void AP_Avoidance::handle_avoidance_local(AP_Avoidance::Obstacle *threat) void AP_Avoidance::handle_avoidance_local(AP_Avoidance::Obstacle *threat)