AP_Common: remove unused Location constructor from Vector3d

Replaced with AHRS method
This commit is contained in:
Peter Barker 2023-09-06 17:21:13 +10:00 committed by Andrew Tridgell
parent a9c62fa565
commit 72f485b5a5
1 changed files with 0 additions and 16 deletions

View File

@ -49,22 +49,6 @@ Location::Location(const Vector3f &ekf_offset_neu, AltFrame frame)
}
}
Location::Location(const Vector3d &ekf_offset_neu, AltFrame frame)
{
zero();
// store alt and alt frame
set_alt_cm(ekf_offset_neu.z, frame);
// calculate lat, lon
Location ekf_origin;
if (AP::ahrs().get_origin(ekf_origin)) {
lat = ekf_origin.lat;
lng = ekf_origin.lng;
offset(ekf_offset_neu.x * 0.01, ekf_offset_neu.y * 0.01);
}
}
void Location::set_alt_cm(int32_t alt_cm, AltFrame frame)
{
alt = alt_cm;