5
0
mirror of https://github.com/ArduPilot/ardupilot synced 2025-01-06 16:08:28 -04:00

AP_Proximity: AirSimSITL: fix left right swap

This commit is contained in:
Iampete1 2020-04-22 18:18:04 +01:00 committed by Andrew Tridgell
parent 8407648316
commit 3618607746

View File

@ -41,7 +41,7 @@ void AP_Proximity_AirSimSITL::update(void)
if (point.is_zero()) {
continue;
}
const float angle_deg = wrap_360(degrees(atan2f(-point.y, point.x)));
const float angle_deg = wrap_360(degrees(atan2f(point.y, point.x)));
const uint8_t sector = convert_angle_to_sector(angle_deg);
const Vector2f v = Vector2f(point.x, point.y);