mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-05-21 04:47:35 +08:00
geo: purge old globallocal_converter
This commit is contained in:
-111
@@ -57,39 +57,19 @@ using matrix::wrap_2pi;
|
||||
* formulas according to: http://mathworld.wolfram.com/AzimuthalEquidistantProjection.html
|
||||
*/
|
||||
|
||||
static struct map_projection_reference_s mp_ref;
|
||||
static struct globallocal_converter_reference_s gl_ref = {0.0f, false};
|
||||
|
||||
bool map_projection_global_initialized()
|
||||
{
|
||||
return map_projection_initialized(&mp_ref);
|
||||
}
|
||||
|
||||
bool map_projection_initialized(const struct map_projection_reference_s *ref)
|
||||
{
|
||||
return ref->init_done;
|
||||
}
|
||||
|
||||
uint64_t map_projection_global_timestamp()
|
||||
{
|
||||
return map_projection_timestamp(&mp_ref);
|
||||
}
|
||||
|
||||
uint64_t map_projection_timestamp(const struct map_projection_reference_s *ref)
|
||||
{
|
||||
return ref->timestamp;
|
||||
}
|
||||
|
||||
// lat_0, lon_0 are expected to be in correct format: -> 47.1234567 and not 471234567
|
||||
int map_projection_global_init(double lat_0, double lon_0, uint64_t timestamp)
|
||||
{
|
||||
return map_projection_init_timestamped(&mp_ref, lat_0, lon_0, timestamp);
|
||||
}
|
||||
|
||||
// lat_0, lon_0 are expected to be in correct format: -> 47.1234567 and not 471234567
|
||||
int map_projection_init_timestamped(struct map_projection_reference_s *ref, double lat_0, double lon_0, uint64_t timestamp)
|
||||
{
|
||||
|
||||
ref->lat_rad = math::radians(lat_0);
|
||||
ref->lon_rad = math::radians(lon_0);
|
||||
ref->sin_lat = sin(ref->lat_rad);
|
||||
@@ -107,11 +87,6 @@ int map_projection_init(struct map_projection_reference_s *ref, double lat_0, do
|
||||
return map_projection_init_timestamped(ref, lat_0, lon_0, ecl_absolute_time());
|
||||
}
|
||||
|
||||
int map_projection_global_reference(double *ref_lat_rad, double *ref_lon_rad)
|
||||
{
|
||||
return map_projection_reference(&mp_ref, ref_lat_rad, ref_lon_rad);
|
||||
}
|
||||
|
||||
int map_projection_reference(const struct map_projection_reference_s *ref, double *ref_lat_rad, double *ref_lon_rad)
|
||||
{
|
||||
if (!map_projection_initialized(ref)) {
|
||||
@@ -124,11 +99,6 @@ int map_projection_reference(const struct map_projection_reference_s *ref, doubl
|
||||
return 0;
|
||||
}
|
||||
|
||||
int map_projection_global_project(double lat, double lon, float *x, float *y)
|
||||
{
|
||||
return map_projection_project(&mp_ref, lat, lon, x, y);
|
||||
}
|
||||
|
||||
int map_projection_project(const struct map_projection_reference_s *ref, double lat, double lon, float *x, float *y)
|
||||
{
|
||||
if (!map_projection_initialized(ref)) {
|
||||
@@ -158,11 +128,6 @@ int map_projection_project(const struct map_projection_reference_s *ref, double
|
||||
return 0;
|
||||
}
|
||||
|
||||
int map_projection_global_reproject(float x, float y, double *lat, double *lon)
|
||||
{
|
||||
return map_projection_reproject(&mp_ref, x, y, lat, lon);
|
||||
}
|
||||
|
||||
int map_projection_reproject(const struct map_projection_reference_s *ref, float x, float y, double *lat, double *lon)
|
||||
{
|
||||
if (!map_projection_initialized(ref)) {
|
||||
@@ -191,82 +156,6 @@ int map_projection_reproject(const struct map_projection_reference_s *ref, float
|
||||
return 0;
|
||||
}
|
||||
|
||||
int map_projection_global_getref(double *lat_0, double *lon_0)
|
||||
{
|
||||
if (!map_projection_global_initialized()) {
|
||||
return -1;
|
||||
}
|
||||
|
||||
if (lat_0 != nullptr) {
|
||||
*lat_0 = math::degrees(mp_ref.lat_rad);
|
||||
}
|
||||
|
||||
if (lon_0 != nullptr) {
|
||||
*lon_0 = math::degrees(mp_ref.lon_rad);
|
||||
}
|
||||
|
||||
return 0;
|
||||
|
||||
}
|
||||
int globallocalconverter_init(double lat_0, double lon_0, float alt_0, uint64_t timestamp)
|
||||
{
|
||||
gl_ref.alt = alt_0;
|
||||
|
||||
if (!map_projection_global_init(lat_0, lon_0, timestamp)) {
|
||||
gl_ref.init_done = true;
|
||||
return 0;
|
||||
}
|
||||
|
||||
gl_ref.init_done = false;
|
||||
return -1;
|
||||
}
|
||||
|
||||
bool globallocalconverter_initialized()
|
||||
{
|
||||
return gl_ref.init_done && map_projection_global_initialized();
|
||||
}
|
||||
|
||||
int globallocalconverter_tolocal(double lat, double lon, float alt, float *x, float *y, float *z)
|
||||
{
|
||||
if (!map_projection_global_initialized()) {
|
||||
return -1;
|
||||
}
|
||||
|
||||
map_projection_global_project(lat, lon, x, y);
|
||||
*z = gl_ref.alt - alt;
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
int globallocalconverter_toglobal(float x, float y, float z, double *lat, double *lon, float *alt)
|
||||
{
|
||||
if (!map_projection_global_initialized()) {
|
||||
return -1;
|
||||
}
|
||||
|
||||
map_projection_global_reproject(x, y, lat, lon);
|
||||
*alt = gl_ref.alt - z;
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
int globallocalconverter_getref(double *lat_0, double *lon_0, float *alt_0)
|
||||
{
|
||||
if (map_projection_global_initialized() != 0) {
|
||||
return -1;
|
||||
}
|
||||
|
||||
if (map_projection_global_getref(lat_0, lon_0)) {
|
||||
return -1;
|
||||
}
|
||||
|
||||
if (alt_0 != nullptr) {
|
||||
*alt_0 = gl_ref.alt;
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
float get_distance_to_next_waypoint(double lat_now, double lon_now, double lat_next, double lon_next)
|
||||
{
|
||||
const double lat_now_rad = math::radians(lat_now);
|
||||
|
||||
Reference in New Issue
Block a user