diff --git a/cmake/configs/nuttx_aerocore2_default.cmake b/cmake/configs/nuttx_aerocore2_default.cmake index b5c10c9fbc710fd6c2bc0a1c088405ee3e348371..7948d848d2f79b9b7b9b2af9cc6aadac7e6ee707 100644 --- a/cmake/configs/nuttx_aerocore2_default.cmake +++ b/cmake/configs/nuttx_aerocore2_default.cmake @@ -112,8 +112,6 @@ set(config_module_list lib/conversion lib/DriverFramework/framework lib/ecl - lib/geo - lib/geo_lookup lib/led lib/mathlib lib/mixer diff --git a/cmake/configs/nuttx_aerofc-v1_default.cmake b/cmake/configs/nuttx_aerofc-v1_default.cmake index aa50d777f3ec06cb682c6a19096de7fe03905e04..35280bcc285335592ae30c00211a3c0913002cc1 100644 --- a/cmake/configs/nuttx_aerofc-v1_default.cmake +++ b/cmake/configs/nuttx_aerofc-v1_default.cmake @@ -82,8 +82,6 @@ set(config_module_list lib/conversion lib/DriverFramework/framework lib/ecl - lib/geo - lib/geo_lookup lib/mathlib lib/mixer lib/rc diff --git a/cmake/configs/nuttx_auav-x21_default.cmake b/cmake/configs/nuttx_auav-x21_default.cmake index 58f779ccd8205744b59cf75526f618dd65372915..5319273beb9c0bc8aa9e1705c96ee8712d25a1f2 100644 --- a/cmake/configs/nuttx_auav-x21_default.cmake +++ b/cmake/configs/nuttx_auav-x21_default.cmake @@ -125,8 +125,6 @@ set(config_module_list lib/conversion lib/DriverFramework/framework lib/ecl - lib/geo - lib/geo_lookup lib/led lib/mathlib lib/mixer diff --git a/cmake/configs/nuttx_crazyflie_default.cmake b/cmake/configs/nuttx_crazyflie_default.cmake index 7426b69f036d969fbae958bb437dfe86bb488b8f..34463b3ae6a7ffe6c2b09799836f40621d9f6568 100644 --- a/cmake/configs/nuttx_crazyflie_default.cmake +++ b/cmake/configs/nuttx_crazyflie_default.cmake @@ -83,8 +83,6 @@ set(config_module_list lib/conversion lib/DriverFramework/framework lib/ecl - lib/geo - lib/geo_lookup lib/mathlib lib/mixer lib/rc diff --git a/cmake/configs/nuttx_mindpx-v2_default.cmake b/cmake/configs/nuttx_mindpx-v2_default.cmake index bae0a4d4d37b79609f429c5d08c3690680aa7e66..79984445825d3b92e2a7a500f21fb30ae841af35 100644 --- a/cmake/configs/nuttx_mindpx-v2_default.cmake +++ b/cmake/configs/nuttx_mindpx-v2_default.cmake @@ -129,8 +129,6 @@ set(config_module_list lib/conversion lib/DriverFramework/framework lib/ecl - lib/geo - lib/geo_lookup lib/led lib/mathlib lib/mixer diff --git a/cmake/configs/nuttx_nxphlite-v3_default.cmake b/cmake/configs/nuttx_nxphlite-v3_default.cmake index ef6193f3d0ee2d4d02808ba96d66222e7b782aeb..cb3e8ec69f128415b122c807a6016acfd45692bf 100644 --- a/cmake/configs/nuttx_nxphlite-v3_default.cmake +++ b/cmake/configs/nuttx_nxphlite-v3_default.cmake @@ -131,8 +131,6 @@ set(config_module_list # lib/controllib lib/ecl - lib/geo - lib/geo_lookup lib/conversion lib/led lib/mathlib diff --git a/cmake/configs/nuttx_px4-same70xplained-v1_default.cmake b/cmake/configs/nuttx_px4-same70xplained-v1_default.cmake index edc51b2d85aedaabf8cfc8acab1b97d8ea4fd4f7..0732983610a1206b6c1a8982cc9356bd32b0e191 100644 --- a/cmake/configs/nuttx_px4-same70xplained-v1_default.cmake +++ b/cmake/configs/nuttx_px4-same70xplained-v1_default.cmake @@ -106,8 +106,6 @@ set(config_module_list lib/conversion lib/DriverFramework/framework lib/ecl - lib/geo - lib/geo_lookup lib/led lib/mathlib lib/mixer diff --git a/cmake/configs/nuttx_px4-stm32f4discovery_default.cmake b/cmake/configs/nuttx_px4-stm32f4discovery_default.cmake index e7439dcccdc765f0f21dc09707c3f4e87a932241..9e8569cc5ddaef98dfc8aff53e1ec59bb690ac0c 100644 --- a/cmake/configs/nuttx_px4-stm32f4discovery_default.cmake +++ b/cmake/configs/nuttx_px4-stm32f4discovery_default.cmake @@ -38,7 +38,6 @@ set(config_module_list lib/conversion lib/DriverFramework/framework lib/ecl - lib/geo lib/mathlib lib/mixer lib/version diff --git a/cmake/configs/nuttx_px4fmu-v2_default.cmake b/cmake/configs/nuttx_px4fmu-v2_default.cmake index 0acc0c5bc0fceae54fc29d44de2343ea27355d3f..369fc556828046205f347064a336923238961282 100644 --- a/cmake/configs/nuttx_px4fmu-v2_default.cmake +++ b/cmake/configs/nuttx_px4fmu-v2_default.cmake @@ -153,8 +153,6 @@ set(config_module_list lib/conversion lib/DriverFramework/framework lib/ecl - lib/geo - lib/geo_lookup lib/led lib/mathlib lib/mixer diff --git a/cmake/configs/nuttx_px4fmu-v2_test.cmake b/cmake/configs/nuttx_px4fmu-v2_test.cmake index 7691814ed9f9769212a8a95bdcdc86af9748113a..19a297944455a0fc20c4aff6c8a97f46a04d9c79 100644 --- a/cmake/configs/nuttx_px4fmu-v2_test.cmake +++ b/cmake/configs/nuttx_px4fmu-v2_test.cmake @@ -125,8 +125,6 @@ set(config_module_list lib/conversion lib/DriverFramework/framework lib/ecl - lib/geo - lib/geo_lookup lib/led lib/mathlib lib/mixer diff --git a/cmake/configs/nuttx_px4fmu-v3_default.cmake b/cmake/configs/nuttx_px4fmu-v3_default.cmake index 116052d9c309f2afe70e80b113e836fea48ecb88..29f4ed00cd5a3a88a95edd7dc8c5e2702fabcf6c 100644 --- a/cmake/configs/nuttx_px4fmu-v3_default.cmake +++ b/cmake/configs/nuttx_px4fmu-v3_default.cmake @@ -142,8 +142,6 @@ set(config_module_list lib/conversion lib/DriverFramework/framework lib/ecl - lib/geo - lib/geo_lookup lib/led lib/mathlib lib/mixer diff --git a/cmake/configs/nuttx_px4fmu-v4_default.cmake b/cmake/configs/nuttx_px4fmu-v4_default.cmake index 33027f192bfd2a004c766a3017ed053a4d1ee969..84ecb505d21d57a4fcab4a336126e584b9c99755 100644 --- a/cmake/configs/nuttx_px4fmu-v4_default.cmake +++ b/cmake/configs/nuttx_px4fmu-v4_default.cmake @@ -129,8 +129,6 @@ set(config_module_list lib/conversion lib/DriverFramework/framework lib/ecl - lib/geo - lib/geo_lookup lib/led lib/mathlib lib/mixer diff --git a/cmake/configs/nuttx_px4fmu-v4pro_default.cmake b/cmake/configs/nuttx_px4fmu-v4pro_default.cmake index 4938208bbc1fcc8e997c1876f02f6f69f2875e38..6101762f631ed2308c533dc7cc3349264f27b84a 100644 --- a/cmake/configs/nuttx_px4fmu-v4pro_default.cmake +++ b/cmake/configs/nuttx_px4fmu-v4pro_default.cmake @@ -133,8 +133,6 @@ set(config_module_list lib/conversion lib/DriverFramework/framework lib/ecl - lib/geo - lib/geo_lookup lib/led lib/mathlib lib/mixer diff --git a/cmake/configs/nuttx_px4fmu-v5_default.cmake b/cmake/configs/nuttx_px4fmu-v5_default.cmake index 4a0df254d96ae0b3f2ae8dc422cfab8d0fabf106..2def3c25693b2b3912eff031ad27827d1918766f 100644 --- a/cmake/configs/nuttx_px4fmu-v5_default.cmake +++ b/cmake/configs/nuttx_px4fmu-v5_default.cmake @@ -134,8 +134,6 @@ set(config_module_list lib/conversion lib/DriverFramework/framework lib/ecl - lib/geo - lib/geo_lookup lib/led lib/mathlib lib/mixer diff --git a/cmake/configs/nuttx_px4nucleoF767ZI-v1_default.cmake b/cmake/configs/nuttx_px4nucleoF767ZI-v1_default.cmake index 3a2256e6f4b1f88ea99e8a39edbf329cf74e8970..5fb9d0957662b73682e668dc1aa3eb8ad5438fd2 100644 --- a/cmake/configs/nuttx_px4nucleoF767ZI-v1_default.cmake +++ b/cmake/configs/nuttx_px4nucleoF767ZI-v1_default.cmake @@ -112,8 +112,6 @@ set(config_module_list lib/conversion lib/DriverFramework/framework lib/ecl - lib/geo - lib/geo_lookup lib/led lib/mathlib lib/mixer diff --git a/cmake/configs/nuttx_tap-v1_default.cmake b/cmake/configs/nuttx_tap-v1_default.cmake index 5a3f44d1db79f11a8520346dabc7125228b7698e..a9b17bacab394fbedfd0e638805e0486b1d25ad1 100644 --- a/cmake/configs/nuttx_tap-v1_default.cmake +++ b/cmake/configs/nuttx_tap-v1_default.cmake @@ -89,8 +89,6 @@ set(config_module_list lib/conversion lib/DriverFramework/framework lib/ecl - lib/geo - lib/geo_lookup lib/led lib/mathlib lib/mixer diff --git a/cmake/configs/posix_bebop_default.cmake b/cmake/configs/posix_bebop_default.cmake index 07601f2c99276435964d9dd37df4d523723d8ac5..59fbb0d2bde8894ee57d776557b4da08fb0cd589 100644 --- a/cmake/configs/posix_bebop_default.cmake +++ b/cmake/configs/posix_bebop_default.cmake @@ -76,8 +76,6 @@ set(config_module_list lib/conversion lib/DriverFramework/framework lib/ecl - lib/geo - lib/geo_lookup lib/mathlib lib/mixer lib/terrain_estimation diff --git a/cmake/configs/posix_eagle_hil.cmake b/cmake/configs/posix_eagle_hil.cmake index bb26284e3691e027d45488ab37871d7185c45773..835e2509d559c5403ffa97d45d097b11cecafa98 100644 --- a/cmake/configs/posix_eagle_hil.cmake +++ b/cmake/configs/posix_eagle_hil.cmake @@ -41,8 +41,6 @@ set(config_module_list lib/controllib lib/mathlib lib/ecl - lib/geo - lib/geo_lookup lib/conversion lib/version lib/DriverFramework/framework diff --git a/cmake/configs/posix_ocpoc_cross.cmake b/cmake/configs/posix_ocpoc_cross.cmake index fb7d0b3a9908730b74b805ddb1d7e54ce0dd5ac1..67d9b0840bba9cafc8506d1e25329159cce42aab 100644 --- a/cmake/configs/posix_ocpoc_cross.cmake +++ b/cmake/configs/posix_ocpoc_cross.cmake @@ -84,8 +84,6 @@ set(config_module_list lib/conversion lib/DriverFramework/framework lib/ecl - lib/geo - lib/geo_lookup lib/led lib/mathlib lib/mixer diff --git a/cmake/configs/posix_ocpoc_ubuntu.cmake b/cmake/configs/posix_ocpoc_ubuntu.cmake index 8a8f3870ddf49d9928f3009ef4903200498511ba..bde798a136e54cd6a185a6fa197db1cfbfb64dce 100644 --- a/cmake/configs/posix_ocpoc_ubuntu.cmake +++ b/cmake/configs/posix_ocpoc_ubuntu.cmake @@ -83,8 +83,6 @@ set(config_module_list lib/conversion lib/DriverFramework/framework lib/ecl - lib/geo - lib/geo_lookup lib/led lib/mathlib lib/mixer diff --git a/cmake/configs/posix_rpi_common.cmake b/cmake/configs/posix_rpi_common.cmake index dff2fb5f4a4b6277f4f07597460a77f066121d91..658e0d896f5328bbb82a3f0762ecc0500e3af9e9 100644 --- a/cmake/configs/posix_rpi_common.cmake +++ b/cmake/configs/posix_rpi_common.cmake @@ -99,8 +99,6 @@ set(config_module_list lib/conversion lib/DriverFramework/framework lib/ecl - lib/geo - lib/geo_lookup lib/led lib/mathlib lib/mixer diff --git a/cmake/configs/posix_sdflight_default.cmake b/cmake/configs/posix_sdflight_default.cmake index dcb0a3beda5d00b135160e17d82e397afc661e79..516eff769c38c1dbc162c77c714e11e74b92a261 100644 --- a/cmake/configs/posix_sdflight_default.cmake +++ b/cmake/configs/posix_sdflight_default.cmake @@ -73,8 +73,6 @@ set(config_module_list lib/conversion lib/DriverFramework/framework lib/ecl - lib/geo - lib/geo_lookup lib/led lib/mathlib lib/mixer diff --git a/cmake/configs/posix_sdflight_legacy.cmake b/cmake/configs/posix_sdflight_legacy.cmake index 01aaa77fdb87c103cbe39ec4ccf51323d4648759..428136c26a3cb19c39f641469585bfdf829ce950 100644 --- a/cmake/configs/posix_sdflight_legacy.cmake +++ b/cmake/configs/posix_sdflight_legacy.cmake @@ -65,8 +65,6 @@ set(config_module_list lib/conversion lib/DriverFramework/framework lib/ecl - lib/geo - lib/geo_lookup lib/led lib/mathlib lib/mixer diff --git a/cmake/configs/posix_sitl_default.cmake b/cmake/configs/posix_sitl_default.cmake index 4a4842b28037c5b6651dfb62e9928090952ec48a..6dc5f271747540174d9e5d90d3fef88d1d8335fd 100644 --- a/cmake/configs/posix_sitl_default.cmake +++ b/cmake/configs/posix_sitl_default.cmake @@ -123,8 +123,6 @@ set(config_module_list lib/conversion lib/DriverFramework/framework lib/ecl - lib/geo - lib/geo_lookup lib/led lib/mixer lib/mathlib diff --git a/cmake/configs/posix_sitl_replay.cmake b/cmake/configs/posix_sitl_replay.cmake index 388451d61d4996e336dcae91e3e0ba436e7e1932..58130ad4a0d6df52729782d6927d244a096f0e0e 100644 --- a/cmake/configs/posix_sitl_replay.cmake +++ b/cmake/configs/posix_sitl_replay.cmake @@ -18,8 +18,6 @@ set(config_module_list lib/mathlib lib/conversion lib/ecl - lib/geo - lib/geo_lookup lib/version lib/DriverFramework/framework lib/micro-CDR diff --git a/cmake/configs/qurt_eagle_hil.cmake b/cmake/configs/qurt_eagle_hil.cmake index a43ed38ceee1276217dc7d4627d149cd59ccea2a..3c35798d366e13c1817f20b46e28d142963ac208 100644 --- a/cmake/configs/qurt_eagle_hil.cmake +++ b/cmake/configs/qurt_eagle_hil.cmake @@ -63,8 +63,6 @@ set(config_module_list lib/controllib lib/conversion lib/DriverFramework/framework - lib/geo - lib/geo_lookup lib/led lib/mathlib lib/mixer diff --git a/cmake/configs/qurt_eagle_muorb.cmake b/cmake/configs/qurt_eagle_muorb.cmake index 9ec8bd9e4dade7960e45e1f418900f9499bebb61..3e1c179d15cac99496316d150ca7c08e0e03dd72 100644 --- a/cmake/configs/qurt_eagle_muorb.cmake +++ b/cmake/configs/qurt_eagle_muorb.cmake @@ -38,8 +38,6 @@ set(config_module_list # Libraries # lib/mathlib - lib/geo - lib/geo_lookup lib/conversion lib/version lib/DriverFramework/framework diff --git a/cmake/configs/qurt_eagle_travis.cmake b/cmake/configs/qurt_eagle_travis.cmake index 5fb5bdc81de16361b73a5ad2cd53caafa0d46466..b690d823864572fa903e623098a238aab2a05604 100644 --- a/cmake/configs/qurt_eagle_travis.cmake +++ b/cmake/configs/qurt_eagle_travis.cmake @@ -69,8 +69,6 @@ set(config_module_list lib/conversion lib/DriverFramework/framework lib/ecl - lib/geo - lib/geo_lookup lib/led lib/mathlib lib/mixer diff --git a/cmake/configs/qurt_sdflight_default.cmake b/cmake/configs/qurt_sdflight_default.cmake index c7586f8fcb960baef3debf9666a50775425f0cde..673785129a6a46284ffa5fe4eb3041ad35f19c28 100644 --- a/cmake/configs/qurt_sdflight_default.cmake +++ b/cmake/configs/qurt_sdflight_default.cmake @@ -87,8 +87,6 @@ set(config_module_list lib/conversion lib/DriverFramework/framework lib/ecl - lib/geo - lib/geo_lookup lib/mathlib lib/mixer lib/rc diff --git a/cmake/configs/qurt_sdflight_legacy.cmake b/cmake/configs/qurt_sdflight_legacy.cmake index 9de21a4c7e6184b93df91753bd74d6ad73a52ab9..cc6fa2b3e10c6c127e3c0eee620eafe6b43536c9 100644 --- a/cmake/configs/qurt_sdflight_legacy.cmake +++ b/cmake/configs/qurt_sdflight_legacy.cmake @@ -86,8 +86,6 @@ set(config_module_list lib/conversion lib/DriverFramework/framework lib/ecl - lib/geo - lib/geo_lookup lib/mathlib lib/mixer lib/rc diff --git a/src/drivers/telemetry/frsky_telemetry/frsky_data.c b/src/drivers/telemetry/frsky_telemetry/frsky_data.c index dd2b83ef9838a6d8411ac77b3285fc44b759ad64..7d8c16bab7d2771ab001ec9499c29c0ec2d8f5d3 100644 --- a/src/drivers/telemetry/frsky_telemetry/frsky_data.c +++ b/src/drivers/telemetry/frsky_telemetry/frsky_data.c @@ -48,7 +48,7 @@ #include <string.h> #include <stdbool.h> #include <arch/math.h> -#include <geo/geo.h> +#include <lib/ecl/geo/geo.h> #include <stdbool.h> #include <uORB/topics/battery_status.h> diff --git a/src/drivers/telemetry/frsky_telemetry/sPort_data.c b/src/drivers/telemetry/frsky_telemetry/sPort_data.c index 5c737be1940ee2f7c2a46ad6d2ad818ee650430d..c68320e0d443bc832ac2b1e19078cfd2f4e5f2f9 100644 --- a/src/drivers/telemetry/frsky_telemetry/sPort_data.c +++ b/src/drivers/telemetry/frsky_telemetry/sPort_data.c @@ -48,7 +48,7 @@ #include <stdio.h> #include <string.h> #include <arch/math.h> -#include <geo/geo.h> +#include <lib/ecl/geo/geo.h> #include <uORB/topics/battery_status.h> #include <uORB/topics/sensor_combined.h> diff --git a/src/drivers/telemetry/hott/messages.cpp b/src/drivers/telemetry/hott/messages.cpp index 92b1664ccf6e8b4b9f2c56f05e9bc3bfebd68c49..86b14c54edae226b1695f7123d6a3a06003d5961 100644 --- a/src/drivers/telemetry/hott/messages.cpp +++ b/src/drivers/telemetry/hott/messages.cpp @@ -42,7 +42,7 @@ #include <math.h> #include <stdio.h> #include <string.h> -#include <geo/geo.h> +#include <lib/ecl/geo/geo.h> #include <unistd.h> #include <uORB/topics/airspeed.h> #include <uORB/topics/battery_status.h> diff --git a/src/drivers/vmount/output.cpp b/src/drivers/vmount/output.cpp index 020470d093c432e03ab585a92d2af920690f10fe..f3a1269b98d93e6ec077d4be7a57bacdf7ed0572 100644 --- a/src/drivers/vmount/output.cpp +++ b/src/drivers/vmount/output.cpp @@ -46,7 +46,7 @@ #include <uORB/topics/vehicle_global_position.h> #include <uORB/topics/mount_orientation.h> #include <px4_defines.h> -#include <geo/geo.h> +#include <lib/ecl/geo/geo.h> #include <math.h> #include <mathlib/mathlib.h> diff --git a/src/drivers/vmount/output.h b/src/drivers/vmount/output.h index 7589af45a3ccf9279716ee3a3a4b6c79b97de727..b54b58a63d25803e85add02da4b59672ca6106f4 100644 --- a/src/drivers/vmount/output.h +++ b/src/drivers/vmount/output.h @@ -41,7 +41,7 @@ #include "common.h" #include <drivers/drv_hrt.h> -#include <geo/geo.h> +#include <lib/ecl/geo/geo.h> #include <uORB/uORB.h> #include <uORB/topics/vehicle_global_position.h> diff --git a/src/examples/bottle_drop/bottle_drop.cpp b/src/examples/bottle_drop/bottle_drop.cpp index fb9256dbf7bb5c6a4486d6209d6165960cf8bac7..7ad7e0e3380c26d9ee0aca76f5cc2d3804718a86 100644 --- a/src/examples/bottle_drop/bottle_drop.cpp +++ b/src/examples/bottle_drop/bottle_drop.cpp @@ -64,7 +64,7 @@ #include <systemlib/param/param.h> #include <systemlib/err.h> #include <systemlib/mavlink_log.h> -#include <geo/geo.h> +#include <lib/ecl/geo/geo.h> #include <dataman/dataman.h> #include <mathlib/mathlib.h> diff --git a/src/examples/fixedwing_control/main.cpp b/src/examples/fixedwing_control/main.cpp index a5854638ca021d3ee7db16537d53931251e4e7aa..cc7cca3cd8292467c7244ebf13b7778edbf8de5d 100644 --- a/src/examples/fixedwing_control/main.cpp +++ b/src/examples/fixedwing_control/main.cpp @@ -47,7 +47,7 @@ #include <poll.h> #include <drivers/drv_hrt.h> -#include <geo/geo.h> +#include <lib/ecl/geo/geo.h> #include <matrix/math.hpp> #include <px4_config.h> #include <px4_tasks.h> diff --git a/src/examples/rover_steering_control/main.cpp b/src/examples/rover_steering_control/main.cpp index 51e7bb0dfb9aae2e019bd864ecbecd443d9d3a02..99da58a6073cea071a0ec714df5e88b68520d7c6 100644 --- a/src/examples/rover_steering_control/main.cpp +++ b/src/examples/rover_steering_control/main.cpp @@ -63,7 +63,7 @@ #include <uORB/topics/parameter_update.h> #include <systemlib/param/param.h> #include <systemlib/pid/pid.h> -#include <geo/geo.h> +#include <lib/ecl/geo/geo.h> #include <systemlib/perf_counter.h> #include <systemlib/err.h> #include <matrix/math.hpp> diff --git a/src/examples/segway/blocks.cpp b/src/examples/segway/blocks.cpp index a2611649b5b9440d0c9b85455ee0b2cfef1c0261..4874ba3471f38d09e8d2eca354367b2990c65068 100644 --- a/src/examples/segway/blocks.cpp +++ b/src/examples/segway/blocks.cpp @@ -38,7 +38,7 @@ */ #include "blocks.hpp" -#include <geo/geo.h> +#include <lib/ecl/geo/geo.h> namespace control { diff --git a/src/examples/uuv_example_app/uuv_example_app.cpp b/src/examples/uuv_example_app/uuv_example_app.cpp index 0d5a5f088f2e2c0df2b23c17ac939275956171e4..e77a7d1a7853c12aea32744531dbe599e2a9f358 100644 --- a/src/examples/uuv_example_app/uuv_example_app.cpp +++ b/src/examples/uuv_example_app/uuv_example_app.cpp @@ -58,7 +58,7 @@ #include <systemlib/circuit_breaker.h> // internal libraries #include <lib/mathlib/mathlib.h> -#include <lib/geo/geo.h> +#include <lib/ecl/geo/geo.h> // Include uORB and the required topics for this app #include <uORB/uORB.h> diff --git a/src/lib/ecl b/src/lib/ecl index 95c4777b355bf05b59b69cb97ae131a03cfec564..8caf52fb413aa148dbfe38b525dd293a42276e45 160000 --- a/src/lib/ecl +++ b/src/lib/ecl @@ -1 +1 @@ -Subproject commit 95c4777b355bf05b59b69cb97ae131a03cfec564 +Subproject commit 8caf52fb413aa148dbfe38b525dd293a42276e45 diff --git a/src/lib/geo/CMakeLists.txt b/src/lib/geo/CMakeLists.txt deleted file mode 100644 index 14b80ef2a565e217332dcd1a6664ad51dd5165fa..0000000000000000000000000000000000000000 --- a/src/lib/geo/CMakeLists.txt +++ /dev/null @@ -1,40 +0,0 @@ -############################################################################ -# -# Copyright (c) 2015 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 -# are met: -# -# 1. Redistributions of source code must retain the above copyright -# notice, this list of conditions and the following disclaimer. -# 2. Redistributions in binary form must reproduce the above copyright -# notice, this list of conditions and the following disclaimer in -# the documentation and/or other materials provided with the -# distribution. -# 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. -# -# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS -# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT -# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS -# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE -# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, -# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, -# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS -# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED -# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT -# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN -# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -# POSSIBILITY OF SUCH DAMAGE. -# -############################################################################ -px4_add_module( - MODULE lib__geo - SRCS - geo.c - DEPENDS - platforms__common - ) -# vim: set noet ft=cmake fenc=utf-8 ff=unix : diff --git a/src/lib/geo/geo.c b/src/lib/geo/geo.c deleted file mode 100644 index 37a595bb7e446bb362b5e74d9d45d47ea316f05e..0000000000000000000000000000000000000000 --- a/src/lib/geo/geo.c +++ /dev/null @@ -1,705 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2012-2014 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 - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 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. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** - * @file geo.c - * - * Geo / math functions to perform geodesic calculations - * - * @author Thomas Gubler <thomasgubler@student.ethz.ch> - * @author Julian Oes <joes@student.ethz.ch> - * @author Lorenz Meier <lm@inf.ethz.ch> - * @author Anton Babushkin <anton.babushkin@me.com> - */ - -#include <geo/geo.h> -#include <px4_config.h> -#include <unistd.h> -#include <pthread.h> -#include <stdio.h> -#include <math.h> -#include <stdbool.h> -#include <string.h> -#include <float.h> - -#include <systemlib/err.h> -#include <drivers/drv_hrt.h> - -/* - * Azimuthal Equidistant Projection - * formulas according to: http://mathworld.wolfram.com/AzimuthalEquidistantProjection.html - */ - -static struct map_projection_reference_s mp_ref = {0.0, 0.0, 0.0, 0.0, false, 0}; -static struct globallocal_converter_reference_s gl_ref = {0.0f, false}; - -__EXPORT bool map_projection_global_initialized() -{ - return map_projection_initialized(&mp_ref); -} - -__EXPORT bool map_projection_initialized(const struct map_projection_reference_s *ref) -{ - return ref->init_done; -} - -__EXPORT uint64_t map_projection_global_timestamp() -{ - return map_projection_timestamp(&mp_ref); -} - -__EXPORT uint64_t map_projection_timestamp(const struct map_projection_reference_s *ref) -{ - return ref->timestamp; -} - -__EXPORT int map_projection_global_init(double lat_0, double lon_0, - uint64_t timestamp) //lat_0, lon_0 are expected to be in correct format: -> 47.1234567 and not 471234567 -{ - return map_projection_init_timestamped(&mp_ref, lat_0, lon_0, timestamp); -} - -__EXPORT int map_projection_init_timestamped(struct map_projection_reference_s *ref, double lat_0, double lon_0, - uint64_t timestamp) //lat_0, lon_0 are expected to be in correct format: -> 47.1234567 and not 471234567 -{ - - ref->lat_rad = lat_0 * M_DEG_TO_RAD; - ref->lon_rad = lon_0 * M_DEG_TO_RAD; - ref->sin_lat = sin(ref->lat_rad); - ref->cos_lat = cos(ref->lat_rad); - - ref->timestamp = timestamp; - ref->init_done = true; - - return 0; -} - -__EXPORT int map_projection_init(struct map_projection_reference_s *ref, double lat_0, - double lon_0) //lat_0, lon_0 are expected to be in correct format: -> 47.1234567 and not 471234567 -{ - return map_projection_init_timestamped(ref, lat_0, lon_0, hrt_absolute_time()); -} - -__EXPORT 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); -} - -__EXPORT int map_projection_reference(const struct map_projection_reference_s *ref, double *ref_lat_rad, - double *ref_lon_rad) -{ - if (!map_projection_initialized(ref)) { - return -1; - } - - *ref_lat_rad = ref->lat_rad; - *ref_lon_rad = ref->lon_rad; - - return 0; -} - -__EXPORT int map_projection_global_project(double lat, double lon, float *x, float *y) -{ - return map_projection_project(&mp_ref, lat, lon, x, y); - -} - -__EXPORT int map_projection_project(const struct map_projection_reference_s *ref, double lat, double lon, float *x, - float *y) -{ - if (!map_projection_initialized(ref)) { - return -1; - } - - double lat_rad = lat * M_DEG_TO_RAD; - double lon_rad = lon * M_DEG_TO_RAD; - - double sin_lat = sin(lat_rad); - double cos_lat = cos(lat_rad); - double cos_d_lon = cos(lon_rad - ref->lon_rad); - - double arg = ref->sin_lat * sin_lat + ref->cos_lat * cos_lat * cos_d_lon; - - if (arg > 1.0) { - arg = 1.0; - - } else if (arg < -1.0) { - arg = -1.0; - } - - double c = acos(arg); - double k = (fabs(c) < DBL_EPSILON) ? 1.0 : (c / sin(c)); - - *x = k * (ref->cos_lat * sin_lat - ref->sin_lat * cos_lat * cos_d_lon) * CONSTANTS_RADIUS_OF_EARTH; - *y = k * cos_lat * sin(lon_rad - ref->lon_rad) * CONSTANTS_RADIUS_OF_EARTH; - - return 0; -} - -__EXPORT int map_projection_global_reproject(float x, float y, double *lat, double *lon) -{ - return map_projection_reproject(&mp_ref, x, y, lat, lon); -} - -__EXPORT int map_projection_reproject(const struct map_projection_reference_s *ref, float x, float y, double *lat, - double *lon) -{ - if (!map_projection_initialized(ref)) { - return -1; - } - - double x_rad = (double)x / CONSTANTS_RADIUS_OF_EARTH; - double y_rad = (double)y / CONSTANTS_RADIUS_OF_EARTH; - double c = sqrtf(x_rad * x_rad + y_rad * y_rad); - double sin_c = sin(c); - double cos_c = cos(c); - - double lat_rad; - double lon_rad; - - if (fabs(c) > DBL_EPSILON) { - lat_rad = asin(cos_c * ref->sin_lat + (x_rad * sin_c * ref->cos_lat) / c); - lon_rad = (ref->lon_rad + atan2(y_rad * sin_c, c * ref->cos_lat * cos_c - x_rad * ref->sin_lat * sin_c)); - - } else { - lat_rad = ref->lat_rad; - lon_rad = ref->lon_rad; - } - - *lat = lat_rad * 180.0 / M_PI; - *lon = lon_rad * 180.0 / M_PI; - - return 0; -} - -__EXPORT int map_projection_global_getref(double *lat_0, double *lon_0) -{ - if (!map_projection_global_initialized()) { - return -1; - } - - if (lat_0 != NULL) { - *lat_0 = M_RAD_TO_DEG * mp_ref.lat_rad; - } - - if (lon_0 != NULL) { - *lon_0 = M_RAD_TO_DEG * mp_ref.lon_rad; - } - - return 0; - -} -__EXPORT 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; - - } else { - gl_ref.init_done = false; - return -1; - } -} - -__EXPORT bool globallocalconverter_initialized() -{ - return gl_ref.init_done && map_projection_global_initialized(); -} - -__EXPORT 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; -} - -__EXPORT 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; -} - -__EXPORT int globallocalconverter_getref(double *lat_0, double *lon_0, float *alt_0) -{ - if (!map_projection_global_initialized()) { - return -1; - } - - if (map_projection_global_getref(lat_0, lon_0)) { - return -1; - } - - if (alt_0 != NULL) { - *alt_0 = gl_ref.alt; - } - - return 0; -} - -__EXPORT float get_distance_to_next_waypoint(double lat_now, double lon_now, double lat_next, double lon_next) -{ - double lat_now_rad = lat_now / (double)180.0 * M_PI; - double lon_now_rad = lon_now / (double)180.0 * M_PI; - double lat_next_rad = lat_next / (double)180.0 * M_PI; - double lon_next_rad = lon_next / (double)180.0 * M_PI; - - - double d_lat = lat_next_rad - lat_now_rad; - double d_lon = lon_next_rad - lon_now_rad; - - double a = sin(d_lat / (double)2.0) * sin(d_lat / (double)2.0) + sin(d_lon / (double)2.0) * sin(d_lon / - (double)2.0) * cos(lat_now_rad) * cos(lat_next_rad); - double c = (double)2.0 * atan2(sqrt(a), sqrt((double)1.0 - a)); - - return CONSTANTS_RADIUS_OF_EARTH * c; -} - -__EXPORT 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) -{ - if (fabsf(dist) < FLT_EPSILON) { - *lat_target = lat_A; - *lon_target = lon_A; - - } else if (dist >= FLT_EPSILON) { - 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); - - } else { - float heading = get_bearing_to_next_waypoint(lat_A, lon_A, lat_B, lon_B); - heading = _wrap_2pi(heading + M_PI_F); - waypoint_from_heading_and_distance(lat_A, lon_A, heading, dist, lat_target, lon_target); - } -} - -__EXPORT void waypoint_from_heading_and_distance(double lat_start, double lon_start, float bearing, float dist, - double *lat_target, double *lon_target) -{ - bearing = _wrap_2pi(bearing); - double radius_ratio = fabs((double)dist) / CONSTANTS_RADIUS_OF_EARTH; - - double lat_start_rad = lat_start * M_DEG_TO_RAD; - double lon_start_rad = lon_start * M_DEG_TO_RAD; - - *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)); - - *lat_target *= M_RAD_TO_DEG; - *lon_target *= M_RAD_TO_DEG; -} -__EXPORT float get_bearing_to_next_waypoint(double lat_now, double lon_now, double lat_next, double lon_next) -{ - double lat_now_rad = lat_now * M_DEG_TO_RAD; - double lon_now_rad = lon_now * M_DEG_TO_RAD; - double lat_next_rad = lat_next * M_DEG_TO_RAD; - double lon_next_rad = lon_next * M_DEG_TO_RAD; - - double d_lon = lon_next_rad - lon_now_rad; - - /* conscious mix of double and float trig function to maximize speed and efficiency */ - float theta = atan2f(sin(d_lon) * cos(lat_next_rad), - cos(lat_now_rad) * sin(lat_next_rad) - sin(lat_now_rad) * cos(lat_next_rad) * cos(d_lon)); - - theta = _wrap_pi(theta); - - return theta; -} - -__EXPORT void get_vector_to_next_waypoint(double lat_now, double lon_now, double lat_next, double lon_next, float *v_n, - float *v_e) -{ - double lat_now_rad = lat_now * M_DEG_TO_RAD; - double lon_now_rad = lon_now * M_DEG_TO_RAD; - double lat_next_rad = lat_next * M_DEG_TO_RAD; - double lon_next_rad = lon_next * M_DEG_TO_RAD; - - double d_lon = lon_next_rad - lon_now_rad; - - /* conscious mix of double and float trig function to maximize speed and efficiency */ - *v_n = 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 = CONSTANTS_RADIUS_OF_EARTH * sin(d_lon) * cos(lat_next_rad); -} - -__EXPORT 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) -{ - double lat_now_rad = lat_now * M_DEG_TO_RAD; - double lon_now_rad = lon_now * M_DEG_TO_RAD; - double lat_next_rad = lat_next * M_DEG_TO_RAD; - double lon_next_rad = lon_next * M_DEG_TO_RAD; - - double d_lat = lat_next_rad - lat_now_rad; - double d_lon = lon_next_rad - lon_now_rad; - - /* conscious mix of double and float trig function to maximize speed and efficiency */ - *v_n = CONSTANTS_RADIUS_OF_EARTH * d_lat; - *v_e = CONSTANTS_RADIUS_OF_EARTH * d_lon * cos(lat_now_rad); -} - -__EXPORT 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 = lat_now * M_DEG_TO_RAD; - double lon_now_rad = lon_now * M_DEG_TO_RAD; - - *lat_res = (lat_now_rad + (double)v_n / CONSTANTS_RADIUS_OF_EARTH) * M_RAD_TO_DEG; - *lon_res = (lon_now_rad + (double)v_e / (CONSTANTS_RADIUS_OF_EARTH * cos(lat_now_rad))) * M_RAD_TO_DEG; -} - -// Additional functions - @author Doug Weibel <douglas.weibel@colorado.edu> - -__EXPORT 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) -{ -// This function returns the distance to the nearest point on the track line. Distance is positive if current -// position is right of the track and negative if left of the track as seen from a point on the track line -// headed towards the end point. - - float dist_to_end; - float bearing_end; - float bearing_track; - float bearing_diff; - - int return_value = ERROR; // Set error flag, cleared when valid result calculated. - crosstrack_error->past_end = false; - crosstrack_error->distance = 0.0f; - crosstrack_error->bearing = 0.0f; - - dist_to_end = get_distance_to_next_waypoint(lat_now, lon_now, lat_end, lon_end); - - // Return error if arguments are bad - if (dist_to_end < 0.1f) { - return ERROR; - } - - bearing_end = get_bearing_to_next_waypoint(lat_now, lon_now, lat_end, lon_end); - bearing_track = get_bearing_to_next_waypoint(lat_start, lon_start, lat_end, lon_end); - bearing_diff = bearing_track - bearing_end; - bearing_diff = _wrap_pi(bearing_diff); - - // Return past_end = true if past end point of line - if (bearing_diff > M_PI_2_F || bearing_diff < -M_PI_2_F) { - crosstrack_error->past_end = true; - return_value = OK; - return return_value; - } - - crosstrack_error->distance = (dist_to_end) * sinf(bearing_diff); - - if (sinf(bearing_diff) >= 0) { - crosstrack_error->bearing = _wrap_pi(bearing_track - M_PI_2_F); - - } else { - crosstrack_error->bearing = _wrap_pi(bearing_track + M_PI_2_F); - } - - return_value = OK; - - return return_value; - -} - - -__EXPORT 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) -{ - // This function returns the distance to the nearest point on the track arc. Distance is positive if current - // position is right of the arc and negative if left of the arc as seen from the closest point on the arc and - // headed towards the end point. - - // Determine if the current position is inside or outside the sector between the line from the center - // to the arc start and the line from the center to the arc end - float bearing_sector_start; - float bearing_sector_end; - float bearing_now = get_bearing_to_next_waypoint(lat_now, lon_now, lat_center, lon_center); - bool in_sector; - - int return_value = ERROR; // Set error flag, cleared when valid result calculated. - crosstrack_error->past_end = false; - crosstrack_error->distance = 0.0f; - crosstrack_error->bearing = 0.0f; - - // Return error if arguments are bad - if (radius < 0.1f) { return return_value; } - - - if (arc_sweep >= 0.0f) { - bearing_sector_start = arc_start_bearing; - bearing_sector_end = arc_start_bearing + arc_sweep; - - if (bearing_sector_end > 2.0f * M_PI_F) { bearing_sector_end -= M_TWOPI_F; } - - } else { - bearing_sector_end = arc_start_bearing; - bearing_sector_start = arc_start_bearing - arc_sweep; - - if (bearing_sector_start < 0.0f) { bearing_sector_start += M_TWOPI_F; } - } - - in_sector = false; - - // Case where sector does not span zero - if (bearing_sector_end >= bearing_sector_start && bearing_now >= bearing_sector_start - && bearing_now <= bearing_sector_end) { in_sector = true; } - - // Case where sector does span zero - if (bearing_sector_end < bearing_sector_start && (bearing_now > bearing_sector_start - || bearing_now < bearing_sector_end)) { in_sector = true; } - - // If in the sector then calculate distance and bearing to closest point - if (in_sector) { - crosstrack_error->past_end = false; - float dist_to_center = get_distance_to_next_waypoint(lat_now, lon_now, lat_center, lon_center); - - if (dist_to_center <= radius) { - crosstrack_error->distance = radius - dist_to_center; - crosstrack_error->bearing = bearing_now + M_PI_F; - - } else { - crosstrack_error->distance = dist_to_center - radius; - crosstrack_error->bearing = bearing_now; - } - - // If out of the sector then calculate dist and bearing to start or end point - - } else { - - // Use the approximation that 111,111 meters in the y direction is 1 degree (of latitude) - // and 111,111 * cos(latitude) meters in the x direction is 1 degree (of longitude) to - // calculate the position of the start and end points. We should not be doing this often - // as this function generally will not be called repeatedly when we are out of the sector. - - double start_disp_x = (double)radius * sin((double)arc_start_bearing); - double start_disp_y = (double)radius * cos((double)arc_start_bearing); - double end_disp_x = (double)radius * sin((double)_wrap_pi((double)(arc_start_bearing + arc_sweep))); - double end_disp_y = (double)radius * cos((double)_wrap_pi((double)(arc_start_bearing + arc_sweep))); - double lon_start = lon_now + start_disp_x / 111111.0; - double lat_start = lat_now + start_disp_y * cos(lat_now) / 111111.0; - double lon_end = lon_now + end_disp_x / 111111.0; - double lat_end = lat_now + end_disp_y * cos(lat_now) / 111111.0; - double dist_to_start = get_distance_to_next_waypoint(lat_now, lon_now, lat_start, lon_start); - double dist_to_end = get_distance_to_next_waypoint(lat_now, lon_now, lat_end, lon_end); - - - if (dist_to_start < dist_to_end) { - crosstrack_error->distance = dist_to_start; - crosstrack_error->bearing = get_bearing_to_next_waypoint(lat_now, lon_now, lat_start, lon_start); - - } else { - crosstrack_error->past_end = true; - crosstrack_error->distance = dist_to_end; - crosstrack_error->bearing = get_bearing_to_next_waypoint(lat_now, lon_now, lat_end, lon_end); - } - - } - - crosstrack_error->bearing = _wrap_pi((double)crosstrack_error->bearing); - return_value = OK; - return return_value; -} - -__EXPORT float get_distance_to_point_global_wgs84(double lat_now, double lon_now, float alt_now, - double lat_next, double lon_next, float alt_next, - float *dist_xy, float *dist_z) -{ - double current_x_rad = lat_next / 180.0 * M_PI; - double current_y_rad = lon_next / 180.0 * M_PI; - double x_rad = lat_now / 180.0 * M_PI; - double y_rad = lon_now / 180.0 * M_PI; - - double d_lat = x_rad - current_x_rad; - double d_lon = y_rad - current_y_rad; - - double a = sin(d_lat / 2.0) * sin(d_lat / 2.0) + sin(d_lon / 2.0) * sin(d_lon / 2.0) * cos(current_x_rad) * cos(x_rad); - double c = 2 * atan2(sqrt(a), sqrt(1 - a)); - - float dxy = CONSTANTS_RADIUS_OF_EARTH * c; - float dz = alt_now - alt_next; - - *dist_xy = fabsf(dxy); - *dist_z = fabsf(dz); - - return sqrtf(dxy * dxy + dz * dz); -} - - -__EXPORT float mavlink_wpm_distance_to_point_local(float x_now, float y_now, float z_now, - float x_next, float y_next, float z_next, - float *dist_xy, float *dist_z) -{ - float dx = x_now - x_next; - float dy = y_now - y_next; - float dz = z_now - z_next; - - *dist_xy = sqrtf(dx * dx + dy * dy); - *dist_z = fabsf(dz); - - return sqrtf(dx * dx + dy * dy + dz * dz); -} - -__EXPORT float _wrap_pi(float bearing) -{ - /* value is inf or NaN */ - if (!isfinite(bearing)) { - return bearing; - } - - int c = 0; - - while (bearing >= M_PI_F) { - bearing -= M_TWOPI_F; - - if (c++ > 3) { - return NAN; - } - } - - c = 0; - - while (bearing < -M_PI_F) { - bearing += M_TWOPI_F; - - if (c++ > 3) { - return NAN; - } - } - - return bearing; -} - -__EXPORT float _wrap_2pi(float bearing) -{ - /* value is inf or NaN */ - if (!isfinite(bearing)) { - return bearing; - } - - int c = 0; - - while (bearing >= M_TWOPI_F) { - bearing -= M_TWOPI_F; - - if (c++ > 3) { - return NAN; - } - } - - c = 0; - - while (bearing < 0.0f) { - bearing += M_TWOPI_F; - - if (c++ > 3) { - return NAN; - } - } - - return bearing; -} - -__EXPORT float _wrap_180(float bearing) -{ - /* value is inf or NaN */ - if (!isfinite(bearing)) { - return bearing; - } - - int c = 0; - - while (bearing >= 180.0f) { - bearing -= 360.0f; - - if (c++ > 3) { - return NAN; - } - } - - c = 0; - - while (bearing < -180.0f) { - bearing += 360.0f; - - if (c++ > 3) { - return NAN; - } - } - - return bearing; -} - -__EXPORT float _wrap_360(float bearing) -{ - /* value is inf or NaN */ - if (!isfinite(bearing)) { - return bearing; - } - - int c = 0; - - while (bearing >= 360.0f) { - bearing -= 360.0f; - - if (c++ > 3) { - return NAN; - } - } - - c = 0; - - while (bearing < 0.0f) { - bearing += 360.0f; - - if (c++ > 3) { - return NAN; - } - } - - return bearing; -} diff --git a/src/lib/geo/geo.h b/src/lib/geo/geo.h deleted file mode 100644 index d077e00524f32d0eda42dc8576c1f74b1ebc2341..0000000000000000000000000000000000000000 --- a/src/lib/geo/geo.h +++ /dev/null @@ -1,315 +0,0 @@ -/**************************************************************************** - * - * Copyright (C) 2012, 2014 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 - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 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. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** - * @file geo.h - * - * Definition of geo / math functions to perform geodesic calculations - * - * @author Thomas Gubler <thomasgubler@student.ethz.ch> - * @author Julian Oes <joes@student.ethz.ch> - * @author Lorenz Meier <lm@inf.ethz.ch> - * @author Anton Babushkin <anton.babushkin@me.com> - * Additional functions - @author Doug Weibel <douglas.weibel@colorado.edu> - */ - -#pragma once -#include <platforms/px4_defines.h> - -#include "geo_lookup/geo_mag_declination.h" - -#include <stdbool.h> - -#define CONSTANTS_ONE_G 9.80665f /* m/s^2 */ -#define CONSTANTS_AIR_DENSITY_SEA_LEVEL_15C 1.225f /* kg/m^3 */ -#define CONSTANTS_AIR_GAS_CONST 287.1f /* J/(kg * K) */ -#define CONSTANTS_ABSOLUTE_NULL_CELSIUS -273.15f /* °C */ -#define CONSTANTS_RADIUS_OF_EARTH 6371000 /* meters (m) */ - -// XXX remove -struct crosstrack_error_s { - bool past_end; // Flag indicating we are past the end of the line/arc segment - float distance; // Distance in meters to closest point on line/arc - float bearing; // Bearing in radians to closest point on line/arc -} ; - -/* lat/lon are in radians */ -struct map_projection_reference_s { - uint64_t timestamp; - double lat_rad; - double lon_rad; - double sin_lat; - double cos_lat; - bool init_done; -}; - -struct globallocal_converter_reference_s { - float alt; - bool init_done; -}; - -__BEGIN_DECLS - -/** - * Checks if global projection was initialized - * @return true if map was initialized before, false else - */ -__EXPORT bool map_projection_global_initialized(void); - -/** - * Checks if projection given as argument was initialized - * @return true if map was initialized before, false else - */ -__EXPORT bool map_projection_initialized(const struct map_projection_reference_s *ref); - -/** - * Get the timestamp of the global map projection - * @return the timestamp of the map_projection - */ -__EXPORT uint64_t map_projection_global_timestamp(void); - -/** - * Get the timestamp of the map projection given by the argument - * @return the timestamp of the map_projection - */ -__EXPORT uint64_t map_projection_timestamp(const struct map_projection_reference_s *ref); - -/** - * Writes the reference values of the global projection to ref_lat and ref_lon - * @return 0 if map_projection_init was called before, -1 else - */ -__EXPORT int map_projection_global_reference(double *ref_lat_rad, double *ref_lon_rad); - -/** - * Writes the reference values of the projection given by the argument to ref_lat and ref_lon - * @return 0 if map_projection_init was called before, -1 else - */ -__EXPORT int map_projection_reference(const struct map_projection_reference_s *ref, double *ref_lat_rad, - double *ref_lon_rad); - -/** - * Initializes the global map transformation. - * - * Initializes the transformation between the geographic coordinate system and - * the azimuthal equidistant plane - * @param lat in degrees (47.1234567°, not 471234567°) - * @param lon in degrees (8.1234567°, not 81234567°) - */ -__EXPORT int map_projection_global_init(double lat_0, double lon_0, uint64_t timestamp); - -/** - * Initializes the map transformation given by the argument. - * - * Initializes the transformation between the geographic coordinate system and - * the azimuthal equidistant plane - * @param lat in degrees (47.1234567°, not 471234567°) - * @param lon in degrees (8.1234567°, not 81234567°) - */ -__EXPORT 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. - * - * Initializes the transformation between the geographic coordinate system and - * the azimuthal equidistant plane - * @param lat in degrees (47.1234567°, not 471234567°) - * @param lon in degrees (8.1234567°, not 81234567°) - */ -__EXPORT int map_projection_init(struct map_projection_reference_s *ref, double lat_0, double lon_0); - -/** - * Transforms a point in the geographic coordinate system to the local - * azimuthal equidistant plane using the global projection - * @param x north - * @param y east - * @param lat in degrees (47.1234567°, not 471234567°) - * @param lon in degrees (8.1234567°, not 81234567°) - * @return 0 if map_projection_init was called before, -1 else - */ -__EXPORT int map_projection_global_project(double lat, double lon, float *x, float *y); - - -/* Transforms a point in the geographic coordinate system to the local - * azimuthal equidistant plane using the projection given by the argument -* @param x north -* @param y east -* @param lat in degrees (47.1234567°, not 471234567°) -* @param lon in degrees (8.1234567°, not 81234567°) -* @return 0 if map_projection_init was called before, -1 else -*/ -__EXPORT int map_projection_project(const struct map_projection_reference_s *ref, double lat, double lon, float *x, - float *y); - -/** - * Transforms a point in the local azimuthal equidistant plane to the - * geographic coordinate system using the global projection - * - * @param x north - * @param y east - * @param lat in degrees (47.1234567°, not 471234567°) - * @param lon in degrees (8.1234567°, not 81234567°) - * @return 0 if map_projection_init was called before, -1 else - */ -__EXPORT int map_projection_global_reproject(float x, float y, double *lat, double *lon); - -/** - * Transforms a point in the local azimuthal equidistant plane to the - * geographic coordinate system using the projection given by the argument - * - * @param x north - * @param y east - * @param lat in degrees (47.1234567°, not 471234567°) - * @param lon in degrees (8.1234567°, not 81234567°) - * @return 0 if map_projection_init was called before, -1 else - */ -__EXPORT int map_projection_reproject(const struct map_projection_reference_s *ref, float x, float y, double *lat, - double *lon); - -/** - * Get reference position of the global map projection - */ -__EXPORT int map_projection_global_getref(double *lat_0, double *lon_0); - -/** - * Initialize the global mapping between global position (spherical) and local position (NED). - */ -__EXPORT int globallocalconverter_init(double lat_0, double lon_0, float alt_0, uint64_t timestamp); - -/** - * Checks if globallocalconverter was initialized - * @return true if map was initialized before, false else - */ -__EXPORT bool globallocalconverter_initialized(void); - -/** - * Convert from global position coordinates to local position coordinates using the global reference - */ -__EXPORT int globallocalconverter_tolocal(double lat, double lon, float alt, float *x, float *y, float *z); - -/** - * Convert from local position coordinates to global position coordinates using the global reference - */ -__EXPORT int globallocalconverter_toglobal(float x, float y, float z, double *lat, double *lon, float *alt); - -/** - * Get reference position of the global to local converter - */ -__EXPORT int globallocalconverter_getref(double *lat_0, double *lon_0, float *alt_0); - -/** - * Returns the distance to the next waypoint in meters. - * - * @param lat_now current position in degrees (47.1234567°, not 471234567°) - * @param lon_now current position in degrees (8.1234567°, not 81234567°) - * @param lat_next next waypoint position in degrees (47.1234567°, not 471234567°) - * @param lon_next next waypoint position in degrees (8.1234567°, not 81234567°) - */ -__EXPORT float get_distance_to_next_waypoint(double lat_now, double lon_now, double lat_next, double lon_next); - - -/** - * Creates a new waypoint C on the line of two given waypoints (A, B) at certain distance - * from waypoint A - * - * @param lat_A waypoint A latitude in degrees (47.1234567°, not 471234567°) - * @param lon_A waypoint A longitude in degrees (8.1234567°, not 81234567°) - * @param lat_B waypoint B latitude in degrees (47.1234567°, not 471234567°) - * @param lon_B waypoint B longitude in degrees (8.1234567°, not 81234567°) - * @param dist distance of target waypoint from waypoint A in meters (can be negative) - * @param lat_target latitude of target waypoint C in degrees (47.1234567°, not 471234567°) - * @param lon_target longitude of target waypoint C in degrees (47.1234567°, not 471234567°) - */ -__EXPORT 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); - -/** - * Creates a waypoint from given waypoint, distance and bearing - * see http://www.movable-type.co.uk/scripts/latlong.html - * - * @param lat_start latitude of starting waypoint in degrees (47.1234567°, not 471234567°) - * @param lon_start longitude of starting waypoint in degrees (8.1234567°, not 81234567°) - * @param bearing in rad - * @param distance in meters - * @param lat_target latitude of target waypoint in degrees (47.1234567°, not 471234567°) - * @param lon_target longitude of target waypoint in degrees (47.1234567°, not 471234567°) - */ -__EXPORT void waypoint_from_heading_and_distance(double lat_start, double lon_start, float bearing, float dist, - double *lat_target, double *lon_target); - -/** - * Returns the bearing to the next waypoint in radians. - * - * @param lat_now current position in degrees (47.1234567°, not 471234567°) - * @param lon_now current position in degrees (8.1234567°, not 81234567°) - * @param lat_next next waypoint position in degrees (47.1234567°, not 471234567°) - * @param lon_next next waypoint position in degrees (8.1234567°, not 81234567°) - */ -__EXPORT float get_bearing_to_next_waypoint(double lat_now, double lon_now, double lat_next, double lon_next); - -__EXPORT void get_vector_to_next_waypoint(double lat_now, double lon_now, double lat_next, double lon_next, float *v_n, - float *v_e); - -__EXPORT 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); - -__EXPORT void add_vector_to_global_position(double lat_now, double lon_now, float v_n, float v_e, double *lat_res, - double *lon_res); - -__EXPORT 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); - -__EXPORT 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); - -/* - * Calculate distance in global frame - */ -__EXPORT float get_distance_to_point_global_wgs84(double lat_now, double lon_now, float alt_now, - double lat_next, double lon_next, float alt_next, - float *dist_xy, float *dist_z); - -/* - * Calculate distance in local frame (NED) - */ -__EXPORT float mavlink_wpm_distance_to_point_local(float x_now, float y_now, float z_now, - float x_next, float y_next, float z_next, - float *dist_xy, float *dist_z); - -__EXPORT float _wrap_180(float bearing); -__EXPORT float _wrap_360(float bearing); -__EXPORT float _wrap_pi(float bearing); -__EXPORT float _wrap_2pi(float bearing); - -__END_DECLS diff --git a/src/lib/geo_lookup/CMakeLists.txt b/src/lib/geo_lookup/CMakeLists.txt deleted file mode 100644 index c28e724bb94fb0c33e84ebb52bc04cb33e0eb2bd..0000000000000000000000000000000000000000 --- a/src/lib/geo_lookup/CMakeLists.txt +++ /dev/null @@ -1,41 +0,0 @@ -############################################################################ -# -# Copyright (c) 2015 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 -# are met: -# -# 1. Redistributions of source code must retain the above copyright -# notice, this list of conditions and the following disclaimer. -# 2. Redistributions in binary form must reproduce the above copyright -# notice, this list of conditions and the following disclaimer in -# the documentation and/or other materials provided with the -# distribution. -# 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. -# -# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS -# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT -# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS -# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE -# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, -# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, -# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS -# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED -# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT -# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN -# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -# POSSIBILITY OF SUCH DAMAGE. -# -############################################################################ -px4_add_module( - MODULE lib__geo_lookup - COMPILE_FLAGS - SRCS - geo_mag_declination.c - DEPENDS - platforms__common - ) -# vim: set noet ft=cmake fenc=utf-8 ff=unix : diff --git a/src/lib/geo_lookup/geo_mag_declination.c b/src/lib/geo_lookup/geo_mag_declination.c deleted file mode 100644 index 0ec1a80cf2c6e87d146bcdb647e38266202523e9..0000000000000000000000000000000000000000 --- a/src/lib/geo_lookup/geo_mag_declination.c +++ /dev/null @@ -1,135 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2014 MAV GEO Library (MAVGEO). All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name MAVGEO nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** -* @file geo_mag_declination.c -* -* Calculation / lookup table for Earth's magnetic field declination. -* -* Lookup table from Scott Ferguson <scottfromscott@gmail.com> and -* Stephan Brown <stephan.brown.07@gmail.com> -* -* XXX Lookup table currently too coarse in resolution (only full degrees) -* and lat/lon res - needs extension medium term. -* -*/ - -#include <stdint.h> -#include "geo_mag_declination.h" - -/** set this always to the sampling in degrees for the table below */ -#define SAMPLING_RES 10.0f -#define SAMPLING_MIN_LAT -60.0f -#define SAMPLING_MAX_LAT 60.0f -#define SAMPLING_MIN_LON -180.0f -#define SAMPLING_MAX_LON 180.0f - -#define constrain(val, min, max) (val < min) ? min : ((val > max) ? max : val) - -static const int8_t declination_table[13][37] = \ -{ - { 47, 45, 44, 43, 41, 40, 38, 36, 33, 28, 23, 16, 10, 4, -1, -5, -9, -14, -19, -26, -33, -41, -48, -55, -61, -67, -71, -74, -75, -72, -61, -23, 23, 41, 46, 47, 47 }, - { 30, 30, 30, 30, 30, 29, 29, 29, 27, 23, 18, 11, 3, -3, -9, -12, -15, -17, -21, -26, -32, -39, -46, -51, -55, -57, -56, -52, -44, -31, -14, 1, 13, 21, 26, 29, 30 }, - { 22, 22, 22, 22, 22, 22, 22, 22, 21, 18, 13, 5, -3, -11, -17, -20, -21, -22, -23, -25, -29, -35, -40, -44, -45, -44, -39, -31, -21, -11, -3, 3, 9, 14, 18, 20, 22 }, - { 16, 17, 17, 17, 17, 16, 16, 16, 15, 13, 8, 0, -9, -17, -22, -24, -25, -24, -22, -20, -21, -24, -29, -31, -31, -28, -23, -16, -9, -3, 0, 4, 7, 10, 13, 15, 16 }, - { 12, 13, 13, 13, 13, 13, 12, 12, 11, 9, 3, -4, -13, -19, -23, -24, -24, -21, -17, -12, -9, -10, -14, -17, -18, -16, -12, -8, -3, 0, 1, 3, 5, 8, 10, 12, 12 }, - { 10, 10, 10, 10, 10, 10, 10, 9, 8, 5, 0, -7, -15, -20, -22, -22, -19, -15, -10, -5, -2, -1, -4, -7, -8, -8, -6, -3, 0, 0, 1, 2, 4, 6, 8, 10, 10 }, - { 9, 9, 9, 9, 9, 9, 8, 8, 7, 3, -2, -9, -15, -19, -20, -17, -13, -9, -5, -2, 0, 1, 0, -2, -3, -4, -3, -2, 0, 0, 0, 1, 2, 5, 7, 8, 9 }, - { 8, 8, 8, 9, 9, 9, 8, 7, 5, 1, -3, -10, -15, -17, -17, -14, -10, -5, -2, 0, 1, 2, 2, 0, -1, -1, -1, -1, 0, 0, 0, 0, 0, 3, 5, 7, 8 }, - { 8, 8, 9, 9, 10, 10, 9, 8, 5, 0, -5, -11, -15, -16, -15, -11, -7, -3, -1, 0, 2, 3, 3, 1, 0, 0, 0, 0, 0, -1, -2, -3, -2, 0, 3, 6, 8 }, - { 6, 8, 10, 11, 12, 12, 11, 9, 5, 0, -7, -12, -15, -15, -13, -10, -6, -3, 0, 1, 3, 4, 4, 3, 2, 1, 1, 0, -1, -3, -5, -6, -5, -3, 0, 3, 6 }, - { 5, 8, 11, 13, 14, 15, 13, 10, 5, -1, -9, -14, -16, -16, -13, -10, -6, -3, 0, 2, 3, 5, 5, 5, 5, 4, 3, 1, -1, -4, -7, -9, -8, -6, -2, 1, 5 }, - { 3, 8, 12, 15, 17, 17, 16, 12, 5, -3, -12, -18, -20, -19, -16, -12, -8, -4, 0, 2, 4, 7, 8, 9, 10, 9, 7, 3, -1, -6, -10, -12, -11, -9, -5, 0, 3 }, - { 3, 8, 13, 16, 19, 20, 19, 14, 4, -7, -18, -24, -26, -24, -21, -16, -11, -6, -2, 2, 6, 10, 13, 15, 17, 16, 13, 7, 0, -7, -13, -15, -14, -11, -6, -1, 3 }, -}; - -static float get_lookup_table_val(unsigned lat, unsigned lon); -static unsigned get_lookup_table_index(float *val, float min, float max); - -unsigned get_lookup_table_index(float *val, float min, float max) -{ - /* for the rare case of hitting the bounds exactly - * the rounding logic wouldn't fit, so enforce it. - */ - /* limit to table bounds - required for maxima even when table spans full globe range */ - if (*val < min) { - *val = min; - } - - /* limit to (table bounds - 1) because bilinear interpolation requires checking (index + 1) */ - if (*val > max) { - *val = max - SAMPLING_RES; - } - - return (-(min) + *val) / SAMPLING_RES; -} - -__EXPORT float get_mag_declination(float lat, float lon) -{ - /* - * If the values exceed valid ranges, return zero as default - * as we have no way of knowing what the closest real value - * would be. - */ - if (lat < -90.0f || lat > 90.0f || - lon < -180.0f || lon > 180.0f) { - return 0.0f; - } - - /* round down to nearest sampling resolution */ - float min_lat = (int)(lat / SAMPLING_RES) * SAMPLING_RES; - float min_lon = (int)(lon / SAMPLING_RES) * SAMPLING_RES; - - /* find index of nearest low sampling point */ - unsigned min_lat_index = get_lookup_table_index(&min_lat, SAMPLING_MIN_LAT, SAMPLING_MAX_LAT); - unsigned min_lon_index = get_lookup_table_index(&min_lon, SAMPLING_MIN_LON, SAMPLING_MAX_LON); - - float declination_sw = get_lookup_table_val(min_lat_index, min_lon_index); - float declination_se = get_lookup_table_val(min_lat_index, min_lon_index + 1); - float declination_ne = get_lookup_table_val(min_lat_index + 1, min_lon_index + 1); - float declination_nw = get_lookup_table_val(min_lat_index + 1, min_lon_index); - - /* perform bilinear interpolation on the four grid corners */ - float lat_scale = constrain((lat - min_lat) / SAMPLING_RES, 0.0f, 1.0f); - float lon_scale = constrain((lon - min_lon) / SAMPLING_RES, 0.0f, 1.0f); - - float declination_min = lon_scale * (declination_se - declination_sw) + declination_sw; - float declination_max = lon_scale * (declination_ne - declination_nw) + declination_nw; - - return lat_scale * (declination_max - declination_min) + declination_min; -} - -float get_lookup_table_val(unsigned lat_index, unsigned lon_index) -{ - return declination_table[lat_index][lon_index]; -} diff --git a/src/lib/geo_lookup/geo_mag_declination.h b/src/lib/geo_lookup/geo_mag_declination.h deleted file mode 100644 index 0ac062d6d43377011f3dfe1d75b6a700160badf2..0000000000000000000000000000000000000000 --- a/src/lib/geo_lookup/geo_mag_declination.h +++ /dev/null @@ -1,47 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2014 MAV GEO Library (MAVGEO). All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name MAVGEO nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** -* @file geo_mag_declination.h -* -* Calculation / lookup table for earth magnetic field declination. -* -*/ - -#pragma once - -__BEGIN_DECLS - -__EXPORT float get_mag_declination(float lat, float lon); - -__END_DECLS diff --git a/src/lib/matrix b/src/lib/matrix index 41a1cc7583253f3063ab4c626c40e7bc2a0bc868..61af508755c59d177c4e61a35cbfa270b06d9684 160000 --- a/src/lib/matrix +++ b/src/lib/matrix @@ -1 +1 @@ -Subproject commit 41a1cc7583253f3063ab4c626c40e7bc2a0bc868 +Subproject commit 61af508755c59d177c4e61a35cbfa270b06d9684 diff --git a/src/lib/terrain_estimation/terrain_estimator.cpp b/src/lib/terrain_estimation/terrain_estimator.cpp index c3c02ba22f3f502847527817ae604f6d47761051..63db46a90eed99c59883409559e58c4cbbaac5a8 100644 --- a/src/lib/terrain_estimation/terrain_estimator.cpp +++ b/src/lib/terrain_estimation/terrain_estimator.cpp @@ -37,7 +37,7 @@ */ #include "terrain_estimator.h" -#include <geo/geo.h> +#include <lib/ecl/geo/geo.h> #define DISTANCE_TIMEOUT 100000 // time in usec after which laser is considered dead diff --git a/src/modules/attitude_estimator_q/attitude_estimator_q_main.cpp b/src/modules/attitude_estimator_q/attitude_estimator_q_main.cpp index b65c29bd488cad0be7f19e1be09db5f008cb1250..b3035969827b3f39c63ad723ce9c08b37decc4dc 100644 --- a/src/modules/attitude_estimator_q/attitude_estimator_q_main.cpp +++ b/src/modules/attitude_estimator_q/attitude_estimator_q_main.cpp @@ -40,7 +40,8 @@ */ #include <drivers/drv_hrt.h> -#include <lib/geo/geo.h> +#include <lib/ecl/geo/geo.h> +#include <lib/ecl/geo_lookup/geo_mag_declination.h> #include <mathlib/math/filter/LowPassFilter2p.hpp> #include <mathlib/mathlib.h> #include <px4_config.h> diff --git a/src/modules/commander/accelerometer_calibration.cpp b/src/modules/commander/accelerometer_calibration.cpp index 38159f91e387c4a6ca684e853b3b436e4788e39f..bbf504b45b7ef19233f8b3a7d430a979c62647fe 100644 --- a/src/modules/commander/accelerometer_calibration.cpp +++ b/src/modules/commander/accelerometer_calibration.cpp @@ -141,7 +141,7 @@ #include <string.h> #include <drivers/drv_hrt.h> #include <drivers/drv_accel.h> -#include <geo/geo.h> +#include <lib/ecl/geo/geo.h> #include <conversion/rotation.h> #include <systemlib/param/param.h> #include <systemlib/err.h> diff --git a/src/modules/commander/calibration_routines.cpp b/src/modules/commander/calibration_routines.cpp index 46aeb909c5021432eb50aaca8038c87f2a44926f..b8f5a1d2114869f471e275a549e7817ce01e944b 100644 --- a/src/modules/commander/calibration_routines.cpp +++ b/src/modules/commander/calibration_routines.cpp @@ -48,7 +48,7 @@ #include <poll.h> #include <drivers/drv_hrt.h> #include <systemlib/mavlink_log.h> -#include <geo/geo.h> +#include <lib/ecl/geo/geo.h> #include <string.h> #include <mathlib/mathlib.h> diff --git a/src/modules/commander/commander.cpp b/src/modules/commander/commander.cpp index ea36195742fddbda9c043eb1469cdae7c4f7d1b1..d936c77cbf32e2bbba1e61eb3fc0f4c52010ee18 100644 --- a/src/modules/commander/commander.cpp +++ b/src/modules/commander/commander.cpp @@ -65,7 +65,7 @@ #include <dataman/dataman.h> #include <drivers/drv_hrt.h> #include <drivers/drv_tone_alarm.h> -#include <geo/geo.h> +#include <lib/ecl/geo/geo.h> #include <mathlib/mathlib.h> #include <navigator/navigation.h> #include <px4_defines.h> diff --git a/src/modules/ekf2/CMakeLists.txt b/src/modules/ekf2/CMakeLists.txt index 4a69cd46fbcb4f0b932e2b6fc62e0743e1ccf213..bea7c1573d75e1558503205e5976c97daa709c8e 100644 --- a/src/modules/ekf2/CMakeLists.txt +++ b/src/modules/ekf2/CMakeLists.txt @@ -37,9 +37,11 @@ px4_add_module( -Wno-sign-compare # TODO: fix all sign-compare STACK_MAIN 2500 STACK_MAX 4000 + INCLUDES + ${PX4_SOURCE_DIR}/src/lib/ecl SRCS ekf2_main.cpp DEPENDS - platforms__common git_ecl + ecl ) diff --git a/src/modules/fw_att_control/CMakeLists.txt b/src/modules/fw_att_control/CMakeLists.txt index 87014c374398720afaa986c26c5ea139f9835d4f..90846f87141204770aaae49320ff1602bbe9df70 100644 --- a/src/modules/fw_att_control/CMakeLists.txt +++ b/src/modules/fw_att_control/CMakeLists.txt @@ -38,5 +38,5 @@ px4_add_module( DEPENDS platforms__common git_ecl - lib__ecl + ecl ) diff --git a/src/modules/fw_att_control/FixedwingAttitudeControl.hpp b/src/modules/fw_att_control/FixedwingAttitudeControl.hpp index 1c09d1a7d1aacd734cd8cc416037f8913961b329..d3575586572ca21c053b62424b06a1889cf3aaf3 100644 --- a/src/modules/fw_att_control/FixedwingAttitudeControl.hpp +++ b/src/modules/fw_att_control/FixedwingAttitudeControl.hpp @@ -37,7 +37,7 @@ #include <ecl/attitude_fw/ecl_roll_controller.h> #include <ecl/attitude_fw/ecl_wheel_controller.h> #include <ecl/attitude_fw/ecl_yaw_controller.h> -#include <geo/geo.h> +#include <lib/ecl/geo/geo.h> #include <mathlib/mathlib.h> #include <px4_config.h> #include <px4_defines.h> diff --git a/src/modules/fw_pos_control_l1/CMakeLists.txt b/src/modules/fw_pos_control_l1/CMakeLists.txt index 225e402f3893497efa2c892f2e566674d6b4d30f..6b7f1e3fd0b57740d98c3fcfb6aaa6f3dc5cd5f0 100644 --- a/src/modules/fw_pos_control_l1/CMakeLists.txt +++ b/src/modules/fw_pos_control_l1/CMakeLists.txt @@ -38,13 +38,14 @@ px4_add_module( MODULE modules__fw_pos_control_l1 MAIN fw_pos_control_l1 STACK_MAIN 1200 - COMPILE_FLAGS + INCLUDES + ${PX4_SOURCE_DIR}/src/lib/ecl SRCS FixedwingPositionControl.cpp Landingslope.cpp DEPENDS git_ecl - lib__ecl + ecl launchdetection runway_takeoff ) diff --git a/src/modules/fw_pos_control_l1/FixedwingPositionControl.hpp b/src/modules/fw_pos_control_l1/FixedwingPositionControl.hpp index 8dbca7277f07df39db52eb469d132da62ae8fc40..63b0820ce136e05e773aa440b8c259c535104aa7 100644 --- a/src/modules/fw_pos_control_l1/FixedwingPositionControl.hpp +++ b/src/modules/fw_pos_control_l1/FixedwingPositionControl.hpp @@ -57,7 +57,7 @@ #include <drivers/drv_hrt.h> #include <ecl/l1/ecl_l1_pos_controller.h> #include <ecl/tecs/tecs.h> -#include <geo/geo.h> +#include <lib/ecl/geo/geo.h> #include <mathlib/mathlib.h> #include <px4_config.h> #include <px4_defines.h> diff --git a/src/modules/gnd_att_control/CMakeLists.txt b/src/modules/gnd_att_control/CMakeLists.txt index dca07b470591917b21dab61f5fa2d4eeffbca5b1..54bdb2b5b59a25b021ff62d3b6649b936656aa5c 100644 --- a/src/modules/gnd_att_control/CMakeLists.txt +++ b/src/modules/gnd_att_control/CMakeLists.txt @@ -38,8 +38,6 @@ px4_add_module( SRCS GroundRoverAttitudeControl.cpp DEPENDS - platforms__common git_ecl - lib__ecl + ecl ) -# vim: set noet ft=cmake fenc=utf-8 ff=unix : diff --git a/src/modules/gnd_pos_control/CMakeLists.txt b/src/modules/gnd_pos_control/CMakeLists.txt index df6257a0d9aa962e39a3cdda2d3eaa1c2fed53d9..fda35ebebf44abc28b2b9c43073a6e5b9f664bd4 100644 --- a/src/modules/gnd_pos_control/CMakeLists.txt +++ b/src/modules/gnd_pos_control/CMakeLists.txt @@ -35,11 +35,11 @@ px4_add_module( MAIN gnd_pos_control STACK_MAIN 1200 COMPILE_FLAGS + INCLUDES + ${PX4_SOURCE_DIR}/src/lib/ecl SRCS GroundRoverPositionControl.cpp DEPENDS - platforms__common git_ecl - lib__ecl + ecl ) -# vim: set noet ft=cmake fenc=utf-8 ff=unix : diff --git a/src/modules/gnd_pos_control/GroundRoverPositionControl.hpp b/src/modules/gnd_pos_control/GroundRoverPositionControl.hpp index 51754247a09a6583f55717f6415aac5ec550cea9..47cc6f8093058e396b0cdebbef2923e71e30ec0d 100644 --- a/src/modules/gnd_pos_control/GroundRoverPositionControl.hpp +++ b/src/modules/gnd_pos_control/GroundRoverPositionControl.hpp @@ -50,7 +50,7 @@ #include <drivers/drv_hrt.h> #include <ecl/l1/ecl_l1_pos_controller.h> -#include <geo/geo.h> +#include <lib/ecl/geo/geo.h> #include <mathlib/mathlib.h> #include <systemlib/perf_counter.h> #include <systemlib/pid/pid.h> diff --git a/src/modules/local_position_estimator/BlockLocalPositionEstimator.hpp b/src/modules/local_position_estimator/BlockLocalPositionEstimator.hpp index 0a3115645c644a11269577c1e3dfa827417c6458..91106cca076d0b4a785ab3d7c66aa64fd3fab01e 100644 --- a/src/modules/local_position_estimator/BlockLocalPositionEstimator.hpp +++ b/src/modules/local_position_estimator/BlockLocalPositionEstimator.hpp @@ -4,7 +4,7 @@ #include <px4_module_params.h> #include <controllib/blocks.hpp> #include <mathlib/mathlib.h> -#include <lib/geo/geo.h> +#include <lib/ecl/geo/geo.h> #include <matrix/Matrix.hpp> // uORB Subscriptions diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp index 18c5646ec003e293828a7d1043371c2b0d1d7b63..0900c799d1d935f028a87230cd28daa4b84bdb88 100644 --- a/src/modules/mavlink/mavlink_main.cpp +++ b/src/modules/mavlink/mavlink_main.cpp @@ -69,7 +69,7 @@ #include <systemlib/perf_counter.h> #include <systemlib/systemlib.h> #include <systemlib/mavlink_log.h> -#include <geo/geo.h> +#include <lib/ecl/geo/geo.h> #include <dataman/dataman.h> #include <version/version.h> diff --git a/src/modules/mavlink/mavlink_messages.cpp b/src/modules/mavlink/mavlink_messages.cpp index fb8be5ad578a3a2795f4d02a6ae476493cfd153c..67a0ddc0ab93a4b4ea1fab0c8e6d96afce20d075 100644 --- a/src/modules/mavlink/mavlink_messages.cpp +++ b/src/modules/mavlink/mavlink_messages.cpp @@ -49,7 +49,7 @@ #include <commander/px4_custom_mode.h> #include <drivers/drv_pwm_output.h> #include <drivers/drv_rc_input.h> -#include <lib/geo/geo.h> +#include <lib/ecl/geo/geo.h> #include <mathlib/mathlib.h> #include <px4_time.h> #include <systemlib/err.h> diff --git a/src/modules/mavlink/mavlink_mission.cpp b/src/modules/mavlink/mavlink_mission.cpp index 4380ff9f5afc14980be96fef5c7990b1ed39f8c7..7e201cf9c5ca8f9b6d5d6950ebb1b51018913056 100644 --- a/src/modules/mavlink/mavlink_mission.cpp +++ b/src/modules/mavlink/mavlink_mission.cpp @@ -45,7 +45,7 @@ #include <errno.h> #include <math.h> -#include <lib/geo/geo.h> +#include <lib/ecl/geo/geo.h> #include <systemlib/err.h> #include <drivers/drv_hrt.h> #include <px4_defines.h> diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp index 74d6c5ca5b9583cfe57421b06f9851f5e0e503ea..8cf9fdcddc163d7fc6a877e818b60fe1e56ec5b5 100644 --- a/src/modules/mavlink/mavlink_receiver.cpp +++ b/src/modules/mavlink/mavlink_receiver.cpp @@ -81,7 +81,7 @@ #include <systemlib/err.h> #include <systemlib/airspeed.h> #include <commander/px4_custom_mode.h> -#include <geo/geo.h> +#include <lib/ecl/geo/geo.h> #include <uORB/topics/vehicle_command_ack.h> diff --git a/src/modules/mc_att_control/mc_att_control_main.cpp b/src/modules/mc_att_control/mc_att_control_main.cpp index 96362c76a9f8c4e8f856c43bbf80ced67c2ccfb5..2250abcea3e60335614b14c3d1ba301ae6e34706 100644 --- a/src/modules/mc_att_control/mc_att_control_main.cpp +++ b/src/modules/mc_att_control/mc_att_control_main.cpp @@ -47,7 +47,7 @@ #include <conversion/rotation.h> #include <drivers/drv_hrt.h> -#include <lib/geo/geo.h> +#include <lib/ecl/geo/geo.h> #include <systemlib/circuit_breaker.h> #include <mathlib/math/Limits.hpp> #include <mathlib/math/Functions.hpp> diff --git a/src/modules/mc_pos_control/mc_pos_control_main.cpp b/src/modules/mc_pos_control/mc_pos_control_main.cpp index 5fb3294a6ea4f44201e0ad0a4e16c55e23e3fa97..148a4f0b34d5e24248acbc3c9ed209b9b3cacba0 100644 --- a/src/modules/mc_pos_control/mc_pos_control_main.cpp +++ b/src/modules/mc_pos_control/mc_pos_control_main.cpp @@ -69,7 +69,7 @@ #include <uORB/topics/vehicle_status.h> #include <float.h> -#include <lib/geo/geo.h> +#include <lib/ecl/geo/geo.h> #include <mathlib/mathlib.h> #include <systemlib/mavlink_log.h> diff --git a/src/modules/navigator/datalinkloss.cpp b/src/modules/navigator/datalinkloss.cpp index bd11fd70bd170a7e737c1b7249a305d0c2f3c3bc..46dd0d3da0a82c44375aa6e44344e06e224f67a4 100644 --- a/src/modules/navigator/datalinkloss.cpp +++ b/src/modules/navigator/datalinkloss.cpp @@ -44,7 +44,7 @@ #include <systemlib/mavlink_log.h> #include <systemlib/err.h> -#include <geo/geo.h> +#include <lib/ecl/geo/geo.h> #include <navigator/navigation.h> #include <uORB/uORB.h> diff --git a/src/modules/navigator/enginefailure.cpp b/src/modules/navigator/enginefailure.cpp index 90c1897f9e5a29d01b3faa6425363b2c8b3fac7e..dcec92cac7a7116cc6fc90dfc071c9f02258772b 100644 --- a/src/modules/navigator/enginefailure.cpp +++ b/src/modules/navigator/enginefailure.cpp @@ -43,7 +43,7 @@ #include <systemlib/mavlink_log.h> #include <systemlib/err.h> -#include <geo/geo.h> +#include <lib/ecl/geo/geo.h> #include <navigator/navigation.h> #include <uORB/uORB.h> diff --git a/src/modules/navigator/follow_target.cpp b/src/modules/navigator/follow_target.cpp index aab2c2f878016c9926fad037657acbfc76cf3bcf..5cbe3190e5bf0c962a89dce5886e6ba9c758a7c6 100644 --- a/src/modules/navigator/follow_target.cpp +++ b/src/modules/navigator/follow_target.cpp @@ -51,7 +51,7 @@ #include <uORB/uORB.h> #include <uORB/topics/position_setpoint_triplet.h> #include <uORB/topics/follow_target.h> -#include <lib/geo/geo.h> +#include <lib/ecl/geo/geo.h> #include <lib/mathlib/math/Limits.hpp> #include "navigator.h" diff --git a/src/modules/navigator/geofence.cpp b/src/modules/navigator/geofence.cpp index 1171de9c4080bbcde340a5c11a227f2da9eea577..9153385c703a790ce55ea242f506b9ef485ac65c 100644 --- a/src/modules/navigator/geofence.cpp +++ b/src/modules/navigator/geofence.cpp @@ -45,7 +45,7 @@ #include <dataman/dataman.h> #include <drivers/drv_hrt.h> -#include <geo/geo.h> +#include <lib/ecl/geo/geo.h> #include <systemlib/mavlink_log.h> #include "navigator.h" diff --git a/src/modules/navigator/geofence.h b/src/modules/navigator/geofence.h index 7fee1f69d9446243583951ffab84e7c95fc78513..2052d2534ab451cf89420ab50f6b9be7ae28f3bb 100644 --- a/src/modules/navigator/geofence.h +++ b/src/modules/navigator/geofence.h @@ -44,7 +44,7 @@ #include <px4_module_params.h> #include <drivers/drv_hrt.h> -#include <geo/geo.h> +#include <lib/ecl/geo/geo.h> #include <px4_defines.h> #include <uORB/topics/sensor_combined.h> #include <uORB/topics/vehicle_global_position.h> diff --git a/src/modules/navigator/gpsfailure.cpp b/src/modules/navigator/gpsfailure.cpp index cd7d7d1704e82600bc84216d3731aca484f6a5d5..d51e5433848bebce5ec25a6624cfaea67b0746ad 100644 --- a/src/modules/navigator/gpsfailure.cpp +++ b/src/modules/navigator/gpsfailure.cpp @@ -41,7 +41,7 @@ #include "navigator.h" #include <systemlib/mavlink_log.h> -#include <geo/geo.h> +#include <lib/ecl/geo/geo.h> #include <navigator/navigation.h> #include <uORB/uORB.h> #include <uORB/topics/mission.h> diff --git a/src/modules/navigator/mission.cpp b/src/modules/navigator/mission.cpp index 688625316f278b64a9e9475de839627c8c6390ab..fd32d46a4b62afca6d50702eadb65830a7766641 100644 --- a/src/modules/navigator/mission.cpp +++ b/src/modules/navigator/mission.cpp @@ -52,7 +52,7 @@ #include <dataman/dataman.h> #include <systemlib/mavlink_log.h> #include <systemlib/err.h> -#include <geo/geo.h> +#include <lib/ecl/geo/geo.h> #include <lib/mathlib/mathlib.h> #include <navigator/navigation.h> #include <uORB/uORB.h> diff --git a/src/modules/navigator/mission_block.cpp b/src/modules/navigator/mission_block.cpp index ea85b7d017ba063cdf347230b32b873d0d7a0af5..044ce7efa47d8ec7bc677b63db6e5238ab717938 100644 --- a/src/modules/navigator/mission_block.cpp +++ b/src/modules/navigator/mission_block.cpp @@ -46,7 +46,7 @@ #include <math.h> #include <float.h> -#include <geo/geo.h> +#include <lib/ecl/geo/geo.h> #include <systemlib/mavlink_log.h> #include <mathlib/mathlib.h> #include <uORB/uORB.h> diff --git a/src/modules/navigator/mission_feasibility_checker.cpp b/src/modules/navigator/mission_feasibility_checker.cpp index e9364c118a3b807157c83050151c7e465ae148cc..4d9c0e90d8ef9971e1243bd26398611817809d9e 100644 --- a/src/modules/navigator/mission_feasibility_checker.cpp +++ b/src/modules/navigator/mission_feasibility_checker.cpp @@ -46,7 +46,7 @@ #include <drivers/drv_pwm_output.h> #include <fw_pos_control_l1/Landingslope.hpp> -#include <geo/geo.h> +#include <lib/ecl/geo/geo.h> #include <mathlib/mathlib.h> #include <systemlib/mavlink_log.h> diff --git a/src/modules/navigator/navigator_main.cpp b/src/modules/navigator/navigator_main.cpp index 7d70d9dc862e03a7061e92b27655b5804e10de5e..1d528ed00e40bbbb27b6725d27c5260bcdbb5752 100644 --- a/src/modules/navigator/navigator_main.cpp +++ b/src/modules/navigator/navigator_main.cpp @@ -52,7 +52,7 @@ #include <dataman/dataman.h> #include <drivers/drv_hrt.h> -#include <geo/geo.h> +#include <lib/ecl/geo/geo.h> #include <mathlib/mathlib.h> #include <px4_config.h> #include <px4_defines.h> diff --git a/src/modules/navigator/precland.h b/src/modules/navigator/precland.h index 0d9177e5d3d68a73a1ea268afd0786566fa66549..f20757f7a78d3df9c0a0f0ad8c85cd200d03bf44 100644 --- a/src/modules/navigator/precland.h +++ b/src/modules/navigator/precland.h @@ -41,7 +41,7 @@ #pragma once #include <matrix/math.hpp> -#include <geo/geo.h> +#include <lib/ecl/geo/geo.h> #include <px4_module_params.h> #include <uORB/topics/landing_target_pose.h> diff --git a/src/modules/navigator/rcloss.cpp b/src/modules/navigator/rcloss.cpp index 74ef1615e017119303b706a0e9b399ae89955aa7..6d34fc7ed29681a4f197803349fe8e22ddd96890 100644 --- a/src/modules/navigator/rcloss.cpp +++ b/src/modules/navigator/rcloss.cpp @@ -44,7 +44,7 @@ #include <systemlib/mavlink_log.h> #include <systemlib/err.h> -#include <geo/geo.h> +#include <lib/ecl/geo/geo.h> #include <uORB/uORB.h> #include <navigator/navigation.h> diff --git a/src/modules/position_estimator_inav/position_estimator_inav_main.cpp b/src/modules/position_estimator_inav/position_estimator_inav_main.cpp index 61fd66ffeb4dc7fb3e7c718855e506d6a396081e..59821bbb9046209f22d416de1394448d64d6ab34 100644 --- a/src/modules/position_estimator_inav/position_estimator_inav_main.cpp +++ b/src/modules/position_estimator_inav/position_estimator_inav_main.cpp @@ -66,7 +66,7 @@ #include <poll.h> #include <systemlib/err.h> #include <systemlib/mavlink_log.h> -#include <geo/geo.h> +#include <lib/ecl/geo/geo.h> #include <drivers/drv_hrt.h> #include <platforms/px4_defines.h> diff --git a/src/modules/simulator/simulator.h b/src/modules/simulator/simulator.h index c22f9f9342a485f9f5de87dc79d758ee69975cce..f471ace5c54f240c83f953e5d23b7d04b0b5ce82 100644 --- a/src/modules/simulator/simulator.h +++ b/src/modules/simulator/simulator.h @@ -61,7 +61,7 @@ #include <uORB/topics/distance_sensor.h> #include <v2.0/mavlink_types.h> #include <v2.0/common/mavlink.h> -#include <geo/geo.h> +#include <lib/ecl/geo/geo.h> namespace simulator { diff --git a/src/modules/simulator/simulator_mavlink.cpp b/src/modules/simulator/simulator_mavlink.cpp index 554c28fbdfa18ad0501474fa59c898f1aab2271b..365440f786adc6436c7de003bb8ad9e465cf9a0f 100644 --- a/src/modules/simulator/simulator_mavlink.cpp +++ b/src/modules/simulator/simulator_mavlink.cpp @@ -38,7 +38,7 @@ #include "simulator.h" #include <simulator_config.h> #include "errno.h" -#include <geo/geo.h> +#include <lib/ecl/geo/geo.h> #include <drivers/drv_pwm_output.h> #include <sys/socket.h> #include <netinet/in.h> diff --git a/src/modules/systemlib/airspeed.c b/src/modules/systemlib/airspeed.c index 6bca3a96a05d420e38c27e7f1f5e7edf4ea4e1d7..23b36a299bf1c24067f524dc4d99a38ceca878f4 100644 --- a/src/modules/systemlib/airspeed.c +++ b/src/modules/systemlib/airspeed.c @@ -40,11 +40,11 @@ * */ -#include <stdio.h> -#include <math.h> -#include <geo/geo.h> #include "airspeed.h" +#include <px4_defines.h> +#include <lib/ecl/geo/geo.h> + /** * Calculate indicated airspeed. * @@ -121,7 +121,7 @@ float calc_indicated_airspeed_corrected(enum AIRSPEED_COMPENSATION_MODEL pmodel, // check if the tube diameter and dp is nonzero to avoid division by 0 if ((tube_dia_mm > 0.0f) && (dp > 0.0f)) { const float d_tubePow4 = powf(tube_dia_mm * 1e-3f, 4); - const float denominator = (float)M_PI * d_tubePow4 * rho_air * dp; + const float denominator = M_PI_F * d_tubePow4 * rho_air * dp; // avoid division by 0 float eps = 0.0f; diff --git a/src/modules/vtol_att_control/vtol_att_control_main.h b/src/modules/vtol_att_control/vtol_att_control_main.h index 29ea822e0a68d3aa720400806238c9e19a1439ba..3f353d1d0a60eb9506b7995ab006fa62dc34501c 100644 --- a/src/modules/vtol_att_control/vtol_att_control_main.h +++ b/src/modules/vtol_att_control/vtol_att_control_main.h @@ -57,7 +57,7 @@ #include <arch/board/board.h> #include <drivers/drv_hrt.h> #include <drivers/drv_pwm_output.h> -#include <lib/geo/geo.h> +#include <lib/ecl/geo/geo.h> #include <lib/mathlib/mathlib.h> #include <systemlib/param/param.h> diff --git a/src/platforms/ros/geo.cpp b/src/platforms/ros/geo.cpp index d13a5e277a82b05c2a83363b747d16fc1f47b4c3..5f3307010e7f337fc5b8ff0b952c513d30dcb5fe 100644 --- a/src/platforms/ros/geo.cpp +++ b/src/platforms/ros/geo.cpp @@ -42,7 +42,7 @@ * @author Anton Babushkin <anton.babushkin@me.com> */ -#include <geo/geo.h> +#include <lib/ecl/geo/geo.h> #include <px4.h> #include <unistd.h> #include <pthread.h> diff --git a/src/systemcmds/tests/test_autodeclination.cpp b/src/systemcmds/tests/test_autodeclination.cpp index 663014edb6360c01aa77f28859019cdfdc259dcb..07404113301611eb277188b69a2f9db08249d0a0 100644 --- a/src/systemcmds/tests/test_autodeclination.cpp +++ b/src/systemcmds/tests/test_autodeclination.cpp @@ -1,7 +1,8 @@ #include <unit_test.h> #include <drivers/drv_hrt.h> -#include <geo/geo.h> +#include <lib/ecl/geo/geo.h> +#include <ecl/geo_lookup/geo_mag_declination.h> #include <px4iofirmware/px4io.h> #include <systemlib/err.h> #include <lib/mixer/mixer.h>