2015-08-10 02:25:15 -03:00
|
|
|
/*
|
|
|
|
* Location.cpp
|
|
|
|
*/
|
|
|
|
|
|
|
|
#include "Location.h"
|
|
|
|
|
|
|
|
#include <AP_AHRS/AP_AHRS.h>
|
|
|
|
#include <AP_Terrain/AP_Terrain.h>
|
|
|
|
|
2019-01-01 22:53:47 -04:00
|
|
|
AP_Terrain *Location::_terrain = nullptr;
|
2015-08-10 02:25:15 -03:00
|
|
|
|
|
|
|
/// constructors
|
2019-01-01 22:53:47 -04:00
|
|
|
Location::Location()
|
2015-08-10 02:25:15 -03:00
|
|
|
{
|
2016-07-10 19:41:20 -03:00
|
|
|
zero();
|
2015-08-10 02:25:15 -03:00
|
|
|
}
|
|
|
|
|
2019-01-01 22:53:47 -04:00
|
|
|
const Location definitely_zero{};
|
|
|
|
bool Location::is_zero(void) const
|
2019-01-01 19:57:48 -04:00
|
|
|
{
|
|
|
|
return !memcmp(this, &definitely_zero, sizeof(*this));
|
|
|
|
}
|
|
|
|
|
2019-01-01 22:53:47 -04:00
|
|
|
void Location::zero(void)
|
2019-01-01 19:57:48 -04:00
|
|
|
{
|
|
|
|
memset(this, 0, sizeof(*this));
|
|
|
|
}
|
|
|
|
|
2021-03-17 18:15:20 -03:00
|
|
|
// Construct location using position (NEU) from ekf_origin for the given altitude frame
|
2019-03-14 22:43:43 -03:00
|
|
|
Location::Location(int32_t latitude, int32_t longitude, int32_t alt_in_cm, AltFrame frame)
|
2015-08-10 02:25:15 -03:00
|
|
|
{
|
2019-01-01 19:57:48 -04:00
|
|
|
zero();
|
2015-08-10 02:25:15 -03:00
|
|
|
lat = latitude;
|
|
|
|
lng = longitude;
|
2016-04-28 07:52:13 -03:00
|
|
|
set_alt_cm(alt_in_cm, frame);
|
2015-08-10 02:25:15 -03:00
|
|
|
}
|
|
|
|
|
2021-03-17 18:15:20 -03:00
|
|
|
Location::Location(const Vector3f &ekf_offset_neu, AltFrame frame)
|
2015-08-10 02:25:15 -03:00
|
|
|
{
|
2021-06-09 05:25:59 -03:00
|
|
|
zero();
|
|
|
|
|
2015-08-10 02:25:15 -03:00
|
|
|
// store alt and alt frame
|
2021-03-17 18:15:20 -03:00
|
|
|
set_alt_cm(ekf_offset_neu.z, frame);
|
2015-08-10 02:25:15 -03:00
|
|
|
|
|
|
|
// calculate lat, lon
|
2018-05-29 22:28:53 -03:00
|
|
|
Location ekf_origin;
|
|
|
|
if (AP::ahrs().get_origin(ekf_origin)) {
|
|
|
|
lat = ekf_origin.lat;
|
|
|
|
lng = ekf_origin.lng;
|
|
|
|
offset(ekf_offset_neu.x / 100.0f, ekf_offset_neu.y / 100.0f);
|
2015-08-10 02:25:15 -03:00
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2019-03-14 22:43:43 -03:00
|
|
|
void Location::set_alt_cm(int32_t alt_cm, AltFrame frame)
|
2015-08-10 02:25:15 -03:00
|
|
|
{
|
|
|
|
alt = alt_cm;
|
2019-01-01 19:57:48 -04:00
|
|
|
relative_alt = false;
|
|
|
|
terrain_alt = false;
|
|
|
|
origin_alt = false;
|
2015-08-10 02:25:15 -03:00
|
|
|
switch (frame) {
|
2019-03-14 22:43:43 -03:00
|
|
|
case AltFrame::ABSOLUTE:
|
2015-08-10 02:25:15 -03:00
|
|
|
// do nothing
|
|
|
|
break;
|
2019-03-14 22:43:43 -03:00
|
|
|
case AltFrame::ABOVE_HOME:
|
2019-01-01 19:57:48 -04:00
|
|
|
relative_alt = true;
|
2015-08-10 02:25:15 -03:00
|
|
|
break;
|
2019-03-14 22:43:43 -03:00
|
|
|
case AltFrame::ABOVE_ORIGIN:
|
2019-01-01 19:57:48 -04:00
|
|
|
origin_alt = true;
|
2015-08-10 02:25:15 -03:00
|
|
|
break;
|
2019-03-14 22:43:43 -03:00
|
|
|
case AltFrame::ABOVE_TERRAIN:
|
2015-08-10 02:25:15 -03:00
|
|
|
// we mark it as a relative altitude, as it doesn't have
|
|
|
|
// home alt added
|
2019-01-01 19:57:48 -04:00
|
|
|
relative_alt = true;
|
|
|
|
terrain_alt = true;
|
2015-08-10 02:25:15 -03:00
|
|
|
break;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
// converts altitude to new frame
|
2019-03-14 22:43:43 -03:00
|
|
|
bool Location::change_alt_frame(AltFrame desired_frame)
|
2015-08-10 02:25:15 -03:00
|
|
|
{
|
|
|
|
int32_t new_alt_cm;
|
|
|
|
if (!get_alt_cm(desired_frame, new_alt_cm)) {
|
|
|
|
return false;
|
|
|
|
}
|
2016-04-28 07:52:13 -03:00
|
|
|
set_alt_cm(new_alt_cm, desired_frame);
|
2015-08-10 02:25:15 -03:00
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
|
|
|
// get altitude frame
|
2019-03-14 22:43:43 -03:00
|
|
|
Location::AltFrame Location::get_alt_frame() const
|
2015-08-10 02:25:15 -03:00
|
|
|
{
|
2019-01-01 19:57:48 -04:00
|
|
|
if (terrain_alt) {
|
2019-03-14 22:43:43 -03:00
|
|
|
return AltFrame::ABOVE_TERRAIN;
|
2015-08-10 02:25:15 -03:00
|
|
|
}
|
2019-01-01 19:57:48 -04:00
|
|
|
if (origin_alt) {
|
2019-03-14 22:43:43 -03:00
|
|
|
return AltFrame::ABOVE_ORIGIN;
|
2015-08-10 02:25:15 -03:00
|
|
|
}
|
2019-01-01 19:57:48 -04:00
|
|
|
if (relative_alt) {
|
2019-03-14 22:43:43 -03:00
|
|
|
return AltFrame::ABOVE_HOME;
|
2015-08-10 02:25:15 -03:00
|
|
|
}
|
2019-03-14 22:43:43 -03:00
|
|
|
return AltFrame::ABSOLUTE;
|
2015-08-10 02:25:15 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
/// get altitude in desired frame
|
2019-03-14 22:43:43 -03:00
|
|
|
bool Location::get_alt_cm(AltFrame desired_frame, int32_t &ret_alt_cm) const
|
2015-08-10 02:25:15 -03:00
|
|
|
{
|
2018-07-25 22:40:05 -03:00
|
|
|
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
2019-06-15 04:59:32 -03:00
|
|
|
if (!initialised()) {
|
2021-05-28 04:44:46 -03:00
|
|
|
AP_HAL::panic("Should not be called on invalid location: Location cannot be (0, 0, 0)");
|
2018-07-25 22:40:05 -03:00
|
|
|
}
|
|
|
|
#endif
|
2019-03-14 22:43:43 -03:00
|
|
|
Location::AltFrame frame = get_alt_frame();
|
2015-08-10 02:25:15 -03:00
|
|
|
|
|
|
|
// shortcut if desired and underlying frame are the same
|
|
|
|
if (desired_frame == frame) {
|
|
|
|
ret_alt_cm = alt;
|
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
|
|
|
// check for terrain altitude
|
2016-05-20 16:28:46 -03:00
|
|
|
float alt_terr_cm = 0;
|
2019-03-14 22:43:43 -03:00
|
|
|
if (frame == AltFrame::ABOVE_TERRAIN || desired_frame == AltFrame::ABOVE_TERRAIN) {
|
2016-05-20 16:28:46 -03:00
|
|
|
#if AP_TERRAIN_AVAILABLE
|
2021-06-07 20:31:58 -03:00
|
|
|
if (_terrain == nullptr || !_terrain->height_amsl(*this, alt_terr_cm, true)) {
|
2015-08-10 02:25:15 -03:00
|
|
|
return false;
|
|
|
|
}
|
|
|
|
// convert terrain alt to cm
|
|
|
|
alt_terr_cm *= 100.0f;
|
2016-05-20 16:28:46 -03:00
|
|
|
#else
|
|
|
|
return false;
|
|
|
|
#endif
|
2015-08-10 02:25:15 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
// convert alt to absolute
|
2018-07-25 22:40:05 -03:00
|
|
|
int32_t alt_abs = 0;
|
2015-08-10 02:25:15 -03:00
|
|
|
switch (frame) {
|
2019-03-14 22:43:43 -03:00
|
|
|
case AltFrame::ABSOLUTE:
|
2015-08-10 02:25:15 -03:00
|
|
|
alt_abs = alt;
|
|
|
|
break;
|
2019-03-14 22:43:43 -03:00
|
|
|
case AltFrame::ABOVE_HOME:
|
2018-05-29 22:28:53 -03:00
|
|
|
if (!AP::ahrs().home_is_set()) {
|
2018-05-29 21:34:09 -03:00
|
|
|
return false;
|
|
|
|
}
|
2018-05-29 22:28:53 -03:00
|
|
|
alt_abs = alt + AP::ahrs().get_home().alt;
|
2015-08-10 02:25:15 -03:00
|
|
|
break;
|
2019-03-14 22:43:43 -03:00
|
|
|
case AltFrame::ABOVE_ORIGIN:
|
2015-08-10 02:25:15 -03:00
|
|
|
{
|
|
|
|
// fail if we cannot get ekf origin
|
|
|
|
Location ekf_origin;
|
2018-05-29 22:28:53 -03:00
|
|
|
if (!AP::ahrs().get_origin(ekf_origin)) {
|
2015-08-10 02:25:15 -03:00
|
|
|
return false;
|
|
|
|
}
|
|
|
|
alt_abs = alt + ekf_origin.alt;
|
|
|
|
}
|
|
|
|
break;
|
2019-03-14 22:43:43 -03:00
|
|
|
case AltFrame::ABOVE_TERRAIN:
|
2015-08-10 02:25:15 -03:00
|
|
|
alt_abs = alt + alt_terr_cm;
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
|
|
|
|
// convert absolute to desired frame
|
|
|
|
switch (desired_frame) {
|
2019-03-14 22:43:43 -03:00
|
|
|
case AltFrame::ABSOLUTE:
|
2015-08-10 02:25:15 -03:00
|
|
|
ret_alt_cm = alt_abs;
|
|
|
|
return true;
|
2019-03-14 22:43:43 -03:00
|
|
|
case AltFrame::ABOVE_HOME:
|
2018-05-29 22:28:53 -03:00
|
|
|
if (!AP::ahrs().home_is_set()) {
|
2018-05-29 21:34:09 -03:00
|
|
|
return false;
|
|
|
|
}
|
2018-05-29 22:28:53 -03:00
|
|
|
ret_alt_cm = alt_abs - AP::ahrs().get_home().alt;
|
2015-08-10 02:25:15 -03:00
|
|
|
return true;
|
2019-03-14 22:43:43 -03:00
|
|
|
case AltFrame::ABOVE_ORIGIN:
|
2015-08-10 02:25:15 -03:00
|
|
|
{
|
|
|
|
// fail if we cannot get ekf origin
|
|
|
|
Location ekf_origin;
|
2018-05-29 22:28:53 -03:00
|
|
|
if (!AP::ahrs().get_origin(ekf_origin)) {
|
2015-08-10 02:25:15 -03:00
|
|
|
return false;
|
|
|
|
}
|
|
|
|
ret_alt_cm = alt_abs - ekf_origin.alt;
|
|
|
|
return true;
|
|
|
|
}
|
2019-03-14 22:43:43 -03:00
|
|
|
case AltFrame::ABOVE_TERRAIN:
|
2015-08-10 02:25:15 -03:00
|
|
|
ret_alt_cm = alt_abs - alt_terr_cm;
|
|
|
|
return true;
|
|
|
|
}
|
2021-06-19 12:04:17 -03:00
|
|
|
return false; // LCOV_EXCL_LINE - not reachable
|
2015-08-10 02:25:15 -03:00
|
|
|
}
|
|
|
|
|
2019-01-01 22:53:47 -04:00
|
|
|
bool Location::get_vector_xy_from_origin_NE(Vector2f &vec_ne) const
|
2015-08-10 02:25:15 -03:00
|
|
|
{
|
|
|
|
Location ekf_origin;
|
2018-05-29 22:28:53 -03:00
|
|
|
if (!AP::ahrs().get_origin(ekf_origin)) {
|
2015-08-10 02:25:15 -03:00
|
|
|
return false;
|
|
|
|
}
|
2017-12-13 22:09:59 -04:00
|
|
|
vec_ne.x = (lat-ekf_origin.lat) * LATLON_TO_CM;
|
2021-06-22 21:14:42 -03:00
|
|
|
vec_ne.y = diff_longitude(lng,ekf_origin.lng) * LATLON_TO_CM * ekf_origin.longitude_scale();
|
2015-08-10 02:25:15 -03:00
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
2019-01-01 22:53:47 -04:00
|
|
|
bool Location::get_vector_from_origin_NEU(Vector3f &vec_neu) const
|
2015-08-10 02:25:15 -03:00
|
|
|
{
|
|
|
|
// convert lat, lon
|
2017-12-13 22:09:59 -04:00
|
|
|
Vector2f vec_ne;
|
|
|
|
if (!get_vector_xy_from_origin_NE(vec_ne)) {
|
2015-08-10 02:25:15 -03:00
|
|
|
return false;
|
|
|
|
}
|
2017-12-13 22:09:59 -04:00
|
|
|
vec_neu.x = vec_ne.x;
|
|
|
|
vec_neu.y = vec_ne.y;
|
2015-08-10 02:25:15 -03:00
|
|
|
|
|
|
|
// convert altitude
|
|
|
|
int32_t alt_above_origin_cm = 0;
|
2019-03-14 22:43:43 -03:00
|
|
|
if (!get_alt_cm(AltFrame::ABOVE_ORIGIN, alt_above_origin_cm)) {
|
2015-08-10 02:25:15 -03:00
|
|
|
return false;
|
|
|
|
}
|
|
|
|
vec_neu.z = alt_above_origin_cm;
|
|
|
|
|
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
|
|
|
// return distance in meters between two locations
|
2019-01-01 22:53:47 -04:00
|
|
|
float Location::get_distance(const struct Location &loc2) const
|
2015-08-10 02:25:15 -03:00
|
|
|
{
|
|
|
|
float dlat = (float)(loc2.lat - lat);
|
2021-06-22 21:14:42 -03:00
|
|
|
float dlng = ((float)diff_longitude(loc2.lng,lng)) * loc2.longitude_scale();
|
2016-04-16 06:58:46 -03:00
|
|
|
return norm(dlat, dlng) * LOCATION_SCALING_FACTOR;
|
2015-08-10 02:25:15 -03:00
|
|
|
}
|
|
|
|
|
2019-04-08 09:22:38 -03:00
|
|
|
|
|
|
|
/*
|
|
|
|
return the distance in meters in North/East plane as a N/E vector
|
|
|
|
from loc1 to loc2
|
|
|
|
*/
|
|
|
|
Vector2f Location::get_distance_NE(const Location &loc2) const
|
|
|
|
{
|
|
|
|
return Vector2f((loc2.lat - lat) * LOCATION_SCALING_FACTOR,
|
2021-06-22 21:14:42 -03:00
|
|
|
diff_longitude(loc2.lng,lng) * LOCATION_SCALING_FACTOR * longitude_scale());
|
2019-04-08 09:22:38 -03:00
|
|
|
}
|
|
|
|
|
2019-04-08 10:27:31 -03:00
|
|
|
// return the distance in meters in North/East/Down plane as a N/E/D vector to loc2
|
|
|
|
Vector3f Location::get_distance_NED(const Location &loc2) const
|
|
|
|
{
|
|
|
|
return Vector3f((loc2.lat - lat) * LOCATION_SCALING_FACTOR,
|
2021-06-22 21:14:42 -03:00
|
|
|
diff_longitude(loc2.lng,lng) * LOCATION_SCALING_FACTOR * longitude_scale(),
|
2021-06-22 02:44:00 -03:00
|
|
|
(alt - loc2.alt) * 0.01);
|
|
|
|
}
|
|
|
|
|
|
|
|
// return the distance in meters in North/East/Down plane as a N/E/D vector to loc2
|
|
|
|
Vector3d Location::get_distance_NED_double(const Location &loc2) const
|
|
|
|
{
|
|
|
|
return Vector3d((loc2.lat - lat) * double(LOCATION_SCALING_FACTOR),
|
2021-06-22 21:14:42 -03:00
|
|
|
diff_longitude(loc2.lng,lng) * LOCATION_SCALING_FACTOR * longitude_scale(),
|
2021-06-22 02:44:00 -03:00
|
|
|
(alt - loc2.alt) * 0.01);
|
2019-04-08 10:27:31 -03:00
|
|
|
}
|
|
|
|
|
2021-06-20 23:01:59 -03:00
|
|
|
Vector2d Location::get_distance_NE_double(const Location &loc2) const
|
|
|
|
{
|
|
|
|
return Vector2d((loc2.lat - lat) * double(LOCATION_SCALING_FACTOR),
|
|
|
|
diff_longitude(loc2.lng,lng) * double(LOCATION_SCALING_FACTOR) * longitude_scale());
|
|
|
|
}
|
|
|
|
|
|
|
|
Vector2F Location::get_distance_NE_ftype(const Location &loc2) const
|
|
|
|
{
|
|
|
|
return Vector2F((loc2.lat - lat) * ftype(LOCATION_SCALING_FACTOR),
|
|
|
|
diff_longitude(loc2.lng,lng) * ftype(LOCATION_SCALING_FACTOR) * longitude_scale());
|
|
|
|
}
|
|
|
|
|
2015-08-10 02:25:15 -03:00
|
|
|
// extrapolate latitude/longitude given distances (in meters) north and east
|
2019-01-01 22:53:47 -04:00
|
|
|
void Location::offset(float ofs_north, float ofs_east)
|
2015-08-10 02:25:15 -03:00
|
|
|
{
|
2019-11-05 20:56:23 -04:00
|
|
|
const int32_t dlat = ofs_north * LOCATION_SCALING_FACTOR_INV;
|
2021-06-20 23:01:59 -03:00
|
|
|
const int64_t dlng = (ofs_east * LOCATION_SCALING_FACTOR_INV) / longitude_scale();
|
2019-11-05 20:56:23 -04:00
|
|
|
lat += dlat;
|
2021-06-20 23:01:59 -03:00
|
|
|
lat = limit_lattitude(lat);
|
|
|
|
lng = wrap_longitude(dlng+lng);
|
2015-08-10 02:25:15 -03:00
|
|
|
}
|
2019-01-01 22:53:47 -04:00
|
|
|
|
2021-06-22 02:44:00 -03:00
|
|
|
void Location::offset_double(double ofs_north, double ofs_east)
|
|
|
|
{
|
2021-06-20 23:01:59 -03:00
|
|
|
const int64_t dlat = ofs_north * double(LOCATION_SCALING_FACTOR_INV);
|
|
|
|
const int64_t dlng = (ofs_east * double(LOCATION_SCALING_FACTOR_INV)) / longitude_scale();
|
|
|
|
lat = limit_lattitude(int64_t(lat)+dlat);
|
|
|
|
lng = wrap_longitude(int64_t(lng)+dlng);
|
2021-06-22 02:44:00 -03:00
|
|
|
}
|
|
|
|
|
2019-04-05 03:11:26 -03:00
|
|
|
/*
|
|
|
|
* extrapolate latitude/longitude given bearing and distance
|
|
|
|
* Note that this function is accurate to about 1mm at a distance of
|
|
|
|
* 100m. This function has the advantage that it works in relative
|
|
|
|
* positions, so it keeps the accuracy even when dealing with small
|
|
|
|
* distances and floating point numbers
|
|
|
|
*/
|
2021-06-04 05:36:02 -03:00
|
|
|
void Location::offset_bearing(float bearing_deg, float distance)
|
2019-04-05 03:11:26 -03:00
|
|
|
{
|
2021-06-04 05:36:02 -03:00
|
|
|
const float ofs_north = cosf(radians(bearing_deg)) * distance;
|
|
|
|
const float ofs_east = sinf(radians(bearing_deg)) * distance;
|
2019-04-05 03:11:26 -03:00
|
|
|
offset(ofs_north, ofs_east);
|
|
|
|
}
|
|
|
|
|
2020-07-01 03:10:55 -03:00
|
|
|
// extrapolate latitude/longitude given bearing, pitch and distance
|
2021-06-04 05:36:02 -03:00
|
|
|
void Location::offset_bearing_and_pitch(float bearing_deg, float pitch_deg, float distance)
|
2020-07-01 03:10:55 -03:00
|
|
|
{
|
2021-06-04 05:36:02 -03:00
|
|
|
const float ofs_north = cosf(radians(pitch_deg)) * cosf(radians(bearing_deg)) * distance;
|
|
|
|
const float ofs_east = cosf(radians(pitch_deg)) * sinf(radians(bearing_deg)) * distance;
|
2020-07-01 03:10:55 -03:00
|
|
|
offset(ofs_north, ofs_east);
|
2021-06-04 05:36:02 -03:00
|
|
|
const int32_t dalt = sinf(radians(pitch_deg)) * distance *100.0f;
|
2020-07-01 03:10:55 -03:00
|
|
|
alt += dalt;
|
|
|
|
}
|
|
|
|
|
|
|
|
|
2019-03-06 03:27:27 -04:00
|
|
|
float Location::longitude_scale() const
|
|
|
|
{
|
|
|
|
float scale = cosf(lat * (1.0e-7f * DEG_TO_RAD));
|
2019-06-11 21:17:17 -03:00
|
|
|
return MAX(scale, 0.01f);
|
2019-03-06 03:27:27 -04:00
|
|
|
}
|
|
|
|
|
2019-03-23 00:29:18 -03:00
|
|
|
/*
|
|
|
|
* convert invalid waypoint with useful data. return true if location changed
|
|
|
|
*/
|
|
|
|
bool Location::sanitize(const Location &defaultLoc)
|
|
|
|
{
|
|
|
|
bool has_changed = false;
|
|
|
|
// convert lat/lng=0 to mean current point
|
|
|
|
if (lat == 0 && lng == 0) {
|
|
|
|
lat = defaultLoc.lat;
|
|
|
|
lng = defaultLoc.lng;
|
|
|
|
has_changed = true;
|
|
|
|
}
|
|
|
|
|
|
|
|
// convert relative alt=0 to mean current alt
|
|
|
|
if (alt == 0 && relative_alt) {
|
|
|
|
relative_alt = false;
|
|
|
|
alt = defaultLoc.alt;
|
|
|
|
has_changed = true;
|
|
|
|
}
|
|
|
|
|
|
|
|
// limit lat/lng to appropriate ranges
|
2019-04-08 10:51:23 -03:00
|
|
|
if (!check_latlng()) {
|
2019-03-23 00:29:18 -03:00
|
|
|
lat = defaultLoc.lat;
|
|
|
|
lng = defaultLoc.lng;
|
|
|
|
has_changed = true;
|
|
|
|
}
|
|
|
|
|
|
|
|
return has_changed;
|
|
|
|
}
|
|
|
|
|
2019-01-01 22:53:47 -04:00
|
|
|
// make sure we know what size the Location object is:
|
|
|
|
assert_storage_size<Location, 16> _assert_storage_size_Location;
|
2019-04-05 10:02:42 -03:00
|
|
|
|
|
|
|
|
|
|
|
// return bearing in centi-degrees from location to loc2
|
|
|
|
int32_t Location::get_bearing_to(const struct Location &loc2) const
|
|
|
|
{
|
2021-06-22 21:14:42 -03:00
|
|
|
const int32_t off_x = diff_longitude(loc2.lng,lng);
|
2019-04-05 10:02:42 -03:00
|
|
|
const int32_t off_y = (loc2.lat - lat) / loc2.longitude_scale();
|
|
|
|
int32_t bearing = 9000 + atan2f(-off_y, off_x) * DEGX100;
|
|
|
|
if (bearing < 0) {
|
|
|
|
bearing += 36000;
|
|
|
|
}
|
|
|
|
return bearing;
|
|
|
|
}
|
2019-04-08 08:45:08 -03:00
|
|
|
|
|
|
|
/*
|
|
|
|
return true if lat and lng match. Ignores altitude and options
|
|
|
|
*/
|
|
|
|
bool Location::same_latlon_as(const Location &loc2) const
|
|
|
|
{
|
|
|
|
return (lat == loc2.lat) && (lng == loc2.lng);
|
|
|
|
}
|
2019-04-08 10:51:23 -03:00
|
|
|
|
|
|
|
// return true when lat and lng are within range
|
|
|
|
bool Location::check_latlng() const
|
|
|
|
{
|
|
|
|
return check_lat(lat) && check_lng(lng);
|
|
|
|
}
|
2019-04-09 05:24:22 -03:00
|
|
|
|
|
|
|
// see if location is past a line perpendicular to
|
|
|
|
// the line between point1 and point2 and passing through point2.
|
|
|
|
// If point1 is our previous waypoint and point2 is our target waypoint
|
|
|
|
// then this function returns true if we have flown past
|
|
|
|
// the target waypoint
|
|
|
|
bool Location::past_interval_finish_line(const Location &point1, const Location &point2) const
|
|
|
|
{
|
|
|
|
return this->line_path_proportion(point1, point2) >= 1.0f;
|
|
|
|
}
|
|
|
|
|
2019-04-09 05:24:44 -03:00
|
|
|
/*
|
|
|
|
return the proportion we are along the path from point1 to
|
|
|
|
point2, along a line parallel to point1<->point2.
|
|
|
|
|
|
|
|
This will be more than 1 if we have passed point2
|
|
|
|
*/
|
|
|
|
float Location::line_path_proportion(const Location &point1, const Location &point2) const
|
|
|
|
{
|
|
|
|
const Vector2f vec1 = point1.get_distance_NE(point2);
|
|
|
|
const Vector2f vec2 = point1.get_distance_NE(*this);
|
|
|
|
const float dsquared = sq(vec1.x) + sq(vec1.y);
|
|
|
|
if (dsquared < 0.001f) {
|
|
|
|
// the two points are very close together
|
|
|
|
return 1.0f;
|
|
|
|
}
|
|
|
|
return (vec1 * vec2) / dsquared;
|
|
|
|
}
|
2021-06-22 21:14:42 -03:00
|
|
|
|
|
|
|
/*
|
|
|
|
wrap longitude for -180e7 to 180e7
|
|
|
|
*/
|
2021-06-20 23:01:59 -03:00
|
|
|
int32_t Location::wrap_longitude(int64_t lon)
|
2021-06-22 21:14:42 -03:00
|
|
|
{
|
|
|
|
if (lon > 1800000000L) {
|
2021-06-20 23:01:59 -03:00
|
|
|
lon = int32_t(lon-3600000000LL);
|
2021-06-22 21:14:42 -03:00
|
|
|
} else if (lon < -1800000000L) {
|
2021-06-20 23:01:59 -03:00
|
|
|
lon = int32_t(lon+3600000000LL);
|
2021-06-22 21:14:42 -03:00
|
|
|
}
|
2021-06-20 23:01:59 -03:00
|
|
|
return int32_t(lon);
|
2021-06-22 21:14:42 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
/*
|
|
|
|
get lon1-lon2, wrapping at -180e7 to 180e7
|
|
|
|
*/
|
|
|
|
int32_t Location::diff_longitude(int32_t lon1, int32_t lon2)
|
|
|
|
{
|
|
|
|
if ((lon1 & 0x80000000) == (lon2 & 0x80000000)) {
|
|
|
|
// common case of same sign
|
|
|
|
return lon1 - lon2;
|
|
|
|
}
|
|
|
|
int64_t dlon = int64_t(lon1)-int64_t(lon2);
|
|
|
|
if (dlon > 1800000000LL) {
|
|
|
|
dlon -= 3600000000LL;
|
|
|
|
} else if (dlon < -1800000000LL) {
|
|
|
|
dlon += 3600000000LL;
|
|
|
|
}
|
|
|
|
return int32_t(dlon);
|
|
|
|
}
|
2021-06-20 23:01:59 -03:00
|
|
|
|
|
|
|
/*
|
|
|
|
limit lattitude to -90e7 to 90e7
|
|
|
|
*/
|
|
|
|
int32_t Location::limit_lattitude(int32_t lat)
|
|
|
|
{
|
|
|
|
if (lat > 900000000L) {
|
|
|
|
lat = 1800000000LL - lat;
|
|
|
|
} else if (lat < -900000000L) {
|
|
|
|
lat = -(1800000000LL + lat);
|
|
|
|
}
|
|
|
|
return lat;
|
|
|
|
}
|