mirror of https://github.com/ArduPilot/ardupilot
AP_Beacon: fix sitl position to be NED
This commit is contained in:
parent
276e56e618
commit
ce55af4d95
|
@ -100,8 +100,8 @@ void AP_Beacon_SITL::update(void)
|
|||
const Vector2f beac_diff = beacon_origin.get_distance_NE(beacon_loc);
|
||||
const Vector2f veh_diff = beacon_origin.get_distance_NE(current_loc);
|
||||
|
||||
Vector3f veh_pos3d(veh_diff.x, veh_diff.y, (current_loc.alt - beacon_origin.alt)*1.0e-2f);
|
||||
Vector3f beac_pos3d(beac_diff.x, beac_diff.y, (beacon_origin.alt - beacon_loc.alt)*1.0e-2f);
|
||||
Vector3f veh_pos3d(veh_diff.x, veh_diff.y, (beacon_origin.alt - current_loc.alt)*1.0e-2f);
|
||||
Vector3f beac_pos3d(beac_diff.x, beac_diff.y, (beacon_loc.alt - beacon_origin.alt)*1.0e-2f);
|
||||
Vector3f beac_veh_offset = veh_pos3d - beac_pos3d;
|
||||
|
||||
set_beacon_position(beacon_id, beac_pos3d);
|
||||
|
|
Loading…
Reference in New Issue