mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-01 13:38:38 -04:00
Copter: use const references for Vector3f parameters
this is more efficient than passing a whole structure on the stack Pair-Programmed-With: Brandon Jones <brnjones@gmail.com>
This commit is contained in:
parent
c4f11e6c74
commit
086c7d70d8
@ -28,23 +28,23 @@ const int32_t pv_get_lat(const Vector3f pos_vec)
|
||||
}
|
||||
|
||||
// pv_get_lon - extract longitude from position vector
|
||||
const int32_t pv_get_lon(const Vector3f pos_vec)
|
||||
const int32_t pv_get_lon(const Vector3f &pos_vec)
|
||||
{
|
||||
return home.lng + (int32_t)(pos_vec.y / LATLON_TO_CM * scaleLongUp);
|
||||
}
|
||||
|
||||
// pv_get_horizontal_distance_cm - return distance between two positions in cm
|
||||
const float pv_get_horizontal_distance_cm(const Vector3f origin, const Vector3f destination)
|
||||
const float pv_get_horizontal_distance_cm(const Vector3f &origin, const Vector3f &destination)
|
||||
{
|
||||
return pythagorous2(destination.x-origin.x,destination.y-origin.y);
|
||||
}
|
||||
|
||||
// pv_get_bearing_cd - return bearing in centi-degrees between two positions
|
||||
const float pv_get_bearing_cd(const Vector3f origin, const Vector3f destination)
|
||||
const float pv_get_bearing_cd(const Vector3f &origin, const Vector3f &destination)
|
||||
{
|
||||
float bearing = 9000 + atan2f(-(destination.x-origin.x), destination.y-origin.y) * DEGX100;
|
||||
if (bearing < 0) {
|
||||
bearing += 36000;
|
||||
}
|
||||
return bearing;
|
||||
}
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user