Skip to content

Commit

Permalink
updated gcs with distance to nearest drone correctly, still 4 second …
Browse files Browse the repository at this point in the history
…delay and occasional glitch in distance calculation
  • Loading branch information
PeterJBurke committed Mar 26, 2024
1 parent 719cb2e commit a40845d
Showing 1 changed file with 3 additions and 2 deletions.
5 changes: 3 additions & 2 deletions libraries/AP_Avoidance/AP_Avoidance.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -676,9 +676,10 @@ void AP_Avoidance::handle_avoidance_local(AP_Avoidance::Obstacle *threat)
}

double instantaneous_xy = my_loc.get_distance(threat->_location);
double instantaneous_z = my_loc.get_alt_distance(threat->_location,instantaneous_xy);
//double instantaneous_z = my_loc.get_alt_distance(threat->_location,instantaneous_xy);
double instantaneous_z = 0.01*(threat->_location.alt-my_loc.alt);
GCS_SEND_TEXT(MAV_SEVERITY_INFO,"xy:%.0fm, z:%.0fm", instantaneous_xy, instantaneous_z);

GCS_SEND_TEXT(MAV_SEVERITY_INFO,"xy: %f,z: %f", instantaneous_xy, instantaneous_z);
//GCS_SEND_TEXT(MAV_SEVERITY_INFO,"xy: %f,z: %f", threat->closest_approach_xy, threat->closest_approach_z);

}
Expand Down

0 comments on commit a40845d

Please sign in to comment.