lib/geo: move from ecl

This commit is contained in:
Daniel Agar 2021-07-14 17:23:39 -04:00
parent 6f6d3f98a6
commit 883624d915
128 changed files with 202 additions and 178 deletions

View File

@ -44,7 +44,7 @@
#pragma once
#include <ecl/geo/geo.h>
#include <geo/geo.h>
#include <lib/drivers/smbus/SMBus.hpp>
#include <mathlib/mathlib.h>
#include <perf/perf_counter.h>

View File

@ -39,7 +39,7 @@
#pragma once
#include <drivers/device/spi.h>
#include <ecl/geo/geo.h>
#include <geo/geo.h>
#include <lib/conversion/rotation.h>
#include <lib/drivers/accelerometer/PX4Accelerometer.hpp>
#include <lib/drivers/gyroscope/PX4Gyroscope.hpp>

View File

@ -39,7 +39,7 @@
#pragma once
#include <drivers/device/spi.h>
#include <ecl/geo/geo.h>
#include <geo/geo.h>
#include <lib/conversion/rotation.h>
#include <lib/drivers/accelerometer/PX4Accelerometer.hpp>
#include <lib/drivers/gyroscope/PX4Gyroscope.hpp>

View File

@ -48,7 +48,7 @@
#include <lib/drivers/barometer/PX4Barometer.hpp>
#include <lib/drivers/gyroscope/PX4Gyroscope.hpp>
#include <lib/drivers/magnetometer/PX4Magnetometer.hpp>
#include <lib/ecl/geo/geo.h>
#include <lib/geo/geo.h>
#include <lib/perf/perf_counter.h>
#include <px4_platform_common/atomic.h>
#include <px4_platform_common/i2c_spi_buses.h>

View File

@ -46,7 +46,7 @@
#include <lib/drivers/accelerometer/PX4Accelerometer.hpp>
#include <lib/drivers/device/spi.h>
#include <lib/drivers/gyroscope/PX4Gyroscope.hpp>
#include <lib/ecl/geo/geo.h>
#include <lib/geo/geo.h>
#include <lib/perf/perf_counter.h>
#include <px4_platform_common/atomic.h>
#include <px4_platform_common/i2c_spi_buses.h>

View File

@ -33,7 +33,7 @@
#include "BMI055_Accelerometer.hpp"
#include <ecl/geo/geo.h> // CONSTANTS_ONE_G
#include <geo/geo.h> // CONSTANTS_ONE_G
using namespace time_literals;

View File

@ -33,7 +33,7 @@
#include "BMI088_Accelerometer.hpp"
#include <ecl/geo/geo.h> // CONSTANTS_ONE_G
#include <geo/geo.h> // CONSTANTS_ONE_G
using namespace time_literals;

View File

@ -33,7 +33,7 @@
#include "BMI088_Accelerometer.hpp"
#include <ecl/geo/geo.h> // CONSTANTS_ONE_G
#include <geo/geo.h> // CONSTANTS_ONE_G
using namespace time_literals;

View File

@ -42,7 +42,7 @@
#include <drivers/device/i2c.h>
#include <drivers/device/spi.h>
#include <lib/drivers/accelerometer/PX4Accelerometer.hpp>
#include <lib/ecl/geo/geo.h>
#include <lib/geo/geo.h>
#include <lib/perf/perf_counter.h>
#include <px4_platform_common/i2c_spi_buses.h>

View File

@ -46,7 +46,7 @@
#include <lib/drivers/accelerometer/PX4Accelerometer.hpp>
#include <lib/drivers/device/spi.h>
#include <lib/drivers/gyroscope/PX4Gyroscope.hpp>
#include <lib/ecl/geo/geo.h>
#include <lib/geo/geo.h>
#include <lib/perf/perf_counter.h>
#include <px4_platform_common/atomic.h>
#include <px4_platform_common/i2c_spi_buses.h>

View File

@ -46,7 +46,7 @@
#include <lib/drivers/accelerometer/PX4Accelerometer.hpp>
#include <lib/drivers/device/spi.h>
#include <lib/drivers/gyroscope/PX4Gyroscope.hpp>
#include <lib/ecl/geo/geo.h>
#include <lib/geo/geo.h>
#include <lib/perf/perf_counter.h>
#include <px4_platform_common/atomic.h>
#include <px4_platform_common/i2c_spi_buses.h>

View File

@ -46,7 +46,7 @@
#include <lib/drivers/accelerometer/PX4Accelerometer.hpp>
#include <lib/drivers/device/spi.h>
#include <lib/drivers/gyroscope/PX4Gyroscope.hpp>
#include <lib/ecl/geo/geo.h>
#include <lib/geo/geo.h>
#include <lib/perf/perf_counter.h>
#include <px4_platform_common/atomic.h>
#include <px4_platform_common/i2c_spi_buses.h>

View File

@ -46,7 +46,7 @@
#include <lib/drivers/accelerometer/PX4Accelerometer.hpp>
#include <lib/drivers/device/spi.h>
#include <lib/drivers/gyroscope/PX4Gyroscope.hpp>
#include <lib/ecl/geo/geo.h>
#include <lib/geo/geo.h>
#include <lib/perf/perf_counter.h>
#include <px4_platform_common/atomic.h>
#include <px4_platform_common/i2c_spi_buses.h>

View File

@ -46,7 +46,7 @@
#include <lib/drivers/accelerometer/PX4Accelerometer.hpp>
#include <lib/drivers/device/spi.h>
#include <lib/drivers/gyroscope/PX4Gyroscope.hpp>
#include <lib/ecl/geo/geo.h>
#include <lib/geo/geo.h>
#include <lib/perf/perf_counter.h>
#include <px4_platform_common/atomic.h>
#include <px4_platform_common/i2c_spi_buses.h>

View File

@ -46,7 +46,7 @@
#include <lib/drivers/accelerometer/PX4Accelerometer.hpp>
#include <lib/drivers/device/spi.h>
#include <lib/drivers/gyroscope/PX4Gyroscope.hpp>
#include <lib/ecl/geo/geo.h>
#include <lib/geo/geo.h>
#include <lib/perf/perf_counter.h>
#include <px4_platform_common/atomic.h>
#include <px4_platform_common/i2c_spi_buses.h>

View File

@ -46,7 +46,7 @@
#include <lib/drivers/accelerometer/PX4Accelerometer.hpp>
#include <lib/drivers/device/spi.h>
#include <lib/drivers/gyroscope/PX4Gyroscope.hpp>
#include <lib/ecl/geo/geo.h>
#include <lib/geo/geo.h>
#include <lib/perf/perf_counter.h>
#include <px4_platform_common/atomic.h>
#include <px4_platform_common/i2c_spi_buses.h>

View File

@ -46,7 +46,7 @@
#include <lib/drivers/accelerometer/PX4Accelerometer.hpp>
#include <lib/drivers/device/spi.h>
#include <lib/drivers/gyroscope/PX4Gyroscope.hpp>
#include <lib/ecl/geo/geo.h>
#include <lib/geo/geo.h>
#include <lib/perf/perf_counter.h>
#include <px4_platform_common/atomic.h>
#include <px4_platform_common/i2c_spi_buses.h>

View File

@ -46,7 +46,7 @@
#include <lib/drivers/accelerometer/PX4Accelerometer.hpp>
#include <lib/drivers/device/spi.h>
#include <lib/drivers/gyroscope/PX4Gyroscope.hpp>
#include <lib/ecl/geo/geo.h>
#include <lib/geo/geo.h>
#include <lib/perf/perf_counter.h>
#include <px4_platform_common/atomic.h>
#include <px4_platform_common/i2c_spi_buses.h>

View File

@ -46,7 +46,7 @@
#include <lib/drivers/accelerometer/PX4Accelerometer.hpp>
#include <lib/drivers/device/spi.h>
#include <lib/drivers/gyroscope/PX4Gyroscope.hpp>
#include <lib/ecl/geo/geo.h>
#include <lib/geo/geo.h>
#include <lib/perf/perf_counter.h>
#include <px4_platform_common/atomic.h>
#include <px4_platform_common/i2c_spi_buses.h>

View File

@ -46,7 +46,7 @@
#include <lib/drivers/accelerometer/PX4Accelerometer.hpp>
#include <lib/drivers/device/spi.h>
#include <lib/drivers/gyroscope/PX4Gyroscope.hpp>
#include <lib/ecl/geo/geo.h>
#include <lib/geo/geo.h>
#include <lib/perf/perf_counter.h>
#include <px4_platform_common/atomic.h>
#include <px4_platform_common/i2c_spi_buses.h>

View File

@ -46,7 +46,7 @@
#include <lib/drivers/accelerometer/PX4Accelerometer.hpp>
#include <lib/drivers/device/i2c.h>
#include <lib/drivers/gyroscope/PX4Gyroscope.hpp>
#include <lib/ecl/geo/geo.h>
#include <lib/geo/geo.h>
#include <lib/perf/perf_counter.h>
#include <px4_platform_common/atomic.h>
#include <px4_platform_common/i2c_spi_buses.h>

View File

@ -39,7 +39,7 @@
#pragma once
#include <drivers/device/spi.h>
#include <ecl/geo/geo.h>
#include <geo/geo.h>
#include <perf/perf_counter.h>
#include <px4_platform_common/i2c_spi_buses.h>
#include <lib/drivers/accelerometer/PX4Accelerometer.hpp>

View File

@ -46,7 +46,7 @@
#include <lib/drivers/accelerometer/PX4Accelerometer.hpp>
#include <lib/drivers/device/spi.h>
#include <lib/drivers/gyroscope/PX4Gyroscope.hpp>
#include <lib/ecl/geo/geo.h>
#include <lib/geo/geo.h>
#include <lib/perf/perf_counter.h>
#include <px4_platform_common/i2c_spi_buses.h>

View File

@ -41,7 +41,7 @@
#include <px4_platform_common/px4_config.h>
#include <px4_platform_common/defines.h>
#include <ecl/geo/geo.h>
#include <geo/geo.h>
/* SPI protocol address bits */
#define DIR_READ (1<<7)

View File

@ -47,7 +47,7 @@
#include <stdio.h>
#include <string.h>
#include <stdbool.h>
#include <lib/ecl/geo/geo.h>
#include <lib/geo/geo.h>
#include <stdbool.h>
#include <math.h>

View File

@ -49,7 +49,7 @@
#include <string.h>
#include <math.h>
#include <lib/ecl/geo/geo.h>
#include <lib/geo/geo.h>
#include <uORB/Subscription.hpp>
#include <uORB/topics/battery_status.h>

View File

@ -42,7 +42,7 @@
#include <math.h>
#include <stdio.h>
#include <string.h>
#include <lib/ecl/geo/geo.h>
#include <lib/geo/geo.h>
#include <unistd.h>
#include <px4_platform_common/defines.h>
#include <uORB/topics/airspeed.h>

View File

@ -38,7 +38,7 @@
#include <drivers/drv_hrt.h>
#include "airspeed.hpp"
#include <math.h>
#include <lib/ecl/geo/geo.h> // For CONSTANTS_*
#include <lib/geo/geo.h> // For CONSTANTS_*
const char *const UavcanAirspeedBridge::NAME = "airspeed";

View File

@ -40,7 +40,7 @@
#include <math.h>
#include <lib/drivers/barometer/PX4Barometer.hpp>
#include <lib/ecl/geo/geo.h> // For CONSTANTS_*
#include <lib/geo/geo.h> // For CONSTANTS_*
const char *const UavcanBarometerBridge::NAME = "baro";

View File

@ -33,7 +33,7 @@
#include "battery.hpp"
#include <lib/ecl/geo/geo.h>
#include <lib/geo/geo.h>
#include <px4_defines.h>
const char *const UavcanBatteryBridge::NAME = "battery";

View File

@ -33,7 +33,7 @@
#include "cbat.hpp"
#include <lib/ecl/geo/geo.h>
#include <lib/geo/geo.h>
#include <px4_defines.h>
const char *const UavcanCBATBridge::NAME = "cbat";

View File

@ -39,7 +39,7 @@
#include <drivers/drv_airspeed.h>
#include <drivers/drv_hrt.h>
#include <lib/ecl/geo/geo.h>
#include <lib/geo/geo.h>
#include <parameters/param.h>
#include <systemlib/err.h>

View File

@ -33,7 +33,7 @@
#include "Uavcan.hpp"
#include <lib/ecl/geo/geo.h>
#include <lib/geo/geo.h>
#include <lib/version/version.h>
using namespace time_literals;

View File

@ -37,7 +37,7 @@
#include "boot_alt_app_shared.h"
#include <drivers/drv_watchdog.h>
#include <lib/ecl/geo/geo.h>
#include <lib/geo/geo.h>
#include <lib/version/version.h>
#include "Publishers/BatteryInfo.hpp"

View File

@ -40,6 +40,6 @@ px4_add_module(
FakeMagnetometer.hpp
DEPENDS
drivers_magnetometer
ecl_geo
geo
px4_work_queue
)

View File

@ -47,7 +47,7 @@
#include <poll.h>
#include <drivers/drv_hrt.h>
#include <lib/ecl/geo/geo.h>
#include <lib/geo/geo.h>
#include <matrix/math.hpp>
#include <px4_platform_common/px4_config.h>
#include <px4_platform_common/tasks.h>

View File

@ -63,7 +63,7 @@
#include <uORB/topics/vehicle_global_position.h>
#include <uORB/topics/parameter_update.h>
#include <parameters/param.h>
#include <lib/ecl/geo/geo.h>
#include <lib/geo/geo.h>
#include <perf/perf_counter.h>
#include <systemlib/err.h>
#include <matrix/math.hpp>

View File

@ -58,7 +58,7 @@
// internal libraries
#include <lib/mathlib/mathlib.h>
#include <matrix/math.hpp>
#include <lib/ecl/geo/geo.h>
#include <lib/geo/geo.h>
// Include uORB and the required topics for this app
#include <uORB/uORB.h>

View File

@ -41,12 +41,13 @@ add_subdirectory(bezier)
add_subdirectory(cdev)
add_subdirectory(circuit_breaker)
add_subdirectory(collision_prevention)
add_subdirectory(controllib)
add_subdirectory(component_information)
add_subdirectory(controllib)
add_subdirectory(conversion)
add_subdirectory(crypto)
add_subdirectory(drivers)
add_subdirectory(ecl)
add_subdirectory(geo)
add_subdirectory(hysteresis)
add_subdirectory(l1)
add_subdirectory(landing_slope)

View File

@ -43,7 +43,7 @@
#include "airspeed.h"
#include <px4_platform_common/defines.h>
#include <lib/ecl/geo/geo.h>
#include <lib/geo/geo.h>
float calc_IAS_corrected(enum AIRSPEED_COMPENSATION_MODEL pmodel, enum AIRSPEED_SENSOR_MODEL smodel,
float tube_len, float tube_dia_mm, float differential_pressure, float pressure_ambient, float temperature_celsius)

View File

@ -35,7 +35,7 @@
#include <drivers/drv_hrt.h>
#include <lib/conversion/rotation.h>
#include <lib/ecl/geo/geo.h>
#include <lib/geo/geo.h>
#include <uORB/PublicationMulti.hpp>
#include <uORB/topics/sensor_accel.h>
#include <uORB/topics/sensor_accel_fifo.h>

View File

@ -47,7 +47,7 @@
#include <lib/drivers/smbus/SMBus.hpp>
#include <uORB/topics/battery_status.h>
#include <px4_platform_common/param.h>
#include <ecl/geo/geo.h>
#include <geo/geo.h>
using namespace time_literals;

View File

@ -95,14 +95,6 @@ if(CMAKE_SOURCE_DIR STREQUAL PROJECT_SOURCE_DIR)
add_custom_target(prebuild_targets)
# temporary
configure_file(${CMAKE_CURRENT_SOURCE_DIR}/../mathlib/math/filter/AlphaFilter.hpp ${CMAKE_CURRENT_BINARY_DIR}/mathlib/math/filter/AlphaFilter.hpp COPYONLY)
include_directories(${CMAKE_CURRENT_BINARY_DIR})
include_directories(${CMAKE_CURRENT_SOURCE_DIR})
add_subdirectory(${CMAKE_CURRENT_SOURCE_DIR}/../world_magnetic_model world_magnetic_model)
include_directories(${CMAKE_CURRENT_SOURCE_DIR}/../..)
if(MSVC)
add_compile_options(
/W4
@ -152,6 +144,17 @@ if(CMAKE_SOURCE_DIR STREQUAL PROJECT_SOURCE_DIR)
add_dependencies(prebuild_targets matrix)
include_directories(${CMAKE_BINARY_DIR}/matrix-prefix/src/matrix)
# temporary
configure_file(${CMAKE_CURRENT_SOURCE_DIR}/../mathlib/math/filter/AlphaFilter.hpp ${CMAKE_CURRENT_BINARY_DIR}/mathlib/math/filter/AlphaFilter.hpp COPYONLY)
include_directories(${CMAKE_CURRENT_BINARY_DIR})
include_directories(${CMAKE_CURRENT_SOURCE_DIR})
add_definitions(-Dhrt_absolute_time=uint64_t)
add_subdirectory(${CMAKE_CURRENT_SOURCE_DIR}/../geo geo)
add_subdirectory(${CMAKE_CURRENT_SOURCE_DIR}/../world_magnetic_model world_magnetic_model)
include_directories(${CMAKE_CURRENT_SOURCE_DIR}/../..)
endif()
if(NOT (${CMAKE_BUILD_TYPE} MATCHES "Coverage") AND NOT (${CMAKE_BUILD_TYPE} MATCHES "Debug"))
@ -179,7 +182,6 @@ if(ECL_ASAN)
endif()
add_subdirectory(EKF)
add_subdirectory(geo)
if(BUILD_TESTING AND CMAKE_SOURCE_DIR STREQUAL PROJECT_SOURCE_DIR)
add_subdirectory(test)

View File

@ -56,7 +56,7 @@ add_library(ecl_EKF
add_dependencies(ecl_EKF prebuild_targets)
target_compile_definitions(ecl_EKF PRIVATE -DMODULE_NAME="ecl/EKF")
target_include_directories(ecl_EKF PUBLIC ${ECL_SOURCE_DIR})
target_link_libraries(ecl_EKF PRIVATE ecl_geo world_magnetic_model)
target_link_libraries(ecl_EKF PRIVATE geo world_magnetic_model)
set_target_properties(ecl_EKF PROPERTIES PUBLIC_HEADER "ekf.h")

View File

@ -1,6 +1,6 @@
#pragma once
#include <geo/geo.h>
#include <lib/geo/geo.h>
#include <matrix/math.hpp>
#include <mathlib/mathlib.h>

View File

@ -48,7 +48,7 @@
#include "sensor_range_finder.hpp"
#include "utils.hpp"
#include <geo/geo.h>
#include <lib/geo/geo.h>
#include <matrix/math.hpp>
#include <mathlib/mathlib.h>
#include <mathlib/math/filter/AlphaFilter.hpp>

View File

@ -52,7 +52,6 @@ set(SRCS
test_EKF_flow.cpp
test_EKF_terrain_estimator.cpp
test_SensorRangeFinder.cpp
test_geo.cpp
test_EKF_utils.cpp
)
add_executable(ECL_GTESTS ${SRCS})

View File

@ -1,6 +1,6 @@
############################################################################
#
# Copyright (c) 2018 ECL Development Team. All rights reserved.
# Copyright (c) 2018-2021 PX4 Development Team. All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
@ -12,7 +12,7 @@
# notice, this list of conditions and the following disclaimer in
# the documentation and/or other materials provided with the
# distribution.
# 3. Neither the name ECL nor the names of its contributors may be
# 3. Neither the name PX4 nor the names of its contributors may be
# used to endorse or promote products derived from this software
# without specific prior written permission.
#
@ -31,10 +31,14 @@
#
############################################################################
add_library(ecl_geo
add_library(geo
geo.cpp
)
add_dependencies(ecl_geo prebuild_targets)
target_compile_definitions(ecl_geo PRIVATE -DMODULE_NAME="ecl/geo")
target_include_directories(ecl_geo PUBLIC ${ECL_SOURCE_DIR})
target_link_libraries(ecl_geo PRIVATE m)
geo.h
)
add_dependencies(geo prebuild_targets)
target_compile_options(geo PRIVATE ${MAX_CUSTOM_OPT_LEVEL})
target_link_libraries(geo PRIVATE m)
if(CMAKE_PROJECT_NAME MATCHES "px4") # temporary
px4_add_unit_gtest(SRC test_geo.cpp LINKLIBS geo)
endif()

View File

@ -1,6 +1,6 @@
/****************************************************************************
*
* Copyright (c) 2012-2014 PX4 Development Team. All rights reserved.
* Copyright (c) 2012-2021 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@ -43,7 +43,6 @@
*/
#include "geo.h"
#include <ecl.h>
#include <mathlib/mathlib.h>
#include <matrix/math.hpp>
@ -52,23 +51,26 @@
using matrix::wrap_pi;
using matrix::wrap_2pi;
#ifndef hrt_absolute_time
# define hrt_absolute_time() (0)
#endif
/*
* Azimuthal Equidistant Projection
* formulas according to: http://mathworld.wolfram.com/AzimuthalEquidistantProjection.html
*/
bool map_projection_initialized(const struct map_projection_reference_s *ref)
bool map_projection_initialized(const map_projection_reference_s *ref)
{
return ref->init_done;
}
uint64_t map_projection_timestamp(const struct map_projection_reference_s *ref)
uint64_t map_projection_timestamp(const 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_init_timestamped(struct map_projection_reference_s *ref, double lat_0, double lon_0, uint64_t timestamp)
int map_projection_init_timestamped(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);
@ -81,13 +83,12 @@ int map_projection_init_timestamped(struct map_projection_reference_s *ref, doub
return 0;
}
//lat_0, lon_0 are expected to be in correct format: -> 47.1234567 and not 471234567
int map_projection_init(struct map_projection_reference_s *ref, double lat_0, double lon_0)
int map_projection_init(map_projection_reference_s *ref, double lat_0, double lon_0)
{
return map_projection_init_timestamped(ref, lat_0, lon_0, ecl_absolute_time());
return map_projection_init_timestamped(ref, lat_0, lon_0, hrt_absolute_time());
}
int map_projection_reference(const struct map_projection_reference_s *ref, double *ref_lat_rad, double *ref_lon_rad)
int map_projection_reference(const map_projection_reference_s *ref, double *ref_lat_rad, double *ref_lon_rad)
{
if (!map_projection_initialized(ref)) {
return -1;
@ -99,7 +100,7 @@ int map_projection_reference(const struct map_projection_reference_s *ref, doubl
return 0;
}
int map_projection_project(const struct map_projection_reference_s *ref, double lat, double lon, float *x, float *y)
int map_projection_project(const map_projection_reference_s *ref, double lat, double lon, float *x, float *y)
{
if (!map_projection_initialized(ref)) {
return -1;
@ -128,7 +129,7 @@ int map_projection_project(const struct map_projection_reference_s *ref, double
return 0;
}
int map_projection_reproject(const struct map_projection_reference_s *ref, float x, float y, double *lat, double *lon)
int map_projection_reproject(const map_projection_reference_s *ref, float x, float y, double *lat, double *lon)
{
if (!map_projection_initialized(ref)) {
return -1;
@ -164,7 +165,8 @@ float get_distance_to_next_waypoint(double lat_now, double lon_now, double lat_n
const double d_lat = lat_next_rad - lat_now_rad;
const double d_lon = math::radians(lon_next) - math::radians(lon_now);
const double a = sin(d_lat / 2.0) * sin(d_lat / 2.0) + sin(d_lon / 2.0) * sin(d_lon / 2.0) * cos(lat_now_rad) * cos(lat_next_rad);
const double a = sin(d_lat / 2.0) * sin(d_lat / 2.0) + sin(d_lon / 2.0) * sin(d_lon / 2.0) * cos(lat_now_rad) * cos(
lat_next_rad);
const double c = atan2(sqrt(a), sqrt(1.0 - a));
@ -177,6 +179,7 @@ void create_waypoint_from_line_and_dist(double lat_A, double lon_A, double lat_B
if (fabsf(dist) < FLT_EPSILON) {
*lat_target = lat_A;
*lon_target = lon_A;
} else {
float heading = get_bearing_to_next_waypoint(lat_A, lon_A, lat_B, lon_B);
waypoint_from_heading_and_distance(lat_A, lon_A, heading, dist, lat_target, lon_target);
@ -192,7 +195,8 @@ void waypoint_from_heading_and_distance(double lat_start, double lon_start, floa
double lat_start_rad = math::radians(lat_start);
double lon_start_rad = math::radians(lon_start);
*lat_target = asin(sin(lat_start_rad) * cos(radius_ratio) + cos(lat_start_rad) * sin(radius_ratio) * cos((double)bearing));
*lat_target = asin(sin(lat_start_rad) * cos(radius_ratio) + cos(lat_start_rad) * sin(radius_ratio) * cos((
double)bearing));
*lon_target = lon_start_rad + atan2(sin((double)bearing) * sin(radius_ratio) * cos(lat_start_rad),
cos(radius_ratio) - sin(lat_start_rad) * sin(*lat_target));
@ -224,12 +228,14 @@ get_vector_to_next_waypoint(double lat_now, double lon_now, double lat_next, dou
const double d_lon = math::radians(lon_next) - math::radians(lon_now);
/* conscious mix of double and float trig function to maximize speed and efficiency */
*v_n = static_cast<float>(CONSTANTS_RADIUS_OF_EARTH * (cos(lat_now_rad) * sin(lat_next_rad) - sin(lat_now_rad) * cos(lat_next_rad) * cos(d_lon)));
*v_n = static_cast<float>(CONSTANTS_RADIUS_OF_EARTH * (cos(lat_now_rad) * sin(lat_next_rad) - sin(lat_now_rad) * cos(
lat_next_rad) * cos(d_lon)));
*v_e = static_cast<float>(CONSTANTS_RADIUS_OF_EARTH * sin(d_lon) * cos(lat_next_rad));
}
void
get_vector_to_next_waypoint_fast(double lat_now, double lon_now, double lat_next, double lon_next, float *v_n, float *v_e)
get_vector_to_next_waypoint_fast(double lat_now, double lon_now, double lat_next, double lon_next, float *v_n,
float *v_e)
{
double lat_now_rad = math::radians(lat_now);
double lon_now_rad = math::radians(lon_now);
@ -244,7 +250,8 @@ get_vector_to_next_waypoint_fast(double lat_now, double lon_now, double lat_next
*v_e = static_cast<float>(CONSTANTS_RADIUS_OF_EARTH * d_lon * cos(lat_now_rad));
}
void add_vector_to_global_position(double lat_now, double lon_now, float v_n, float v_e, double *lat_res, double *lon_res)
void add_vector_to_global_position(double lat_now, double lon_now, float v_n, float v_e, double *lat_res,
double *lon_res)
{
double lat_now_rad = math::radians(lat_now);
double lon_now_rad = math::radians(lon_now);

View File

@ -1,6 +1,6 @@
/****************************************************************************
*
* Copyright (C) 2012, 2014 PX4 Development Team. All rights reserved.
* Copyright (C) 2012-2021 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@ -52,7 +52,8 @@ static constexpr float CONSTANTS_ONE_G = 9.80665f; // m/s^2
static constexpr float CONSTANTS_STD_PRESSURE_PA = 101325.0f; // pascals (Pa)
static constexpr float CONSTANTS_STD_PRESSURE_KPA = CONSTANTS_STD_PRESSURE_PA / 1000.0f; // kilopascals (kPa)
static constexpr float CONSTANTS_STD_PRESSURE_MBAR = CONSTANTS_STD_PRESSURE_PA / 100.0f; // Millibar (mbar) (1 mbar = 100 Pa)
static constexpr float CONSTANTS_STD_PRESSURE_MBAR = CONSTANTS_STD_PRESSURE_PA /
100.0f; // Millibar (mbar) (1 mbar = 100 Pa)
static constexpr float CONSTANTS_AIR_DENSITY_SEA_LEVEL_15C = 1.225f; // kg/m^3
static constexpr float CONSTANTS_AIR_GAS_CONST = 287.1f; // J/(kg * K)
@ -107,7 +108,8 @@ int map_projection_reference(const struct map_projection_reference_s *ref, doubl
* @param lat in degrees (47.1234567°, not 471234567°)
* @param lon in degrees (8.1234567°, not 81234567°)
*/
int map_projection_init_timestamped(struct map_projection_reference_s *ref, double lat_0, double lon_0, uint64_t timestamp);
int map_projection_init_timestamped(struct map_projection_reference_s *ref, double lat_0, double lon_0,
uint64_t timestamp);
/**
* Initializes the map transformation given by the argument and sets the timestamp to now.
@ -164,7 +166,7 @@ float get_distance_to_next_waypoint(double lat_now, double lon_now, double lat_n
* @param lon_target longitude of target waypoint C in degrees (47.1234567°, not 471234567°)
*/
void create_waypoint_from_line_and_dist(double lat_A, double lon_A, double lat_B, double lon_B, float dist,
double *lat_target, double *lon_target);
double *lat_target, double *lon_target);
/**
* Creates a waypoint from given waypoint, distance and bearing
@ -178,7 +180,7 @@ void create_waypoint_from_line_and_dist(double lat_A, double lon_A, double lat_B
* @param lon_target longitude of target waypoint in degrees (47.1234567°, not 471234567°)
*/
void waypoint_from_heading_and_distance(double lat_start, double lon_start, float bearing, float dist,
double *lat_target, double *lon_target);
double *lat_target, double *lon_target);
/**
* Returns the bearing to the next waypoint in radians.
@ -190,18 +192,21 @@ void waypoint_from_heading_and_distance(double lat_start, double lon_start, floa
*/
float get_bearing_to_next_waypoint(double lat_now, double lon_now, double lat_next, double lon_next);
void get_vector_to_next_waypoint(double lat_now, double lon_now, double lat_next, double lon_next, float *v_n, float *v_e);
void get_vector_to_next_waypoint(double lat_now, double lon_now, double lat_next, double lon_next, float *v_n,
float *v_e);
void get_vector_to_next_waypoint_fast(double lat_now, double lon_now, double lat_next, double lon_next, float *v_n, float *v_e);
void get_vector_to_next_waypoint_fast(double lat_now, double lon_now, double lat_next, double lon_next, float *v_n,
float *v_e);
void add_vector_to_global_position(double lat_now, double lon_now, float v_n, float v_e, double *lat_res, double *lon_res);
void add_vector_to_global_position(double lat_now, double lon_now, float v_n, float v_e, double *lat_res,
double *lon_res);
int get_distance_to_line(struct crosstrack_error_s *crosstrack_error, double lat_now, double lon_now,
double lat_start, double lon_start, double lat_end, double lon_end);
double lat_start, double lon_start, double lat_end, double lon_end);
int get_distance_to_arc(struct crosstrack_error_s *crosstrack_error, double lat_now, double lon_now,
double lat_center, double lon_center,
float radius, float arc_start_bearing, float arc_sweep);
double lat_center, double lon_center,
float radius, float arc_start_bearing, float arc_sweep);
/*
* Calculate distance in global frame

View File

@ -35,10 +35,11 @@
#include <math.h>
#include <mathlib/mathlib.h>
#include <memory>
#include <geo/geo.h>
#include <lib/geo/geo.h>
class GeoTest : public ::testing::Test {
public:
class GeoTest : public ::testing::Test
{
public:
void SetUp() override
{
origin.timestamp = 0;
@ -49,7 +50,7 @@ class GeoTest : public ::testing::Test {
origin.init_done = true;
}
protected:
protected:
map_projection_reference_s origin;
};
@ -123,7 +124,7 @@ TEST_F(GeoTest, waypoint_from_heading_and_negative_distance)
double lon_start = 18;
float bearing = 0;
float lat_offset = -0.01f;
float dist = CONSTANTS_RADIUS_OF_EARTH * M_PI / 180.f * lat_offset;
float dist = CONSTANTS_RADIUS_OF_EARTH_F * M_PI_F / 180.f * lat_offset;
double lat_target = 0;
double lon_target = 0;
@ -132,7 +133,7 @@ TEST_F(GeoTest, waypoint_from_heading_and_negative_distance)
waypoint_from_heading_and_distance(lat_start, lon_start, bearing, dist, &lat_target, &lon_target);
// THEN: it should be the same
EXPECT_FLOAT_EQ(lat_start + lat_offset, lat_target);
EXPECT_FLOAT_EQ(static_cast<float>(lat_start) + lat_offset, lat_target);
EXPECT_DOUBLE_EQ(lon_start, lon_target);
}
@ -143,7 +144,7 @@ TEST_F(GeoTest, waypoint_from_heading_and_positive_distance)
double lon_start = 18;
float bearing = 0;
float lat_offset = 0.01f;
float dist = CONSTANTS_RADIUS_OF_EARTH * M_PI / 180.f * lat_offset;
float dist = CONSTANTS_RADIUS_OF_EARTH_F * M_PI_F / 180.f * lat_offset;
double lat_target = 0;
double lon_target = 0;
@ -152,7 +153,7 @@ TEST_F(GeoTest, waypoint_from_heading_and_positive_distance)
waypoint_from_heading_and_distance(lat_start, lon_start, bearing, dist, &lat_target, &lon_target);
// THEN: it should be the same
EXPECT_FLOAT_EQ(lat_start + lat_offset, lat_target);
EXPECT_FLOAT_EQ(static_cast<float>(lat_start) + lat_offset, lat_target);
EXPECT_DOUBLE_EQ(lon_start, lon_target);
}
@ -184,7 +185,7 @@ TEST_F(GeoTest, waypoint_from_line_and_positive_distance)
double lat_offset = 0.01;
double lat_end = lat_start + lat_offset;
double lon_end = 18;
float dist = CONSTANTS_RADIUS_OF_EARTH * M_PI / 180.f * lat_offset;
float dist = CONSTANTS_RADIUS_OF_EARTH_F * M_PI_F / 180.f * static_cast<float>(lat_offset);
double lat_target = 0;
double lon_target = 0;
@ -206,7 +207,7 @@ TEST_F(GeoTest, waypoint_from_line_and_negative_distance)
double lat_offset = 0.01;
double lat_end = lat_start + lat_offset;
double lon_end = 18;
float dist = -CONSTANTS_RADIUS_OF_EARTH * M_PI / 180.f * lat_offset;
float dist = -CONSTANTS_RADIUS_OF_EARTH_F * M_PI_F / 180.f * static_cast<float>(lat_offset);
double lat_target = 0;
double lon_target = 0;

View File

@ -36,4 +36,4 @@ px4_add_library(l1
ECL_L1_Pos_Controller.hpp
)
target_link_libraries(l1 PRIVATE ecl_geo)
target_link_libraries(l1 PRIVATE geo)

View File

@ -40,7 +40,7 @@
#include "ECL_L1_Pos_Controller.hpp"
#include <lib/ecl/geo/geo.h>
#include <lib/geo/geo.h>
#include <px4_platform_common/defines.h>

View File

@ -36,4 +36,4 @@ px4_add_library(tecs
TECS.hpp
)
target_link_libraries(tecs PRIVATE ecl_geo)
target_link_libraries(tecs PRIVATE geo)

View File

@ -33,7 +33,7 @@
#include "TECS.hpp"
#include <lib/ecl/geo/geo.h>
#include <lib/geo/geo.h>
#include <px4_platform_common/defines.h>

View File

@ -37,7 +37,7 @@
*/
#include "terrain_estimator.h"
#include <lib/ecl/geo/geo.h>
#include <lib/geo/geo.h>
#include <px4_platform_common/defines.h>
#define DISTANCE_TIMEOUT 100000 // time in usec after which laser is considered dead

View File

@ -36,6 +36,7 @@ add_library(world_magnetic_model
geo_mag_declination.h
geo_magnetic_tables.hpp
)
add_dependencies(world_magnetic_model prebuild_targets)
target_compile_options(world_magnetic_model PRIVATE ${MAX_CUSTOM_OPT_LEVEL})
if(CMAKE_PROJECT_NAME MATCHES "px4") # temporary

View File

@ -37,7 +37,7 @@
#include <circuit_breaker/circuit_breaker.h>
#include <mathlib/math/Limits.hpp>
#include <mathlib/math/Functions.hpp>
#include <ecl/geo/geo.h>
#include <geo/geo.h>
using namespace matrix;
using namespace time_literals;

View File

@ -42,7 +42,7 @@
#include <float.h>
#include <drivers/drv_hrt.h>
#include <lib/ecl/geo/geo.h>
#include <lib/geo/geo.h>
#include <lib/world_magnetic_model/geo_mag_declination.h>
#include <lib/mathlib/mathlib.h>
#include <lib/parameters/param.h>

View File

@ -57,7 +57,7 @@ px4_add_module(
DEPENDS
circuit_breaker
failure_detector
ecl_geo
geo
hysteresis
PreFlightCheck
ArmAuthorization

View File

@ -57,7 +57,7 @@
#include <dataman/dataman.h>
#include <drivers/drv_hrt.h>
#include <drivers/drv_tone_alarm.h>
#include <lib/ecl/geo/geo.h>
#include <lib/geo/geo.h>
#include <mathlib/mathlib.h>
#include <navigator/navigation.h>
#include <px4_platform_common/px4_config.h>

View File

@ -134,7 +134,7 @@
#include <lib/sensor_calibration/Accelerometer.hpp>
#include <lib/sensor_calibration/Utilities.hpp>
#include <lib/mathlib/mathlib.h>
#include <lib/ecl/geo/geo.h>
#include <lib/geo/geo.h>
#include <matrix/math.hpp>
#include <lib/conversion/rotation.h>
#include <lib/parameters/param.h>

View File

@ -45,7 +45,7 @@
#include <drivers/drv_hrt.h>
#include <drivers/drv_tone_alarm.h>
#include <lib/ecl/geo/geo.h>
#include <lib/geo/geo.h>
#include <lib/mathlib/mathlib.h>
#include <lib/systemlib/mavlink_log.h>
#include <matrix/math.hpp>

View File

@ -42,7 +42,7 @@
#include <drivers/drv_hrt.h>
#include <lib/mathlib/mathlib.h>
#include <lib/ecl/geo/geo.h>
#include <lib/geo/geo.h>
#include <matrix/math.hpp>
#include <lib/conversion/rotation.h>
#include <lib/parameters/param.h>

View File

@ -45,7 +45,7 @@ px4_add_module(
EKF2Selector.hpp
DEPENDS
ecl_EKF
ecl_geo
geo
perf
EKF2Utility
px4_work_queue

View File

@ -45,7 +45,7 @@
#include <uORB/topics/home_position.h>
#include <uORB/topics/manual_control_setpoint.h>
#include <uORB/topics/vehicle_status.h>
#include <lib/ecl/geo/geo.h>
#include <lib/geo/geo.h>
// TODO: make this switchable in the board config, like a module
#if CONSTRAINED_FLASH

View File

@ -1,6 +1,6 @@
#include "FlightTask.hpp"
#include <mathlib/mathlib.h>
#include <lib/ecl/geo/geo.h>
#include <lib/geo/geo.h>
constexpr uint64_t FlightTask::_timeout;
// First index of empty_setpoint corresponds to time-stamp and requires a finite number.

View File

@ -53,7 +53,7 @@
#include <uORB/topics/vehicle_attitude.h>
#include <uORB/topics/vehicle_trajectory_waypoint.h>
#include <uORB/topics/home_position.h>
#include <lib/ecl/geo/geo.h>
#include <lib/geo/geo.h>
#include <lib/weather_vane/WeatherVane.hpp>
struct ekf_reset_counters_s {

View File

@ -38,7 +38,7 @@
#include "FlightTaskManualAltitude.hpp"
#include <float.h>
#include <mathlib/mathlib.h>
#include <ecl/geo/geo.h>
#include <geo/geo.h>
using namespace matrix;

View File

@ -38,7 +38,7 @@
#include "FlightTaskOrbit.hpp"
#include <mathlib/mathlib.h>
#include <lib/ecl/geo/geo.h>
#include <lib/geo/geo.h>
using namespace matrix;

View File

@ -37,7 +37,7 @@
#include "StickAccelerationXY.hpp"
#include <ecl/geo/geo.h>
#include <geo/geo.h>
#include "Sticks.hpp"
using namespace matrix;

View File

@ -36,7 +36,7 @@
#include "ecl_roll_controller.h"
#include "ecl_wheel_controller.h"
#include "ecl_yaw_controller.h"
#include <lib/ecl/geo/geo.h>
#include <lib/geo/geo.h>
#include <lib/mathlib/mathlib.h>
#include <lib/parameters/param.h>
#include <lib/perf/perf_counter.h>

View File

@ -40,7 +40,7 @@
#include "ecl_pitch_controller.h"
#include <float.h>
#include <lib/ecl/geo/geo.h>
#include <lib/geo/geo.h>
#include <mathlib/mathlib.h>
float ECL_PitchController::control_attitude(const float dt, const ECL_ControlData &ctl_data)

View File

@ -40,7 +40,7 @@
#include "ecl_roll_controller.h"
#include <float.h>
#include <lib/ecl/geo/geo.h>
#include <lib/geo/geo.h>
#include <mathlib/mathlib.h>
float ECL_RollController::control_attitude(const float dt, const ECL_ControlData &ctl_data)

View File

@ -40,7 +40,7 @@
#include "ecl_wheel_controller.h"
#include <float.h>
#include <lib/ecl/geo/geo.h>
#include <lib/geo/geo.h>
#include <mathlib/mathlib.h>
#include <matrix/math.hpp>

View File

@ -40,7 +40,7 @@
#include "ecl_yaw_controller.h"
#include <float.h>
#include <lib/ecl/geo/geo.h>
#include <lib/geo/geo.h>
#include <mathlib/mathlib.h>
float ECL_YawController::control_attitude(const float dt, const ECL_ControlData &ctl_data)

View File

@ -54,7 +54,7 @@
#include <float.h>
#include <drivers/drv_hrt.h>
#include <lib/ecl/geo/geo.h>
#include <lib/geo/geo.h>
#include <lib/l1/ECL_L1_Pos_Controller.hpp>
#include <lib/tecs/TECS.hpp>
#include <lib/landing_slope/Landingslope.hpp>

View File

@ -33,7 +33,7 @@
#include "GyroCalibration.hpp"
#include <lib/ecl/geo/geo.h>
#include <lib/geo/geo.h>
using namespace time_literals;
using matrix::Vector3f;

View File

@ -5,7 +5,7 @@
#include <px4_platform_common/module_params.h>
#include <px4_platform_common/posix.h>
#include <lib/controllib/blocks.hpp>
#include <lib/ecl/geo/geo.h>
#include <lib/geo/geo.h>
#include <lib/mathlib/mathlib.h>
#include <matrix/Matrix.hpp>

View File

@ -49,6 +49,6 @@ px4_add_module(
sensors/landing_target.cpp
DEPENDS
controllib
ecl_geo
geo
px4_work_queue
)

View File

@ -72,7 +72,7 @@ px4_add_module(
drivers_magnetometer
git_mavlink_v2
conversion
ecl_geo
geo
version
UNITY_BUILD
)

View File

@ -49,7 +49,7 @@
#endif
#include <containers/LockGuard.hpp>
#include <lib/ecl/geo/geo.h>
#include <lib/geo/geo.h>
#include <lib/mathlib/mathlib.h>
#include <lib/systemlib/mavlink_log.h>
#include <lib/version/version.h>

View File

@ -46,7 +46,7 @@
#include <drivers/drv_pwm_output.h>
#include <lib/conversion/rotation.h>
#include <lib/ecl/geo/geo.h>
#include <lib/geo/geo.h>
#include <lib/mathlib/mathlib.h>
#include <lib/matrix/matrix/math.hpp>
#include <px4_platform_common/time.h>

View File

@ -43,7 +43,7 @@
#include "mavlink_mission.h"
#include "mavlink_main.h"
#include <lib/ecl/geo/geo.h>
#include <lib/geo/geo.h>
#include <systemlib/err.h>
#include <drivers/drv_hrt.h>
#include <px4_platform_common/defines.h>

View File

@ -43,7 +43,7 @@
#include <airspeed/airspeed.h>
#include <conversion/rotation.h>
#include <drivers/drv_rc_input.h>
#include <ecl/geo/geo.h>
#include <geo/geo.h>
#include <systemlib/px4_macros.h>
#include <math.h>

View File

@ -34,7 +34,7 @@
#ifndef HIGH_LATENCY2_HPP
#define HIGH_LATENCY2_HPP
#include <lib/ecl/geo/geo.h>
#include <lib/geo/geo.h>
#include <lib/mathlib/mathlib.h>
#include <lib/matrix/matrix/math.hpp>

View File

@ -34,7 +34,7 @@
#ifndef SCALED_IMU_HPP
#define SCALED_IMU_HPP
#include <lib/ecl/geo/geo.h>
#include <lib/geo/geo.h>
#include <lib/matrix/matrix/math.hpp>
#include <uORB/topics/sensor_mag.h>

View File

@ -34,7 +34,7 @@
#ifndef SCALED_IMU2_HPP
#define SCALED_IMU2_HPP
#include <lib/ecl/geo/geo.h>
#include <lib/geo/geo.h>
#include <lib/matrix/matrix/math.hpp>
#include <uORB/topics/sensor_mag.h>

View File

@ -34,7 +34,7 @@
#ifndef SCALED_IMU3_HPP
#define SCALED_IMU3_HPP
#include <lib/ecl/geo/geo.h>
#include <lib/geo/geo.h>
#include <lib/matrix/matrix/math.hpp>
#include <uORB/topics/sensor_mag.h>

View File

@ -64,7 +64,7 @@
#pragma once
#include <matrix/matrix/math.hpp>
#include <ecl/geo/geo.h>
#include <geo/geo.h>
#include <mathlib/mathlib.h>
class ZeroOrderHoverThrustEkf

View File

@ -45,6 +45,6 @@ px4_add_module(
PositionControl
Takeoff
controllib
ecl_geo
geo
SlewRate
)

View File

@ -40,7 +40,7 @@
#include <float.h>
#include <mathlib/mathlib.h>
#include <px4_platform_common/defines.h>
#include <ecl/geo/geo.h>
#include <geo/geo.h>
using namespace matrix;

View File

@ -37,7 +37,7 @@
#include "Takeoff.hpp"
#include <mathlib/mathlib.h>
#include <lib/ecl/geo/geo.h>
#include <lib/geo/geo.h>
void Takeoff::generateInitialRampValue(float velocity_p_gain)
{

View File

@ -34,7 +34,7 @@
#include <gtest/gtest.h>
#include <Takeoff.hpp>
#include <drivers/drv_hrt.h>
#include <lib/ecl/geo/geo.h>
#include <lib/geo/geo.h>
TEST(TakeoffTest, Initialization)
{

View File

@ -52,7 +52,7 @@ px4_add_module(
gpsfailure.cpp
follow_target.cpp
DEPENDS
ecl_geo
geo
landing_slope
geofence_breach_avoidance
motion_planning

View File

@ -36,4 +36,4 @@ px4_add_library(geofence_breach_avoidance
geofence_breach_avoidance.h
)
px4_add_functional_gtest(SRC GeofenceBreachAvoidanceTest.cpp LINKLIBS geofence_breach_avoidance modules__navigator ecl_geo motion_planning)
px4_add_functional_gtest(SRC GeofenceBreachAvoidanceTest.cpp LINKLIBS geofence_breach_avoidance modules__navigator motion_planning)

View File

@ -32,7 +32,7 @@
****************************************************************************/
#include "geofence_breach_avoidance.h"
#include <lib/ecl/geo/geo.h>
#include <lib/geo/geo.h>
#include <motion_planning/VelocitySmoothing.hpp>
using Vector2d = matrix::Vector2<double>;

View File

@ -43,7 +43,7 @@
#include <systemlib/mavlink_log.h>
#include <systemlib/err.h>
#include <lib/ecl/geo/geo.h>
#include <lib/geo/geo.h>
#include <navigator/navigation.h>
#include <uORB/uORB.h>

View File

@ -51,7 +51,7 @@
#include <uORB/uORB.h>
#include <uORB/topics/position_setpoint_triplet.h>
#include <uORB/topics/follow_target.h>
#include <lib/ecl/geo/geo.h>
#include <lib/geo/geo.h>
#include <lib/mathlib/math/Limits.hpp>
#include "navigator.h"

View File

@ -45,7 +45,7 @@
#include <dataman/dataman.h>
#include <drivers/drv_hrt.h>
#include <lib/ecl/geo/geo.h>
#include <lib/geo/geo.h>
#include <systemlib/mavlink_log.h>
#include "navigator.h"

Some files were not shown because too many files have changed in this diff Show More