Browse Source

AP_Proximity: AirSimSITL: fix left right swap

zr-v5.1
Iampete1 5 years ago committed by Andrew Tridgell
parent
commit
3618607746
  1. 2
      libraries/AP_Proximity/AP_Proximity_AirSimSITL.cpp

2
libraries/AP_Proximity/AP_Proximity_AirSimSITL.cpp

@ -41,7 +41,7 @@ void AP_Proximity_AirSimSITL::update(void) @@ -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);

Loading…
Cancel
Save