2015-05-29 23:12:49 -03:00
|
|
|
#include "Copter.h"
|
|
|
|
|
2016-07-25 15:45:29 -03:00
|
|
|
// Position vectors related utility functions
|
2013-02-25 04:50:56 -04:00
|
|
|
|
2014-05-27 04:30:32 -03:00
|
|
|
// position vectors are Vector3f
|
2013-02-25 04:50:56 -04:00
|
|
|
// .x = latitude from home in cm
|
|
|
|
// .y = longitude from home in cm
|
2013-03-20 10:29:08 -03:00
|
|
|
// .z = altitude above home in cm
|
2013-02-25 04:50:56 -04:00
|
|
|
|
|
|
|
|
2015-02-10 08:26:53 -04:00
|
|
|
// pv_alt_above_origin - convert altitude above home to altitude above EKF origin
|
2015-05-29 23:12:49 -03:00
|
|
|
float Copter::pv_alt_above_origin(float alt_above_home_cm)
|
2015-02-10 08:26:53 -04:00
|
|
|
{
|
|
|
|
const struct Location &origin = inertial_nav.get_origin();
|
|
|
|
return alt_above_home_cm + (ahrs.get_home().alt - origin.alt);
|
|
|
|
}
|
|
|
|
|
|
|
|
// pv_alt_above_home - convert altitude above EKF origin to altitude above home
|
2015-05-29 23:12:49 -03:00
|
|
|
float Copter::pv_alt_above_home(float alt_above_origin_cm)
|
2015-02-10 08:26:53 -04:00
|
|
|
{
|
|
|
|
const struct Location &origin = inertial_nav.get_origin();
|
|
|
|
return alt_above_origin_cm + (origin.alt - ahrs.get_home().alt);
|
|
|
|
}
|