mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-23 09:08:30 -04:00
Copter: remove unused pv_location_to_vector_with_default
This commit is contained in:
parent
390d06a400
commit
cb9ca94dd1
@ -931,7 +931,6 @@ private:
|
||||
uint16_t perf_info_get_num_long_running();
|
||||
uint32_t perf_info_get_num_dropped();
|
||||
Vector3f pv_location_to_vector(const Location& loc);
|
||||
Vector3f pv_location_to_vector_with_default(const Location& loc, const Vector3f& default_posvec);
|
||||
float pv_alt_above_origin(float alt_above_home_cm);
|
||||
float pv_alt_above_home(float alt_above_origin_cm);
|
||||
float pv_get_bearing_cd(const Vector3f &origin, const Vector3f &destination);
|
||||
|
@ -17,26 +17,6 @@ Vector3f Copter::pv_location_to_vector(const Location& loc)
|
||||
return Vector3f((loc.lat-origin.lat) * LATLON_TO_CM, (loc.lng-origin.lng) * LATLON_TO_CM * scaleLongDown, alt_above_origin);
|
||||
}
|
||||
|
||||
// pv_location_to_vector_with_default - convert lat/lon coordinates to a position vector,
|
||||
// defaults to the default_posvec's lat/lon and alt if the provided lat/lon or alt are zero
|
||||
Vector3f Copter::pv_location_to_vector_with_default(const Location& loc, const Vector3f& default_posvec)
|
||||
{
|
||||
Vector3f pos = pv_location_to_vector(loc);
|
||||
|
||||
// set target altitude to default if not provided
|
||||
if (loc.alt == 0) {
|
||||
pos.z = default_posvec.z;
|
||||
}
|
||||
|
||||
// set target position to default if not provided
|
||||
if (loc.lat == 0 && loc.lng == 0) {
|
||||
pos.x = default_posvec.x;
|
||||
pos.y = default_posvec.y;
|
||||
}
|
||||
|
||||
return pos;
|
||||
}
|
||||
|
||||
// pv_alt_above_origin - convert altitude above home to altitude above EKF origin
|
||||
float Copter::pv_alt_above_origin(float alt_above_home_cm)
|
||||
{
|
||||
|
Loading…
Reference in New Issue
Block a user