mirror of https://github.com/ArduPilot/ardupilot
AP_Proximity: Follow NED convention
This commit is contained in:
parent
74bda4952d
commit
8cab737bdd
|
@ -116,7 +116,7 @@ void AP_Proximity_Backend::database_push(float angle, float pitch, float distanc
|
||||||
|
|
||||||
//Assume object is angle and pitch bearing and distance meters away from the vehicle
|
//Assume object is angle and pitch bearing and distance meters away from the vehicle
|
||||||
Vector3f object_3D;
|
Vector3f object_3D;
|
||||||
object_3D.offset_bearing(wrap_180(angle), wrap_180(pitch), distance);
|
object_3D.offset_bearing(wrap_180(angle), wrap_180(pitch * -1.0f), distance);
|
||||||
const Vector3f rotated_object_3D = body_to_ned * object_3D;
|
const Vector3f rotated_object_3D = body_to_ned * object_3D;
|
||||||
|
|
||||||
//Calculate the position vector from origin
|
//Calculate the position vector from origin
|
||||||
|
|
Loading…
Reference in New Issue