diff --git a/CMakeLists.txt b/CMakeLists.txt index 4beca52e6..c405d0c58 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -411,13 +411,13 @@ set(GNSSSDR_PROTOBUF_MIN_VERSION "3.0.0") ################################################################################ set(GNSSSDR_GFLAGS_LOCAL_VERSION "2.2.2") set(GNSSSDR_GLOG_LOCAL_VERSION "0.4.0") -set(GNSSSDR_ARMADILLO_LOCAL_VERSION "9.300.x") +set(GNSSSDR_ARMADILLO_LOCAL_VERSION "9.500.x") set(GNSSSDR_GTEST_LOCAL_VERSION "1.8.1") set(GNSSSDR_GNSS_SIM_LOCAL_VERSION "master") set(GNSSSDR_GPSTK_LOCAL_VERSION "2.10.6") -set(GNSSSDR_MATIO_LOCAL_VERSION "1.5.14") +set(GNSSSDR_MATIO_LOCAL_VERSION "1.5.15") set(GNSSSDR_PUGIXML_LOCAL_VERSION "1.9") -set(GNSSSDR_PROTOCOLBUFFERS_LOCAL_VERSION "3.7.1") +set(GNSSSDR_PROTOCOLBUFFERS_LOCAL_VERSION "3.8.0") if(CMAKE_VERSION VERSION_LESS "3.0.2") # Fix for CentOS 7 set(GNSSSDR_GFLAGS_LOCAL_VERSION "2.2.1") @@ -596,102 +596,6 @@ endif() -################################################################################ -# Boost - https://www.boost.org -################################################################################ -if(UNIX AND EXISTS "/usr/lib64") - list(APPEND BOOST_LIBRARYDIR "/usr/lib64") # Fedora 64-bit fix -endif() -set(Boost_ADDITIONAL_VERSIONS - "1.53.0" "1.53" "1.54.0" "1.54" - "1.55.0" "1.55" "1.56.0" "1.56" "1.57.0" "1.57" "1.58.0" "1.58" "1.59.0" "1.59" - "1.60.0" "1.60" "1.61.0" "1.61" "1.62.0" "1.62" "1.63.0" "1.63" "1.64.0" "1.64" - "1.65.0" "1.65" "1.66.0" "1.66" "1.67.0" "1.67" "1.68.0" "1.68" "1.69.0" "1.69" - "1.70.0" "1.70" "1.71.0" "1.71" "1.72.0" "1.72" "1.73.0" "1.73" "1.74.0" "1.74" - "1.75.0" "1.75" "1.76.0" "1.76" "1.77.0" "1.77" "1.78.0" "1.78" "1.79.0" "1.79" - "1.80.0" "1.80" "1.81.0" "1.81" "1.82.0" "1.82" "1.83.0" "1.83" "1.84.0" "1.84" -) -set(Boost_USE_MULTITHREAD ON) -set(Boost_USE_STATIC_LIBS OFF) -find_package(Boost ${GNSSSDR_BOOST_MIN_VERSION} COMPONENTS atomic chrono date_time filesystem serialization system thread REQUIRED) -set_package_properties(Boost PROPERTIES - URL "https://www.boost.org" - DESCRIPTION "Portable C++ source libraries" - PURPOSE "Used widely across the source code." - TYPE REQUIRED -) -if(NOT Boost_FOUND) - message(FATAL_ERROR "Fatal error: Boost (version >=${GNSSSDR_BOOST_MIN_VERSION}) required.") -endif() - -if(CMAKE_VERSION VERSION_LESS 3.5) - if(NOT TARGET Boost::boost) - add_library(Boost::boost SHARED IMPORTED) # Trick for CMake 2.8.12 - set_target_properties(Boost::boost PROPERTIES - INTERFACE_INCLUDE_DIRECTORIES ${Boost_INCLUDE_DIR} - IMPORTED_LOCATION ${Boost_DATE_TIME_LIBRARIES} - ) - endif() - if(NOT TARGET Boost::date_time) - add_library(Boost::date_time SHARED IMPORTED) - set_target_properties(Boost::date_time PROPERTIES - INTERFACE_INCLUDE_DIRECTORIES ${Boost_INCLUDE_DIR} - INTERFACE_LINK_LIBRARIES ${Boost_DATE_TIME_LIBRARIES} - IMPORTED_LOCATION ${Boost_DATE_TIME_LIBRARIES} - ) - endif() - if(NOT TARGET Boost::system) - add_library(Boost::system SHARED IMPORTED) - set_target_properties(Boost::system PROPERTIES - INTERFACE_INCLUDE_DIRECTORIES ${Boost_INCLUDE_DIR} - INTERFACE_LINK_LIBRARIES ${Boost_SYSTEM_LIBRARIES} - IMPORTED_LOCATION ${Boost_SYSTEM_LIBRARIES} - ) - endif() - if(NOT TARGET Boost::filesystem) - add_library(Boost::filesystem SHARED IMPORTED) - set_target_properties(Boost::filesystem PROPERTIES - INTERFACE_INCLUDE_DIRECTORIES ${Boost_INCLUDE_DIR} - INTERFACE_LINK_LIBRARIES ${Boost_FILESYSTEM_LIBRARIES} - IMPORTED_LOCATION ${Boost_FILESYSTEM_LIBRARIES} - ) - endif() - if(NOT TARGET Boost::thread) - add_library(Boost::thread SHARED IMPORTED) - set_target_properties(Boost::thread PROPERTIES - INTERFACE_INCLUDE_DIRECTORIES ${Boost_INCLUDE_DIR} - INTERFACE_LINK_LIBRARIES ${Boost_THREAD_LIBRARIES} - IMPORTED_LOCATION ${Boost_THREAD_LIBRARIES} - ) - endif() - if(NOT TARGET Boost::serialization) - add_library(Boost::serialization SHARED IMPORTED) - set_target_properties(Boost::serialization PROPERTIES - INTERFACE_INCLUDE_DIRECTORIES ${Boost_INCLUDE_DIR} - INTERFACE_LINK_LIBRARIES ${Boost_SERIALIZATION_LIBRARIES} - IMPORTED_LOCATION ${Boost_SERIALIZATION_LIBRARIES} - ) - endif() - if(NOT TARGET Boost::chrono) - add_library(Boost::chrono SHARED IMPORTED) - set_target_properties(Boost::chrono PROPERTIES - INTERFACE_INCLUDE_DIRECTORIES ${Boost_INCLUDE_DIR} - INTERFACE_LINK_LIBRARIES ${Boost_CHRONO_LIBRARIES} - IMPORTED_LOCATION ${Boost_CHRONO_LIBRARIES} - ) - endif() - if(NOT TARGET Boost::atomic) - add_library(Boost::atomic SHARED IMPORTED) - set_target_properties(Boost::atomic PROPERTIES - INTERFACE_INCLUDE_DIRECTORIES ${Boost_INCLUDE_DIR} - INTERFACE_LINK_LIBRARIES ${Boost_ATOMIC_LIBRARIES} - IMPORTED_LOCATION ${Boost_ATOMIC_LIBRARIES} - ) - endif() -endif() - - - ################################################################################ # GNU Radio - https://gnuradio.org ################################################################################ @@ -848,6 +752,150 @@ endif() +################################################################################ +# Dectect availability of std::filesystem +################################################################################ +set(FILESYSTEM_FOUND FALSE) +if(NOT (GNURADIO_VERSION VERSION_LESS 3.8)) + # Check if we have std::filesystem + if(NOT (CMAKE_VERSION VERSION_LESS 3.8)) + if(POLICY CMP0057) + cmake_policy(SET CMP0057 NEW) + endif() + if(NOT ENABLE_UNIT_TESTING_EXTRA) # Workaround for GPSTk + find_package(FILESYSTEM) + set_package_properties(FILESYSTEM PROPERTIES + URL "https://en.cppreference.com/w/cpp/filesystem" + DESCRIPTION "Provides facilities for performing operations on file systems and their components" + PURPOSE "Work with paths, regular files, and directories." + TYPE OPTIONAL + ) + if(${FILESYSTEM_FOUND}) + set(CMAKE_CXX_STANDARD 17) + set(CMAKE_CXX_STANDARD_REQUIRED ON) + endif() + endif() + endif() +endif() + + + +################################################################################ +# Boost - https://www.boost.org +################################################################################ +if(UNIX AND EXISTS "/usr/lib64") + list(APPEND BOOST_LIBRARYDIR "/usr/lib64") # Fedora 64-bit fix +endif() +set(Boost_ADDITIONAL_VERSIONS + "1.53.0" "1.53" "1.54.0" "1.54" + "1.55.0" "1.55" "1.56.0" "1.56" "1.57.0" "1.57" "1.58.0" "1.58" "1.59.0" "1.59" + "1.60.0" "1.60" "1.61.0" "1.61" "1.62.0" "1.62" "1.63.0" "1.63" "1.64.0" "1.64" + "1.65.0" "1.65" "1.66.0" "1.66" "1.67.0" "1.67" "1.68.0" "1.68" "1.69.0" "1.69" + "1.70.0" "1.70" "1.71.0" "1.71" "1.72.0" "1.72" "1.73.0" "1.73" "1.74.0" "1.74" + "1.75.0" "1.75" "1.76.0" "1.76" "1.77.0" "1.77" "1.78.0" "1.78" "1.79.0" "1.79" + "1.80.0" "1.80" "1.81.0" "1.81" "1.82.0" "1.82" "1.83.0" "1.83" "1.84.0" "1.84" +) +set(Boost_USE_MULTITHREAD ON) +set(Boost_USE_STATIC_LIBS OFF) +set(BOOST_COMPONENTS atomic chrono date_time serialization system thread) +if(NOT ${FILESYSTEM_FOUND}) + set(BOOST_COMPONENTS ${BOOST_COMPONENTS} filesystem) +endif() +find_package(Boost ${GNSSSDR_BOOST_MIN_VERSION} COMPONENTS ${BOOST_COMPONENTS} REQUIRED) +set_package_properties(Boost PROPERTIES + URL "https://www.boost.org" + DESCRIPTION "Portable C++ source libraries" + PURPOSE "Used widely across the source code." + TYPE REQUIRED +) +if(NOT Boost_FOUND) + message(FATAL_ERROR "Fatal error: Boost (version >=${GNSSSDR_BOOST_MIN_VERSION}) required.") +endif() + +if(CMAKE_VERSION VERSION_LESS 3.5) + if(NOT TARGET Boost::boost) + add_library(Boost::boost SHARED IMPORTED) # Trick for CMake 2.8.12 + set_target_properties(Boost::boost PROPERTIES + INTERFACE_INCLUDE_DIRECTORIES ${Boost_INCLUDE_DIR} + IMPORTED_LOCATION ${Boost_DATE_TIME_LIBRARIES} + ) + endif() + if(NOT TARGET Boost::date_time) + add_library(Boost::date_time SHARED IMPORTED) + set_target_properties(Boost::date_time PROPERTIES + INTERFACE_INCLUDE_DIRECTORIES ${Boost_INCLUDE_DIR} + INTERFACE_LINK_LIBRARIES ${Boost_DATE_TIME_LIBRARIES} + IMPORTED_LOCATION ${Boost_DATE_TIME_LIBRARIES} + ) + endif() + if(NOT TARGET Boost::system) + add_library(Boost::system SHARED IMPORTED) + set_target_properties(Boost::system PROPERTIES + INTERFACE_INCLUDE_DIRECTORIES ${Boost_INCLUDE_DIR} + INTERFACE_LINK_LIBRARIES ${Boost_SYSTEM_LIBRARIES} + IMPORTED_LOCATION ${Boost_SYSTEM_LIBRARIES} + ) + endif() + if(NOT TARGET Boost::thread) + add_library(Boost::thread SHARED IMPORTED) + set_target_properties(Boost::thread PROPERTIES + INTERFACE_INCLUDE_DIRECTORIES ${Boost_INCLUDE_DIR} + INTERFACE_LINK_LIBRARIES ${Boost_THREAD_LIBRARIES} + IMPORTED_LOCATION ${Boost_THREAD_LIBRARIES} + ) + endif() + if(NOT TARGET Boost::serialization) + add_library(Boost::serialization SHARED IMPORTED) + set_target_properties(Boost::serialization PROPERTIES + INTERFACE_INCLUDE_DIRECTORIES ${Boost_INCLUDE_DIR} + INTERFACE_LINK_LIBRARIES ${Boost_SERIALIZATION_LIBRARIES} + IMPORTED_LOCATION ${Boost_SERIALIZATION_LIBRARIES} + ) + endif() + if(NOT TARGET Boost::chrono) + add_library(Boost::chrono SHARED IMPORTED) + set_target_properties(Boost::chrono PROPERTIES + INTERFACE_INCLUDE_DIRECTORIES ${Boost_INCLUDE_DIR} + INTERFACE_LINK_LIBRARIES ${Boost_CHRONO_LIBRARIES} + IMPORTED_LOCATION ${Boost_CHRONO_LIBRARIES} + ) + endif() + if(NOT TARGET Boost::atomic) + add_library(Boost::atomic SHARED IMPORTED) + set_target_properties(Boost::atomic PROPERTIES + INTERFACE_INCLUDE_DIRECTORIES ${Boost_INCLUDE_DIR} + INTERFACE_LINK_LIBRARIES ${Boost_ATOMIC_LIBRARIES} + IMPORTED_LOCATION ${Boost_ATOMIC_LIBRARIES} + ) + endif() + if(NOT ${FILESYSTEM_FOUND}) + if(NOT TARGET Boost::filesystem) + add_library(Boost::filesystem SHARED IMPORTED) + set_target_properties(Boost::filesystem PROPERTIES + INTERFACE_INCLUDE_DIRECTORIES ${Boost_INCLUDE_DIR} + INTERFACE_LINK_LIBRARIES ${Boost_FILESYSTEM_LIBRARIES} + IMPORTED_LOCATION ${Boost_FILESYSTEM_LIBRARIES} + ) + endif() + endif() +endif() + +# Fix for Boost Asio < 1.70 when using Clang in macOS +if(${Boost_VERSION} VERSION_LESS 107000) + # Check if we have std::string_view + include(CheckCXXSourceCompiles) + check_cxx_source_compiles(" + #include  + int main() + { std::string_view sv; }" + has_string_view + ) +endif() + + + + + ################################################################################ # VOLK - Vector-Optimized Library of Kernels ################################################################################ diff --git a/README.md b/README.md index 54d8a3f47..7240ccbca 100644 --- a/README.md +++ b/README.md @@ -220,9 +220,9 @@ $ sudo apt-get install libblas-dev liblapack-dev # For Debian/Ubuntu/Linux $ sudo yum install lapack-devel blas-devel # For Fedora/CentOS/RHEL $ sudo zypper install lapack-devel blas-devel # For OpenSUSE $ sudo pacman -S blas lapack # For Arch Linux -$ wget https://sourceforge.net/projects/arma/files/armadillo-9.300.2.tar.xz -$ tar xvfz armadillo-9.300.2.tar.xz -$ cd armadillo-9.300.2 +$ wget http://sourceforge.net/projects/arma/files/armadillo-9.400.4.tar.xz +$ tar xvfz armadillo-9.400.4.tar.xz +$ cd armadillo-9.400.4 $ cmake . $ make $ sudo make install @@ -305,9 +305,9 @@ $ sudo apt-get install autoconf automake libtool curl make g++ unzip and then: ~~~~~~ -$ wget https://github.com/protocolbuffers/protobuf/releases/download/v3.7.1/protobuf-cpp-3.7.1.tar.gz -$ tar xvfz protobuf-cpp-3.7.1.tar.gz -$ cd protobuf-3.7.1 +$ wget https://github.com/protocolbuffers/protobuf/releases/download/v3.8.0/protobuf-cpp-3.8.0.tar.gz +$ tar xvfz protobuf-cpp-3.8.0.tar.gz +$ cd protobuf-3.8.0 $ ./autogen.sh $ ./configure $ make @@ -708,14 +708,18 @@ $ cmake -DCMAKE_PREFIX_PATH=/opt/local -DUSE_MACPORTS_PYTHON=/opt/local/bin/pyth changing ```/opt/local``` by the base directory in which your software is installed. -The CMake script will create Makefiles that download, build and link Armadillo, Gflags, Glog, Matio, PugiXML and Google Test on the fly at compile time if they are not detected in your machine. +The CMake script will create Makefiles that download, build and link Armadillo, Gflags, Glog, Matio, Protocol Buffers, PugiXML and Google Test on the fly at compile time if they are not detected in your machine. Other builds --------- -* **Docker container**: A technology providing operating-system-level virtualization to build, ship, and run distributed applications, whether on laptops, data center VMs, or the cloud. Visit [https://github.com/carlesfernandez/docker-gnsssdr](https://github.com/carlesfernandez/docker-gnsssdr) or [https://github.com/carlesfernandez/docker-pybombs-gnsssdr](https://github.com/carlesfernandez/docker-pybombs-gnsssdr) for instructions. +* **Docker image**: A technology providing operating-system-level virtualization to build, ship, and run distributed applications, whether on laptops, data center VMs, or the cloud. Visit [https://github.com/carlesfernandez/docker-gnsssdr](https://github.com/carlesfernandez/docker-gnsssdr) or [https://github.com/carlesfernandez/docker-pybombs-gnsssdr](https://github.com/carlesfernandez/docker-pybombs-gnsssdr) for instructions. -* **Snap packages**: [Snaps](https://snapcraft.io) are universal Linux packages aimed to work on any distribution or device, from IoT devices to servers, desktops to mobile devices. Visit [https://github.com/carlesfernandez/snapcraft-sandbox](https://github.com/carlesfernandez/snapcraft-sandbox) for instructions. +* **Snap package**: [Snaps](https://snapcraft.io) are universal Linux packages aimed to work on any distribution or device, from IoT devices to servers, desktops to mobile devices. Visit [https://github.com/carlesfernandez/snapcraft-sandbox](https://github.com/carlesfernandez/snapcraft-sandbox) for instructions, or directly [get the software from the Snap Store](https://snapcraft.io/gnss-sdr-next): + +

+ Get GNSS-SDR from the Snap Store +

* **GNSS-SDR in embedded platforms**: we provide a Software Development Kit (SDK) based on [OpenEmbedded](http://www.openembedded.org/wiki/Main_Page) for cross-compiling GNSS-SDR in your desktop computer and for producing executables that can run in embedded platforms, such as a Zedboard or a Raspberry Pi 3. Visit [Cross-compiling GNSS-SDR](https://gnss-sdr.org/docs/tutorials/cross-compiling/) for instructions. @@ -1299,7 +1303,8 @@ Tracking_1C.implementation=GPS_L1_CA_DLL_PLL_Tracking Tracking_1C.item_type=gr_complex Tracking_1C.pll_bw_hz=50.0 ; PLL loop filter bandwidth [Hz] Tracking_1C.dll_bw_hz=2.0 ; DLL loop filter bandwidth [Hz] -Tracking_1C.order=3 ; PLL/DLL loop filter order [2] or [3] +Tracking_1C.pll_filter_order=3 ; PLL loop filter order [2] or [3] +Tracking_1C.dll_filter_order=2 ; DLL loop filter order [1], [2] or [3] Tracking_1C.early_late_space_chips=0.5 ; correlator early-late space [chips]. Tracking_1C.dump=false ; Enable internal binary data file logging [true] or [false] Tracking_1C.dump_filename=./tracking_ch_ ; Log path and filename. Notice that the tracking channel will add "x.dat" where x is the channel number. @@ -1313,7 +1318,8 @@ Tracking_1B.implementation=Galileo_E1_DLL_PLL_VEML_Tracking Tracking_1B.item_type=gr_complex Tracking_1B.pll_bw_hz=15.0; Tracking_1B.dll_bw_hz=2.0; -Tracking_1B.order=3; +Tracking_1B.pll_filter_order=3 ; PLL loop filter order [2] or [3] +Tracking_1B.dll_filter_order=2 ; DLL loop filter order [1], [2] or [3] Tracking_1B.early_late_space_chips=0.15; Tracking_1B.very_early_late_space_chips=0.6; Tracking_1B.dump=false diff --git a/cmake/Modules/FindFILESYSTEM.cmake b/cmake/Modules/FindFILESYSTEM.cmake new file mode 100644 index 000000000..c4ae39556 --- /dev/null +++ b/cmake/Modules/FindFILESYSTEM.cmake @@ -0,0 +1,260 @@ +# Copyright (C) 2019 (see AUTHORS file for a list of contributors) +# +# This file is part of GNSS-SDR. +# +# GNSS-SDR is free software: you can redistribute it and/or modify +# it under the terms of the GNU General Public License as published by +# the Free Software Foundation, either version 3 of the License, or +# (at your option) any later version. +# +# GNSS-SDR is distributed in the hope that it will be useful, +# but WITHOUT ANY WARRANTY; without even the implied warranty of +# MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +# GNU General Public License for more details. +# +# You should have received a copy of the GNU General Public License +# along with GNSS-SDR. If not, see . + +# Original Source: https://github.com/vector-of-bool/CMakeCM +# Modified by C. Fernandez-Prades. + +#[=======================================================================[.rst: + +FindFILESYSTEM +############## + +This module supports the C++17 standard library's filesystem utilities. Use the +:imp-target:`std::filesystem` imported target to + +Options +******* + +The ``COMPONENTS`` argument to this module supports the following values: + +.. find-component:: Experimental + :name: fs.Experimental + + Allows the module to find the "experimental" Filesystem TS version of the + Filesystem library. This is the library that should be used with the + ``std::experimental::filesystem`` namespace. + +.. find-component:: Final + :name: fs.Final + + Finds the final C++17 standard version of the filesystem library. + +If no components are provided, behaves as if the +:find-component:`fs.Final` component was specified. + +If both :find-component:`fs.Experimental` and :find-component:`fs.Final` are +provided, first looks for ``Final``, and falls back to ``Experimental`` in case +of failure. If ``Final`` is found, :imp-target:`std::filesystem` and all +:ref:`variables ` will refer to the ``Final`` version. + + +Imported Targets +**************** + +.. imp-target:: std::filesystem + + The ``std::filesystem`` imported target is defined when any requested + version of the C++ filesystem library has been found, whether it is + *Experimental* or *Final*. + + If no version of the filesystem library is available, this target will not + be defined. + + .. note:: + This target has ``cxx_std_17`` as an ``INTERFACE`` + :ref:`compile language standard feature `. Linking + to this target will automatically enable C++17 if no later standard + version is already required on the linking target. + + +.. _fs.variables: + +Variables +********* + +.. variable:: CXX_FILESYSTEM_IS_EXPERIMENTAL + + Set to ``TRUE`` when the :find-component:`fs.Experimental` version of C++ + filesystem library was found, otherwise ``FALSE``. + +.. variable:: CXX_FILESYSTEM_HAVE_FS + + Set to ``TRUE`` when a filesystem header was found. + +.. variable:: CXX_FILESYSTEM_HEADER + + Set to either ``filesystem`` or ``experimental/filesystem`` depending on + whether :find-component:`fs.Final` or :find-component:`fs.Experimental` was + found. + +.. variable:: CXX_FILESYSTEM_NAMESPACE + + Set to either ``std::filesystem`` or ``std::experimental::filesystem`` + depending on whether :find-component:`fs.Final` or + :find-component:`fs.Experimental` was found. + + +Examples +******** + +Using `find_package(FILESYSTEM)` with no component arguments: + +.. code-block:: cmake + + find_package(FILESYSTEM REQUIRED) + + add_executable(my-program main.cpp) + target_link_libraries(my-program PRIVATE std::filesystem) + + +#]=======================================================================] + + +if(TARGET std::filesystem) + # This module has already been processed. Don't do it again. + return() +endif() + +include(CMakePushCheckState) +include(CheckIncludeFileCXX) +include(CheckCXXSourceCompiles) + +cmake_push_check_state() + +set(CMAKE_REQUIRED_QUIET ${FILESYSTEM_FIND_QUIETLY}) + +# All of our tests require C++17 or later +set(OLD_CMAKE_CXX_STANDARD ${CMAKE_CXX_STANDARD}) +set(CMAKE_CXX_STANDARD 17) +if((CMAKE_CXX_COMPILER_ID STREQUAL "GNU") AND (CMAKE_CXX_COMPILER_VERSION VERSION_GREATER "9.0.0")) + set(CMAKE_REQUIRED_FLAGS "-std=c++17") +endif() +if((CMAKE_CXX_COMPILER_ID STREQUAL "Clang") AND NOT (CMAKE_CXX_COMPILER_VERSION VERSION_LESS "8.99")) + set(CMAKE_REQUIRED_FLAGS "-std=c++17") +endif() + +# Normalize and check the component list we were given +set(want_components ${FILESYSTEM_FIND_COMPONENTS}) +if(FILESYSTEM_FIND_COMPONENTS STREQUAL "") + set(want_components Final) +endif() + +# Warn on any unrecognized components +set(extra_components ${want_components}) +list(REMOVE_ITEM extra_components Final Experimental) +foreach(component IN LISTS extra_components) + message(WARNING "Extraneous find_package component for FILESYSTEM: ${component}") +endforeach() + +# Detect which of Experimental and Final we should look for +set(find_experimental TRUE) +set(find_final TRUE) +if(NOT "Final" IN_LIST want_components) + set(find_final FALSE) +endif() +if(NOT "Experimental" IN_LIST want_components) + set(find_experimental FALSE) +endif() + +if(find_final) + check_include_file_cxx("filesystem" _CXX_FILESYSTEM_HAVE_HEADER) + mark_as_advanced(_CXX_FILESYSTEM_HAVE_HEADER) + if(_CXX_FILESYSTEM_HAVE_HEADER) + # We found the non-experimental header. Don't bother looking for the + # experimental one. + set(find_experimental FALSE) + endif() +else() + set(_CXX_FILESYSTEM_HAVE_HEADER FALSE) +endif() + +if(find_experimental) + check_include_file_cxx("experimental/filesystem" _CXX_FILESYSTEM_HAVE_EXPERIMENTAL_HEADER) + mark_as_advanced(_CXX_FILESYSTEM_HAVE_EXPERIMENTAL_HEADER) +else() + set(_CXX_FILESYSTEM_HAVE_EXPERIMENTAL_HEADER FALSE) +endif() + +if(_CXX_FILESYSTEM_HAVE_HEADER) + set(_have_fs TRUE) + set(_fs_header filesystem) + set(_fs_namespace std::filesystem) +elseif(_CXX_FILESYSTEM_HAVE_EXPERIMENTAL_HEADER) + set(_have_fs TRUE) + set(_fs_header experimental/filesystem) + set(_fs_namespace std::experimental::filesystem) +else() + set(_have_fs FALSE) +endif() + +set(CXX_FILESYSTEM_HAVE_FS ${_have_fs} CACHE BOOL "TRUE if we have the C++ filesystem headers") +set(CXX_FILESYSTEM_HEADER ${_fs_header} CACHE STRING "The header that should be included to obtain the filesystem APIs") +set(CXX_FILESYSTEM_NAMESPACE ${_fs_namespace} CACHE STRING "The C++ namespace that contains the filesystem APIs") + +set(_found FALSE) + +if(CXX_FILESYSTEM_HAVE_FS) + # We have some filesystem library available. Do link checks + string(CONFIGURE [[ + #include <@CXX_FILESYSTEM_HEADER@> + + int main() { + auto cwd = @CXX_FILESYSTEM_NAMESPACE@::current_path(); + return static_cast(cwd.string().size()); + } + ]] code @ONLY) + + # Try to compile a simple filesystem program without any linker flags + check_cxx_source_compiles("${code}" CXX_FILESYSTEM_NO_LINK_NEEDED) + + set(can_link ${CXX_FILESYSTEM_NO_LINK_NEEDED}) + + if(NOT CXX_FILESYSTEM_NO_LINK_NEEDED) + set(prev_libraries ${CMAKE_REQUIRED_LIBRARIES}) + set(CMAKE_REQUIRED_FLAGS "-std=c++17") + # Add the libstdc++ flag + set(CMAKE_REQUIRED_LIBRARIES ${prev_libraries} -lstdc++fs) + check_cxx_source_compiles("${code}" CXX_FILESYSTEM_STDCPPFS_NEEDED) + set(can_link ${CXX_FILESYSTEM_STDCPPFS_NEEDED}) + if(NOT CXX_FILESYSTEM_STDCPPFS_NEEDED) + # Try the libc++ flag + set(CMAKE_REQUIRED_LIBRARIES ${prev_libraries} -lc++fs) + check_cxx_source_compiles("${code}" CXX_FILESYSTEM_CPPFS_NEEDED) + set(can_link ${CXX_FILESYSTEM_CPPFS_NEEDED}) + endif() + endif() + + if(can_link) + if(CMAKE_VERSION VERSION_LESS 3.12) + add_library(std::filesystem INTERFACE IMPORTED GLOBAL) + else() + add_library(std::filesystem INTERFACE IMPORTED) + target_compile_features(std::filesystem INTERFACE cxx_std_17) + endif() + set(_found TRUE) + + if(CXX_FILESYSTEM_NO_LINK_NEEDED) + # Nothing to add... + elseif(CXX_FILESYSTEM_STDCPPFS_NEEDED) + target_link_libraries(std::filesystem INTERFACE -lstdc++fs) + elseif(CXX_FILESYSTEM_CPPFS_NEEDED) + target_link_libraries(std::filesystem INTERFACE -lc++fs) + endif() + endif() +endif() + +if(NOT ${_found}) + set(CMAKE_CXX_STANDARD ${OLD_CMAKE_CXX_STANDARD}) +endif() + +cmake_pop_check_state() + +set(FILESYSTEM_FOUND ${_found} CACHE BOOL "TRUE if we can compile and link a program using std::filesystem" FORCE) + +if(FILESYSTEM_FIND_REQUIRED AND NOT FILESYSTEM_FOUND) + message(FATAL_ERROR "Cannot compile a simple program using std::filesystem") +endif() diff --git a/cmake/Modules/FindGNURADIO.cmake b/cmake/Modules/FindGNURADIO.cmake index d58e87c85..37b106833 100644 --- a/cmake/Modules/FindGNURADIO.cmake +++ b/cmake/Modules/FindGNURADIO.cmake @@ -166,34 +166,48 @@ gr_module(WAVELET gnuradio-wavelet gnuradio/wavelet/api.h gnuradio-wavelet) list(REMOVE_DUPLICATES GNURADIO_ALL_INCLUDE_DIRS) list(REMOVE_DUPLICATES GNURADIO_ALL_LIBRARIES) +if(NOT PC_GNURADIO_RUNTIME_VERSION) + list(GET GNURADIO_BLOCKS_LIBRARIES 0 FIRST_DIR) + get_filename_component(GNURADIO_BLOCKS_DIR ${FIRST_DIR} DIRECTORY) + if(EXISTS ${GNURADIO_BLOCKS_DIR}/cmake/gnuradio/GnuradioConfigVersion.cmake) + set(PACKAGE_FIND_VERSION_MAJOR 3) + set(PACKAGE_FIND_VERSION_MINOR 7) + set(PACKAGE_FIND_VERSION_PATCH 4) + include(${GNURADIO_BLOCKS_DIR}/cmake/gnuradio/GnuradioConfigVersion.cmake) + endif() + if(PACKAGE_VERSION) + set(PC_GNURADIO_RUNTIME_VERSION ${PACKAGE_VERSION}) + endif() +endif() + # Trick to find out that GNU Radio is >= 3.7.4 if pkgconfig is not present if(NOT PC_GNURADIO_RUNTIME_VERSION) find_file(GNURADIO_VERSION_GREATER_THAN_373 - NAMES gnuradio/blocks/tsb_vector_sink_f.h - HINTS $ENV{GNURADIO_RUNTIME_DIR}/include - ${CMAKE_INSTALL_PREFIX}/include - ${GNURADIO_INSTALL_PREFIX}/include - PATHS /usr/local/include - /usr/include - ${GNURADIO_INSTALL_PREFIX}/include - ${GNURADIO_ROOT}/include - $ENV{GNURADIO_ROOT}/include - ) + NAMES gnuradio/blocks/tsb_vector_sink_f.h + HINTS $ENV{GNURADIO_RUNTIME_DIR}/include + ${CMAKE_INSTALL_PREFIX}/include + ${GNURADIO_INSTALL_PREFIX}/include + PATHS /usr/local/include + /usr/include + ${GNURADIO_INSTALL_PREFIX}/include + ${GNURADIO_ROOT}/include + $ENV{GNURADIO_ROOT}/include + ) if(GNURADIO_VERSION_GREATER_THAN_373) set(PC_GNURADIO_RUNTIME_VERSION "3.7.4+") endif() find_file(GNURADIO_VERSION_GREATER_THAN_38 - NAMES gnuradio/filter/mmse_resampler_cc.h - HINTS $ENV{GNURADIO_RUNTIME_DIR}/include - ${CMAKE_INSTALL_PREFIX}/include - ${GNURADIO_INSTALL_PREFIX}/include - PATHS /usr/local/include - /usr/include - ${GNURADIO_INSTALL_PREFIX}/include - ${GNURADIO_ROOT}/include - $ENV{GNURADIO_ROOT}/include - ) + NAMES gnuradio/filter/mmse_resampler_cc.h + HINTS $ENV{GNURADIO_RUNTIME_DIR}/include + ${CMAKE_INSTALL_PREFIX}/include + ${GNURADIO_INSTALL_PREFIX}/include + PATHS /usr/local/include + /usr/include + ${GNURADIO_INSTALL_PREFIX}/include + ${GNURADIO_ROOT}/include + $ENV{GNURADIO_ROOT}/include + ) if(GNURADIO_VERSION_GREATER_THAN_38) set(PC_GNURADIO_RUNTIME_VERSION "3.8.0+") endif() diff --git a/cmake/Modules/FindGRIIO.cmake b/cmake/Modules/FindGRIIO.cmake index 8cb8e9efc..8b83d9386 100644 --- a/cmake/Modules/FindGRIIO.cmake +++ b/cmake/Modules/FindGRIIO.cmake @@ -35,6 +35,22 @@ find_path(IIO_INCLUDE_DIRS $ENV{GRIIO_ROOT}/include ) +if(IIO_INCLUDE_DIRS) + set(GR_IIO_INCLUDE_HAS_GNURADIO TRUE) +else() + find_path(IIO_INCLUDE_DIRS + NAMES iio/api.h + HINTS $ENV{IIO_DIR}/include + ${PC_IIO_INCLUDEDIR} + PATHS ${CMAKE_INSTALL_PREFIX}/include + /usr/local/include + /usr/include + ${GRIIO_ROOT}/include + $ENV{GRIIO_ROOT}/include + ) + set(GR_IIO_INCLUDE_HAS_GNURADIO FALSE) +endif() + find_library(IIO_LIBRARIES NAMES gnuradio-iio HINTS $ENV{IIO_DIR}/lib @@ -86,4 +102,4 @@ if(GRIIO_FOUND AND NOT TARGET Gnuradio::iio) ) endif() -mark_as_advanced(IIO_LIBRARIES IIO_INCLUDE_DIRS) +mark_as_advanced(IIO_LIBRARIES IIO_INCLUDE_DIRS GR_IIO_INCLUDE_HAS_GNURADIO) diff --git a/cmake/Modules/FindLIBIIO.cmake b/cmake/Modules/FindLIBIIO.cmake index 5a9a3806f..ccf9fd133 100644 --- a/cmake/Modules/FindLIBIIO.cmake +++ b/cmake/Modules/FindLIBIIO.cmake @@ -76,6 +76,12 @@ find_library( $ENV{LIBIIO_ROOT}/lib64 ) +if(LIBIIO_LIBRARIES AND APPLE) + if(LIBIIO_LIBRARIES MATCHES "framework") + set(LIBIIO_LIBRARIES ${LIBIIO_LIBRARIES}/iio) + endif() +endif() + include(FindPackageHandleStandardArgs) find_package_handle_standard_args(LIBIIO DEFAULT_MSG LIBIIO_LIBRARIES LIBIIO_INCLUDE_DIRS) diff --git a/conf/gnss-sdr_GPS_L1_FPGA.conf b/conf/gnss-sdr_GPS_L1_FPGA.conf index 70ec83ed5..d9629fdcd 100644 --- a/conf/gnss-sdr_GPS_L1_FPGA.conf +++ b/conf/gnss-sdr_GPS_L1_FPGA.conf @@ -50,7 +50,7 @@ Acquisition_1C.doppler_max=10000 Acquisition_1C.doppler_step=500 ;######### TRACKING GLOBAL CONFIG ############ -Tracking_1C.implementation=GPS_L1_CA_DLL_PLL_C_Aid_Tracking_Fpga +Tracking_1C.implementation=GPS_L1_CA_DLL_PLL_Tracking_Fpga Tracking_1C.item_type=cshort Tracking_1C.dump=false Tracking_1C.dump_filename=../data/epl_tracking_ch_ diff --git a/conf/gnss-sdr_GPS_L1_gr_complex.conf b/conf/gnss-sdr_GPS_L1_gr_complex.conf index 7f83c666c..322190e7e 100644 --- a/conf/gnss-sdr_GPS_L1_gr_complex.conf +++ b/conf/gnss-sdr_GPS_L1_gr_complex.conf @@ -57,7 +57,7 @@ Acquisition_1C.dump_filename=./acq_dump.dat ;######### TRACKING GLOBAL CONFIG ############ -Tracking_1C.implementation=GPS_L1_CA_DLL_PLL_C_Aid_Tracking +Tracking_1C.implementation=GPS_L1_CA_DLL_PLL_Tracking Tracking_1C.item_type=gr_complex Tracking_1C.dump=true Tracking_1C.dump_filename=epl_tracking_ch_ diff --git a/conf/gnss-sdr_GPS_L1_ishort.conf b/conf/gnss-sdr_GPS_L1_ishort.conf index 373049a25..11d958d7d 100644 --- a/conf/gnss-sdr_GPS_L1_ishort.conf +++ b/conf/gnss-sdr_GPS_L1_ishort.conf @@ -56,7 +56,7 @@ Acquisition_1C.dump_filename=./acq_dump.dat Acquisition_1C.blocking=false; ;######### TRACKING GLOBAL CONFIG ############ -Tracking_1C.implementation=GPS_L1_CA_DLL_PLL_C_Aid_Tracking +Tracking_1C.implementation=GPS_L1_CA_DLL_PLL_Tracking Tracking_1C.item_type=cshort Tracking_1C.pll_bw_hz=40.0; Tracking_1C.dll_bw_hz=4.0; diff --git a/conf/gnss-sdr_GPS_L1_pulse_blanking_gr_complex.conf b/conf/gnss-sdr_GPS_L1_pulse_blanking_gr_complex.conf index 618341f48..e48395ac3 100644 --- a/conf/gnss-sdr_GPS_L1_pulse_blanking_gr_complex.conf +++ b/conf/gnss-sdr_GPS_L1_pulse_blanking_gr_complex.conf @@ -69,7 +69,7 @@ Acquisition_1C.dump_filename=./acq_dump.dat ;######### TRACKING GPS CONFIG ############ -Tracking_1C.implementation=GPS_L1_CA_DLL_PLL_C_Aid_Tracking +Tracking_1C.implementation=GPS_L1_CA_DLL_PLL_Tracking Tracking_1C.item_type=gr_complex Tracking_1C.extend_correlation_ms=10 Tracking_1C.pll_bw_hz=35; diff --git a/conf/gnss-sdr_Hybrid_byte.conf b/conf/gnss-sdr_Hybrid_byte.conf index b7f4e58ff..09a1b00d0 100644 --- a/conf/gnss-sdr_Hybrid_byte.conf +++ b/conf/gnss-sdr_Hybrid_byte.conf @@ -104,7 +104,7 @@ Acquisition_1B.dump=false Acquisition_1B.dump_filename=./acq_dump.dat ;######### TRACKING GPS CONFIG ############ -Tracking_1C.implementation=GPS_L1_CA_DLL_PLL_C_Aid_Tracking +Tracking_1C.implementation=GPS_L1_CA_DLL_PLL_Tracking Tracking_1C.item_type=gr_complex Tracking_1C.extend_correlation_ms=1 Tracking_1C.pll_bw_hz=40; diff --git a/conf/gnss-sdr_Hybrid_gr_complex.conf b/conf/gnss-sdr_Hybrid_gr_complex.conf index 14fee756d..11592e9d8 100644 --- a/conf/gnss-sdr_Hybrid_gr_complex.conf +++ b/conf/gnss-sdr_Hybrid_gr_complex.conf @@ -75,7 +75,7 @@ Acquisition_1B.dump_filename=./acq_dump.dat ;######### TRACKING GPS CONFIG ############ -Tracking_1C.implementation=GPS_L1_CA_DLL_PLL_C_Aid_Tracking +Tracking_1C.implementation=GPS_L1_CA_DLL_PLL_Tracking Tracking_1C.item_type=gr_complex Tracking_1C.extend_correlation_ms=10 Tracking_1C.pll_bw_hz=40; diff --git a/conf/gnss-sdr_Hybrid_ishort.conf b/conf/gnss-sdr_Hybrid_ishort.conf index c634009f3..f21a3ee60 100644 --- a/conf/gnss-sdr_Hybrid_ishort.conf +++ b/conf/gnss-sdr_Hybrid_ishort.conf @@ -103,7 +103,7 @@ Acquisition_1B.dump_filename=./acq_dump.dat ;######### TRACKING GPS CONFIG ############ -Tracking_1C.implementation=GPS_L1_CA_DLL_PLL_C_Aid_Tracking +Tracking_1C.implementation=GPS_L1_CA_DLL_PLL_Tracking Tracking_1C.item_type=gr_complex Tracking_1C.pll_bw_hz=50.0; Tracking_1C.dll_bw_hz=5.0; diff --git a/conf/gnss-sdr_Hybrid_nsr.conf b/conf/gnss-sdr_Hybrid_nsr.conf index 9f65ead4b..5778473da 100644 --- a/conf/gnss-sdr_Hybrid_nsr.conf +++ b/conf/gnss-sdr_Hybrid_nsr.conf @@ -120,7 +120,7 @@ Acquisition_1B.dump=false Acquisition_1B.dump_filename=./acq_dump.dat ;######### TRACKING GPS CONFIG ############ -Tracking_1C.implementation=GPS_L1_CA_DLL_PLL_C_Aid_Tracking +Tracking_1C.implementation=GPS_L1_CA_DLL_PLL_Tracking Tracking_1C.item_type=gr_complex Tracking_1C.extend_correlation_ms=1 Tracking_1C.pll_bw_hz=40; diff --git a/conf/gnss-sdr_multichannel_GPS_L1_Flexiband_bin_file_III_1a.conf b/conf/gnss-sdr_multichannel_GPS_L1_Flexiband_bin_file_III_1a.conf index c395a5f3c..8f8addc40 100644 --- a/conf/gnss-sdr_multichannel_GPS_L1_Flexiband_bin_file_III_1a.conf +++ b/conf/gnss-sdr_multichannel_GPS_L1_Flexiband_bin_file_III_1a.conf @@ -143,7 +143,7 @@ Acquisition_1C.dump_filename=./acq_dump.dat ;######### TRACKING GLOBAL CONFIG ############ -Tracking_1C.implementation=GPS_L1_CA_DLL_PLL_C_Aid_Tracking +Tracking_1C.implementation=GPS_L1_CA_DLL_PLL_Tracking Tracking_1C.item_type=gr_complex Tracking_1C.extend_correlation_ms=10 Tracking_1C.pll_bw_hz=40.0; diff --git a/docs/changelog b/docs/changelog index 7abd99d06..5cfa4faee 100644 --- a/docs/changelog +++ b/docs/changelog @@ -1,9 +1,14 @@ ## [Unreleased](https://github.com/gnss-sdr/gnss-sdr/tree/next) +### Improvements in Accuracy + +- Local clock correction based on PVT solution (error kept below 1 ms). + + ### Improvements in Availability - Fixed bug that caused a random deadlock in the Observables block, preventing the computation of PVT fixes. -- Fixed bug in Galileo INAV message decoding when PLL is locked at 180 degrees, which prevented from correct navigation message decoding in some situations. +- Fixed bug in Galileo INAV/FNAV message decoding when PLL is locked at 180 degrees, which prevented from correct navigation message decoding in some situations. - Fixed PVT computation continuity through the TOW rollover. @@ -27,7 +32,7 @@ - Fix bug in GLONASS dual frequency receiver. - Added a custom UDP/IP output for PVT data streaming. - Improved Monitor block with UDP/IP output for internal receiver's data streaming. -- Custom output formats described with .proto files, making easier to other applications reading them in a forward and backward-compatible fashion upon future format changes. +- Custom output formats described with .proto files, making easier to other applications reading them in a forward and backward-compatible fashion upon future format changes. New dependency: Protocol Buffers >= 3.0.0 - Fixes in RINEX generation: week rollover, annotations are not repeated anymore in navigation files. Parameter rinexnav_rate_ms has been removed, annotations are made as new ephemeris arrive. - Fixes in RTCM messages generation: week rollover. @@ -45,6 +50,7 @@ - Added interfaces for FPGA off-loading. - CMake scripts now follow a modern approach (targets and properties) but still work with 2.8.12. - Improvements for macOS users using Homebrew. +- The volk_gnsssdr library can now be built without requiring Boost if the compiler supports C++17. ### Improvements in Reliability diff --git a/src/algorithms/PVT/adapters/rtklib_pvt.cc b/src/algorithms/PVT/adapters/rtklib_pvt.cc index fa89f74cc..cae7fc052 100644 --- a/src/algorithms/PVT/adapters/rtklib_pvt.cc +++ b/src/algorithms/PVT/adapters/rtklib_pvt.cc @@ -277,7 +277,7 @@ Rtklib_Pvt::Rtklib_Pvt(ConfigurationInterface* configuration, { pvt_output_parameters.type_of_receiver = 21; // GPS L1 C/A + Galileo E1B + GPS L2C } - if ((gps_1C_count != 0) && (gps_2S_count == 0) && (gps_L5_count != 0) && (gal_1B_count != 0) && (gal_E5a_count == 0) && (gal_E5b_count = 0) && (glo_1G_count == 0) && (glo_2G_count == 0) && (bds_B1_count == 0) && (bds_B3_count == 0)) + if ((gps_1C_count != 0) && (gps_2S_count == 0) && (gps_L5_count != 0) && (gal_1B_count != 0) && (gal_E5a_count == 0) && (gal_E5b_count == 0) && (glo_1G_count == 0) && (glo_2G_count == 0) && (bds_B1_count == 0) && (bds_B3_count == 0)) { pvt_output_parameters.type_of_receiver = 22; // GPS L1 C/A + Galileo E1B + GPS L5 } diff --git a/src/algorithms/PVT/gnuradio_blocks/CMakeLists.txt b/src/algorithms/PVT/gnuradio_blocks/CMakeLists.txt index 37f5de8fe..060318af0 100644 --- a/src/algorithms/PVT/gnuradio_blocks/CMakeLists.txt +++ b/src/algorithms/PVT/gnuradio_blocks/CMakeLists.txt @@ -28,6 +28,13 @@ source_group(Headers FILES ${PVT_GR_BLOCKS_HEADERS}) add_library(pvt_gr_blocks ${PVT_GR_BLOCKS_SOURCES} ${PVT_GR_BLOCKS_HEADERS}) +if(${FILESYSTEM_FOUND}) + target_compile_definitions(pvt_gr_blocks PRIVATE -DHAS_STD_FILESYSTEM=1) + target_link_libraries(pvt_gr_blocks PRIVATE std::filesystem) +else() + target_link_libraries(pvt_gr_blocks PRIVATE Boost::filesystem Boost::system) +endif() + target_link_libraries(pvt_gr_blocks PUBLIC algorithms_libs_rtklib @@ -40,8 +47,6 @@ target_link_libraries(pvt_gr_blocks algorithms_libs Gflags::gflags Glog::glog - Boost::filesystem - Boost::system Boost::serialization ) diff --git a/src/algorithms/PVT/gnuradio_blocks/rtklib_pvt_gs.cc b/src/algorithms/PVT/gnuradio_blocks/rtklib_pvt_gs.cc index 0b6f265d0..3a8bfc697 100644 --- a/src/algorithms/PVT/gnuradio_blocks/rtklib_pvt_gs.cc +++ b/src/algorithms/PVT/gnuradio_blocks/rtklib_pvt_gs.cc @@ -66,10 +66,8 @@ #include // for bind_t, bind #include #include -#include #include #include // for nvp, make_nvp -#include // for error_code #include // for LOG #include // for io_signature #include // for mp @@ -83,6 +81,19 @@ #include // for length_error #include // for IPC_CREAT #include // for msgctl + +#if HAS_STD_FILESYSTEM +#include +#include +namespace fs = std::filesystem; +namespace errorlib = std; +#else +#include +#include // for error_code +namespace fs = boost::filesystem; +namespace errorlib = boost::system; +#endif + #if OLD_BOOST #include namespace bc = boost::math; @@ -140,7 +151,7 @@ rtklib_pvt_gs::rtklib_pvt_gs(uint32_t nchannels, { d_dump_filename = d_dump_filename.substr(0, d_dump_filename.find_last_of('.')); } - dump_ls_pvt_filename = dump_path + boost::filesystem::path::preferred_separator + d_dump_filename; + dump_ls_pvt_filename = dump_path + fs::path::preferred_separator + d_dump_filename; dump_ls_pvt_filename.append(".dat"); // create directory if (!gnss_sdr_create_directory(dump_path)) @@ -305,24 +316,24 @@ rtklib_pvt_gs::rtklib_pvt_gs(uint32_t nchannels, if (d_xml_storage) { xml_base_path = conf_.xml_output_path; - boost::filesystem::path full_path(boost::filesystem::current_path()); - const boost::filesystem::path p(xml_base_path); - if (!boost::filesystem::exists(p)) + fs::path full_path(fs::current_path()); + const fs::path p(xml_base_path); + if (!fs::exists(p)) { std::string new_folder; - for (auto& folder : boost::filesystem::path(xml_base_path)) + for (auto& folder : fs::path(xml_base_path)) { new_folder += folder.string(); - boost::system::error_code ec; - if (!boost::filesystem::exists(new_folder)) + errorlib::error_code ec; + if (!fs::exists(new_folder)) { - if (!boost::filesystem::create_directory(new_folder, ec)) + if (!fs::create_directory(new_folder, ec)) { std::cout << "Could not create the " << new_folder << " folder." << std::endl; xml_base_path = full_path.string(); } } - new_folder += boost::filesystem::path::preferred_separator; + new_folder += fs::path::preferred_separator; } } else @@ -334,7 +345,7 @@ rtklib_pvt_gs::rtklib_pvt_gs(uint32_t nchannels, std::cout << "XML files will be stored at " << xml_base_path << std::endl; } - xml_base_path = xml_base_path + boost::filesystem::path::preferred_separator; + xml_base_path = xml_base_path + fs::path::preferred_separator; } d_rx_time = 0.0; diff --git a/src/algorithms/PVT/libs/CMakeLists.txt b/src/algorithms/PVT/libs/CMakeLists.txt index d4df48600..92e1aec04 100644 --- a/src/algorithms/PVT/libs/CMakeLists.txt +++ b/src/algorithms/PVT/libs/CMakeLists.txt @@ -61,6 +61,13 @@ source_group(Headers FILES ${PVT_LIB_HEADERS}) add_library(pvt_libs ${PVT_LIB_SOURCES} ${PVT_LIB_HEADERS}) +if(${FILESYSTEM_FOUND}) + target_compile_definitions(pvt_libs PRIVATE -DHAS_STD_FILESYSTEM=1) + target_link_libraries(pvt_libs PRIVATE std::filesystem) +else() + target_link_libraries(pvt_libs PRIVATE Boost::filesystem Boost::system) +endif() + target_link_libraries(pvt_libs PUBLIC Armadillo::armadillo @@ -70,8 +77,6 @@ target_link_libraries(pvt_libs core_system_parameters PRIVATE algorithms_libs - Boost::filesystem - Boost::system Gflags::gflags Glog::glog Matio::matio @@ -94,12 +99,20 @@ if(Boost_VERSION VERSION_GREATER "106599") ) endif() +# Fix for Boost Asio < 1.70 if(OS_IS_MACOSX) - if(CMAKE_CXX_COMPILER_ID STREQUAL "Clang") # not AppleClang - target_compile_definitions(pvt_libs - PUBLIC - -DBOOST_ASIO_HAS_STD_STRING_VIEW - ) + if((CMAKE_CXX_COMPILER_ID MATCHES "Clang") AND (${Boost_VERSION} VERSION_LESS 107000)) + if(${has_string_view}) + target_compile_definitions(pvt_libs + PUBLIC + -DBOOST_ASIO_HAS_STD_STRING_VIEW=1 + ) + else() + target_compile_definitions(pvt_libs + PUBLIC + -DBOOST_ASIO_HAS_STD_STRING_VIEW=0 + ) + endif() endif() endif() diff --git a/src/algorithms/PVT/libs/geojson_printer.cc b/src/algorithms/PVT/libs/geojson_printer.cc index e38984a88..6f9dcffe4 100644 --- a/src/algorithms/PVT/libs/geojson_printer.cc +++ b/src/algorithms/PVT/libs/geojson_printer.cc @@ -33,10 +33,15 @@ #include "geojson_printer.h" #include "pvt_solution.h" #include +#if HAS_STD_FILESYSTEM +#include +#include +#else #include // for create_directories, exists #include // for path, operator<< #include // for filesystem #include // for error_code +#endif #include #include // for remove #include // for tm @@ -45,29 +50,36 @@ #include // for cout, cerr #include // for stringstream +#if HAS_STD_FILESYSTEM +namespace fs = std::filesystem; +namespace errorlib = std; +#else +namespace fs = boost::filesystem; +namespace errorlib = boost::system; +#endif GeoJSON_Printer::GeoJSON_Printer(const std::string& base_path) { first_pos = true; geojson_base_path = base_path; - boost::filesystem::path full_path(boost::filesystem::current_path()); - const boost::filesystem::path p(geojson_base_path); - if (!boost::filesystem::exists(p)) + fs::path full_path(fs::current_path()); + const fs::path p(geojson_base_path); + if (!fs::exists(p)) { std::string new_folder; - for (auto& folder : boost::filesystem::path(geojson_base_path)) + for (auto& folder : fs::path(geojson_base_path)) { new_folder += folder.string(); - boost::system::error_code ec; - if (!boost::filesystem::exists(new_folder)) + errorlib::error_code ec; + if (!fs::exists(new_folder)) { - if (!boost::filesystem::create_directory(new_folder, ec)) + if (!fs::create_directory(new_folder, ec)) { std::cout << "Could not create the " << new_folder << " folder." << std::endl; geojson_base_path = full_path.string(); } } - new_folder += boost::filesystem::path::preferred_separator; + new_folder += fs::path::preferred_separator; } } else @@ -79,7 +91,7 @@ GeoJSON_Printer::GeoJSON_Printer(const std::string& base_path) std::cout << "GeoJSON files will be stored at " << geojson_base_path << std::endl; } - geojson_base_path = geojson_base_path + boost::filesystem::path::preferred_separator; + geojson_base_path = geojson_base_path + fs::path::preferred_separator; } diff --git a/src/algorithms/PVT/libs/gpx_printer.cc b/src/algorithms/PVT/libs/gpx_printer.cc index 3066ae824..8925f281a 100644 --- a/src/algorithms/PVT/libs/gpx_printer.cc +++ b/src/algorithms/PVT/libs/gpx_printer.cc @@ -33,10 +33,15 @@ #include "gpx_printer.h" #include "rtklib_solver.h" #include +#if HAS_STD_FILESYSTEM +#include +#include +#else #include // for create_directories, exists #include // for path, operator<< #include // for filesystem #include // for error_code +#endif #include #include // for remove #include // for tm @@ -45,30 +50,38 @@ #include // for cout, cerr #include // for stringstream +#if HAS_STD_FILESYSTEM +namespace fs = std::filesystem; +namespace errorlib = std; +#else +namespace fs = boost::filesystem; +namespace errorlib = boost::system; +#endif + Gpx_Printer::Gpx_Printer(const std::string& base_path) { positions_printed = false; indent = " "; gpx_base_path = base_path; - boost::filesystem::path full_path(boost::filesystem::current_path()); - const boost::filesystem::path p(gpx_base_path); - if (!boost::filesystem::exists(p)) + fs::path full_path(fs::current_path()); + const fs::path p(gpx_base_path); + if (!fs::exists(p)) { std::string new_folder; - for (auto& folder : boost::filesystem::path(gpx_base_path)) + for (auto& folder : fs::path(gpx_base_path)) { new_folder += folder.string(); - boost::system::error_code ec; - if (!boost::filesystem::exists(new_folder)) + errorlib::error_code ec; + if (!fs::exists(new_folder)) { - if (!boost::filesystem::create_directory(new_folder, ec)) + if (!fs::create_directory(new_folder, ec)) { std::cout << "Could not create the " << new_folder << " folder." << std::endl; gpx_base_path = full_path.string(); } } - new_folder += boost::filesystem::path::preferred_separator; + new_folder += fs::path::preferred_separator; } } else @@ -80,7 +93,7 @@ Gpx_Printer::Gpx_Printer(const std::string& base_path) std::cout << "GPX files will be stored at " << gpx_base_path << std::endl; } - gpx_base_path = gpx_base_path + boost::filesystem::path::preferred_separator; + gpx_base_path = gpx_base_path + fs::path::preferred_separator; } diff --git a/src/algorithms/PVT/libs/kml_printer.cc b/src/algorithms/PVT/libs/kml_printer.cc index e1335490c..335fc0fee 100644 --- a/src/algorithms/PVT/libs/kml_printer.cc +++ b/src/algorithms/PVT/libs/kml_printer.cc @@ -33,17 +33,34 @@ #include "kml_printer.h" #include "rtklib_solver.h" #include +#if HAS_STD_FILESYSTEM +#include +#include +#else #include // for create_directories, exists #include // for path, operator<< #include // for filesystem #include // for error_code +#endif #include #include // for remove +#include // for mkstemp +#include // for strncpy #include // for tm #include // for exception #include // for cout, cerr #include #include +#include // for S_IXUSR | S_IRWXG | S_IRWXO +#include //for mode_t + +#if HAS_STD_FILESYSTEM +namespace fs = std::filesystem; +namespace errorlib = std; +#else +namespace fs = boost::filesystem; +namespace errorlib = boost::system; +#endif Kml_Printer::Kml_Printer(const std::string& base_path) @@ -51,24 +68,24 @@ Kml_Printer::Kml_Printer(const std::string& base_path) positions_printed = false; indent = " "; kml_base_path = base_path; - boost::filesystem::path full_path(boost::filesystem::current_path()); - const boost::filesystem::path p(kml_base_path); - if (!boost::filesystem::exists(p)) + fs::path full_path(fs::current_path()); + const fs::path p(kml_base_path); + if (!fs::exists(p)) { std::string new_folder; - for (auto& folder : boost::filesystem::path(kml_base_path)) + for (auto& folder : fs::path(kml_base_path)) { new_folder += folder.string(); - boost::system::error_code ec; - if (!boost::filesystem::exists(new_folder)) + errorlib::error_code ec; + if (!fs::exists(new_folder)) { - if (!boost::filesystem::create_directory(new_folder, ec)) + if (!fs::create_directory(new_folder, ec)) { std::cout << "Could not create the " << new_folder << " folder." << std::endl; kml_base_path = full_path.string(); } } - new_folder += boost::filesystem::path::preferred_separator; + new_folder += fs::path::preferred_separator; } } else @@ -80,13 +97,23 @@ Kml_Printer::Kml_Printer(const std::string& base_path) std::cout << "KML files will be stored at " << kml_base_path << std::endl; } - kml_base_path = kml_base_path + boost::filesystem::path::preferred_separator; + kml_base_path = kml_base_path + fs::path::preferred_separator; - boost::filesystem::path tmp_base_path = boost::filesystem::temp_directory_path(); - boost::filesystem::path tmp_filename = boost::filesystem::unique_path(); - boost::filesystem::path tmp_file = tmp_base_path / tmp_filename; + char tmp_filename_[] = "/tmp/file.XXXXXX"; + mode_t mask = umask(S_IXUSR | S_IRWXG | S_IRWXO); + int fd = mkstemp(tmp_filename_); + if (fd == -1) + { + std::cerr << "Error in KML printer: failed to create temporary file" << std::endl; + } + else + { + close(fd); + } + umask(mask); + fs::path tmp_filename = fs::path(tmp_filename_); - tmp_file_str = tmp_file.string(); + tmp_file_str = tmp_filename.string(); point_id = 0; } diff --git a/src/algorithms/PVT/libs/nmea_printer.cc b/src/algorithms/PVT/libs/nmea_printer.cc index 9186d48e0..0e7127003 100644 --- a/src/algorithms/PVT/libs/nmea_printer.cc +++ b/src/algorithms/PVT/libs/nmea_printer.cc @@ -36,10 +36,15 @@ #include "nmea_printer.h" #include "rtklib_solution.h" #include "rtklib_solver.h" +#if HAS_STD_FILESYSTEM +#include +#include +#else #include // for create_directories, exists #include // for path, operator<< #include // for filesystem #include // for error_code +#endif #include #include #include @@ -47,6 +52,14 @@ #include // for cout, cerr #include +#if HAS_STD_FILESYSTEM +namespace fs = std::filesystem; +namespace errorlib = std; +#else +namespace fs = boost::filesystem; +namespace errorlib = boost::system; +#endif + Nmea_Printer::Nmea_Printer(const std::string& filename, bool flag_nmea_output_file, bool flag_nmea_tty_port, std::string nmea_dump_devname, const std::string& base_path) { @@ -54,24 +67,24 @@ Nmea_Printer::Nmea_Printer(const std::string& filename, bool flag_nmea_output_fi d_flag_nmea_output_file = flag_nmea_output_file; if (d_flag_nmea_output_file == true) { - boost::filesystem::path full_path(boost::filesystem::current_path()); - const boost::filesystem::path p(nmea_base_path); - if (!boost::filesystem::exists(p)) + fs::path full_path(fs::current_path()); + const fs::path p(nmea_base_path); + if (!fs::exists(p)) { std::string new_folder; - for (auto& folder : boost::filesystem::path(nmea_base_path)) + for (auto& folder : fs::path(nmea_base_path)) { new_folder += folder.string(); - boost::system::error_code ec; - if (!boost::filesystem::exists(new_folder)) + errorlib::error_code ec; + if (!fs::exists(new_folder)) { - if (!boost::filesystem::create_directory(new_folder, ec)) + if (!fs::create_directory(new_folder, ec)) { std::cout << "Could not create the " << new_folder << " folder." << std::endl; nmea_base_path = full_path.string(); } } - new_folder += boost::filesystem::path::preferred_separator; + new_folder += fs::path::preferred_separator; } } else @@ -84,7 +97,7 @@ Nmea_Printer::Nmea_Printer(const std::string& filename, bool flag_nmea_output_fi std::cout << "NMEA files will be stored at " << nmea_base_path << std::endl; } - nmea_base_path = nmea_base_path + boost::filesystem::path::preferred_separator; + nmea_base_path = nmea_base_path + fs::path::preferred_separator; nmea_filename = nmea_base_path + filename; diff --git a/src/algorithms/PVT/libs/rinex_printer.cc b/src/algorithms/PVT/libs/rinex_printer.cc index bf9b73dbd..7da65c565 100644 --- a/src/algorithms/PVT/libs/rinex_printer.cc +++ b/src/algorithms/PVT/libs/rinex_printer.cc @@ -53,9 +53,15 @@ #include #include #include +#if HAS_STD_FILESYSTEM +#include +#include +#else #include // for create_directories, exists #include // for path, operator<< #include // for filesystem +#include // for error_code +#endif #include #include // for min and max #include // for floor @@ -69,28 +75,36 @@ #include #include +#if HAS_STD_FILESYSTEM +namespace fs = std::filesystem; +namespace errorlib = std; +#else +namespace fs = boost::filesystem; +namespace errorlib = boost::system; +#endif + Rinex_Printer::Rinex_Printer(int32_t conf_version, const std::string& base_path) { std::string base_rinex_path = base_path; - boost::filesystem::path full_path(boost::filesystem::current_path()); - const boost::filesystem::path p(base_rinex_path); - if (!boost::filesystem::exists(p)) + fs::path full_path(fs::current_path()); + const fs::path p(base_rinex_path); + if (!fs::exists(p)) { std::string new_folder; - for (auto& folder : boost::filesystem::path(base_rinex_path)) + for (auto& folder : fs::path(base_rinex_path)) { new_folder += folder.string(); - boost::system::error_code ec; - if (!boost::filesystem::exists(new_folder)) + errorlib::error_code ec; + if (!fs::exists(new_folder)) { - if (!boost::filesystem::create_directory(new_folder, ec)) + if (!fs::create_directory(new_folder, ec)) { std::cout << "Could not create the " << new_folder << " folder." << std::endl; base_rinex_path = full_path.string(); } } - new_folder += boost::filesystem::path::preferred_separator; + new_folder += fs::path::preferred_separator; } } else @@ -102,13 +116,13 @@ Rinex_Printer::Rinex_Printer(int32_t conf_version, const std::string& base_path) std::cout << "RINEX files will be stored at " << base_rinex_path << std::endl; } - navfilename = base_rinex_path + boost::filesystem::path::preferred_separator + Rinex_Printer::createFilename("RINEX_FILE_TYPE_GPS_NAV"); - obsfilename = base_rinex_path + boost::filesystem::path::preferred_separator + Rinex_Printer::createFilename("RINEX_FILE_TYPE_OBS"); - sbsfilename = base_rinex_path + boost::filesystem::path::preferred_separator + Rinex_Printer::createFilename("RINEX_FILE_TYPE_SBAS"); - navGalfilename = base_rinex_path + boost::filesystem::path::preferred_separator + Rinex_Printer::createFilename("RINEX_FILE_TYPE_GAL_NAV"); - navMixfilename = base_rinex_path + boost::filesystem::path::preferred_separator + Rinex_Printer::createFilename("RINEX_FILE_TYPE_MIXED_NAV"); - navGlofilename = base_rinex_path + boost::filesystem::path::preferred_separator + Rinex_Printer::createFilename("RINEX_FILE_TYPE_GLO_NAV"); - navBdsfilename = base_rinex_path + boost::filesystem::path::preferred_separator + Rinex_Printer::createFilename("RINEX_FILE_TYPE_BDS_NAV"); + navfilename = base_rinex_path + fs::path::preferred_separator + Rinex_Printer::createFilename("RINEX_FILE_TYPE_GPS_NAV"); + obsfilename = base_rinex_path + fs::path::preferred_separator + Rinex_Printer::createFilename("RINEX_FILE_TYPE_OBS"); + sbsfilename = base_rinex_path + fs::path::preferred_separator + Rinex_Printer::createFilename("RINEX_FILE_TYPE_SBAS"); + navGalfilename = base_rinex_path + fs::path::preferred_separator + Rinex_Printer::createFilename("RINEX_FILE_TYPE_GAL_NAV"); + navMixfilename = base_rinex_path + fs::path::preferred_separator + Rinex_Printer::createFilename("RINEX_FILE_TYPE_MIXED_NAV"); + navGlofilename = base_rinex_path + fs::path::preferred_separator + Rinex_Printer::createFilename("RINEX_FILE_TYPE_GLO_NAV"); + navBdsfilename = base_rinex_path + fs::path::preferred_separator + Rinex_Printer::createFilename("RINEX_FILE_TYPE_BDS_NAV"); Rinex_Printer::navFile.open(navfilename, std::ios::out | std::ios::in | std::ios::app); Rinex_Printer::obsFile.open(obsfilename, std::ios::out | std::ios::in | std::ios::app); diff --git a/src/algorithms/PVT/libs/rtcm_printer.cc b/src/algorithms/PVT/libs/rtcm_printer.cc index fce92af08..bccec8dce 100644 --- a/src/algorithms/PVT/libs/rtcm_printer.cc +++ b/src/algorithms/PVT/libs/rtcm_printer.cc @@ -39,11 +39,16 @@ #include "gps_cnav_ephemeris.h" #include "gps_ephemeris.h" #include "rtcm.h" +#if HAS_STD_FILESYSTEM +#include +#include +#else #include #include // for create_directories, exists #include // for path, operator<< #include // for filesystem #include // for error_codes +#endif #include #include // for remove #include // for tm @@ -53,6 +58,14 @@ #include // for tcgetattr #include // for close, write +#if HAS_STD_FILESYSTEM +namespace fs = std::filesystem; +namespace errorlib = std; +#else +namespace fs = boost::filesystem; +namespace errorlib = boost::system; +#endif + Rtcm_Printer::Rtcm_Printer(const std::string& filename, bool flag_rtcm_file_dump, bool flag_rtcm_server, bool flag_rtcm_tty_port, uint16_t rtcm_tcp_port, uint16_t rtcm_station_id, const std::string& rtcm_dump_devname, bool time_tag_name, const std::string& base_path) { @@ -62,24 +75,24 @@ Rtcm_Printer::Rtcm_Printer(const std::string& filename, bool flag_rtcm_file_dump rtcm_base_path = base_path; if (d_rtcm_file_dump) { - boost::filesystem::path full_path(boost::filesystem::current_path()); - const boost::filesystem::path p(rtcm_base_path); - if (!boost::filesystem::exists(p)) + fs::path full_path(fs::current_path()); + const fs::path p(rtcm_base_path); + if (!fs::exists(p)) { std::string new_folder; - for (auto& folder : boost::filesystem::path(rtcm_base_path)) + for (auto& folder : fs::path(rtcm_base_path)) { new_folder += folder.string(); - boost::system::error_code ec; - if (!boost::filesystem::exists(new_folder)) + errorlib::error_code ec; + if (!fs::exists(new_folder)) { - if (!boost::filesystem::create_directory(new_folder, ec)) + if (!fs::create_directory(new_folder, ec)) { std::cout << "Could not create the " << new_folder << " folder." << std::endl; rtcm_base_path = full_path.string(); } } - new_folder += boost::filesystem::path::preferred_separator; + new_folder += fs::path::preferred_separator; } } else @@ -91,7 +104,7 @@ Rtcm_Printer::Rtcm_Printer(const std::string& filename, bool flag_rtcm_file_dump std::cout << "RTCM binary file will be stored at " << rtcm_base_path << std::endl; } - rtcm_base_path = rtcm_base_path + boost::filesystem::path::preferred_separator; + rtcm_base_path = rtcm_base_path + fs::path::preferred_separator; } if (time_tag_name) diff --git a/src/algorithms/PVT/libs/rtklib_solver.cc b/src/algorithms/PVT/libs/rtklib_solver.cc index 5365a3a08..ecf0efe9a 100644 --- a/src/algorithms/PVT/libs/rtklib_solver.cc +++ b/src/algorithms/PVT/libs/rtklib_solver.cc @@ -961,15 +961,18 @@ bool Rtklib_Solver::get_PVT(const std::map &gnss_observables_ rx_position_and_time(0) = pvt_sol.rr[0]; // [m] rx_position_and_time(1) = pvt_sol.rr[1]; // [m] rx_position_and_time(2) = pvt_sol.rr[2]; // [m] - //todo: fix this ambiguity in the RTKLIB units in receiver clock offset! if (rtk_.opt.mode == PMODE_SINGLE) { - rx_position_and_time(3) = pvt_sol.dtr[0]; // if the RTKLIB solver is set to SINGLE, the dtr is already expressed in [s] + // if the RTKLIB solver is set to SINGLE, the dtr is already expressed in [s] + // add also the clock offset from gps to galileo (pvt_sol.dtr[2]) + rx_position_and_time(3) = pvt_sol.dtr[0] + pvt_sol.dtr[2]; } else { - rx_position_and_time(3) = pvt_sol.dtr[0] / GPS_C_M_S; // the receiver clock offset is expressed in [meters], so we convert it into [s] + // the receiver clock offset is expressed in [meters], so we convert it into [s] + // add also the clock offset from gps to galileo (pvt_sol.dtr[2]) + rx_position_and_time(3) = pvt_sol.dtr[2] + pvt_sol.dtr[0] / GPS_C_M_S; } this->set_rx_pos(rx_position_and_time.rows(0, 2)); // save ECEF position for the next iteration diff --git a/src/algorithms/acquisition/gnuradio_blocks/CMakeLists.txt b/src/algorithms/acquisition/gnuradio_blocks/CMakeLists.txt index a23bfba82..dfec5b089 100644 --- a/src/algorithms/acquisition/gnuradio_blocks/CMakeLists.txt +++ b/src/algorithms/acquisition/gnuradio_blocks/CMakeLists.txt @@ -66,6 +66,13 @@ source_group(Headers FILES ${ACQ_GR_BLOCKS_HEADERS}) add_library(acquisition_gr_blocks ${ACQ_GR_BLOCKS_SOURCES} ${ACQ_GR_BLOCKS_HEADERS}) +if(${FILESYSTEM_FOUND}) + target_compile_definitions(acquisition_gr_blocks PRIVATE -DHAS_STD_FILESYSTEM=1) + target_link_libraries(acquisition_gr_blocks PRIVATE std::filesystem) +else() + target_link_libraries(acquisition_gr_blocks PRIVATE Boost::filesystem) +endif() + target_link_libraries(acquisition_gr_blocks PUBLIC Gnuradio::runtime @@ -76,7 +83,6 @@ target_link_libraries(acquisition_gr_blocks core_system_parameters ${OPT_LIBRARIES} PRIVATE - Boost::filesystem Gflags::gflags Glog::glog Matio::matio diff --git a/src/algorithms/acquisition/gnuradio_blocks/pcps_acquisition.cc b/src/algorithms/acquisition/gnuradio_blocks/pcps_acquisition.cc index a13794974..abb00ea79 100644 --- a/src/algorithms/acquisition/gnuradio_blocks/pcps_acquisition.cc +++ b/src/algorithms/acquisition/gnuradio_blocks/pcps_acquisition.cc @@ -39,7 +39,11 @@ #include "gnss_frequencies.h" #include "gnss_sdr_create_directory.h" #include "gnss_synchro.h" +#if HAS_STD_FILESYSTEM +#include +#else #include +#endif #include #include #include @@ -53,6 +57,12 @@ #include #include +#if HAS_STD_FILESYSTEM +namespace fs = std::filesystem; +#else +namespace fs = boost::filesystem; +#endif + pcps_acquisition_sptr pcps_make_acquisition(const Acq_Conf& conf_) { @@ -184,7 +194,7 @@ pcps_acquisition::pcps_acquisition(const Acq_Conf& conf_) : gr::block("pcps_acqu { d_dump_filename = d_dump_filename.substr(0, d_dump_filename.find_last_of('.')); } - d_dump_filename = dump_path + boost::filesystem::path::preferred_separator + d_dump_filename; + d_dump_filename = dump_path + fs::path::preferred_separator + d_dump_filename; // create directory if (!gnss_sdr_create_directory(dump_path)) { diff --git a/src/algorithms/acquisition/gnuradio_blocks/pcps_acquisition_fine_doppler_cc.cc b/src/algorithms/acquisition/gnuradio_blocks/pcps_acquisition_fine_doppler_cc.cc index eab92d8a8..051c81130 100644 --- a/src/algorithms/acquisition/gnuradio_blocks/pcps_acquisition_fine_doppler_cc.cc +++ b/src/algorithms/acquisition/gnuradio_blocks/pcps_acquisition_fine_doppler_cc.cc @@ -34,7 +34,11 @@ #include "GPS_L1_CA.h" #include "gnss_sdr_create_directory.h" #include "gps_sdr_signal_processing.h" +#if HAS_STD_FILESYSTEM +#include +#else #include +#endif #include #include #include @@ -43,6 +47,12 @@ #include // std::rotate, std::fill_n #include +#if HAS_STD_FILESYSTEM +namespace fs = std::filesystem; +#else +namespace fs = boost::filesystem; +#endif + pcps_acquisition_fine_doppler_cc_sptr pcps_make_acquisition_fine_doppler_cc(const Acq_Conf &conf_) { @@ -107,7 +117,7 @@ pcps_acquisition_fine_doppler_cc::pcps_acquisition_fine_doppler_cc(const Acq_Con { d_dump_filename = d_dump_filename.substr(0, d_dump_filename.find_last_of('.')); } - d_dump_filename = dump_path + boost::filesystem::path::preferred_separator + d_dump_filename; + d_dump_filename = dump_path + fs::path::preferred_separator + d_dump_filename; // create directory if (!gnss_sdr_create_directory(dump_path)) { diff --git a/src/algorithms/input_filter/adapters/freq_xlating_fir_filter.cc b/src/algorithms/input_filter/adapters/freq_xlating_fir_filter.cc index e85c9b88f..f6e062ab8 100644 --- a/src/algorithms/input_filter/adapters/freq_xlating_fir_filter.cc +++ b/src/algorithms/input_filter/adapters/freq_xlating_fir_filter.cc @@ -121,7 +121,7 @@ FreqXlatingFirFilter::FreqXlatingFirFilter(ConfigurationInterface* configuration } size_t item_size; - + LOG(INFO) << "Created freq_xlating_fir_filter with " << taps_.size()<<" taps"; if ((taps_item_type_ == "float") && (input_item_type_ == "gr_complex") && (output_item_type_ == "gr_complex")) { item_size = sizeof(gr_complex); //output diff --git a/src/algorithms/libs/CMakeLists.txt b/src/algorithms/libs/CMakeLists.txt index a9c292c50..4dc71a6bb 100644 --- a/src/algorithms/libs/CMakeLists.txt +++ b/src/algorithms/libs/CMakeLists.txt @@ -88,6 +88,13 @@ source_group(Headers FILES ${GNSS_SPLIBS_HEADERS}) add_library(algorithms_libs ${GNSS_SPLIBS_SOURCES} ${GNSS_SPLIBS_HEADERS}) +if(${FILESYSTEM_FOUND}) + target_compile_definitions(algorithms_libs PRIVATE -DHAS_STD_FILESYSTEM=1) + target_link_libraries(algorithms_libs PRIVATE std::filesystem) +else() + target_link_libraries(algorithms_libs PRIVATE Boost::filesystem Boost::system) +endif() + target_link_libraries(algorithms_libs PUBLIC Armadillo::armadillo @@ -100,7 +107,6 @@ target_link_libraries(algorithms_libs core_system_parameters Volk::volk ${ORC_LIBRARIES} Volkgnsssdr::volkgnsssdr - Boost::filesystem Glog::glog ) @@ -133,11 +139,16 @@ source_group(Headers FILES gnss_sdr_flags.h) add_library(gnss_sdr_flags gnss_sdr_flags.cc gnss_sdr_flags.h) +if(${FILESYSTEM_FOUND}) + target_compile_definitions(gnss_sdr_flags PRIVATE -DHAS_STD_FILESYSTEM=1) + target_link_libraries(gnss_sdr_flags PRIVATE std::filesystem) +else() + target_link_libraries(gnss_sdr_flags PRIVATE Boost::filesystem) +endif() + target_link_libraries(gnss_sdr_flags PUBLIC Gflags::gflags - PRIVATE - Boost::filesystem ) if(${GFLAGS_GREATER_20}) diff --git a/src/algorithms/libs/gnss_sdr_create_directory.cc b/src/algorithms/libs/gnss_sdr_create_directory.cc index 2a3c66cad..325f5ebac 100644 --- a/src/algorithms/libs/gnss_sdr_create_directory.cc +++ b/src/algorithms/libs/gnss_sdr_create_directory.cc @@ -29,35 +29,46 @@ */ #include "gnss_sdr_create_directory.h" +#if HAS_STD_FILESYSTEM +#include +#include +#else #include // for create_directories, exists #include // for path, operator<< #include // for filesystem #include // for error_code -#include // for exception -#include // for ofstream +#endif +#include // for exception +#include // for ofstream + +#if HAS_STD_FILESYSTEM +namespace fs = std::filesystem; +namespace errorlib = std; +#else +namespace fs = boost::filesystem; +namespace errorlib = boost::system; +#endif bool gnss_sdr_create_directory(const std::string& foldername) { std::string new_folder; - for (auto& folder : boost::filesystem::path(foldername)) + for (auto& folder : fs::path(foldername)) { new_folder += folder.string(); - boost::system::error_code ec; - if (!boost::filesystem::exists(new_folder)) + errorlib::error_code ec; + if (!fs::exists(new_folder)) { - try + if (!fs::create_directory(new_folder, ec)) { - if (!boost::filesystem::create_directory(new_folder, ec)) - { - return false; - } + return false; } - catch (std::exception& e) + + if (static_cast(ec)) { return false; } } - new_folder += boost::filesystem::path::preferred_separator; + new_folder += fs::path::preferred_separator; } // Check if we have writing permissions @@ -67,19 +78,16 @@ bool gnss_sdr_create_directory(const std::string& foldername) if (os_test_file.is_open()) { - boost::system::error_code ec; + errorlib::error_code ec; os_test_file.close(); - try - { - boost::filesystem::remove(test_file, ec); - } - catch (std::exception& e) + + fs::remove(test_file, ec); + if (static_cast(ec)) { return false; } return true; } - os_test_file.close(); return false; } diff --git a/src/algorithms/libs/gnss_sdr_flags.cc b/src/algorithms/libs/gnss_sdr_flags.cc index e44812281..756d428f4 100644 --- a/src/algorithms/libs/gnss_sdr_flags.cc +++ b/src/algorithms/libs/gnss_sdr_flags.cc @@ -30,11 +30,22 @@ #include "gnss_sdr_flags.h" +#if HAS_STD_FILESYSTEM +#include +#else #include // for exists +#endif #include #include #include +#if HAS_STD_FILESYSTEM +namespace fs = std::filesystem; +#else +namespace fs = boost::filesystem; +#endif + + DEFINE_string(c, "-", "Path to the configuration file (if set, overrides --config_file)."); DEFINE_string(config_file, std::string(GNSSSDR_INSTALL_DIR "/share/gnss-sdr/conf/default.conf"), @@ -69,7 +80,7 @@ DEFINE_double(pll_bw_hz, 0.0, "If defined, bandwidth of the PLL low pass filter, static bool ValidateC(const char* flagname, const std::string& value) { - if (boost::filesystem::exists(value) or value == "-") + if (fs::exists(value) or value == "-") { // value is ok return true; } @@ -80,7 +91,7 @@ static bool ValidateC(const char* flagname, const std::string& value) static bool ValidateConfigFile(const char* flagname, const std::string& value) { - if (boost::filesystem::exists(value) or value == std::string(GNSSSDR_INSTALL_DIR "/share/gnss-sdr/conf/default.conf")) + if (fs::exists(value) or value == std::string(GNSSSDR_INSTALL_DIR "/share/gnss-sdr/conf/default.conf")) { // value is ok return true; } @@ -91,7 +102,7 @@ static bool ValidateConfigFile(const char* flagname, const std::string& value) static bool ValidateS(const char* flagname, const std::string& value) { - if (boost::filesystem::exists(value) or value == "-") + if (fs::exists(value) or value == "-") { // value is ok return true; } @@ -102,7 +113,7 @@ static bool ValidateS(const char* flagname, const std::string& value) static bool ValidateSignalSource(const char* flagname, const std::string& value) { - if (boost::filesystem::exists(value) or value == "-") + if (fs::exists(value) or value == "-") { // value is ok return true; } diff --git a/src/algorithms/libs/gps_l5_signal.cc b/src/algorithms/libs/gps_l5_signal.cc index c1f234506..c5fc6e13c 100644 --- a/src/algorithms/libs/gps_l5_signal.cc +++ b/src/algorithms/libs/gps_l5_signal.cc @@ -32,13 +32,10 @@ #include "gps_l5_signal.h" #include "GPS_L5.h" -#include -#include -#include #include -std::deque l5i_xa_shift(std::deque xa) +std::deque l5i_xa_shift(std::deque xa) // GPS-IS-705E Figure 3-4 pp. 15 { if (xa == std::deque{true, true, true, true, true, true, true, true, true, true, true, false, true}) { @@ -62,7 +59,7 @@ std::deque l5q_xa_shift(std::deque xa) } -std::deque l5i_xb_shift(std::deque xb) +std::deque l5i_xb_shift(std::deque xb) // GPS-IS-705E Figure 3-5 pp. 16 { std::deque out(xb.begin(), xb.end() - 1); out.push_front(xb[12] xor xb[11] xor xb[7] xor xb[6] xor xb[5] xor xb[3] xor xb[2] xor xb[0]); @@ -146,7 +143,7 @@ void make_l5i(int32_t* _dest, int32_t prn) { xb_shift[n] = xb[(xb_offset + n) % GPS_L5I_CODE_LENGTH_CHIPS]; } - std::deque out_code(GPS_L5I_CODE_LENGTH_CHIPS, false); + for (int32_t n = 0; n < GPS_L5I_CODE_LENGTH_CHIPS; n++) { _dest[n] = xa[n] xor xb_shift[n]; @@ -166,7 +163,7 @@ void make_l5q(int32_t* _dest, int32_t prn) { xb_shift[n] = xb[(xb_offset + n) % GPS_L5Q_CODE_LENGTH_CHIPS]; } - std::deque out_code(GPS_L5Q_CODE_LENGTH_CHIPS, false); + for (int32_t n = 0; n < GPS_L5Q_CODE_LENGTH_CHIPS; n++) { _dest[n] = xa[n] xor xb_shift[n]; @@ -231,28 +228,24 @@ void gps_l5i_code_gen_complex_sampled(std::complex* _dest, uint32_t _prn, //--- Find time constants -------------------------------------------------- _ts = 1.0 / static_cast(_fs); // Sampling period in sec - _tc = 1.0 / static_cast(GPS_L5I_CODE_RATE_HZ); // C/A chip period in sec + _tc = 1.0 / static_cast(GPS_L5I_CODE_RATE_HZ); // L5I primary chip period in sec - //float aux; for (int32_t i = 0; i < _samplesPerCode; i++) { //=== Digitizing ======================================================= //--- Make index array to read L5 code values ------------------------- - //TODO: Check this formula! Seems to start with an extra sample - _codeValueIndex = std::ceil((_ts * (static_cast(i) + 1)) / _tc) - 1; - //aux = (_ts * (i + 1)) / _tc; - //_codeValueIndex = static_cast (static_cast(aux)) - 1; + _codeValueIndex = static_cast(std::ceil(_ts * static_cast(i + 1) / _tc)) - 1; - //--- Make the digitized version of the L2C code ----------------------- + //--- Make the digitized version of the L5I code ----------------------- if (i == _samplesPerCode - 1) { //--- Correct the last index (due to number rounding issues) ----------- - _dest[i] = std::complex(1.0 - 2.0 * _code[_codeLength - 1], 0); + _dest[i] = std::complex(1.0 - 2.0 * _code[_codeLength - 1], 0.0); } else { - _dest[i] = std::complex(1.0 - 2.0 * _code[_codeValueIndex], 0); //repeat the chip -> upsample + _dest[i] = std::complex(1.0 - 2.0 * _code[_codeValueIndex], 0.0); // repeat the chip -> upsample } } delete[] _code; @@ -296,7 +289,7 @@ void gps_l5q_code_gen_float(float* _dest, uint32_t _prn) /* - * Generates complex GPS L5i code for the desired SV ID and sampled to specific sampling frequency + * Generates complex GPS L5Q code for the desired SV ID and sampled to specific sampling frequency */ void gps_l5q_code_gen_complex_sampled(std::complex* _dest, uint32_t _prn, int32_t _fs) { @@ -316,7 +309,7 @@ void gps_l5q_code_gen_complex_sampled(std::complex* _dest, uint32_t _prn, //--- Find time constants -------------------------------------------------- _ts = 1.0 / static_cast(_fs); // Sampling period in sec - _tc = 1.0 / static_cast(GPS_L5Q_CODE_RATE_HZ); // C/A chip period in sec + _tc = 1.0 / static_cast(GPS_L5Q_CODE_RATE_HZ); // L5Q chip period in sec //float aux; for (int32_t i = 0; i < _samplesPerCode; i++) @@ -324,12 +317,9 @@ void gps_l5q_code_gen_complex_sampled(std::complex* _dest, uint32_t _prn, //=== Digitizing ======================================================= //--- Make index array to read L5 code values ------------------------- - //TODO: Check this formula! Seems to start with an extra sample - _codeValueIndex = std::ceil((_ts * (static_cast(i) + 1)) / _tc) - 1; - //aux = (_ts * (i + 1)) / _tc; - //_codeValueIndex = static_cast (static_cast(aux)) - 1; + _codeValueIndex = static_cast(std::ceil(_ts * static_cast(i + 1) / _tc)) - 1; - //--- Make the digitized version of the L2C code ----------------------- + //--- Make the digitized version of the L5Q code ----------------------- if (i == _samplesPerCode - 1) { //--- Correct the last index (due to number rounding issues) ----------- @@ -337,7 +327,7 @@ void gps_l5q_code_gen_complex_sampled(std::complex* _dest, uint32_t _prn, } else { - _dest[i] = std::complex(1.0 - 2.0 * _code[_codeValueIndex], 0); //repeat the chip -> upsample + _dest[i] = std::complex(1.0 - 2.0 * _code[_codeValueIndex], 0); // repeat the chip -> upsample } } delete[] _code; diff --git a/src/algorithms/libs/gps_l5_signal.h b/src/algorithms/libs/gps_l5_signal.h index b0b24d2a5..de8e44c0d 100644 --- a/src/algorithms/libs/gps_l5_signal.h +++ b/src/algorithms/libs/gps_l5_signal.h @@ -36,18 +36,22 @@ #include #include -//!Generates complex GPS L5i M code for the desired SV ID +//! Generates complex GPS L5I code for the desired SV ID void gps_l5i_code_gen_complex(std::complex* _dest, uint32_t _prn); + +//! Generates real GPS L5I code for the desired SV ID void gps_l5i_code_gen_float(float* _dest, uint32_t _prn); -//!Generates complex GPS L5q M code for the desired SV ID +//! Generates complex GPS L5Q code for the desired SV ID void gps_l5q_code_gen_complex(std::complex* _dest, uint32_t _prn); + +//! Generates real GPS L5Q code for the desired SV ID void gps_l5q_code_gen_float(float* _dest, uint32_t _prn); -//! Generates complex GPS L5i M code for the desired SV ID, and sampled to specific sampling frequency +//! Generates complex GPS L5I code for the desired SV ID, and sampled to specific sampling frequency void gps_l5i_code_gen_complex_sampled(std::complex* _dest, uint32_t _prn, int32_t _fs); -//! Generates complex GPS L5q M code for the desired SV ID, and sampled to specific sampling frequency +//! Generates complex GPS L5Q code for the desired SV ID, and sampled to specific sampling frequency void gps_l5q_code_gen_complex_sampled(std::complex* _dest, uint32_t _prn, int32_t _fs); diff --git a/src/algorithms/libs/volk_gnsssdr_module/volk_gnsssdr/CMakeLists.txt b/src/algorithms/libs/volk_gnsssdr_module/volk_gnsssdr/CMakeLists.txt index 79e64245e..8d515f584 100644 --- a/src/algorithms/libs/volk_gnsssdr_module/volk_gnsssdr/CMakeLists.txt +++ b/src/algorithms/libs/volk_gnsssdr_module/volk_gnsssdr/CMakeLists.txt @@ -27,6 +27,20 @@ enable_language(CXX) enable_language(C) enable_testing() +set(PROJECT_SOURCE_DIR ${CMAKE_CURRENT_SOURCE_DIR}) # allows this to be a sub-project +set(PROJECT_BINARY_DIR ${CMAKE_CURRENT_BINARY_DIR}) # allows this to be a sub-project +list(INSERT CMAKE_MODULE_PATH 0 ${CMAKE_CURRENT_SOURCE_DIR}/cmake/Modules) # location for custom "Modules" + +if(POLICY CMP0042) + cmake_policy(SET CMP0042 NEW) +endif() +if(POLICY CMP0068) + cmake_policy(SET CMP0068 NEW) +endif() +if(POLICY CMP0057) + cmake_policy(SET CMP0057 NEW) +endif() + # Set compiler flags set(GNSSSDR_CLANG_MIN_VERSION "3.4.0") set(GNSSSDR_APPLECLANG_MIN_VERSION "500") @@ -59,42 +73,72 @@ if(CMAKE_CXX_COMPILER_ID MATCHES "Clang") endif() endif() -# Enable C++17 support in GCC >= 8.0.0 -# Enable C++14 support in 8.0.0 > GCC >= 6.1.1 -# Fallback to C++11 when using GCC < 6.1.1 +#### Set C++ standard +set(CMAKE_CXX_EXTENSIONS OFF) + +# Check if we have std::filesystem +if(CMAKE_VERSION VERSION_LESS 3.8) + set(FILESYSTEM_FOUND FALSE) +else() + find_package(FILESYSTEM COMPONENTS Final Experimental) +endif() if((CMAKE_CXX_COMPILER_ID STREQUAL "GNU") AND NOT WIN32) if(CMAKE_CXX_COMPILER_VERSION VERSION_LESS "6.1.1") - set(MY_CXX_FLAGS "${MY_CXX_FLAGS} -std=c++11") - else() - if(CMAKE_CXX_COMPILER_VERSION VERSION_LESS "8.0.0") - set(MY_CXX_FLAGS "${MY_CXX_FLAGS} -std=c++14") - else() - set(MY_CXX_FLAGS "${MY_CXX_FLAGS} -std=c++17") - endif() - endif() - set(MY_CXX_FLAGS "${MY_CXX_FLAGS} -Wall -Wextra") #Add warning flags: For "-Wall" see http://gcc.gnu.org/onlinedocs/gcc/Warning-Options.html -endif() - -# Enable C++17 support in Clang >= 6.0.0 -# Enable C++14 support in 6.0.0 > Clang >= 3.5.0 or AppleClang >= 600 -# Fallback to C++11 if older version -if(CMAKE_CXX_COMPILER_ID MATCHES "Clang") - if(CMAKE_SYSTEM_NAME MATCHES "Darwin") - # See https://trac.macports.org/wiki/XcodeVersionInfo for Apple Clang version equivalences - if(CLANG_VERSION VERSION_LESS "600") + if(CMAKE_VERSION VERSION_LESS "3.1") set(MY_CXX_FLAGS "${MY_CXX_FLAGS} -std=c++11") else() - set(MY_CXX_FLAGS "${MY_CXX_FLAGS} -std=c++14") + set(CMAKE_CXX_STANDARD 11) + endif() + else() + if(CMAKE_CXX_COMPILER_VERSION VERSION_LESS "8.0.0") + set(CMAKE_CXX_STANDARD 14) + else() + if(${FILESYSTEM_FOUND}) + set(CMAKE_CXX_STANDARD 17) + set(CMAKE_CXX_STANDARD_REQUIRED ON) + else() + set(CMAKE_CXX_STANDARD 14) + endif() + endif() + endif() + set(MY_CXX_FLAGS "${MY_CXX_FLAGS} -Wall -Wextra") # Add warning flags: For "-Wall" see http://gcc.gnu.org/onlinedocs/gcc/Warning-Options.html +endif() + +if(CMAKE_CXX_COMPILER_ID MATCHES "Clang") + if(CMAKE_CXX_COMPILER_ID STREQUAL "AppleClang") + # See https://trac.macports.org/wiki/XcodeVersionInfo for Apple Clang version equivalences + if(CLANG_VERSION VERSION_LESS "600") + set(CMAKE_CXX_STANDARD 11) + else() + if(CLANG_VERSION VERSION_LESS "1000") + set(CMAKE_CXX_STANDARD 14) + else() + if(${FILESYSTEM_FOUND}) + set(CMAKE_CXX_STANDARD 17) + set(CMAKE_CXX_STANDARD_REQUIRED ON) + else() + set(CMAKE_CXX_STANDARD 14) + endif() + endif() endif() else() if(CMAKE_CXX_COMPILER_VERSION VERSION_LESS "3.5.0") - set(MY_CXX_FLAGS "${MY_CXX_FLAGS} -std=c++11") + if(CMAKE_VERSION VERSION_LESS "3.1") + set(MY_CXX_FLAGS "${MY_CXX_FLAGS} -std=c++11") + else() + set(CMAKE_CXX_STANDARD 11) + endif() else() if(CMAKE_CXX_COMPILER_VERSION VERSION_LESS "6.0.0") - set(MY_CXX_FLAGS "${MY_CXX_FLAGS} -std=c++14") + set(CMAKE_CXX_STANDARD 14) else() - set(MY_CXX_FLAGS "${MY_CXX_FLAGS} -std=c++17") + if(${FILESYSTEM_FOUND}) + set(CMAKE_CXX_STANDARD 17) + set(CMAKE_CXX_STANDARD_REQUIRED ON) + else() + set(CMAKE_CXX_STANDARD 14) + endif() endif() endif() endif() @@ -110,21 +154,10 @@ endif() set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} ${MY_CXX_FLAGS} -Wall") set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} -Wall") -if(CMAKE_VERSION VERSION_GREATER "3.0") - cmake_policy(SET CMP0042 NEW) - if(CMAKE_VERSION VERSION_GREATER "3.9") - cmake_policy(SET CMP0068 NEW) - endif() -endif() - option(ENABLE_STRIP "Create a stripped volk_gnsssdr_profile binary (without shared libraries)" OFF) -set(PROJECT_SOURCE_DIR ${CMAKE_CURRENT_SOURCE_DIR}) #allows this to be a sub-project -set(PROJECT_BINARY_DIR ${CMAKE_CURRENT_BINARY_DIR}) #allows this to be a sub-project -list(INSERT CMAKE_MODULE_PATH 0 ${CMAKE_CURRENT_SOURCE_DIR}/cmake/Modules) #location for custom "Modules" - include(VolkBuildTypes) -#select the release build type by default to get optimization flags +# select the release build type by default to get optimization flags if(NOT CMAKE_BUILD_TYPE) set(CMAKE_BUILD_TYPE "Release") message(STATUS "Build type not specified: defaulting to release.") @@ -136,7 +169,7 @@ message(STATUS "Build type set to ${CMAKE_BUILD_TYPE}.") set(VERSION_INFO_MAJOR_VERSION 0) set(VERSION_INFO_MINOR_VERSION 0) set(VERSION_INFO_MAINT_VERSION 10.git) -include(VolkVersion) #setup version info +include(VolkVersion) # setup version info @@ -154,8 +187,8 @@ endif() set(CROSSCOMPILE_MULTILIB ${CROSSCOMPILE_MULTILIB} CACHE STRING "Define \"true\" if you have and want to use multiple C development libs installed for cross compile") if(MSVC) - add_definitions(-D_USE_MATH_DEFINES) #enables math constants on all supported versions of MSVC - add_compile_options(/W1) #reduce warnings + add_definitions(-D_USE_MATH_DEFINES) # enables math constants on all supported versions of MSVC + add_compile_options(/W1) # reduce warnings add_compile_options(/wo4309) add_compile_options(/wd4752) add_compile_options(/wo4273) @@ -177,7 +210,7 @@ endif() ######################################################################## # Python -include(VolkPython) #sets PYTHON_EXECUTABLE and PYTHON_DASH_B +include(VolkPython) # sets PYTHON_EXECUTABLE and PYTHON_DASH_B volk_python_check_module("python >= 2.7" sys "sys.version.split()[0] >= '2.7'" PYTHON_MIN_VER_FOUND) volk_python_check_module("mako >= 0.4.2" mako "mako.__version__ >= '0.4.2'" MAKO_FOUND) volk_python_check_module("six - python 2 and 3 compatibility library" six "True" SIX_FOUND) @@ -204,20 +237,24 @@ if(MSVC) endif() set(BOOST_ALL_DYN_LINK "${BOOST_ALL_DYN_LINK}" CACHE BOOL "boost enable dynamic linking") if(BOOST_ALL_DYN_LINK) - add_definitions(-DBOOST_ALL_DYN_LINK) #setup boost auto-linking in msvc + add_definitions(-DBOOST_ALL_DYN_LINK) # setup boost auto-linking in msvc else() - unset(BOOST_REQUIRED_COMPONENTS) #empty components list for static link + unset(BOOST_REQUIRED_COMPONENTS) # empty components list for static link + endif() +endif() +if(${FILESYSTEM_FOUND}) + set(Boost_LIBRARIES "") + set(Boost_INCLUDE_DIRS "") + set(CMAKE_INCLUDE_PATH ${CMAKE_INCLUDE_PATH}) +else() + include(VolkBoost) + if(NOT Boost_FOUND) + message(FATAL_ERROR "VOLK-GNSSSDR requires Boost to build") endif() endif() -include(VolkBoost) - -if(NOT Boost_FOUND) - message(FATAL_ERROR "VOLK_GNSSSDR Requires boost to build") -endif() - # Orc -option(ENABLE_ORC "Enable Orc" True) +option(ENABLE_ORC "Enable Orc" TRUE) if(ENABLE_ORC) find_package(ORC) else() @@ -246,7 +283,7 @@ endif() ######################################################################## # Setup the package config file ######################################################################## -#set variables found in the pc.in file +# set variables found in the pc.in file set(prefix ${CMAKE_INSTALL_PREFIX}) set(exec_prefix "\${prefix}") set(libdir "\${exec_prefix}/lib${LIB_SUFFIX}") @@ -335,7 +372,6 @@ endif() - ######################################################################## # Install our Cmake modules into $prefix/lib/cmake/volk_gnsssdr # See "Package Configuration Files" on page: diff --git a/src/algorithms/libs/volk_gnsssdr_module/volk_gnsssdr/README.md b/src/algorithms/libs/volk_gnsssdr_module/volk_gnsssdr/README.md index f37cc5b35..a88977385 100644 --- a/src/algorithms/libs/volk_gnsssdr_module/volk_gnsssdr/README.md +++ b/src/algorithms/libs/volk_gnsssdr_module/volk_gnsssdr/README.md @@ -6,7 +6,7 @@ VOLK's. Please see http://libvolk.org for documentation, source code, and contact information about the original VOLK library. The boilerplate of this code was initially generated with -```volk_modtool```, an application provided by VOLK that creates the +`volk_modtool`, an application provided by VOLK that creates the skeleton that can then be filled with custom kernels. Some modifications were added to accommodate the specificities of Global Navigation Satellite Systems (GNSS) signal processing. Those changes are clearly @@ -16,7 +16,7 @@ This library contains kernels of hand-written SIMD code for different mathematical operations, mainly with 8-bit and 16-bit real and complex data types, offering a platform/architecture agnostic version that will run in all machines, plus other versions for different SIMD instruction -sets. Then, the application ```volk_gnsssdr_profile``` runs some +sets. Then, the application `volk_gnsssdr_profile` runs some iterations of all versions that your machine can execute and annotates which is the fastest, which will then be selected at runtime when executing GNSS-SDR. In this way, we can address at the same time @@ -49,6 +49,12 @@ $ sudo apt-get install cmake python-mako python-six libboost-dev \ libboost-filesystem-dev libboost-system-dev ~~~~~~ +Please note that if you are using a compiler supporting the C++17 standard +(for instance, gcc >= 8.0), specifically the std::filesystem library, packages +`libboost-dev`, `libboost-filesystem-dev` and `libboost-system-dev` are no +longer required dependencies. The CMake script will detect that availability for +you. + In order to build and install the library, go to the base folder of the source code and do: @@ -62,7 +68,7 @@ $ sudo make install That's it! -Before its first use, please execute ```volk_gnsssdr_profile``` to let +Before its first use, please execute `volk_gnsssdr_profile` to let your system know which is the fastest available implementation. This only has to be done once: @@ -74,7 +80,7 @@ From now on, GNSS-SDR (and any other program of your own that makes use of VOLK_GNSSSDR) will benefit from the acceleration provided by SIMD instructions available in your processor. -The execution of ```volk_gnsssdr_profile``` can be set automatically +The execution of `volk_gnsssdr_profile` can be set automatically after building, leaving your system ready to use: ~~~~~~ diff --git a/src/algorithms/libs/volk_gnsssdr_module/volk_gnsssdr/apps/CMakeLists.txt b/src/algorithms/libs/volk_gnsssdr_module/volk_gnsssdr/apps/CMakeLists.txt index b1afa4ed0..a333ea576 100644 --- a/src/algorithms/libs/volk_gnsssdr_module/volk_gnsssdr/apps/CMakeLists.txt +++ b/src/algorithms/libs/volk_gnsssdr_module/volk_gnsssdr/apps/CMakeLists.txt @@ -35,14 +35,6 @@ include_directories( ) -set(Clang_required_link "") -if(${CMAKE_SYSTEM_NAME} MATCHES "Darwin") - if("${CMAKE_CXX_COMPILER_ID}" STREQUAL "Clang") - set(Clang_required_link "c++") - endif() -endif() - - if(ORC_FOUND) set(orc_lib ${ORC_LIBRARIES}) else() @@ -66,10 +58,18 @@ add_executable(volk_gnsssdr_profile ${CMAKE_CURRENT_SOURCE_DIR}/volk_gnsssdr_option_helpers.cc ) +if(${FILESYSTEM_FOUND}) + add_definitions(-DHAS_STD_FILESYSTEM=1) + if(${find_experimental}) + add_definitions(-DHAS_STD_FILESYSTEM_EXPERIMENTAL=1) + endif() + target_link_libraries(volk_gnsssdr_profile PRIVATE std::filesystem) +endif() + if(ENABLE_STATIC_LIBS) - target_link_libraries(volk_gnsssdr_profile volk_gnsssdr_static ${Boost_LIBRARIES} ${Clang_required_link} ${orc_lib}) + target_link_libraries(volk_gnsssdr_profile PUBLIC volk_gnsssdr_static ${Boost_LIBRARIES} ${orc_lib}) else() - target_link_libraries(volk_gnsssdr_profile volk_gnsssdr ${Boost_LIBRARIES} ${Clang_required_link} ${orc_lib}) + target_link_libraries(volk_gnsssdr_profile PUBLIC volk_gnsssdr ${Boost_LIBRARIES} ${orc_lib}) add_dependencies(volk_gnsssdr_profile volk_gnsssdr) endif() @@ -91,10 +91,12 @@ install( # MAKE volk_gnsssdr-config-info add_executable(volk_gnsssdr-config-info volk_gnsssdr-config-info.cc ${CMAKE_CURRENT_SOURCE_DIR}/volk_gnsssdr_option_helpers.cc) + + if(ENABLE_STATIC_LIBS) - target_link_libraries(volk_gnsssdr-config-info volk_gnsssdr_static ${Clang_required_link} ${orc_lib}) + target_link_libraries(volk_gnsssdr-config-info volk_gnsssdr_static ${orc_lib}) else() - target_link_libraries(volk_gnsssdr-config-info volk_gnsssdr ${Clang_required_link} ${orc_lib}) + target_link_libraries(volk_gnsssdr-config-info volk_gnsssdr ${orc_lib}) add_dependencies(volk_gnsssdr-config-info volk_gnsssdr) endif() diff --git a/src/algorithms/libs/volk_gnsssdr_module/volk_gnsssdr/apps/volk_gnsssdr_profile.cc b/src/algorithms/libs/volk_gnsssdr_module/volk_gnsssdr/apps/volk_gnsssdr_profile.cc index c18bb2e3a..132e7df44 100644 --- a/src/algorithms/libs/volk_gnsssdr_module/volk_gnsssdr/apps/volk_gnsssdr_profile.cc +++ b/src/algorithms/libs/volk_gnsssdr_module/volk_gnsssdr/apps/volk_gnsssdr_profile.cc @@ -22,19 +22,34 @@ #include "volk_gnsssdr/volk_gnsssdr_complex.h" // for lv_32fc_t #include "volk_gnsssdr/volk_gnsssdr_prefs.h" // for volk_gnsssdr_get_config_path #include "volk_gnsssdr_option_helpers.h" // for option_list, option_t -#include // for create_directories, exists -#include // for path, operator<< -#include // for filesystem -#include // for size_t -#include // IWYU pragma: keep -#include // for operator<<, basic_ostream -#include // for map, map<>::iterator -#include // for stat -#include // for pair -#include // for vector, vector<>::const_.. - +#if HAS_STD_FILESYSTEM +#if HAS_STD_FILESYSTEM_EXPERIMENTAL +#include +#else +#include +#endif +#else +#include // for create_directories, exists +#include // for path, operator<< +#include // for filesystem +#endif +#include // for size_t +#include // IWYU pragma: keep +#include // for operator<<, basic_ostream +#include // for map, map<>::iterator +#include // for stat +#include // for pair +#include // for vector, vector<>::const_.. +#if HAS_STD_FILESYSTEM +#if HAS_STD_FILESYSTEM_EXPERIMENTAL +namespace fs = std::experimental::filesystem; +#else +namespace fs = std::filesystem; +#endif +#else namespace fs = boost::filesystem; +#endif volk_gnsssdr_test_params_t test_params(1e-6f, 327.f, 8111, 1987, false, ""); @@ -253,7 +268,16 @@ void write_results(const std::vector *results, bool if (!fs::exists(config_path.parent_path())) { std::cout << "Creating " << config_path.parent_path() << " ..." << std::endl; - fs::create_directories(config_path.parent_path()); + try + { + fs::create_directories(config_path.parent_path()); + } + catch (const fs::filesystem_error &e) + { + std::cerr << "ERROR: Could not create folder " << config_path.parent_path() << std::endl; + std::cerr << "Reason: " << e.what() << std::endl; + return; + } } std::ofstream config; diff --git a/src/algorithms/libs/volk_gnsssdr_module/volk_gnsssdr/cmake/Modules/FindFILESYSTEM.cmake b/src/algorithms/libs/volk_gnsssdr_module/volk_gnsssdr/cmake/Modules/FindFILESYSTEM.cmake new file mode 100644 index 000000000..1359615e4 --- /dev/null +++ b/src/algorithms/libs/volk_gnsssdr_module/volk_gnsssdr/cmake/Modules/FindFILESYSTEM.cmake @@ -0,0 +1,259 @@ +# Copyright (C) 2019 (see AUTHORS file for a list of contributors) +# +# This file is part of GNSS-SDR. +# +# GNSS-SDR is free software: you can redistribute it and/or modify +# it under the terms of the GNU General Public License as published by +# the Free Software Foundation, either version 3 of the License, or +# (at your option) any later version. +# +# GNSS-SDR is distributed in the hope that it will be useful, +# but WITHOUT ANY WARRANTY; without even the implied warranty of +# MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +# GNU General Public License for more details. +# +# You should have received a copy of the GNU General Public License +# along with GNSS-SDR. If not, see . + +# Original Source: https://github.com/vector-of-bool/CMakeCM +# Modified by C. Fernandez-Prades. + +#[=======================================================================[.rst: + +FindFILESYSTEM +############## + +This module supports the C++17 standard library's filesystem utilities. Use the +:imp-target:`std::filesystem` imported target to + +Options +******* + +The ``COMPONENTS`` argument to this module supports the following values: + +.. find-component:: Experimental + :name: fs.Experimental + + Allows the module to find the "experimental" Filesystem TS version of the + Filesystem library. This is the library that should be used with the + ``std::experimental::filesystem`` namespace. + +.. find-component:: Final + :name: fs.Final + + Finds the final C++17 standard version of the filesystem library. + +If no components are provided, behaves as if the +:find-component:`fs.Final` component was specified. + +If both :find-component:`fs.Experimental` and :find-component:`fs.Final` are +provided, first looks for ``Final``, and falls back to ``Experimental`` in case +of failure. If ``Final`` is found, :imp-target:`std::filesystem` and all +:ref:`variables ` will refer to the ``Final`` version. + + +Imported Targets +**************** + +.. imp-target:: std::filesystem + + The ``std::filesystem`` imported target is defined when any requested + version of the C++ filesystem library has been found, whether it is + *Experimental* or *Final*. + + If no version of the filesystem library is available, this target will not + be defined. + + .. note:: + This target has ``cxx_std_17`` as an ``INTERFACE`` + :ref:`compile language standard feature `. Linking + to this target will automatically enable C++17 if no later standard + version is already required on the linking target. + + +.. _fs.variables: + +Variables +********* + +.. variable:: CXX_FILESYSTEM_IS_EXPERIMENTAL + + Set to ``TRUE`` when the :find-component:`fs.Experimental` version of C++ + filesystem library was found, otherwise ``FALSE``. + +.. variable:: CXX_FILESYSTEM_HAVE_FS + + Set to ``TRUE`` when a filesystem header was found. + +.. variable:: CXX_FILESYSTEM_HEADER + + Set to either ``filesystem`` or ``experimental/filesystem`` depending on + whether :find-component:`fs.Final` or :find-component:`fs.Experimental` was + found. + +.. variable:: CXX_FILESYSTEM_NAMESPACE + + Set to either ``std::filesystem`` or ``std::experimental::filesystem`` + depending on whether :find-component:`fs.Final` or + :find-component:`fs.Experimental` was found. + + +Examples +******** + +Using `find_package(FILESYSTEM)` with no component arguments: + +.. code-block:: cmake + + find_package(FILESYSTEM REQUIRED) + + add_executable(my-program main.cpp) + target_link_libraries(my-program PRIVATE std::filesystem) + + +#]=======================================================================] + + +if(TARGET std::filesystem) + # This module has already been processed. Don't do it again. + return() +endif() + +include(CMakePushCheckState) +include(CheckIncludeFileCXX) +include(CheckCXXSourceCompiles) + +cmake_push_check_state() + +set(CMAKE_REQUIRED_QUIET ${FILESYSTEM_FIND_QUIETLY}) + +# All of our tests require C++17 or later +set(CMAKE_CXX_STANDARD 17) +if((CMAKE_CXX_COMPILER_ID STREQUAL "GNU") AND (CMAKE_CXX_COMPILER_VERSION VERSION_GREATER "9.0.0")) + set(CMAKE_REQUIRED_FLAGS "-std=c++17") +endif() +if((CMAKE_CXX_COMPILER_ID STREQUAL "Clang") AND NOT (CMAKE_CXX_COMPILER_VERSION VERSION_LESS "8.99")) + set(CMAKE_REQUIRED_FLAGS "-std=c++17") +endif() + +# Normalize and check the component list we were given +set(want_components ${FILESYSTEM_FIND_COMPONENTS}) +if(FILESYSTEM_FIND_COMPONENTS STREQUAL "") + set(want_components Final) +endif() + +# Warn on any unrecognized components +set(extra_components ${want_components}) +list(REMOVE_ITEM extra_components Final Experimental) +foreach(component IN LISTS extra_components) + message(WARNING "Extraneous find_package component for FILESYSTEM: ${component}") +endforeach() + +# Detect which of Experimental and Final we should look for +set(find_experimental TRUE) +set(find_final TRUE) +if(NOT "Final" IN_LIST want_components) + set(find_final FALSE) +endif() +if(NOT "Experimental" IN_LIST want_components) + set(find_experimental FALSE) +endif() + +if(find_final) + check_include_file_cxx("filesystem" _CXX_FILESYSTEM_HAVE_HEADER) + mark_as_advanced(_CXX_FILESYSTEM_HAVE_HEADER) + if(_CXX_FILESYSTEM_HAVE_HEADER) + # We found the non-experimental header. Don't bother looking for the + # experimental one. + set(find_experimental FALSE) + endif() +else() + set(_CXX_FILESYSTEM_HAVE_HEADER FALSE) +endif() + +if(find_experimental) + check_include_file_cxx("experimental/filesystem" _CXX_FILESYSTEM_HAVE_EXPERIMENTAL_HEADER) + mark_as_advanced(_CXX_FILESYSTEM_HAVE_EXPERIMENTAL_HEADER) +else() + set(_CXX_FILESYSTEM_HAVE_EXPERIMENTAL_HEADER FALSE) +endif() + +if(_CXX_FILESYSTEM_HAVE_HEADER) + set(_have_fs TRUE) + set(_fs_header filesystem) + set(_fs_namespace std::filesystem) +elseif(_CXX_FILESYSTEM_HAVE_EXPERIMENTAL_HEADER) + set(_have_fs TRUE) + set(_fs_header experimental/filesystem) + set(_fs_namespace std::experimental::filesystem) +else() + set(_have_fs FALSE) +endif() + +set(CXX_FILESYSTEM_HAVE_FS ${_have_fs} CACHE BOOL "TRUE if we have the C++ filesystem headers") +set(CXX_FILESYSTEM_HEADER ${_fs_header} CACHE STRING "The header that should be included to obtain the filesystem APIs") +set(CXX_FILESYSTEM_NAMESPACE ${_fs_namespace} CACHE STRING "The C++ namespace that contains the filesystem APIs") + +set(_found FALSE) + +if(CXX_FILESYSTEM_HAVE_FS) + # We have some filesystem library available. Do link checks + string(CONFIGURE [[ + #include <@CXX_FILESYSTEM_HEADER@> + + int main() { + auto cwd = @CXX_FILESYSTEM_NAMESPACE@::current_path(); + return static_cast(cwd.string().size()); + } + ]] code @ONLY) + + # Try to compile a simple filesystem program without any linker flags + check_cxx_source_compiles("${code}" CXX_FILESYSTEM_NO_LINK_NEEDED) + + set(can_link ${CXX_FILESYSTEM_NO_LINK_NEEDED}) + + if(NOT CXX_FILESYSTEM_NO_LINK_NEEDED) + set(prev_libraries ${CMAKE_REQUIRED_LIBRARIES}) + set(CMAKE_REQUIRED_FLAGS "-std=c++17") + # Add the libstdc++ flag + set(CMAKE_REQUIRED_LIBRARIES ${prev_libraries} -lstdc++fs) + check_cxx_source_compiles("${code}" CXX_FILESYSTEM_STDCPPFS_NEEDED) + set(can_link ${CXX_FILESYSTEM_STDCPPFS_NEEDED}) + if(NOT CXX_FILESYSTEM_STDCPPFS_NEEDED) + # Try the libc++ flag + set(CMAKE_REQUIRED_LIBRARIES ${prev_libraries} -lc++fs) + check_cxx_source_compiles("${code}" CXX_FILESYSTEM_CPPFS_NEEDED) + set(can_link ${CXX_FILESYSTEM_CPPFS_NEEDED}) + endif() + endif() + + if(can_link) + if(CMAKE_VERSION VERSION_LESS 3.12) + add_library(std::filesystem INTERFACE IMPORTED GLOBAL) + else() + add_library(std::filesystem INTERFACE IMPORTED) + target_compile_features(std::filesystem INTERFACE cxx_std_17) + endif() + set(_found TRUE) + + if(CXX_FILESYSTEM_NO_LINK_NEEDED) + # Nothing to add... + elseif(CXX_FILESYSTEM_STDCPPFS_NEEDED) + target_link_libraries(std::filesystem INTERFACE -lstdc++fs) + elseif(CXX_FILESYSTEM_CPPFS_NEEDED) + target_link_libraries(std::filesystem INTERFACE -lc++fs) + endif() + endif() +endif() + +if(NOT ${_found}) + set(CMAKE_CXX_STANDARD 11) +endif() + +cmake_pop_check_state() + +set(FILESYSTEM_FOUND ${_found} CACHE BOOL "TRUE if we can compile and link a program using std::filesystem" FORCE) + +if(FILESYSTEM_FIND_REQUIRED AND NOT FILESYSTEM_FOUND) + message(FATAL_ERROR "Cannot compile a simple program using std::filesystem") +endif() diff --git a/src/algorithms/libs/volk_gnsssdr_module/volk_gnsssdr/cmake/Modules/VolkGnsssdrConfig.cmake.in b/src/algorithms/libs/volk_gnsssdr_module/volk_gnsssdr/cmake/Modules/VolkGnsssdrConfig.cmake.in index ef8dce6e6..18f22da44 100644 --- a/src/algorithms/libs/volk_gnsssdr_module/volk_gnsssdr/cmake/Modules/VolkGnsssdrConfig.cmake.in +++ b/src/algorithms/libs/volk_gnsssdr_module/volk_gnsssdr/cmake/Modules/VolkGnsssdrConfig.cmake.in @@ -20,3 +20,32 @@ get_filename_component(VOLK_GNSSSDR_CMAKE_DIR "${CMAKE_CURRENT_LIST_FILE}" PATH) if(NOT TARGET VolkGnsssdr::volkgnsssdr) include("${VOLK_GNSSSDR_CMAKE_DIR}/VolkGnsssdrTargets.cmake") endif() + +# set VOLKGNSSSDR_FOUND to be set globally, for whether a compatible Volk GNSS-SDR +# was found -- could be a correct enough version or any version depending +# on how find_package was called. +if(NOT TARGET Volkgnsssdr::volkgnsssdr) + set(VOLKGNSSSDR_FOUND FALSE) +else() + set(VOLKGNSSSDR_FOUND TRUE) +endif() + +# cache whether a compatible VolkGnsssdr was found for +# use anywhere in the calling project +set(VOLKGNSSSDR_FOUND ${VOLKGNSSSDR_FOUND} CACHE BOOL "Whether a compatible Volk GNSS-SDR was found" FORCE) + +if(VOLKGNSSSDR_FOUND) + # use the new target library, regardless of whether new or old style + # we still need to set a variable with the library name so that there + # is a variable to reference in the using-project's cmake scripts! + set(VOLK_GNSSSDR_LIBRARIES Volkgnsssdr::volkgnsssdr CACHE STRING "Volk GNSS-SDR Library" FORCE) + + # INTERFACE_INCLUDE_DIRECTORIES should always be set + get_target_property(VOLK_GNSSSDR_INCLUDE_DIRS Volkgnsssdr::volkgnsssdr INTERFACE_INCLUDE_DIRECTORIES) + set(VOLK_GNSSSDR_INCLUDE_DIRS ${VOLK_GNSSSDR_INCLUDE_DIRS} CACHE STRING "Volk GNSS-SDR Include Directories" FORCE) + + # for backward compatibility with old-CMake non-target project finding + include(FindPackageHandleStandardArgs) + find_package_handle_standard_args(VOLKGNSSSDR DEFAULT_MSG VOLK_GNSSSDR_LIBRARIES VOLK_GNSSSDR_INCLUDE_DIRS) + mark_as_advanced(VOLK_GNSSSDR_LIBRARIES VOLK_GNSSSDR_INCLUDE_DIRS) +endif() diff --git a/src/algorithms/libs/volk_gnsssdr_module/volk_gnsssdr/lib/qa_utils.cc b/src/algorithms/libs/volk_gnsssdr_module/volk_gnsssdr/lib/qa_utils.cc index 906028e6d..5eaefe5f1 100644 --- a/src/algorithms/libs/volk_gnsssdr_module/volk_gnsssdr/lib/qa_utils.cc +++ b/src/algorithms/libs/volk_gnsssdr_module/volk_gnsssdr/lib/qa_utils.cc @@ -32,24 +32,18 @@ #include // for vector -float uniform() +template +void random_values(T *buf, unsigned int n, std::default_random_engine &e1) { - std::random_device r; - std::default_random_engine e1(r()); - std::uniform_real_distribution uniform_dist(-1, 1); - return uniform_dist(e1); // uniformly (-1, 1) -} - -template -void random_floats(t *buf, unsigned n) -{ - for (unsigned i = 0; i < n; i++) - buf[i] = uniform(); + std::uniform_real_distribution uniform_dist(T(-1), T(1)); + for (unsigned int i = 0; i < n; i++) + buf[i] = uniform_dist(e1); } void load_random_data(void *data, volk_gnsssdr_type_t type, unsigned int n) { std::random_device r; + std::default_random_engine e1(r()); std::default_random_engine e2(r()); if (type.is_complex) n *= 2; @@ -57,9 +51,9 @@ void load_random_data(void *data, volk_gnsssdr_type_t type, unsigned int n) if (type.is_float) { if (type.size == 8) - random_floats((double *)data, n); + random_values((double *)data, n, e1); else - random_floats((float *)data, n); + random_values((float *)data, n, e1); } else { diff --git a/src/algorithms/libs/volk_gnsssdr_module/volk_gnsssdr/lib/qa_utils.h b/src/algorithms/libs/volk_gnsssdr_module/volk_gnsssdr/lib/qa_utils.h index 2a69e5947..2b511896e 100644 --- a/src/algorithms/libs/volk_gnsssdr_module/volk_gnsssdr/lib/qa_utils.h +++ b/src/algorithms/libs/volk_gnsssdr_module/volk_gnsssdr/lib/qa_utils.h @@ -124,9 +124,6 @@ public: ************************************************/ volk_gnsssdr_type_t volk_gnsssdr_type_from_string(std::string); -float uniform(void); -void random_floats(float *buf, unsigned n); - bool run_volk_gnsssdr_tests( volk_gnsssdr_func_desc_t, void (*)(), diff --git a/src/algorithms/libs/volk_gnsssdr_module/volk_gnsssdr/lib/volk_gnsssdr_prefs.c b/src/algorithms/libs/volk_gnsssdr_module/volk_gnsssdr/lib/volk_gnsssdr_prefs.c index 87a51732d..26934bcaf 100644 --- a/src/algorithms/libs/volk_gnsssdr_module/volk_gnsssdr/lib/volk_gnsssdr_prefs.c +++ b/src/algorithms/libs/volk_gnsssdr_module/volk_gnsssdr/lib/volk_gnsssdr_prefs.c @@ -19,6 +19,13 @@ #include #include #include +#if defined(_MSC_VER) +#include +#define access _access +#define F_OK 0 +#else +#include +#endif #include @@ -29,7 +36,7 @@ void volk_gnsssdr_get_config_path(char *path) const char *suffix2 = "/volk_gnsssdr/volk_gnsssdr_config"; // non-hidden char *home = NULL; - //allows config redirection via env variable + // allows config redirection via env variable home = getenv("VOLK_CONFIGPATH"); if (home != NULL) { @@ -38,17 +45,52 @@ void volk_gnsssdr_get_config_path(char *path) return; } - if (home == NULL) home = getenv("HOME"); - if (home == NULL) home = getenv("APPDATA"); - if (home == NULL) + // check for user-local config file + home = getenv("HOME"); + if (home != NULL) { - path[0] = 0; + strncpy(path, home, 512); + strcat(path, suffix); + if (access(path, F_OK) != -1) + { + return; + } + } + + // check for config file in APPDATA (Windows) + home = getenv("APPDATA"); + if (home != NULL) + { + strncpy(path, home, 512); + strcat(path, suffix); + if (access(path, F_OK) != -1) + { + return; + } + } + + // check for system-wide config file + if (access("/etc/volk_gnsssdr/volk_gnsssdr_config", F_OK) != -1) + { + strncpy(path, "/etc", 512); + strcat(path, suffix2); return; } - strncpy(path, home, 512); - strcat(path, suffix); + + // if nothing exists, write to HOME or APPDATA + home = getenv("HOME"); + if (home == NULL) home = getenv("APPDATA"); + if (home != NULL) + { + strncpy(path, home, 512); + strcat(path, suffix); + return; + } + path[0] = 0; + return; } + size_t volk_gnsssdr_load_preferences(volk_gnsssdr_arch_pref_t **prefs_res) { FILE *config_file; @@ -56,13 +98,13 @@ size_t volk_gnsssdr_load_preferences(volk_gnsssdr_arch_pref_t **prefs_res) size_t n_arch_prefs = 0; volk_gnsssdr_arch_pref_t *prefs = NULL; - //get the config path + // get the config path volk_gnsssdr_get_config_path(path); if (!path[0]) return n_arch_prefs; //no prefs found config_file = fopen(path, "r"); if (!config_file) return n_arch_prefs; //no prefs found - //reset the file pointer and write the prefs into volk_gnsssdr_arch_prefs + // reset the file pointer and write the prefs into volk_gnsssdr_arch_prefs while (fgets(line, sizeof(line), config_file) != NULL) { prefs = (volk_gnsssdr_arch_pref_t *)realloc(prefs, (n_arch_prefs + 1) * sizeof(*prefs)); diff --git a/src/algorithms/observables/gnuradio_blocks/CMakeLists.txt b/src/algorithms/observables/gnuradio_blocks/CMakeLists.txt index 90bc7236b..c1d7bd7dc 100644 --- a/src/algorithms/observables/gnuradio_blocks/CMakeLists.txt +++ b/src/algorithms/observables/gnuradio_blocks/CMakeLists.txt @@ -28,6 +28,13 @@ source_group(Headers FILES ${OBS_GR_BLOCKS_HEADERS}) add_library(obs_gr_blocks ${OBS_GR_BLOCKS_SOURCES} ${OBS_GR_BLOCKS_HEADERS}) +if(${FILESYSTEM_FOUND}) + target_compile_definitions(obs_gr_blocks PRIVATE -DHAS_STD_FILESYSTEM=1) + target_link_libraries(obs_gr_blocks PRIVATE std::filesystem) +else() + target_link_libraries(obs_gr_blocks PRIVATE Boost::filesystem) +endif() + target_include_directories(obs_gr_blocks PUBLIC ${CMAKE_SOURCE_DIR}/src/algorithms/libs @@ -42,7 +49,6 @@ target_link_libraries(obs_gr_blocks core_system_parameters Gflags::gflags Glog::glog - Boost::filesystem Matio::matio ) diff --git a/src/algorithms/observables/gnuradio_blocks/hybrid_observables_gs.cc b/src/algorithms/observables/gnuradio_blocks/hybrid_observables_gs.cc index 24c53587c..36d977fdd 100644 --- a/src/algorithms/observables/gnuradio_blocks/hybrid_observables_gs.cc +++ b/src/algorithms/observables/gnuradio_blocks/hybrid_observables_gs.cc @@ -35,7 +35,6 @@ #include "gnss_circular_deque.h" #include "gnss_sdr_create_directory.h" #include "gnss_synchro.h" -#include #include #include #include @@ -46,6 +45,13 @@ #include // for numeric_limits #include // for move +#if HAS_STD_FILESYSTEM +#include +namespace fs = std::filesystem; +#else +#include +namespace fs = boost::filesystem; +#endif hybrid_observables_gs_sptr hybrid_observables_gs_make(unsigned int nchannels_in, unsigned int nchannels_out, bool dump, bool dump_mat, std::string dump_filename) { @@ -125,7 +131,7 @@ hybrid_observables_gs::hybrid_observables_gs(uint32_t nchannels_in, d_dump_filename = d_dump_filename.substr(0, d_dump_filename.find_last_of('.')); } d_dump_filename.append(".dat"); - d_dump_filename = dump_path + boost::filesystem::path::preferred_separator + d_dump_filename; + d_dump_filename = dump_path + fs::path::preferred_separator + d_dump_filename; // create directory if (!gnss_sdr_create_directory(dump_path)) { diff --git a/src/algorithms/signal_source/adapters/CMakeLists.txt b/src/algorithms/signal_source/adapters/CMakeLists.txt index fb00b503f..ba3cd23b0 100644 --- a/src/algorithms/signal_source/adapters/CMakeLists.txt +++ b/src/algorithms/signal_source/adapters/CMakeLists.txt @@ -238,6 +238,14 @@ target_compile_definitions(signal_source_adapters PRIVATE -DGNSSSDR_INSTALL_DIR="${CMAKE_INSTALL_PREFIX}" ) +if(ENABLE_PLUTOSDR OR ENABLE_FMCOMMS2) + if(GR_IIO_INCLUDE_HAS_GNURADIO) + target_compile_definitions(signal_source_adapters + PUBLIC -DGRIIO_INCLUDE_HAS_GNURADIO=1 + ) + endif() +endif() + if(ENABLE_CLANG_TIDY) if(CLANG_TIDY_EXE) set_target_properties(signal_source_adapters diff --git a/src/algorithms/signal_source/adapters/fmcomms2_signal_source.h b/src/algorithms/signal_source/adapters/fmcomms2_signal_source.h index 820ce1a14..1388a514d 100644 --- a/src/algorithms/signal_source/adapters/fmcomms2_signal_source.h +++ b/src/algorithms/signal_source/adapters/fmcomms2_signal_source.h @@ -36,7 +36,11 @@ #include "gnss_block_interface.h" #include #include +#if GRIIO_INCLUDE_HAS_GNURADIO #include +#else +#include +#endif #include #include diff --git a/src/algorithms/signal_source/adapters/plutosdr_signal_source.h b/src/algorithms/signal_source/adapters/plutosdr_signal_source.h index 4cedb3787..e765ff7c4 100644 --- a/src/algorithms/signal_source/adapters/plutosdr_signal_source.h +++ b/src/algorithms/signal_source/adapters/plutosdr_signal_source.h @@ -35,7 +35,11 @@ #include "gnss_block_interface.h" #include #include +#if GRIIO_INCLUDE_HAS_GNURADIO #include +#else +#include +#endif #include #include diff --git a/src/algorithms/signal_source/gnuradio_blocks/CMakeLists.txt b/src/algorithms/signal_source/gnuradio_blocks/CMakeLists.txt index b32774dd9..4f05f3169 100644 --- a/src/algorithms/signal_source/gnuradio_blocks/CMakeLists.txt +++ b/src/algorithms/signal_source/gnuradio_blocks/CMakeLists.txt @@ -76,12 +76,20 @@ if(ENABLE_RAW_UDP AND PCAP_FOUND) ) endif() +# Fix for Boost Asio < 1.70 if(OS_IS_MACOSX) - if(CMAKE_CXX_COMPILER_ID STREQUAL "Clang") # not AppleClang - target_compile_definitions(signal_source_gr_blocks - PUBLIC - -DBOOST_ASIO_HAS_STD_STRING_VIEW - ) + if((CMAKE_CXX_COMPILER_ID MATCHES "Clang") AND (${Boost_VERSION} VERSION_LESS 107000)) + if(${has_string_view}) + target_compile_definitions(signal_source_gr_blocks + PUBLIC + -DBOOST_ASIO_HAS_STD_STRING_VIEW=1 + ) + else() + target_compile_definitions(signal_source_gr_blocks + PUBLIC + -DBOOST_ASIO_HAS_STD_STRING_VIEW=0 + ) + endif() endif() endif() diff --git a/src/algorithms/telemetry_decoder/gnuradio_blocks/galileo_telemetry_decoder_gs.cc b/src/algorithms/telemetry_decoder/gnuradio_blocks/galileo_telemetry_decoder_gs.cc index 4851235ba..00b20a8fd 100644 --- a/src/algorithms/telemetry_decoder/gnuradio_blocks/galileo_telemetry_decoder_gs.cc +++ b/src/algorithms/telemetry_decoder/gnuradio_blocks/galileo_telemetry_decoder_gs.cc @@ -97,7 +97,7 @@ galileo_telemetry_decoder_gs::galileo_telemetry_decoder_gs( d_frame_length_symbols = GALILEO_INAV_PAGE_PART_SYMBOLS - GALILEO_INAV_PREAMBLE_LENGTH_BITS; CodeLength = GALILEO_INAV_PAGE_PART_SYMBOLS - GALILEO_INAV_PREAMBLE_LENGTH_BITS; DataLength = (CodeLength / nn) - mm; - d_max_symbols_without_valid_frame = GALILEO_INAV_PAGE_PART_SYMBOLS * 10; //rise alarm 10 seconds without valid tlm + d_max_symbols_without_valid_frame = GALILEO_INAV_PAGE_PART_SYMBOLS * 30; //rise alarm 30 seconds without valid tlm break; } @@ -127,7 +127,7 @@ galileo_telemetry_decoder_gs::galileo_telemetry_decoder_gs( d_secondary_code_samples[i] = -1; } } - d_max_symbols_without_valid_frame = GALILEO_FNAV_CODES_PER_SYMBOL * GALILEO_FNAV_SYMBOLS_PER_PAGE * 10; //rise alarm 10 seconds without valid tlm + d_max_symbols_without_valid_frame = GALILEO_FNAV_CODES_PER_SYMBOL * GALILEO_FNAV_SYMBOLS_PER_PAGE * 30; //rise alarm 30 seconds without valid tlm break; } default: @@ -532,13 +532,14 @@ int galileo_telemetry_decoder_gs::general_work(int noutput_items __attribute__(( corr_value += d_preamble_samples[i]; } } + if (abs(corr_value) >= d_samples_per_preamble) + { + d_preamble_index = d_sample_counter; // record the preamble sample stamp + DLOG(INFO) << "Preamble detection for Galileo satellite " << this->d_satellite; + d_stat = 1; // enter into frame pre-detection status + } } - if (abs(corr_value) >= d_samples_per_preamble) - { - d_preamble_index = d_sample_counter; // record the preamble sample stamp - DLOG(INFO) << "Preamble detection for Galileo satellite " << this->d_satellite; - d_stat = 1; // enter into frame pre-detection status - } + break; } case 1: // possible preamble lock @@ -560,25 +561,32 @@ int galileo_telemetry_decoder_gs::general_work(int noutput_items __attribute__(( corr_value += d_preamble_samples[i]; } } - } - if (abs(corr_value) >= d_samples_per_preamble) - { - // check preamble separation - preamble_diff = static_cast(d_sample_counter - d_preamble_index); - if (abs(preamble_diff - d_preamble_period_symbols) == 0) + if (abs(corr_value) >= d_samples_per_preamble) { - // try to decode frame - DLOG(INFO) << "Starting page decoder for Galileo satellite " << this->d_satellite; - d_preamble_index = d_sample_counter; // record the preamble sample stamp - d_CRC_error_counter = 0; - if (corr_value < 0) flag_PLL_180_deg_phase_locked = true; - d_stat = 2; - } - else - { - if (preamble_diff > d_preamble_period_symbols) + // check preamble separation + preamble_diff = static_cast(d_sample_counter - d_preamble_index); + if (abs(preamble_diff - d_preamble_period_symbols) == 0) { - d_stat = 0; // start again + // try to decode frame + DLOG(INFO) << "Starting page decoder for Galileo satellite " << this->d_satellite; + d_preamble_index = d_sample_counter; // record the preamble sample stamp + d_CRC_error_counter = 0; + if (corr_value < 0) + { + flag_PLL_180_deg_phase_locked = true; + } + else + { + flag_PLL_180_deg_phase_locked = false; + } + d_stat = 2; + } + else + { + if (preamble_diff > d_preamble_period_symbols) + { + d_stat = 0; // start again + } } } } diff --git a/src/algorithms/telemetry_decoder/gnuradio_blocks/gps_l1_ca_telemetry_decoder_gs.cc b/src/algorithms/telemetry_decoder/gnuradio_blocks/gps_l1_ca_telemetry_decoder_gs.cc index 2fb25b023..7d06833e2 100644 --- a/src/algorithms/telemetry_decoder/gnuradio_blocks/gps_l1_ca_telemetry_decoder_gs.cc +++ b/src/algorithms/telemetry_decoder/gnuradio_blocks/gps_l1_ca_telemetry_decoder_gs.cc @@ -261,7 +261,7 @@ bool gps_l1_ca_telemetry_decoder_gs::decode_subframe() { GPS_frame_4bytes ^= 0x3FFFFFC0; // invert the data bits (using XOR) } - //check parity. If ANY word inside the subframe fails the parity, set subframe_synchro_confirmation = false + // check parity. If ANY word inside the subframe fails the parity, set subframe_synchro_confirmation = false if (not gps_l1_ca_telemetry_decoder_gs::gps_word_parityCheck(GPS_frame_4bytes)) { subframe_synchro_confirmation = false; @@ -457,6 +457,7 @@ int gps_l1_ca_telemetry_decoder_gs::general_work(int noutput_items __attribute__ { d_CRC_error_counter = 0; d_flag_preamble = true; // valid preamble indicator (initialized to false every work()) + gr::thread::scoped_lock lock(d_setlock); d_last_valid_preamble = d_sample_counter; if (!d_flag_frame_sync) { @@ -537,7 +538,7 @@ int gps_l1_ca_telemetry_decoder_gs::general_work(int noutput_items __attribute__ } } - // 3. Make the output (copy the object contents to the GNURadio reserved memory) + // 3. Make the output (copy the object contents to the GNU Radio reserved memory) *out[0] = current_symbol; return 1; diff --git a/src/algorithms/tracking/adapters/CMakeLists.txt b/src/algorithms/tracking/adapters/CMakeLists.txt index f3191eaf7..7fbb840f3 100644 --- a/src/algorithms/tracking/adapters/CMakeLists.txt +++ b/src/algorithms/tracking/adapters/CMakeLists.txt @@ -51,7 +51,6 @@ set(TRACKING_ADAPTER_SOURCES galileo_e1_dll_pll_veml_tracking.cc galileo_e1_tcp_connector_tracking.cc gps_l1_ca_dll_pll_tracking.cc - gps_l1_ca_dll_pll_c_aid_tracking.cc gps_l1_ca_tcp_connector_tracking.cc galileo_e5a_dll_pll_tracking.cc gps_l2_m_dll_pll_tracking.cc @@ -70,7 +69,6 @@ set(TRACKING_ADAPTER_HEADERS galileo_e1_dll_pll_veml_tracking.h galileo_e1_tcp_connector_tracking.h gps_l1_ca_dll_pll_tracking.h - gps_l1_ca_dll_pll_c_aid_tracking.h gps_l1_ca_tcp_connector_tracking.h galileo_e5a_dll_pll_tracking.h gps_l2_m_dll_pll_tracking.h diff --git a/src/algorithms/tracking/adapters/gps_l1_ca_dll_pll_c_aid_tracking.cc b/src/algorithms/tracking/adapters/gps_l1_ca_dll_pll_c_aid_tracking.cc deleted file mode 100644 index 21d174ad4..000000000 --- a/src/algorithms/tracking/adapters/gps_l1_ca_dll_pll_c_aid_tracking.cc +++ /dev/null @@ -1,240 +0,0 @@ -/*! - * \file gps_l1_ca_dll_pll_c_aid_tracking.cc - * \brief Implementation of an adapter of a DLL+PLL tracking loop block - * for GPS L1 C/A to a TrackingInterface - * \author Carlos Aviles, 2010. carlos.avilesr(at)googlemail.com - * Javier Arribas, 2011. jarribas(at)cttc.es - * - * Code DLL + carrier PLL according to the algorithms described in: - * K.Borre, D.M.Akos, N.Bertelsen, P.Rinder, and S.H.Jensen, - * A Software-Defined GPS and Galileo Receiver. A Single-Frequency - * Approach, Birkhauser, 2007 - * - * ------------------------------------------------------------------------- - * - * Copyright (C) 2010-2018 (see AUTHORS file for a list of contributors) - * - * GNSS-SDR is a software defined Global Navigation - * Satellite Systems receiver - * - * This file is part of GNSS-SDR. - * - * GNSS-SDR is free software: you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * GNSS-SDR is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - * GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with GNSS-SDR. If not, see . - * - * ------------------------------------------------------------------------- - */ - - -#include "gps_l1_ca_dll_pll_c_aid_tracking.h" -#include "GPS_L1_CA.h" -#include "configuration_interface.h" -#include "gnss_sdr_flags.h" -#include - - -GpsL1CaDllPllCAidTracking::GpsL1CaDllPllCAidTracking( - ConfigurationInterface* configuration, const std::string& role, - unsigned int in_streams, unsigned int out_streams) : role_(role), in_streams_(in_streams), out_streams_(out_streams) -{ - DLOG(INFO) << "role " << role; - //################# CONFIGURATION PARAMETERS ######################## - int fs_in; - int vector_length; - bool dump; - std::string dump_filename; - std::string default_item_type = "gr_complex"; - float pll_bw_hz; - float pll_bw_narrow_hz; - float dll_bw_hz; - float dll_bw_narrow_hz; - float early_late_space_chips; - item_type_ = configuration->property(role + ".item_type", default_item_type); - //vector_length = configuration->property(role + ".vector_length", 2048); - int fs_in_deprecated = configuration->property("GNSS-SDR.internal_fs_hz", 2048000); - fs_in = configuration->property("GNSS-SDR.internal_fs_sps", fs_in_deprecated); - dump = configuration->property(role + ".dump", false); - pll_bw_hz = configuration->property(role + ".pll_bw_hz", 50.0); - if (FLAGS_pll_bw_hz != 0.0) - { - pll_bw_hz = static_cast(FLAGS_pll_bw_hz); - } - dll_bw_hz = configuration->property(role + ".dll_bw_hz", 2.0); - if (FLAGS_dll_bw_hz != 0.0) - { - dll_bw_hz = static_cast(FLAGS_dll_bw_hz); - } - pll_bw_narrow_hz = configuration->property(role + ".pll_bw_narrow_hz", 20.0); - dll_bw_narrow_hz = configuration->property(role + ".dll_bw_narrow_hz", 2.0); - int extend_correlation_ms; - extend_correlation_ms = configuration->property(role + ".extend_correlation_ms", 1); - - early_late_space_chips = configuration->property(role + ".early_late_space_chips", 0.5); - std::string default_dump_filename = "./track_ch"; - dump_filename = configuration->property(role + ".dump_filename", default_dump_filename); - vector_length = std::round(fs_in / (GPS_L1_CA_CODE_RATE_HZ / GPS_L1_CA_CODE_LENGTH_CHIPS)); - - //################# MAKE TRACKING GNURadio object ################### - if (item_type_ == "gr_complex") - { - item_size_ = sizeof(gr_complex); - tracking_cc = gps_l1_ca_dll_pll_c_aid_make_tracking_cc( - fs_in, - vector_length, - dump, - dump_filename, - pll_bw_hz, - dll_bw_hz, - pll_bw_narrow_hz, - dll_bw_narrow_hz, - extend_correlation_ms, - early_late_space_chips); - DLOG(INFO) << "tracking(" << tracking_cc->unique_id() << ")"; - } - else if (item_type_ == "cshort") - { - item_size_ = sizeof(lv_16sc_t); - tracking_sc = gps_l1_ca_dll_pll_c_aid_make_tracking_sc( - fs_in, - vector_length, - dump, - dump_filename, - pll_bw_hz, - dll_bw_hz, - pll_bw_narrow_hz, - dll_bw_narrow_hz, - extend_correlation_ms, - early_late_space_chips); - DLOG(INFO) << "tracking(" << tracking_sc->unique_id() << ")"; - } - else - { - item_size_ = sizeof(gr_complex); - LOG(WARNING) << item_type_ << " unknown tracking item type."; - } - channel_ = 0; - if (in_streams_ > 1) - { - LOG(ERROR) << "This implementation only supports one input stream"; - } - if (out_streams_ > 1) - { - LOG(ERROR) << "This implementation only supports one output stream"; - } -} - - -GpsL1CaDllPllCAidTracking::~GpsL1CaDllPllCAidTracking() = default; - - -void GpsL1CaDllPllCAidTracking::stop_tracking() -{ -} - - -void GpsL1CaDllPllCAidTracking::start_tracking() -{ - if (item_type_ == "gr_complex") - { - tracking_cc->start_tracking(); - } - else if (item_type_ == "cshort") - { - tracking_sc->start_tracking(); - } - else - { - LOG(WARNING) << item_type_ << " unknown tracking item type"; - } -} - -/* - * Set tracking channel unique ID - */ -void GpsL1CaDllPllCAidTracking::set_channel(unsigned int channel) -{ - channel_ = channel; - - if (item_type_ == "gr_complex") - { - tracking_cc->set_channel(channel); - } - else if (item_type_ == "cshort") - { - tracking_sc->set_channel(channel); - } - else - { - LOG(WARNING) << item_type_ << " unknown tracking item type"; - } -} - -void GpsL1CaDllPllCAidTracking::set_gnss_synchro(Gnss_Synchro* p_gnss_synchro) -{ - if (item_type_ == "gr_complex") - { - tracking_cc->set_gnss_synchro(p_gnss_synchro); - } - else if (item_type_ == "cshort") - { - tracking_sc->set_gnss_synchro(p_gnss_synchro); - } - else - { - LOG(WARNING) << item_type_ << " unknown tracking item type"; - } -} - -void GpsL1CaDllPllCAidTracking::connect(gr::top_block_sptr top_block) -{ - if (top_block) - { /* top_block is not null */ - }; - //nothing to connect, now the tracking uses gr_sync_decimator -} - -void GpsL1CaDllPllCAidTracking::disconnect(gr::top_block_sptr top_block) -{ - if (top_block) - { /* top_block is not null */ - }; - //nothing to disconnect, now the tracking uses gr_sync_decimator -} - -gr::basic_block_sptr GpsL1CaDllPllCAidTracking::get_left_block() -{ - if (item_type_ == "gr_complex") - { - return tracking_cc; - } - if (item_type_ == "cshort") - { - return tracking_sc; - } - LOG(WARNING) << item_type_ << " unknown tracking item type"; - return nullptr; -} - -gr::basic_block_sptr GpsL1CaDllPllCAidTracking::get_right_block() -{ - if (item_type_ == "gr_complex") - { - return tracking_cc; - } - if (item_type_ == "cshort") - { - return tracking_sc; - } - LOG(WARNING) << item_type_ << " unknown tracking item type"; - return nullptr; -} diff --git a/src/algorithms/tracking/adapters/gps_l1_ca_dll_pll_c_aid_tracking.h b/src/algorithms/tracking/adapters/gps_l1_ca_dll_pll_c_aid_tracking.h deleted file mode 100644 index a1c54aa46..000000000 --- a/src/algorithms/tracking/adapters/gps_l1_ca_dll_pll_c_aid_tracking.h +++ /dev/null @@ -1,111 +0,0 @@ -/*! - * \file gps_l1_ca_dll_pll_c_aid_tracking.h - * \brief Interface of an adapter of a DLL+PLL tracking loop block - * for GPS L1 C/A to a TrackingInterface - * \author Carlos Aviles, 2010. carlos.avilesr(at)googlemail.com - * Javier Arribas, 2011. jarribas(at)cttc.es - * - * Code DLL + carrier PLL according to the algorithms described in: - * K.Borre, D.M.Akos, N.Bertelsen, P.Rinder, and S.H.Jensen, - * A Software-Defined GPS and Galileo Receiver. A Single-Frequency - * Approach, Birkhauser, 2007 - * - * ------------------------------------------------------------------------- - * - * Copyright (C) 2010-2018 (see AUTHORS file for a list of contributors) - * - * GNSS-SDR is a software defined Global Navigation - * Satellite Systems receiver - * - * This file is part of GNSS-SDR. - * - * GNSS-SDR is free software: you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * GNSS-SDR is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - * GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with GNSS-SDR. If not, see . - * - * ------------------------------------------------------------------------- - */ - -#ifndef GNSS_SDR_GPS_L1_CA_DLL_PLL_C_AID_TRACKING_H_ -#define GNSS_SDR_GPS_L1_CA_DLL_PLL_C_AID_TRACKING_H_ - -#include "gps_l1_ca_dll_pll_c_aid_tracking_cc.h" -#include "gps_l1_ca_dll_pll_c_aid_tracking_sc.h" -#include "tracking_interface.h" -#include - - -class ConfigurationInterface; - -/*! - * \brief This class implements a code DLL + carrier PLL tracking loop - */ -class GpsL1CaDllPllCAidTracking : public TrackingInterface -{ -public: - GpsL1CaDllPllCAidTracking(ConfigurationInterface* configuration, - const std::string& role, - unsigned int in_streams, - unsigned int out_streams); - - virtual ~GpsL1CaDllPllCAidTracking(); - - inline std::string role() override - { - return role_; - } - - //! Returns "GPS_L1_CA_DLL_PLL_C_Aid_Tracking" - inline std::string implementation() override - { - return "GPS_L1_CA_DLL_PLL_C_Aid_Tracking"; - } - - inline size_t item_size() override - { - return item_size_; - } - - void connect(gr::top_block_sptr top_block) override; - void disconnect(gr::top_block_sptr top_block) override; - gr::basic_block_sptr get_left_block() override; - gr::basic_block_sptr get_right_block() override; - - /*! - * \brief Set tracking channel unique ID - */ - void set_channel(unsigned int channel) override; - - /*! - * \brief Set acquisition/tracking common Gnss_Synchro object pointer - * to efficiently exchange synchronization data between acquisition and tracking blocks - */ - void set_gnss_synchro(Gnss_Synchro* p_gnss_synchro) override; - - void start_tracking() override; - /*! - * \brief Stop running tracking - */ - void stop_tracking() override; - -private: - gps_l1_ca_dll_pll_c_aid_tracking_cc_sptr tracking_cc; - gps_l1_ca_dll_pll_c_aid_tracking_sc_sptr tracking_sc; - size_t item_size_; - std::string item_type_; - unsigned int channel_; - std::string role_; - unsigned int in_streams_; - unsigned int out_streams_; -}; - -#endif // GNSS_SDR_GPS_L1_CA_DLL_PLL_C_AID_TRACKING_H_ diff --git a/src/algorithms/tracking/gnuradio_blocks/CMakeLists.txt b/src/algorithms/tracking/gnuradio_blocks/CMakeLists.txt index 48da0fc1b..7544c2f4a 100644 --- a/src/algorithms/tracking/gnuradio_blocks/CMakeLists.txt +++ b/src/algorithms/tracking/gnuradio_blocks/CMakeLists.txt @@ -41,8 +41,6 @@ endif() set(TRACKING_GR_BLOCKS_SOURCES galileo_e1_tcp_connector_tracking_cc.cc gps_l1_ca_tcp_connector_tracking_cc.cc - gps_l1_ca_dll_pll_c_aid_tracking_cc.cc - gps_l1_ca_dll_pll_c_aid_tracking_sc.cc glonass_l1_ca_dll_pll_tracking_cc.cc glonass_l1_ca_dll_pll_c_aid_tracking_cc.cc glonass_l1_ca_dll_pll_c_aid_tracking_sc.cc @@ -57,8 +55,6 @@ set(TRACKING_GR_BLOCKS_SOURCES set(TRACKING_GR_BLOCKS_HEADERS galileo_e1_tcp_connector_tracking_cc.h gps_l1_ca_tcp_connector_tracking_cc.h - gps_l1_ca_dll_pll_c_aid_tracking_cc.h - gps_l1_ca_dll_pll_c_aid_tracking_sc.h glonass_l1_ca_dll_pll_tracking_cc.h glonass_l1_ca_dll_pll_c_aid_tracking_cc.h glonass_l1_ca_dll_pll_c_aid_tracking_sc.h @@ -80,6 +76,13 @@ add_library(tracking_gr_blocks ${TRACKING_GR_BLOCKS_HEADERS} ) +if(${FILESYSTEM_FOUND}) + target_compile_definitions(tracking_gr_blocks PRIVATE -DHAS_STD_FILESYSTEM=1) + target_link_libraries(tracking_gr_blocks PRIVATE std::filesystem) +else() + target_link_libraries(tracking_gr_blocks PRIVATE Boost::filesystem) +endif() + target_link_libraries(tracking_gr_blocks PUBLIC Boost::boost diff --git a/src/algorithms/tracking/gnuradio_blocks/dll_pll_veml_tracking.cc b/src/algorithms/tracking/gnuradio_blocks/dll_pll_veml_tracking.cc index 61e407656..2e9610bf5 100644 --- a/src/algorithms/tracking/gnuradio_blocks/dll_pll_veml_tracking.cc +++ b/src/algorithms/tracking/gnuradio_blocks/dll_pll_veml_tracking.cc @@ -54,7 +54,6 @@ #include "gps_sdr_signal_processing.h" #include "lock_detectors.h" #include "tracking_discriminators.h" -#include #include #include // for io_signature #include // for scoped_lock @@ -67,6 +66,14 @@ #include // for cout, cerr #include +#if HAS_STD_FILESYSTEM +#include +namespace fs = std::filesystem; +#else +#include +namespace fs = boost::filesystem; +#endif + dll_pll_veml_tracking_sptr dll_pll_veml_make_tracking(const Dll_Pll_Conf &conf_) { @@ -497,7 +504,7 @@ dll_pll_veml_tracking::dll_pll_veml_tracking(const Dll_Pll_Conf &conf_) : gr::bl d_dump_filename = d_dump_filename.substr(0, d_dump_filename.find_last_of('.')); } - d_dump_filename = dump_path + boost::filesystem::path::preferred_separator + d_dump_filename; + d_dump_filename = dump_path + fs::path::preferred_separator + d_dump_filename; // create directory if (!gnss_sdr_create_directory(dump_path)) { diff --git a/src/algorithms/tracking/gnuradio_blocks/dll_pll_veml_tracking_fpga.cc b/src/algorithms/tracking/gnuradio_blocks/dll_pll_veml_tracking_fpga.cc index 43cc30e7a..5ee4bee2a 100644 --- a/src/algorithms/tracking/gnuradio_blocks/dll_pll_veml_tracking_fpga.cc +++ b/src/algorithms/tracking/gnuradio_blocks/dll_pll_veml_tracking_fpga.cc @@ -46,7 +46,6 @@ #include "gnss_synchro.h" #include "lock_detectors.h" #include "tracking_discriminators.h" -#include #include #include #include @@ -60,6 +59,15 @@ #include #include +#if HAS_STD_FILESYSTEM +#include +namespace fs = std::filesystem; +#else +#include +namespace fs = boost::filesystem; +#endif + + dll_pll_veml_tracking_fpga_sptr dll_pll_veml_make_tracking_fpga(const Dll_Pll_Conf_Fpga &conf_) { return dll_pll_veml_tracking_fpga_sptr(new dll_pll_veml_tracking_fpga(conf_)); @@ -413,7 +421,7 @@ dll_pll_veml_tracking_fpga::dll_pll_veml_tracking_fpga(const Dll_Pll_Conf_Fpga & d_dump_filename = d_dump_filename.substr(0, d_dump_filename.find_last_of('.')); } - d_dump_filename = dump_path + boost::filesystem::path::preferred_separator + d_dump_filename; + d_dump_filename = dump_path + fs::path::preferred_separator + d_dump_filename; // create directory if (!gnss_sdr_create_directory(dump_path)) { diff --git a/src/algorithms/tracking/gnuradio_blocks/gps_l1_ca_dll_pll_c_aid_tracking_cc.cc b/src/algorithms/tracking/gnuradio_blocks/gps_l1_ca_dll_pll_c_aid_tracking_cc.cc deleted file mode 100644 index cfe2215fa..000000000 --- a/src/algorithms/tracking/gnuradio_blocks/gps_l1_ca_dll_pll_c_aid_tracking_cc.cc +++ /dev/null @@ -1,920 +0,0 @@ -/*! - * \file gps_l1_ca_dll_pll_c_aid_tracking_cc.cc - * \brief Implementation of a code DLL + carrier PLL tracking block - * \author Javier Arribas, 2015. jarribas(at)cttc.es - * - * ------------------------------------------------------------------------- - * - * Copyright (C) 2010-2018 (see AUTHORS file for a list of contributors) - * - * GNSS-SDR is a software defined Global Navigation - * Satellite Systems receiver - * - * This file is part of GNSS-SDR. - * - * GNSS-SDR is free software: you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * GNSS-SDR is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - * GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with GNSS-SDR. If not, see . - * - * ------------------------------------------------------------------------- - */ - -#include "gps_l1_ca_dll_pll_c_aid_tracking_cc.h" -#include "GPS_L1_CA.h" -#include "gnss_sdr_flags.h" -#include "gps_sdr_signal_processing.h" -#include "lock_detectors.h" -#include "tracking_discriminators.h" -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - - -gps_l1_ca_dll_pll_c_aid_tracking_cc_sptr -gps_l1_ca_dll_pll_c_aid_make_tracking_cc( - int64_t fs_in, - uint32_t vector_length, - bool dump, - std::string dump_filename, - float pll_bw_hz, - float dll_bw_hz, - float pll_bw_narrow_hz, - float dll_bw_narrow_hz, - int32_t extend_correlation_ms, - float early_late_space_chips) -{ - return gps_l1_ca_dll_pll_c_aid_tracking_cc_sptr(new gps_l1_ca_dll_pll_c_aid_tracking_cc( - fs_in, vector_length, dump, std::move(dump_filename), pll_bw_hz, dll_bw_hz, pll_bw_narrow_hz, dll_bw_narrow_hz, extend_correlation_ms, early_late_space_chips)); -} - - -void gps_l1_ca_dll_pll_c_aid_tracking_cc::forecast(int noutput_items, - gr_vector_int &ninput_items_required) -{ - if (noutput_items != 0) - { - ninput_items_required[0] = static_cast(d_vector_length) * 2; //set the required available samples in each call - } -} - - -void gps_l1_ca_dll_pll_c_aid_tracking_cc::msg_handler_preamble_index(pmt::pmt_t msg) -{ - //pmt::print(msg); - DLOG(INFO) << "Extended correlation enabled for Tracking CH " << d_channel << ": Satellite " << Gnss_Satellite(systemName[sys], d_acquisition_gnss_synchro->PRN); - if (d_enable_extended_integration == false) //avoid re-setting preamble indicator - { - d_preamble_timestamp_s = pmt::to_double(std::move(msg)); - d_enable_extended_integration = true; - d_preamble_synchronized = false; - } -} - - -gps_l1_ca_dll_pll_c_aid_tracking_cc::gps_l1_ca_dll_pll_c_aid_tracking_cc( - int64_t fs_in, - uint32_t vector_length, - bool dump, - std::string dump_filename, - float pll_bw_hz, - float dll_bw_hz, - float pll_bw_narrow_hz, - float dll_bw_narrow_hz, - int32_t extend_correlation_ms, - float early_late_space_chips) : gr::block("gps_l1_ca_dll_pll_c_aid_tracking_cc", gr::io_signature::make(1, 1, sizeof(gr_complex)), - gr::io_signature::make(1, 1, sizeof(Gnss_Synchro))) -{ - // Telemetry bit synchronization message port input - this->message_port_register_in(pmt::mp("preamble_timestamp_s")); - - this->set_msg_handler(pmt::mp("preamble_timestamp_s"), - boost::bind(&gps_l1_ca_dll_pll_c_aid_tracking_cc::msg_handler_preamble_index, this, _1)); - - this->message_port_register_out(pmt::mp("events")); - this->message_port_register_in(pmt::mp("telemetry_to_trk")); - - // initialize internal vars - d_dump = dump; - d_fs_in = fs_in; - d_vector_length = vector_length; - d_dump_filename = std::move(dump_filename); - d_correlation_length_samples = static_cast(d_vector_length); - - // Initialize tracking ========================================== - d_pll_bw_hz = pll_bw_hz; - d_dll_bw_hz = dll_bw_hz; - d_pll_bw_narrow_hz = pll_bw_narrow_hz; - d_dll_bw_narrow_hz = dll_bw_narrow_hz; - d_extend_correlation_ms = extend_correlation_ms; - d_code_loop_filter.set_DLL_BW(d_dll_bw_hz); - d_carrier_loop_filter.set_params(10.0, d_pll_bw_hz, 2); - - // --- DLL variables -------------------------------------------------------- - d_early_late_spc_chips = early_late_space_chips; // Define early-late offset (in chips) - - // Initialization of local code replica - // Get space for a vector with the C/A code replica sampled 1x/chip - d_ca_code = static_cast(volk_gnsssdr_malloc(static_cast(GPS_L1_CA_CODE_LENGTH_CHIPS) * sizeof(gr_complex), volk_gnsssdr_get_alignment())); - - // correlator outputs (scalar) - d_n_correlator_taps = 3; // Early, Prompt, and Late - d_correlator_outs = static_cast(volk_gnsssdr_malloc(d_n_correlator_taps * sizeof(gr_complex), volk_gnsssdr_get_alignment())); - for (int32_t n = 0; n < d_n_correlator_taps; n++) - { - d_correlator_outs[n] = gr_complex(0, 0); - } - d_local_code_shift_chips = static_cast(volk_gnsssdr_malloc(d_n_correlator_taps * sizeof(float), volk_gnsssdr_get_alignment())); - // Set TAPs delay values [chips] - d_local_code_shift_chips[0] = -d_early_late_spc_chips; - d_local_code_shift_chips[1] = 0.0; - d_local_code_shift_chips[2] = d_early_late_spc_chips; - - multicorrelator_cpu.init(2 * d_correlation_length_samples, d_n_correlator_taps); - - //--- Perform initializations ------------------------------ - // define initial code frequency basis of NCO - d_code_freq_chips = GPS_L1_CA_CODE_RATE_HZ; - // define residual code phase (in chips) - d_rem_code_phase_samples = 0.0; - // define residual carrier phase - d_rem_carrier_phase_rad = 0.0; - - // sample synchronization - d_sample_counter = 0ULL; //(from trk to tlm) - d_acq_sample_stamp = 0; - d_enable_tracking = false; - d_pull_in = false; - - // CN0 estimation and lock detector buffers - d_cn0_estimation_counter = 0; - d_Prompt_buffer = new gr_complex[FLAGS_cn0_samples]; - d_carrier_lock_test = 1; - d_CN0_SNV_dB_Hz = 0; - d_carrier_lock_fail_counter = 0; - d_carrier_lock_threshold = FLAGS_carrier_lock_th; - - systemName["G"] = std::string("GPS"); - systemName["S"] = std::string("SBAS"); - - set_relative_rate(1.0 / static_cast(d_vector_length)); - - d_acquisition_gnss_synchro = nullptr; - d_channel = 0; - d_acq_code_phase_samples = 0.0; - d_acq_carrier_doppler_hz = 0.0; - d_carrier_doppler_hz = 0.0; - d_code_error_filt_chips_Ti = 0.0; - d_acc_carrier_phase_cycles = 0.0; - d_code_phase_samples = 0.0; - - d_pll_to_dll_assist_secs_Ti = 0.0; - d_rem_code_phase_chips = 0.0; - d_code_phase_step_chips = 0.0; - d_carrier_phase_step_rad = 0.0; - d_enable_extended_integration = false; - d_preamble_synchronized = false; - d_rem_code_phase_integer_samples = 0; - d_code_error_chips_Ti = 0.0; - d_code_error_filt_chips_s = 0.0; - d_carr_phase_error_secs_Ti = 0.0; - d_preamble_timestamp_s = 0.0; - //set_min_output_buffer((int64_t)300); -} - - -void gps_l1_ca_dll_pll_c_aid_tracking_cc::start_tracking() -{ - /* - * correct the code phase according to the delay between acq and trk - */ - d_acq_code_phase_samples = d_acquisition_gnss_synchro->Acq_delay_samples; - d_acq_carrier_doppler_hz = d_acquisition_gnss_synchro->Acq_doppler_hz; - d_acq_sample_stamp = d_acquisition_gnss_synchro->Acq_samplestamp_samples; - - int64_t acq_trk_diff_samples; - double acq_trk_diff_seconds; - acq_trk_diff_samples = static_cast(d_sample_counter) - static_cast(d_acq_sample_stamp); //-d_vector_length; - DLOG(INFO) << "Number of samples between Acquisition and Tracking =" << acq_trk_diff_samples; - acq_trk_diff_seconds = static_cast(acq_trk_diff_samples) / static_cast(d_fs_in); - // Doppler effect - // Fd=(C/(C+Vr))*F - double radial_velocity = (GPS_L1_FREQ_HZ + d_acq_carrier_doppler_hz) / GPS_L1_FREQ_HZ; - // new chip and prn sequence periods based on acq Doppler - double T_chip_mod_seconds; - double T_prn_mod_seconds; - double T_prn_mod_samples; - d_code_freq_chips = radial_velocity * GPS_L1_CA_CODE_RATE_HZ; - d_code_phase_step_chips = static_cast(d_code_freq_chips) / static_cast(d_fs_in); - T_chip_mod_seconds = 1.0 / d_code_freq_chips; - T_prn_mod_seconds = T_chip_mod_seconds * GPS_L1_CA_CODE_LENGTH_CHIPS; - T_prn_mod_samples = T_prn_mod_seconds * static_cast(d_fs_in); - - d_correlation_length_samples = round(T_prn_mod_samples); - - double T_prn_true_seconds = GPS_L1_CA_CODE_LENGTH_CHIPS / GPS_L1_CA_CODE_RATE_HZ; - double T_prn_true_samples = T_prn_true_seconds * static_cast(d_fs_in); - double T_prn_diff_seconds = T_prn_true_seconds - T_prn_mod_seconds; - double N_prn_diff = acq_trk_diff_seconds / T_prn_true_seconds; - double corrected_acq_phase_samples, delay_correction_samples; - corrected_acq_phase_samples = fmod((d_acq_code_phase_samples + T_prn_diff_seconds * N_prn_diff * static_cast(d_fs_in)), T_prn_true_samples); - if (corrected_acq_phase_samples < 0) - { - corrected_acq_phase_samples = T_prn_mod_samples + corrected_acq_phase_samples; - } - delay_correction_samples = d_acq_code_phase_samples - corrected_acq_phase_samples; - - d_acq_code_phase_samples = corrected_acq_phase_samples; - - d_carrier_doppler_hz = d_acq_carrier_doppler_hz; - - d_carrier_phase_step_rad = GPS_TWO_PI * d_carrier_doppler_hz / static_cast(d_fs_in); - - // DLL/PLL filter initialization - d_carrier_loop_filter.initialize(d_acq_carrier_doppler_hz); // The carrier loop filter implements the Doppler accumulator - d_code_loop_filter.initialize(); // initialize the code filter - - // generate local reference ALWAYS starting at chip 1 (1 sample per chip) - gps_l1_ca_code_gen_complex(d_ca_code, d_acquisition_gnss_synchro->PRN, 0); - - multicorrelator_cpu.set_local_code_and_taps(static_cast(GPS_L1_CA_CODE_LENGTH_CHIPS), d_ca_code, d_local_code_shift_chips); - for (int32_t n = 0; n < d_n_correlator_taps; n++) - { - d_correlator_outs[n] = gr_complex(0, 0); - } - - d_carrier_lock_fail_counter = 0; - d_rem_code_phase_samples = 0.0; - d_rem_carrier_phase_rad = 0.0; - d_rem_code_phase_chips = 0.0; - d_acc_carrier_phase_cycles = 0.0; - d_pll_to_dll_assist_secs_Ti = 0.0; - d_code_phase_samples = d_acq_code_phase_samples; - - std::string sys_ = &d_acquisition_gnss_synchro->System; - sys = sys_.substr(0, 1); - - // DEBUG OUTPUT - std::cout << "Tracking of GPS L1 C/A signal started on channel " << d_channel << " for satellite " << Gnss_Satellite(systemName[sys], d_acquisition_gnss_synchro->PRN) << std::endl; - LOG(INFO) << "Tracking of GPS L1 C/A signal for satellite " << Gnss_Satellite(systemName[sys], d_acquisition_gnss_synchro->PRN) << " on channel " << d_channel; - - // enable tracking - d_pull_in = true; - d_enable_tracking = true; - d_enable_extended_integration = false; - d_preamble_synchronized = false; - LOG(INFO) << "PULL-IN Doppler [Hz]=" << d_carrier_doppler_hz - << " Code Phase correction [samples]=" << delay_correction_samples - << " PULL-IN Code Phase [samples]=" << d_acq_code_phase_samples; -} - - -gps_l1_ca_dll_pll_c_aid_tracking_cc::~gps_l1_ca_dll_pll_c_aid_tracking_cc() -{ - if (d_dump_file.is_open()) - { - try - { - d_dump_file.close(); - } - catch (const std::exception &ex) - { - LOG(WARNING) << "Exception in destructor " << ex.what(); - } - } - - if (d_dump) - { - if (d_channel == 0) - { - std::cout << "Writing .mat files ..."; - } - try - { - gps_l1_ca_dll_pll_c_aid_tracking_cc::save_matfile(); - } - catch (const std::exception &ex) - { - LOG(WARNING) << "Error saving the .mat file: " << ex.what(); - } - - if (d_channel == 0) - { - std::cout << " done." << std::endl; - } - } - - try - { - volk_gnsssdr_free(d_local_code_shift_chips); - volk_gnsssdr_free(d_correlator_outs); - volk_gnsssdr_free(d_ca_code); - delete[] d_Prompt_buffer; - multicorrelator_cpu.free(); - } - catch (const std::exception &ex) - { - LOG(WARNING) << "Exception in destructor " << ex.what(); - } -} - - -int32_t gps_l1_ca_dll_pll_c_aid_tracking_cc::save_matfile() -{ - // READ DUMP FILE - std::ifstream::pos_type size; - int32_t number_of_double_vars = 11; - int32_t number_of_float_vars = 5; - int32_t epoch_size_bytes = sizeof(uint64_t) + sizeof(double) * number_of_double_vars + - sizeof(float) * number_of_float_vars + sizeof(uint32_t); - std::ifstream dump_file; - dump_file.exceptions(std::ifstream::failbit | std::ifstream::badbit); - try - { - dump_file.open(d_dump_filename.c_str(), std::ios::binary | std::ios::ate); - } - catch (const std::ifstream::failure &e) - { - std::cerr << "Problem opening dump file:" << e.what() << std::endl; - return 1; - } - // count number of epochs and rewind - int64_t num_epoch = 0; - if (dump_file.is_open()) - { - size = dump_file.tellg(); - num_epoch = static_cast(size) / static_cast(epoch_size_bytes); - dump_file.seekg(0, std::ios::beg); - } - else - { - return 1; - } - auto *abs_E = new float[num_epoch]; - auto *abs_P = new float[num_epoch]; - auto *abs_L = new float[num_epoch]; - auto *Prompt_I = new float[num_epoch]; - auto *Prompt_Q = new float[num_epoch]; - auto *PRN_start_sample_count = new uint64_t[num_epoch]; - auto *acc_carrier_phase_rad = new double[num_epoch]; - auto *carrier_doppler_hz = new double[num_epoch]; - auto *code_freq_chips = new double[num_epoch]; - auto *carr_error_hz = new double[num_epoch]; - auto *carr_error_filt_hz = new double[num_epoch]; - auto *code_error_chips = new double[num_epoch]; - auto *code_error_filt_chips = new double[num_epoch]; - auto *CN0_SNV_dB_Hz = new double[num_epoch]; - auto *carrier_lock_test = new double[num_epoch]; - auto *aux1 = new double[num_epoch]; - auto *aux2 = new double[num_epoch]; - auto *PRN = new uint32_t[num_epoch]; - - try - { - if (dump_file.is_open()) - { - for (int64_t i = 0; i < num_epoch; i++) - { - dump_file.read(reinterpret_cast(&abs_E[i]), sizeof(float)); - dump_file.read(reinterpret_cast(&abs_P[i]), sizeof(float)); - dump_file.read(reinterpret_cast(&abs_L[i]), sizeof(float)); - dump_file.read(reinterpret_cast(&Prompt_I[i]), sizeof(float)); - dump_file.read(reinterpret_cast(&Prompt_Q[i]), sizeof(float)); - dump_file.read(reinterpret_cast(&PRN_start_sample_count[i]), sizeof(uint64_t)); - dump_file.read(reinterpret_cast(&acc_carrier_phase_rad[i]), sizeof(double)); - dump_file.read(reinterpret_cast(&carrier_doppler_hz[i]), sizeof(double)); - dump_file.read(reinterpret_cast(&code_freq_chips[i]), sizeof(double)); - dump_file.read(reinterpret_cast(&carr_error_hz[i]), sizeof(double)); - dump_file.read(reinterpret_cast(&carr_error_filt_hz[i]), sizeof(double)); - dump_file.read(reinterpret_cast(&code_error_chips[i]), sizeof(double)); - dump_file.read(reinterpret_cast(&code_error_filt_chips[i]), sizeof(double)); - dump_file.read(reinterpret_cast(&CN0_SNV_dB_Hz[i]), sizeof(double)); - dump_file.read(reinterpret_cast(&carrier_lock_test[i]), sizeof(double)); - dump_file.read(reinterpret_cast(&aux1[i]), sizeof(double)); - dump_file.read(reinterpret_cast(&aux2[i]), sizeof(double)); - dump_file.read(reinterpret_cast(&PRN[i]), sizeof(uint32_t)); - } - } - dump_file.close(); - } - catch (const std::ifstream::failure &e) - { - std::cerr << "Problem reading dump file:" << e.what() << std::endl; - delete[] abs_E; - delete[] abs_P; - delete[] abs_L; - delete[] Prompt_I; - delete[] Prompt_Q; - delete[] PRN_start_sample_count; - delete[] acc_carrier_phase_rad; - delete[] carrier_doppler_hz; - delete[] code_freq_chips; - delete[] carr_error_hz; - delete[] carr_error_filt_hz; - delete[] code_error_chips; - delete[] code_error_filt_chips; - delete[] CN0_SNV_dB_Hz; - delete[] carrier_lock_test; - delete[] aux1; - delete[] aux2; - delete[] PRN; - return 1; - } - - // WRITE MAT FILE - mat_t *matfp; - matvar_t *matvar; - std::string filename = d_dump_filename; - filename.erase(filename.length() - 4, 4); - filename.append(".mat"); - matfp = Mat_CreateVer(filename.c_str(), nullptr, MAT_FT_MAT73); - if (reinterpret_cast(matfp) != nullptr) - { - size_t dims[2] = {1, static_cast(num_epoch)}; - matvar = Mat_VarCreate("abs_E", MAT_C_SINGLE, MAT_T_SINGLE, 2, dims, abs_E, 0); - Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE - Mat_VarFree(matvar); - - matvar = Mat_VarCreate("abs_P", MAT_C_SINGLE, MAT_T_SINGLE, 2, dims, abs_P, 0); - Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE - Mat_VarFree(matvar); - - matvar = Mat_VarCreate("abs_L", MAT_C_SINGLE, MAT_T_SINGLE, 2, dims, abs_L, 0); - Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE - Mat_VarFree(matvar); - - matvar = Mat_VarCreate("Prompt_I", MAT_C_SINGLE, MAT_T_SINGLE, 2, dims, Prompt_I, 0); - Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE - Mat_VarFree(matvar); - - matvar = Mat_VarCreate("Prompt_Q", MAT_C_SINGLE, MAT_T_SINGLE, 2, dims, Prompt_Q, 0); - Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE - Mat_VarFree(matvar); - - matvar = Mat_VarCreate("PRN_start_sample_count", MAT_C_UINT64, MAT_T_UINT64, 2, dims, PRN_start_sample_count, 0); - Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE - Mat_VarFree(matvar); - - matvar = Mat_VarCreate("acc_carrier_phase_rad", MAT_C_DOUBLE, MAT_T_DOUBLE, 2, dims, acc_carrier_phase_rad, 0); - Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE - Mat_VarFree(matvar); - - matvar = Mat_VarCreate("carrier_doppler_hz", MAT_C_DOUBLE, MAT_T_DOUBLE, 2, dims, carrier_doppler_hz, 0); - Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE - Mat_VarFree(matvar); - - matvar = Mat_VarCreate("code_freq_chips", MAT_C_DOUBLE, MAT_T_DOUBLE, 2, dims, code_freq_chips, 0); - Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE - Mat_VarFree(matvar); - - matvar = Mat_VarCreate("carr_error_hz", MAT_C_DOUBLE, MAT_T_DOUBLE, 2, dims, carr_error_hz, 0); - Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE - Mat_VarFree(matvar); - - matvar = Mat_VarCreate("carr_error_filt_hz", MAT_C_DOUBLE, MAT_T_DOUBLE, 2, dims, carr_error_filt_hz, 0); - Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE - Mat_VarFree(matvar); - - matvar = Mat_VarCreate("code_error_chips", MAT_C_DOUBLE, MAT_T_DOUBLE, 2, dims, code_error_chips, 0); - Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE - Mat_VarFree(matvar); - - matvar = Mat_VarCreate("code_error_filt_chips", MAT_C_DOUBLE, MAT_T_DOUBLE, 2, dims, code_error_filt_chips, 0); - Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE - Mat_VarFree(matvar); - - matvar = Mat_VarCreate("CN0_SNV_dB_Hz", MAT_C_DOUBLE, MAT_T_DOUBLE, 2, dims, CN0_SNV_dB_Hz, 0); - Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE - Mat_VarFree(matvar); - - matvar = Mat_VarCreate("carrier_lock_test", MAT_C_DOUBLE, MAT_T_DOUBLE, 2, dims, carrier_lock_test, 0); - Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE - Mat_VarFree(matvar); - - matvar = Mat_VarCreate("aux1", MAT_C_DOUBLE, MAT_T_DOUBLE, 2, dims, aux1, 0); - Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE - Mat_VarFree(matvar); - - matvar = Mat_VarCreate("aux2", MAT_C_DOUBLE, MAT_T_DOUBLE, 2, dims, aux2, 0); - Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE - Mat_VarFree(matvar); - - matvar = Mat_VarCreate("PRN", MAT_C_UINT32, MAT_T_UINT32, 2, dims, PRN, 0); - Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE - Mat_VarFree(matvar); - } - Mat_Close(matfp); - delete[] abs_E; - delete[] abs_P; - delete[] abs_L; - delete[] Prompt_I; - delete[] Prompt_Q; - delete[] PRN_start_sample_count; - delete[] acc_carrier_phase_rad; - delete[] carrier_doppler_hz; - delete[] code_freq_chips; - delete[] carr_error_hz; - delete[] carr_error_filt_hz; - delete[] code_error_chips; - delete[] code_error_filt_chips; - delete[] CN0_SNV_dB_Hz; - delete[] carrier_lock_test; - delete[] aux1; - delete[] aux2; - delete[] PRN; - return 0; -} - - -void gps_l1_ca_dll_pll_c_aid_tracking_cc::set_channel(uint32_t channel) -{ - d_channel = channel; - LOG(INFO) << "Tracking Channel set to " << d_channel; - // ############# ENABLE DATA FILE LOG ################# - if (d_dump == true) - { - if (d_dump_file.is_open() == false) - { - try - { - d_dump_filename.append(std::to_string(d_channel)); - d_dump_filename.append(".dat"); - d_dump_file.exceptions(std::ifstream::failbit | std::ifstream::badbit); - d_dump_file.open(d_dump_filename.c_str(), std::ios::out | std::ios::binary); - LOG(INFO) << "Tracking dump enabled on channel " << d_channel << " Log file: " << d_dump_filename.c_str(); - } - catch (const std::ifstream::failure &e) - { - LOG(WARNING) << "channel " << d_channel << " Exception opening trk dump file " << e.what(); - } - } - } -} - - -void gps_l1_ca_dll_pll_c_aid_tracking_cc::set_gnss_synchro(Gnss_Synchro *p_gnss_synchro) -{ - d_acquisition_gnss_synchro = p_gnss_synchro; -} - - -int gps_l1_ca_dll_pll_c_aid_tracking_cc::general_work(int noutput_items __attribute__((unused)), gr_vector_int &ninput_items __attribute__((unused)), - gr_vector_const_void_star &input_items, gr_vector_void_star &output_items) -{ - // Block input data and block output stream pointers - const auto *in = reinterpret_cast(input_items[0]); - auto **out = reinterpret_cast(&output_items[0]); - - // GNSS_SYNCHRO OBJECT to interchange data between tracking->telemetry_decoder - Gnss_Synchro current_synchro_data = Gnss_Synchro(); - - // process vars - double code_error_filt_secs_Ti = 0.0; - double CURRENT_INTEGRATION_TIME_S = 0.0; - double CORRECTED_INTEGRATION_TIME_S = 0.0; - - if (d_enable_tracking == true) - { - // Fill the acquisition data - current_synchro_data = *d_acquisition_gnss_synchro; - // Receiver signal alignment - if (d_pull_in == true) - { - int32_t samples_offset; - double acq_trk_shif_correction_samples; - int32_t acq_to_trk_delay_samples; - acq_to_trk_delay_samples = d_sample_counter - d_acq_sample_stamp; - acq_trk_shif_correction_samples = d_correlation_length_samples - fmod(static_cast(acq_to_trk_delay_samples), static_cast(d_correlation_length_samples)); - samples_offset = round(d_acq_code_phase_samples + acq_trk_shif_correction_samples); - current_synchro_data.Tracking_sample_counter = d_sample_counter + static_cast(samples_offset); - d_sample_counter += static_cast(samples_offset); // count for the processed samples - d_pull_in = false; - d_acc_carrier_phase_cycles -= d_carrier_phase_step_rad * samples_offset / GPS_TWO_PI; - current_synchro_data.Carrier_phase_rads = d_acc_carrier_phase_cycles * GPS_TWO_PI; - current_synchro_data.Carrier_Doppler_hz = d_carrier_doppler_hz; - current_synchro_data.fs = d_fs_in; - *out[0] = current_synchro_data; - consume_each(samples_offset); // shift input to perform alignment with local replica - return 1; - } - - // ################# CARRIER WIPEOFF AND CORRELATORS ############################## - // perform carrier wipe-off and compute Early, Prompt and Late correlation - multicorrelator_cpu.set_input_output_vectors(d_correlator_outs, in); - multicorrelator_cpu.Carrier_wipeoff_multicorrelator_resampler(d_rem_carrier_phase_rad, - d_carrier_phase_step_rad, - d_rem_code_phase_chips, - d_code_phase_step_chips, - d_correlation_length_samples); - - // ####### coherent integration extension - // keep the last symbols - d_E_history.push_back(d_correlator_outs[0]); // save early output - d_P_history.push_back(d_correlator_outs[1]); // save prompt output - d_L_history.push_back(d_correlator_outs[2]); // save late output - - if (static_cast(d_P_history.size()) > d_extend_correlation_ms) - { - d_E_history.pop_front(); - d_P_history.pop_front(); - d_L_history.pop_front(); - } - - bool enable_dll_pll; - if (d_enable_extended_integration == true) - { - int64_t symbol_diff = round(1000.0 * ((static_cast(d_sample_counter) + d_rem_code_phase_samples) / static_cast(d_fs_in) - d_preamble_timestamp_s)); - if (symbol_diff > 0 and symbol_diff % d_extend_correlation_ms == 0) - { - // compute coherent integration and enable tracking loop - // perform coherent integration using correlator output history - // std::cout<<"##### RESET COHERENT INTEGRATION ####"<PRN) - << " pll_bw = " << d_pll_bw_hz << " [Hz], pll_narrow_bw = " << d_pll_bw_narrow_hz << " [Hz]" << std::endl - << " dll_bw = " << d_dll_bw_hz << " [Hz], dll_narrow_bw = " << d_dll_bw_narrow_hz << " [Hz]" << std::endl; - } - // UPDATE INTEGRATION TIME - CURRENT_INTEGRATION_TIME_S = static_cast(d_extend_correlation_ms) * GPS_L1_CA_CODE_PERIOD; - d_code_loop_filter.set_pdi(CURRENT_INTEGRATION_TIME_S); - enable_dll_pll = true; - } - else - { - if (d_preamble_synchronized == true) - { - // continue extended coherent correlation - // Compute the next buffer length based on the period of the PRN sequence and the code phase error estimation - double T_chip_seconds = 1.0 / d_code_freq_chips; - double T_prn_seconds = T_chip_seconds * GPS_L1_CA_CODE_LENGTH_CHIPS; - double T_prn_samples = T_prn_seconds * static_cast(d_fs_in); - int32_t K_prn_samples = round(T_prn_samples); - double K_T_prn_error_samples = K_prn_samples - T_prn_samples; - - d_rem_code_phase_samples = d_rem_code_phase_samples - K_T_prn_error_samples; - d_rem_code_phase_integer_samples = round(d_rem_code_phase_samples); // round to a discrete number of samples - d_correlation_length_samples = K_prn_samples + d_rem_code_phase_integer_samples; - d_rem_code_phase_samples = d_rem_code_phase_samples - d_rem_code_phase_integer_samples; - // code phase step (Code resampler phase increment per sample) [chips/sample] - d_code_phase_step_chips = d_code_freq_chips / static_cast(d_fs_in); - // remnant code phase [chips] - d_rem_code_phase_chips = d_rem_code_phase_samples * (d_code_freq_chips / static_cast(d_fs_in)); - d_rem_carrier_phase_rad = fmod(d_rem_carrier_phase_rad + d_carrier_phase_step_rad * static_cast(d_correlation_length_samples), GPS_TWO_PI); - - // UPDATE ACCUMULATED CARRIER PHASE - CORRECTED_INTEGRATION_TIME_S = (static_cast(d_correlation_length_samples) / static_cast(d_fs_in)); - d_acc_carrier_phase_cycles -= d_carrier_phase_step_rad * d_correlation_length_samples / GPS_TWO_PI; - - // disable tracking loop and inform telemetry decoder - enable_dll_pll = false; - } - else - { - // perform basic (1ms) correlation - // UPDATE INTEGRATION TIME - CURRENT_INTEGRATION_TIME_S = static_cast(d_correlation_length_samples) / static_cast(d_fs_in); - d_code_loop_filter.set_pdi(CURRENT_INTEGRATION_TIME_S); - enable_dll_pll = true; - } - } - } - else - { - // UPDATE INTEGRATION TIME - CURRENT_INTEGRATION_TIME_S = static_cast(d_correlation_length_samples) / static_cast(d_fs_in); - enable_dll_pll = true; - } - - if (enable_dll_pll == true) - { - // ################## PLL ########################################################## - // Update PLL discriminator [rads/Ti -> Secs/Ti] - d_carr_phase_error_secs_Ti = pll_cloop_two_quadrant_atan(d_correlator_outs[1]) / GPS_TWO_PI; // prompt output - // Carrier discriminator filter - // NOTICE: The carrier loop filter includes the Carrier Doppler accumulator, as described in Kaplan - // Input [s/Ti] -> output [Hz] - d_carrier_doppler_hz = d_carrier_loop_filter.get_carrier_error(0.0, d_carr_phase_error_secs_Ti, CURRENT_INTEGRATION_TIME_S); - // PLL to DLL assistance [Secs/Ti] - d_pll_to_dll_assist_secs_Ti = (d_carrier_doppler_hz * CURRENT_INTEGRATION_TIME_S) / GPS_L1_FREQ_HZ; - // code Doppler frequency update - d_code_freq_chips = GPS_L1_CA_CODE_RATE_HZ + ((d_carrier_doppler_hz * GPS_L1_CA_CODE_RATE_HZ) / GPS_L1_FREQ_HZ); - - // ################## DLL ########################################################## - // DLL discriminator - d_code_error_chips_Ti = dll_nc_e_minus_l_normalized(d_correlator_outs[0], d_correlator_outs[2]); // [chips/Ti] //early and late - // Code discriminator filter - d_code_error_filt_chips_s = d_code_loop_filter.get_code_nco(d_code_error_chips_Ti); // input [chips/Ti] -> output [chips/second] - d_code_error_filt_chips_Ti = d_code_error_filt_chips_s * CURRENT_INTEGRATION_TIME_S; - code_error_filt_secs_Ti = d_code_error_filt_chips_Ti / d_code_freq_chips; // [s/Ti] - - // ################## CARRIER AND CODE NCO BUFFER ALIGNMENT ####################### - // keep alignment parameters for the next input buffer - // Compute the next buffer length based in the new period of the PRN sequence and the code phase error estimation - double T_chip_seconds = 1.0 / d_code_freq_chips; - double T_prn_seconds = T_chip_seconds * GPS_L1_CA_CODE_LENGTH_CHIPS; - double T_prn_samples = T_prn_seconds * static_cast(d_fs_in); - double K_prn_samples = round(T_prn_samples); - double K_T_prn_error_samples = K_prn_samples - T_prn_samples; - - d_rem_code_phase_samples = d_rem_code_phase_samples - K_T_prn_error_samples + code_error_filt_secs_Ti * static_cast(d_fs_in); //(code_error_filt_secs_Ti + d_pll_to_dll_assist_secs_Ti) * static_cast(d_fs_in); - d_rem_code_phase_integer_samples = round(d_rem_code_phase_samples); // round to a discrete number of samples - d_correlation_length_samples = K_prn_samples + d_rem_code_phase_integer_samples; - d_rem_code_phase_samples = d_rem_code_phase_samples - d_rem_code_phase_integer_samples; - - //################### PLL COMMANDS ################################################# - //carrier phase step (NCO phase increment per sample) [rads/sample] - d_carrier_phase_step_rad = GPS_TWO_PI * d_carrier_doppler_hz / static_cast(d_fs_in); - d_acc_carrier_phase_cycles -= d_carrier_phase_step_rad * d_correlation_length_samples / GPS_TWO_PI; - // UPDATE ACCUMULATED CARRIER PHASE - CORRECTED_INTEGRATION_TIME_S = (static_cast(d_correlation_length_samples) / static_cast(d_fs_in)); - //remnant carrier phase [rad] - d_rem_carrier_phase_rad = fmod(d_rem_carrier_phase_rad + GPS_TWO_PI * d_carrier_doppler_hz * CORRECTED_INTEGRATION_TIME_S, GPS_TWO_PI); - - //################### DLL COMMANDS ################################################# - //code phase step (Code resampler phase increment per sample) [chips/sample] - d_code_phase_step_chips = d_code_freq_chips / static_cast(d_fs_in); - //remnant code phase [chips] - d_rem_code_phase_chips = d_rem_code_phase_samples * (d_code_freq_chips / static_cast(d_fs_in)); - - // ####### CN0 ESTIMATION AND LOCK DETECTORS ####################################### - if (d_cn0_estimation_counter < FLAGS_cn0_samples) - { - // fill buffer with prompt correlator output values - d_Prompt_buffer[d_cn0_estimation_counter] = d_correlator_outs[1]; // prompt - d_cn0_estimation_counter++; - } - else - { - d_cn0_estimation_counter = 0; - // Code lock indicator - d_CN0_SNV_dB_Hz = cn0_svn_estimator(d_Prompt_buffer, FLAGS_cn0_samples, GPS_L1_CA_CODE_PERIOD); - // Carrier lock indicator - d_carrier_lock_test = carrier_lock_detector(d_Prompt_buffer, FLAGS_cn0_samples); - // Loss of lock detection - if (d_carrier_lock_test < d_carrier_lock_threshold or d_CN0_SNV_dB_Hz < FLAGS_cn0_min) - { - d_carrier_lock_fail_counter++; - } - else - { - if (d_carrier_lock_fail_counter > 0) - { - d_carrier_lock_fail_counter--; - } - } - if (d_carrier_lock_fail_counter > FLAGS_max_lock_fail) - { - std::cout << "Loss of lock in channel " << d_channel << "!" << std::endl; - LOG(INFO) << "Loss of lock in channel " << d_channel << "!"; - this->message_port_pub(pmt::mp("events"), pmt::from_long(3)); //3 -> loss of lock - d_carrier_lock_fail_counter = 0; - d_enable_tracking = false; // TODO: check if disabling tracking is consistent with the channel state machine - } - } - // ########### Output the tracking data to navigation and PVT ########## - current_synchro_data.Prompt_I = static_cast((d_correlator_outs[1]).real()); - current_synchro_data.Prompt_Q = static_cast((d_correlator_outs[1]).imag()); - current_synchro_data.Tracking_sample_counter = d_sample_counter + static_cast(d_correlation_length_samples); - current_synchro_data.Code_phase_samples = d_rem_code_phase_samples; - current_synchro_data.Carrier_phase_rads = GPS_TWO_PI * d_acc_carrier_phase_cycles; - current_synchro_data.Carrier_Doppler_hz = d_carrier_doppler_hz; - current_synchro_data.CN0_dB_hz = d_CN0_SNV_dB_Hz; - current_synchro_data.Flag_valid_symbol_output = true; - if (d_preamble_synchronized == true) - { - current_synchro_data.correlation_length_ms = d_extend_correlation_ms; - } - else - { - current_synchro_data.correlation_length_ms = 1; - } - } - else - { - current_synchro_data.Prompt_I = static_cast((d_correlator_outs[1]).real()); - current_synchro_data.Prompt_Q = static_cast((d_correlator_outs[1]).imag()); - current_synchro_data.Tracking_sample_counter = d_sample_counter + static_cast(d_correlation_length_samples); - current_synchro_data.Code_phase_samples = d_rem_code_phase_samples; - current_synchro_data.Carrier_phase_rads = GPS_TWO_PI * d_acc_carrier_phase_cycles; - current_synchro_data.Carrier_Doppler_hz = d_carrier_doppler_hz; // todo: project the carrier doppler - current_synchro_data.CN0_dB_hz = d_CN0_SNV_dB_Hz; - } - } - else - { - for (int32_t n = 0; n < d_n_correlator_taps; n++) - { - d_correlator_outs[n] = gr_complex(0, 0); - } - - current_synchro_data.System = {'G'}; - current_synchro_data.Tracking_sample_counter = d_sample_counter + static_cast(d_correlation_length_samples); - } - //assign the GNURadio block output data - current_synchro_data.fs = d_fs_in; - *out[0] = current_synchro_data; - if (d_dump) - { - // MULTIPLEXED FILE RECORDING - Record results to file - float prompt_I; - float prompt_Q; - float tmp_E, tmp_P, tmp_L; - float tmp_VE = 0.0; - float tmp_VL = 0.0; - float tmp_float; - prompt_I = d_correlator_outs[1].real(); - prompt_Q = d_correlator_outs[1].imag(); - tmp_E = std::abs(d_correlator_outs[0]); - tmp_P = std::abs(d_correlator_outs[1]); - tmp_L = std::abs(d_correlator_outs[2]); - try - { - // Dump correlators output - d_dump_file.write(reinterpret_cast(&tmp_VE), sizeof(float)); - d_dump_file.write(reinterpret_cast(&tmp_E), sizeof(float)); - d_dump_file.write(reinterpret_cast(&tmp_P), sizeof(float)); - d_dump_file.write(reinterpret_cast(&tmp_L), sizeof(float)); - d_dump_file.write(reinterpret_cast(&tmp_VL), sizeof(float)); - // PROMPT I and Q (to analyze navigation symbols) - d_dump_file.write(reinterpret_cast(&prompt_I), sizeof(float)); - d_dump_file.write(reinterpret_cast(&prompt_Q), sizeof(float)); - // PRN start sample stamp - d_dump_file.write(reinterpret_cast(&d_sample_counter), sizeof(uint64_t)); - // accumulated carrier phase - tmp_float = d_acc_carrier_phase_cycles * GPS_TWO_PI; - d_dump_file.write(reinterpret_cast(&tmp_float), sizeof(float)); - // carrier and code frequency - tmp_float = d_carrier_doppler_hz; - d_dump_file.write(reinterpret_cast(&tmp_float), sizeof(float)); - tmp_float = d_code_freq_chips; - d_dump_file.write(reinterpret_cast(&tmp_float), sizeof(float)); - // PLL commands - tmp_float = 1.0 / (d_carr_phase_error_secs_Ti * CURRENT_INTEGRATION_TIME_S); - d_dump_file.write(reinterpret_cast(&tmp_float), sizeof(float)); - tmp_float = 1.0 / (d_code_error_filt_chips_Ti * CURRENT_INTEGRATION_TIME_S); - d_dump_file.write(reinterpret_cast(&tmp_float), sizeof(float)); - // DLL commands - tmp_float = d_code_error_chips_Ti * CURRENT_INTEGRATION_TIME_S; - d_dump_file.write(reinterpret_cast(&tmp_float), sizeof(float)); - tmp_float = d_code_error_filt_chips_Ti; - d_dump_file.write(reinterpret_cast(&tmp_float), sizeof(float)); - // CN0 and carrier lock test - tmp_float = d_CN0_SNV_dB_Hz; - d_dump_file.write(reinterpret_cast(&tmp_float), sizeof(float)); - tmp_float = d_carrier_lock_test; - d_dump_file.write(reinterpret_cast(&tmp_float), sizeof(float)); - // AUX vars (for debug purposes) - tmp_float = d_code_error_chips_Ti * CURRENT_INTEGRATION_TIME_S; - d_dump_file.write(reinterpret_cast(&tmp_float), sizeof(float)); - auto tmp_double = static_cast(d_sample_counter + d_correlation_length_samples); - d_dump_file.write(reinterpret_cast(&tmp_double), sizeof(double)); - // PRN - uint32_t prn_ = d_acquisition_gnss_synchro->PRN; - d_dump_file.write(reinterpret_cast(&prn_), sizeof(uint32_t)); - } - catch (const std::ifstream::failure &e) - { - LOG(WARNING) << "Exception writing trk dump file " << e.what(); - } - } - - consume_each(d_correlation_length_samples); // this is necessary in gr::block derivates - d_sample_counter += d_correlation_length_samples; //count for the processed samples - - if (d_enable_tracking) - { - return 1; - } - - return 0; -} diff --git a/src/algorithms/tracking/gnuradio_blocks/gps_l1_ca_dll_pll_c_aid_tracking_cc.h b/src/algorithms/tracking/gnuradio_blocks/gps_l1_ca_dll_pll_c_aid_tracking_cc.h deleted file mode 100644 index dc9283932..000000000 --- a/src/algorithms/tracking/gnuradio_blocks/gps_l1_ca_dll_pll_c_aid_tracking_cc.h +++ /dev/null @@ -1,197 +0,0 @@ -/*! - * \file gps_l1_ca_dll_pll_c_aid_tracking_cc.h - * \brief Interface of a code DLL + carrier PLL tracking block - * \author Carlos Aviles, 2010. carlos.avilesr(at)googlemail.com - * Javier Arribas, 2011. jarribas(at)cttc.es - * - * Code DLL + carrier PLL according to the algorithms described in: - * K.Borre, D.M.Akos, N.Bertelsen, P.Rinder, and S.H.Jensen, - * A Software-Defined GPS and Galileo Receiver. A Single-Frequency Approach, - * Birkhauser, 2007 - * - * ------------------------------------------------------------------------- - * - * Copyright (C) 2010-2018 (see AUTHORS file for a list of contributors) - * - * GNSS-SDR is a software defined Global Navigation - * Satellite Systems receiver - * - * This file is part of GNSS-SDR. - * - * GNSS-SDR is free software: you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * GNSS-SDR is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - * GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with GNSS-SDR. If not, see . - * - * ------------------------------------------------------------------------- - */ - -#ifndef GNSS_SDR_GPS_L1_CA_DLL_PLL_C_AID_TRACKING_CC_H -#define GNSS_SDR_GPS_L1_CA_DLL_PLL_C_AID_TRACKING_CC_H - -#include "gnss_synchro.h" -#include "tracking_2nd_DLL_filter.h" -#include "tracking_FLL_PLL_filter.h" -//#include "tracking_loop_filter.h" -#include "cpu_multicorrelator.h" -#include -#include -#include -#include -#include -#include - -class gps_l1_ca_dll_pll_c_aid_tracking_cc; - -using gps_l1_ca_dll_pll_c_aid_tracking_cc_sptr = boost::shared_ptr; - -gps_l1_ca_dll_pll_c_aid_tracking_cc_sptr -gps_l1_ca_dll_pll_c_aid_make_tracking_cc( - int64_t fs_in, uint32_t vector_length, - bool dump, - std::string dump_filename, - float pll_bw_hz, - float dll_bw_hz, - float pll_bw_narrow_hz, - float dll_bw_narrow_hz, - int32_t extend_correlation_ms, - float early_late_space_chips); - - -/*! - * \brief This class implements a DLL + PLL tracking loop block - */ -class gps_l1_ca_dll_pll_c_aid_tracking_cc : public gr::block -{ -public: - ~gps_l1_ca_dll_pll_c_aid_tracking_cc(); - - void set_channel(uint32_t channel); - void set_gnss_synchro(Gnss_Synchro* p_gnss_synchro); - void start_tracking(); - - int general_work(int noutput_items, gr_vector_int& ninput_items, - gr_vector_const_void_star& input_items, gr_vector_void_star& output_items); - - void forecast(int noutput_items, gr_vector_int& ninput_items_required); - -private: - friend gps_l1_ca_dll_pll_c_aid_tracking_cc_sptr - gps_l1_ca_dll_pll_c_aid_make_tracking_cc( - int64_t fs_in, uint32_t vector_length, - bool dump, - std::string dump_filename, - float pll_bw_hz, - float dll_bw_hz, - float pll_bw_narrow_hz, - float dll_bw_narrow_hz, - int32_t extend_correlation_ms, - float early_late_space_chips); - - gps_l1_ca_dll_pll_c_aid_tracking_cc( - int64_t fs_in, uint32_t vector_length, - bool dump, - std::string dump_filename, - float pll_bw_hz, - float dll_bw_hz, - float pll_bw_narrow_hz, - float dll_bw_narrow_hz, - int32_t extend_correlation_ms, - float early_late_space_chips); - - // tracking configuration vars - uint32_t d_vector_length; - bool d_dump; - - Gnss_Synchro* d_acquisition_gnss_synchro; - uint32_t d_channel; - int64_t d_fs_in; - - double d_early_late_spc_chips; - int32_t d_n_correlator_taps; - - gr_complex* d_ca_code; - float* d_local_code_shift_chips; - gr_complex* d_correlator_outs; - Cpu_Multicorrelator multicorrelator_cpu; - - // remaining code phase and carrier phase between tracking loops - double d_rem_code_phase_samples; - double d_rem_code_phase_chips; - double d_rem_carrier_phase_rad; - int32_t d_rem_code_phase_integer_samples; - - // PLL and DLL filter library - //Tracking_2nd_DLL_filter d_code_loop_filter; - Tracking_2nd_DLL_filter d_code_loop_filter; - Tracking_FLL_PLL_filter d_carrier_loop_filter; - - // acquisition - double d_acq_code_phase_samples; - double d_acq_carrier_doppler_hz; - - // tracking vars - float d_dll_bw_hz; - float d_pll_bw_hz; - float d_dll_bw_narrow_hz; - float d_pll_bw_narrow_hz; - double d_code_freq_chips; - double d_code_phase_step_chips; - double d_carrier_doppler_hz; - double d_carrier_phase_step_rad; - double d_acc_carrier_phase_cycles; - double d_code_phase_samples; - double d_pll_to_dll_assist_secs_Ti; - double d_code_error_chips_Ti; - double d_code_error_filt_chips_s; - double d_code_error_filt_chips_Ti; - double d_carr_phase_error_secs_Ti; - - // symbol history to detect bit transition - std::deque d_E_history; - std::deque d_P_history; - std::deque d_L_history; - double d_preamble_timestamp_s; - int32_t d_extend_correlation_ms; - bool d_enable_extended_integration; - bool d_preamble_synchronized; - void msg_handler_preamble_index(pmt::pmt_t msg); - - //Integration period in samples - int32_t d_correlation_length_samples; - - //processing samples counters - uint64_t d_sample_counter; - uint64_t d_acq_sample_stamp; - - // CN0 estimation and lock detector - int32_t d_cn0_estimation_counter; - gr_complex* d_Prompt_buffer; - double d_carrier_lock_test; - double d_CN0_SNV_dB_Hz; - double d_carrier_lock_threshold; - int32_t d_carrier_lock_fail_counter; - - // control vars - bool d_enable_tracking; - bool d_pull_in; - - // file dump - std::string d_dump_filename; - std::ofstream d_dump_file; - - std::map systemName; - std::string sys; - - int32_t save_matfile(); -}; - -#endif //GNSS_SDR_GPS_L1_CA_DLL_PLL_C_AID_TRACKING_CC_H diff --git a/src/algorithms/tracking/gnuradio_blocks/gps_l1_ca_dll_pll_c_aid_tracking_sc.cc b/src/algorithms/tracking/gnuradio_blocks/gps_l1_ca_dll_pll_c_aid_tracking_sc.cc deleted file mode 100644 index 80bdb24a0..000000000 --- a/src/algorithms/tracking/gnuradio_blocks/gps_l1_ca_dll_pll_c_aid_tracking_sc.cc +++ /dev/null @@ -1,920 +0,0 @@ -/*! - * \file gps_l1_ca_dll_pll_c_aid_tracking_sc.cc - * \brief Implementation of a code DLL + carrier PLL tracking block - * \author Javier Arribas, 2015. jarribas(at)cttc.es - * - * ------------------------------------------------------------------------- - * - * Copyright (C) 2010-2018 (see AUTHORS file for a list of contributors) - * - * GNSS-SDR is a software defined Global Navigation - * Satellite Systems receiver - * - * This file is part of GNSS-SDR. - * - * GNSS-SDR is free software: you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * GNSS-SDR is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - * GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with GNSS-SDR. If not, see . - * - * ------------------------------------------------------------------------- - */ - -#include "gps_l1_ca_dll_pll_c_aid_tracking_sc.h" -#include "GPS_L1_CA.h" -#include "gnss_sdr_flags.h" -#include "gps_sdr_signal_processing.h" -#include "lock_detectors.h" -#include "tracking_discriminators.h" -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - - -gps_l1_ca_dll_pll_c_aid_tracking_sc_sptr -gps_l1_ca_dll_pll_c_aid_make_tracking_sc( - int64_t fs_in, - uint32_t vector_length, - bool dump, - std::string dump_filename, - float pll_bw_hz, - float dll_bw_hz, - float pll_bw_narrow_hz, - float dll_bw_narrow_hz, - int32_t extend_correlation_ms, - float early_late_space_chips) -{ - return gps_l1_ca_dll_pll_c_aid_tracking_sc_sptr(new gps_l1_ca_dll_pll_c_aid_tracking_sc( - fs_in, vector_length, dump, std::move(dump_filename), pll_bw_hz, dll_bw_hz, pll_bw_narrow_hz, dll_bw_narrow_hz, extend_correlation_ms, early_late_space_chips)); -} - - -void gps_l1_ca_dll_pll_c_aid_tracking_sc::forecast(int noutput_items, - gr_vector_int &ninput_items_required) -{ - if (noutput_items != 0) - { - ninput_items_required[0] = static_cast(d_vector_length) * 2; //set the required available samples in each call - } -} - - -void gps_l1_ca_dll_pll_c_aid_tracking_sc::msg_handler_preamble_index(pmt::pmt_t msg) -{ - //pmt::print(msg); - DLOG(INFO) << "Extended correlation enabled for Tracking CH " << d_channel << ": Satellite " << Gnss_Satellite(systemName[sys], d_acquisition_gnss_synchro->PRN); - if (d_enable_extended_integration == false) //avoid re-setting preamble indicator - { - d_preamble_timestamp_s = pmt::to_double(std::move(msg)); - d_enable_extended_integration = true; - d_preamble_synchronized = false; - } -} - -gps_l1_ca_dll_pll_c_aid_tracking_sc::gps_l1_ca_dll_pll_c_aid_tracking_sc( - int64_t fs_in, - uint32_t vector_length, - bool dump, - std::string dump_filename, - float pll_bw_hz, - float dll_bw_hz, - float pll_bw_narrow_hz, - float dll_bw_narrow_hz, - int32_t extend_correlation_ms, - float early_late_space_chips) : gr::block("gps_l1_ca_dll_pll_c_aid_tracking_sc", gr::io_signature::make(1, 1, sizeof(lv_16sc_t)), - gr::io_signature::make(1, 1, sizeof(Gnss_Synchro))) -{ - // Telemetry bit synchronization message port input - this->message_port_register_in(pmt::mp("preamble_timestamp_s")); - this->set_msg_handler(pmt::mp("preamble_timestamp_s"), - boost::bind(&gps_l1_ca_dll_pll_c_aid_tracking_sc::msg_handler_preamble_index, this, _1)); - this->message_port_register_out(pmt::mp("events")); - this->message_port_register_in(pmt::mp("telemetry_to_trk")); - // initialize internal vars - d_dump = dump; - d_fs_in = fs_in; - d_vector_length = vector_length; - d_dump_filename = std::move(dump_filename); - d_correlation_length_samples = static_cast(d_vector_length); - - // Initialize tracking ========================================== - d_pll_bw_hz = pll_bw_hz; - d_dll_bw_hz = dll_bw_hz; - d_pll_bw_narrow_hz = pll_bw_narrow_hz; - d_dll_bw_narrow_hz = dll_bw_narrow_hz; - d_code_loop_filter.set_DLL_BW(d_dll_bw_hz); - d_carrier_loop_filter.set_params(10.0, d_pll_bw_hz, 2); - d_extend_correlation_ms = extend_correlation_ms; - - // --- DLL variables -------------------------------------------------------- - d_early_late_spc_chips = early_late_space_chips; // Define early-late offset (in chips) - - // Initialization of local code replica - // Get space for a vector with the C/A code replica sampled 1x/chip - d_ca_code = static_cast(volk_gnsssdr_malloc(static_cast(GPS_L1_CA_CODE_LENGTH_CHIPS) * sizeof(gr_complex), volk_gnsssdr_get_alignment())); - d_ca_code_16sc = static_cast(volk_gnsssdr_malloc(static_cast(GPS_L1_CA_CODE_LENGTH_CHIPS) * sizeof(lv_16sc_t), volk_gnsssdr_get_alignment())); - - // correlator outputs (scalar) - d_n_correlator_taps = 3; // Early, Prompt, and Late - - d_correlator_outs_16sc = static_cast(volk_gnsssdr_malloc(d_n_correlator_taps * sizeof(lv_16sc_t), volk_gnsssdr_get_alignment())); - for (int32_t n = 0; n < d_n_correlator_taps; n++) - { - d_correlator_outs_16sc[n] = lv_cmake(0, 0); - } - - d_local_code_shift_chips = static_cast(volk_gnsssdr_malloc(d_n_correlator_taps * sizeof(float), volk_gnsssdr_get_alignment())); - // Set TAPs delay values [chips] - d_local_code_shift_chips[0] = -d_early_late_spc_chips; - d_local_code_shift_chips[1] = 0.0; - d_local_code_shift_chips[2] = d_early_late_spc_chips; - - multicorrelator_cpu_16sc.init(2 * d_correlation_length_samples, d_n_correlator_taps); - - //--- Perform initializations ------------------------------ - // define initial code frequency basis of NCO - d_code_freq_chips = GPS_L1_CA_CODE_RATE_HZ; - // define residual code phase (in chips) - d_rem_code_phase_samples = 0.0; - // define residual carrier phase - d_rem_carrier_phase_rad = 0.0; - - // sample synchronization - d_sample_counter = 0ULL; //(from trk to tlm) - d_acq_sample_stamp = 0; - d_enable_tracking = false; - d_pull_in = false; - - // CN0 estimation and lock detector buffers - d_cn0_estimation_counter = 0; - d_Prompt_buffer = new gr_complex[FLAGS_cn0_samples]; - d_carrier_lock_test = 1; - d_CN0_SNV_dB_Hz = 0; - d_carrier_lock_fail_counter = 0; - d_carrier_lock_threshold = FLAGS_carrier_lock_th; - - systemName["G"] = std::string("GPS"); - systemName["S"] = std::string("SBAS"); - - set_relative_rate(1.0 / static_cast(d_vector_length)); - - d_acquisition_gnss_synchro = nullptr; - d_channel = 0; - d_acq_code_phase_samples = 0.0; - d_acq_carrier_doppler_hz = 0.0; - d_carrier_doppler_hz = 0.0; - d_acc_carrier_phase_cycles = 0.0; - d_code_phase_samples = 0.0; - d_enable_extended_integration = false; - d_preamble_synchronized = false; - d_rem_code_phase_integer_samples = 0; - d_code_error_chips_Ti = 0.0; - d_pll_to_dll_assist_secs_Ti = 0.0; - d_rem_code_phase_chips = 0.0; - d_code_phase_step_chips = 0.0; - d_carrier_phase_step_rad = 0.0; - d_code_error_filt_chips_s = 0.0; - d_code_error_filt_chips_Ti = 0.0; - d_preamble_timestamp_s = 0.0; - d_carr_phase_error_secs_Ti = 0.0; - //set_min_output_buffer((int64_t)300); -} - - -void gps_l1_ca_dll_pll_c_aid_tracking_sc::start_tracking() -{ - /* - * correct the code phase according to the delay between acq and trk - */ - d_acq_code_phase_samples = d_acquisition_gnss_synchro->Acq_delay_samples; - d_acq_carrier_doppler_hz = d_acquisition_gnss_synchro->Acq_doppler_hz; - d_acq_sample_stamp = d_acquisition_gnss_synchro->Acq_samplestamp_samples; - - int64_t acq_trk_diff_samples; - double acq_trk_diff_seconds; - acq_trk_diff_samples = static_cast(d_sample_counter) - static_cast(d_acq_sample_stamp); //-d_vector_length; - DLOG(INFO) << "Number of samples between Acquisition and Tracking =" << acq_trk_diff_samples; - acq_trk_diff_seconds = static_cast(acq_trk_diff_samples) / static_cast(d_fs_in); - // Doppler effect - // Fd=(C/(C+Vr))*F - double radial_velocity = (GPS_L1_FREQ_HZ + d_acq_carrier_doppler_hz) / GPS_L1_FREQ_HZ; - // new chip and prn sequence periods based on acq Doppler - double T_chip_mod_seconds; - double T_prn_mod_seconds; - double T_prn_mod_samples; - d_code_freq_chips = radial_velocity * GPS_L1_CA_CODE_RATE_HZ; - d_code_phase_step_chips = static_cast(d_code_freq_chips) / static_cast(d_fs_in); - T_chip_mod_seconds = 1.0 / d_code_freq_chips; - T_prn_mod_seconds = T_chip_mod_seconds * GPS_L1_CA_CODE_LENGTH_CHIPS; - T_prn_mod_samples = T_prn_mod_seconds * static_cast(d_fs_in); - - d_correlation_length_samples = round(T_prn_mod_samples); - - double T_prn_true_seconds = GPS_L1_CA_CODE_LENGTH_CHIPS / GPS_L1_CA_CODE_RATE_HZ; - double T_prn_true_samples = T_prn_true_seconds * static_cast(d_fs_in); - double T_prn_diff_seconds = T_prn_true_seconds - T_prn_mod_seconds; - double N_prn_diff = acq_trk_diff_seconds / T_prn_true_seconds; - double corrected_acq_phase_samples, delay_correction_samples; - corrected_acq_phase_samples = fmod((d_acq_code_phase_samples + T_prn_diff_seconds * N_prn_diff * static_cast(d_fs_in)), T_prn_true_samples); - if (corrected_acq_phase_samples < 0) - { - corrected_acq_phase_samples = T_prn_mod_samples + corrected_acq_phase_samples; - } - delay_correction_samples = d_acq_code_phase_samples - corrected_acq_phase_samples; - - d_acq_code_phase_samples = corrected_acq_phase_samples; - - d_carrier_doppler_hz = d_acq_carrier_doppler_hz; - - d_carrier_phase_step_rad = GPS_TWO_PI * d_carrier_doppler_hz / static_cast(d_fs_in); - - // DLL/PLL filter initialization - d_carrier_loop_filter.initialize(d_acq_carrier_doppler_hz); // The carrier loop filter implements the Doppler accumulator - d_code_loop_filter.initialize(); // initialize the code filter - - // generate local reference ALWAYS starting at chip 1 (1 sample per chip) - gps_l1_ca_code_gen_complex(d_ca_code, d_acquisition_gnss_synchro->PRN, 0); - volk_gnsssdr_32fc_convert_16ic(d_ca_code_16sc, d_ca_code, static_cast(GPS_L1_CA_CODE_LENGTH_CHIPS)); - - multicorrelator_cpu_16sc.set_local_code_and_taps(static_cast(GPS_L1_CA_CODE_LENGTH_CHIPS), d_ca_code_16sc, d_local_code_shift_chips); - for (int32_t n = 0; n < d_n_correlator_taps; n++) - { - d_correlator_outs_16sc[n] = lv_16sc_t(0, 0); - } - - d_carrier_lock_fail_counter = 0; - d_rem_code_phase_samples = 0.0; - d_rem_carrier_phase_rad = 0.0; - d_rem_code_phase_chips = 0.0; - d_acc_carrier_phase_cycles = 0.0; - d_pll_to_dll_assist_secs_Ti = 0.0; - d_code_phase_samples = d_acq_code_phase_samples; - - std::string sys_ = &d_acquisition_gnss_synchro->System; - sys = sys_.substr(0, 1); - - // DEBUG OUTPUT - std::cout << "Tracking of GPS L1 C/A signal started on channel " << d_channel << " for satellite " << Gnss_Satellite(systemName[sys], d_acquisition_gnss_synchro->PRN) << std::endl; - LOG(INFO) << "Tracking of GPS L1 C/A signal for satellite " << Gnss_Satellite(systemName[sys], d_acquisition_gnss_synchro->PRN) << " on channel " << d_channel; - - // enable tracking - d_pull_in = true; - d_enable_tracking = true; - d_enable_extended_integration = false; - d_preamble_synchronized = false; - - LOG(INFO) << "PULL-IN Doppler [Hz]=" << d_carrier_doppler_hz - << " Code Phase correction [samples]=" << delay_correction_samples - << " PULL-IN Code Phase [samples]=" << d_acq_code_phase_samples; -} - - -gps_l1_ca_dll_pll_c_aid_tracking_sc::~gps_l1_ca_dll_pll_c_aid_tracking_sc() -{ - if (d_dump_file.is_open()) - { - try - { - d_dump_file.close(); - } - catch (const std::exception &ex) - { - LOG(WARNING) << "Exception in destructor " << ex.what(); - } - } - - if (d_dump) - { - if (d_channel == 0) - { - std::cout << "Writing .mat files ..."; - } - try - { - gps_l1_ca_dll_pll_c_aid_tracking_sc::save_matfile(); - } - catch (const std::exception &ex) - { - LOG(WARNING) << "Error saving the .mat file: " << ex.what(); - } - - if (d_channel == 0) - { - std::cout << " done." << std::endl; - } - } - - try - { - volk_gnsssdr_free(d_local_code_shift_chips); - volk_gnsssdr_free(d_ca_code); - volk_gnsssdr_free(d_ca_code_16sc); - volk_gnsssdr_free(d_correlator_outs_16sc); - delete[] d_Prompt_buffer; - multicorrelator_cpu_16sc.free(); - } - catch (const std::exception &ex) - { - LOG(WARNING) << "Exception in destructor " << ex.what(); - } -} - - -int32_t gps_l1_ca_dll_pll_c_aid_tracking_sc::save_matfile() -{ - // READ DUMP FILE - std::ifstream::pos_type size; - int32_t number_of_double_vars = 11; - int32_t number_of_float_vars = 5; - int32_t epoch_size_bytes = sizeof(uint64_t) + sizeof(double) * number_of_double_vars + - sizeof(float) * number_of_float_vars + sizeof(uint32_t); - std::ifstream dump_file; - dump_file.exceptions(std::ifstream::failbit | std::ifstream::badbit); - try - { - dump_file.open(d_dump_filename.c_str(), std::ios::binary | std::ios::ate); - } - catch (const std::ifstream::failure &e) - { - std::cerr << "Problem opening dump file:" << e.what() << std::endl; - return 1; - } - // count number of epochs and rewind - int64_t num_epoch = 0; - if (dump_file.is_open()) - { - size = dump_file.tellg(); - num_epoch = static_cast(size) / static_cast(epoch_size_bytes); - dump_file.seekg(0, std::ios::beg); - } - else - { - return 1; - } - auto *abs_E = new float[num_epoch]; - auto *abs_P = new float[num_epoch]; - auto *abs_L = new float[num_epoch]; - auto *Prompt_I = new float[num_epoch]; - auto *Prompt_Q = new float[num_epoch]; - auto *PRN_start_sample_count = new uint64_t[num_epoch]; - auto *acc_carrier_phase_rad = new double[num_epoch]; - auto *carrier_doppler_hz = new double[num_epoch]; - auto *code_freq_chips = new double[num_epoch]; - auto *carr_error_hz = new double[num_epoch]; - auto *carr_error_filt_hz = new double[num_epoch]; - auto *code_error_chips = new double[num_epoch]; - auto *code_error_filt_chips = new double[num_epoch]; - auto *CN0_SNV_dB_Hz = new double[num_epoch]; - auto *carrier_lock_test = new double[num_epoch]; - auto *aux1 = new double[num_epoch]; - auto *aux2 = new double[num_epoch]; - auto *PRN = new uint32_t[num_epoch]; - - try - { - if (dump_file.is_open()) - { - for (int64_t i = 0; i < num_epoch; i++) - { - dump_file.read(reinterpret_cast(&abs_E[i]), sizeof(float)); - dump_file.read(reinterpret_cast(&abs_P[i]), sizeof(float)); - dump_file.read(reinterpret_cast(&abs_L[i]), sizeof(float)); - dump_file.read(reinterpret_cast(&Prompt_I[i]), sizeof(float)); - dump_file.read(reinterpret_cast(&Prompt_Q[i]), sizeof(float)); - dump_file.read(reinterpret_cast(&PRN_start_sample_count[i]), sizeof(uint64_t)); - dump_file.read(reinterpret_cast(&acc_carrier_phase_rad[i]), sizeof(double)); - dump_file.read(reinterpret_cast(&carrier_doppler_hz[i]), sizeof(double)); - dump_file.read(reinterpret_cast(&code_freq_chips[i]), sizeof(double)); - dump_file.read(reinterpret_cast(&carr_error_hz[i]), sizeof(double)); - dump_file.read(reinterpret_cast(&carr_error_filt_hz[i]), sizeof(double)); - dump_file.read(reinterpret_cast(&code_error_chips[i]), sizeof(double)); - dump_file.read(reinterpret_cast(&code_error_filt_chips[i]), sizeof(double)); - dump_file.read(reinterpret_cast(&CN0_SNV_dB_Hz[i]), sizeof(double)); - dump_file.read(reinterpret_cast(&carrier_lock_test[i]), sizeof(double)); - dump_file.read(reinterpret_cast(&aux1[i]), sizeof(double)); - dump_file.read(reinterpret_cast(&aux2[i]), sizeof(double)); - dump_file.read(reinterpret_cast(&PRN[i]), sizeof(uint32_t)); - } - } - dump_file.close(); - } - catch (const std::ifstream::failure &e) - { - std::cerr << "Problem reading dump file:" << e.what() << std::endl; - delete[] abs_E; - delete[] abs_P; - delete[] abs_L; - delete[] Prompt_I; - delete[] Prompt_Q; - delete[] PRN_start_sample_count; - delete[] acc_carrier_phase_rad; - delete[] carrier_doppler_hz; - delete[] code_freq_chips; - delete[] carr_error_hz; - delete[] carr_error_filt_hz; - delete[] code_error_chips; - delete[] code_error_filt_chips; - delete[] CN0_SNV_dB_Hz; - delete[] carrier_lock_test; - delete[] aux1; - delete[] aux2; - delete[] PRN; - return 1; - } - - // WRITE MAT FILE - mat_t *matfp; - matvar_t *matvar; - std::string filename = d_dump_filename; - filename.erase(filename.length() - 4, 4); - filename.append(".mat"); - matfp = Mat_CreateVer(filename.c_str(), nullptr, MAT_FT_MAT73); - if (reinterpret_cast(matfp) != nullptr) - { - size_t dims[2] = {1, static_cast(num_epoch)}; - matvar = Mat_VarCreate("abs_E", MAT_C_SINGLE, MAT_T_SINGLE, 2, dims, abs_E, 0); - Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE - Mat_VarFree(matvar); - - matvar = Mat_VarCreate("abs_P", MAT_C_SINGLE, MAT_T_SINGLE, 2, dims, abs_P, 0); - Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE - Mat_VarFree(matvar); - - matvar = Mat_VarCreate("abs_L", MAT_C_SINGLE, MAT_T_SINGLE, 2, dims, abs_L, 0); - Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE - Mat_VarFree(matvar); - - matvar = Mat_VarCreate("Prompt_I", MAT_C_SINGLE, MAT_T_SINGLE, 2, dims, Prompt_I, 0); - Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE - Mat_VarFree(matvar); - - matvar = Mat_VarCreate("Prompt_Q", MAT_C_SINGLE, MAT_T_SINGLE, 2, dims, Prompt_Q, 0); - Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE - Mat_VarFree(matvar); - - matvar = Mat_VarCreate("PRN_start_sample_count", MAT_C_UINT64, MAT_T_UINT64, 2, dims, PRN_start_sample_count, 0); - Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE - Mat_VarFree(matvar); - - matvar = Mat_VarCreate("acc_carrier_phase_rad", MAT_C_DOUBLE, MAT_T_DOUBLE, 2, dims, acc_carrier_phase_rad, 0); - Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE - Mat_VarFree(matvar); - - matvar = Mat_VarCreate("carrier_doppler_hz", MAT_C_DOUBLE, MAT_T_DOUBLE, 2, dims, carrier_doppler_hz, 0); - Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE - Mat_VarFree(matvar); - - matvar = Mat_VarCreate("code_freq_chips", MAT_C_DOUBLE, MAT_T_DOUBLE, 2, dims, code_freq_chips, 0); - Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE - Mat_VarFree(matvar); - - matvar = Mat_VarCreate("carr_error_hz", MAT_C_DOUBLE, MAT_T_DOUBLE, 2, dims, carr_error_hz, 0); - Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE - Mat_VarFree(matvar); - - matvar = Mat_VarCreate("carr_error_filt_hz", MAT_C_DOUBLE, MAT_T_DOUBLE, 2, dims, carr_error_filt_hz, 0); - Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE - Mat_VarFree(matvar); - - matvar = Mat_VarCreate("code_error_chips", MAT_C_DOUBLE, MAT_T_DOUBLE, 2, dims, code_error_chips, 0); - Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE - Mat_VarFree(matvar); - - matvar = Mat_VarCreate("code_error_filt_chips", MAT_C_DOUBLE, MAT_T_DOUBLE, 2, dims, code_error_filt_chips, 0); - Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE - Mat_VarFree(matvar); - - matvar = Mat_VarCreate("CN0_SNV_dB_Hz", MAT_C_DOUBLE, MAT_T_DOUBLE, 2, dims, CN0_SNV_dB_Hz, 0); - Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE - Mat_VarFree(matvar); - - matvar = Mat_VarCreate("carrier_lock_test", MAT_C_DOUBLE, MAT_T_DOUBLE, 2, dims, carrier_lock_test, 0); - Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE - Mat_VarFree(matvar); - - matvar = Mat_VarCreate("aux1", MAT_C_DOUBLE, MAT_T_DOUBLE, 2, dims, aux1, 0); - Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE - Mat_VarFree(matvar); - - matvar = Mat_VarCreate("aux2", MAT_C_DOUBLE, MAT_T_DOUBLE, 2, dims, aux2, 0); - Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE - Mat_VarFree(matvar); - - matvar = Mat_VarCreate("PRN", MAT_C_UINT32, MAT_T_UINT32, 2, dims, PRN, 0); - Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE - Mat_VarFree(matvar); - } - Mat_Close(matfp); - delete[] abs_E; - delete[] abs_P; - delete[] abs_L; - delete[] Prompt_I; - delete[] Prompt_Q; - delete[] PRN_start_sample_count; - delete[] acc_carrier_phase_rad; - delete[] carrier_doppler_hz; - delete[] code_freq_chips; - delete[] carr_error_hz; - delete[] carr_error_filt_hz; - delete[] code_error_chips; - delete[] code_error_filt_chips; - delete[] CN0_SNV_dB_Hz; - delete[] carrier_lock_test; - delete[] aux1; - delete[] aux2; - delete[] PRN; - return 0; -} - - -void gps_l1_ca_dll_pll_c_aid_tracking_sc::set_channel(uint32_t channel) -{ - d_channel = channel; - LOG(INFO) << "Tracking Channel set to " << d_channel; - // ############# ENABLE DATA FILE LOG ################# - if (d_dump == true) - { - if (d_dump_file.is_open() == false) - { - try - { - d_dump_filename.append(std::to_string(d_channel)); - d_dump_filename.append(".dat"); - d_dump_file.exceptions(std::ifstream::failbit | std::ifstream::badbit); - d_dump_file.open(d_dump_filename.c_str(), std::ios::out | std::ios::binary); - LOG(INFO) << "Tracking dump enabled on channel " << d_channel << " Log file: " << d_dump_filename.c_str(); - } - catch (const std::ifstream::failure &e) - { - LOG(WARNING) << "channel " << d_channel << " Exception opening trk dump file " << e.what(); - } - } - } -} - - -void gps_l1_ca_dll_pll_c_aid_tracking_sc::set_gnss_synchro(Gnss_Synchro *p_gnss_synchro) -{ - d_acquisition_gnss_synchro = p_gnss_synchro; -} - - -int gps_l1_ca_dll_pll_c_aid_tracking_sc::general_work(int noutput_items __attribute__((unused)), gr_vector_int &ninput_items __attribute__((unused)), - gr_vector_const_void_star &input_items, gr_vector_void_star &output_items) -{ - // Block input data and block output stream pointers - const auto *in = reinterpret_cast(input_items[0]); //PRN start block alignment - auto **out = reinterpret_cast(&output_items[0]); - - // GNSS_SYNCHRO OBJECT to interchange data between tracking->telemetry_decoder - Gnss_Synchro current_synchro_data = Gnss_Synchro(); - - // process vars - double code_error_filt_secs_Ti = 0.0; - double CURRENT_INTEGRATION_TIME_S = 0.0; - double CORRECTED_INTEGRATION_TIME_S = 0.0; - - if (d_enable_tracking == true) - { - // Fill the acquisition data - current_synchro_data = *d_acquisition_gnss_synchro; - // Receiver signal alignment - if (d_pull_in == true) - { - int32_t samples_offset; - double acq_trk_shif_correction_samples; - int32_t acq_to_trk_delay_samples; - acq_to_trk_delay_samples = d_sample_counter - d_acq_sample_stamp; - acq_trk_shif_correction_samples = d_correlation_length_samples - fmod(static_cast(acq_to_trk_delay_samples), static_cast(d_correlation_length_samples)); - samples_offset = round(d_acq_code_phase_samples + acq_trk_shif_correction_samples); - current_synchro_data.Tracking_sample_counter = d_sample_counter + static_cast(samples_offset); - d_sample_counter += static_cast(samples_offset); // count for the processed samples - d_pull_in = false; - d_acc_carrier_phase_cycles -= d_carrier_phase_step_rad * samples_offset / GPS_TWO_PI; - current_synchro_data.Carrier_phase_rads = d_acc_carrier_phase_cycles * GPS_TWO_PI; - current_synchro_data.Carrier_Doppler_hz = d_carrier_doppler_hz; - current_synchro_data.fs = d_fs_in; - *out[0] = current_synchro_data; - consume_each(samples_offset); // shift input to perform alignment with local replica - return 1; - } - - // ################# CARRIER WIPEOFF AND CORRELATORS ############################## - // perform carrier wipe-off and compute Early, Prompt and Late correlation - multicorrelator_cpu_16sc.set_input_output_vectors(d_correlator_outs_16sc, in); - multicorrelator_cpu_16sc.Carrier_wipeoff_multicorrelator_resampler(d_rem_carrier_phase_rad, - d_carrier_phase_step_rad, - d_rem_code_phase_chips, - d_code_phase_step_chips, - d_correlation_length_samples); - - // ####### coherent integration extension - // keep the last symbols - d_E_history.push_back(d_correlator_outs_16sc[0]); // save early output - d_P_history.push_back(d_correlator_outs_16sc[1]); // save prompt output - d_L_history.push_back(d_correlator_outs_16sc[2]); // save late output - - if (static_cast(d_P_history.size()) > d_extend_correlation_ms) - { - d_E_history.pop_front(); - d_P_history.pop_front(); - d_L_history.pop_front(); - } - - bool enable_dll_pll; - if (d_enable_extended_integration == true) - { - int64_t symbol_diff = round(1000.0 * ((static_cast(d_sample_counter) + d_rem_code_phase_samples) / static_cast(d_fs_in) - d_preamble_timestamp_s)); - if (symbol_diff > 0 and symbol_diff % d_extend_correlation_ms == 0) - { - // compute coherent integration and enable tracking loop - // perform coherent integration using correlator output history - // std::cout<<"##### RESET COHERENT INTEGRATION ####"<PRN) - << " pll_bw = " << d_pll_bw_hz << " [Hz], pll_narrow_bw = " << d_pll_bw_narrow_hz << " [Hz]" << std::endl - << " dll_bw = " << d_dll_bw_hz << " [Hz], dll_narrow_bw = " << d_dll_bw_narrow_hz << " [Hz]" << std::endl; - } - // UPDATE INTEGRATION TIME - CURRENT_INTEGRATION_TIME_S = static_cast(d_extend_correlation_ms) * GPS_L1_CA_CODE_PERIOD; - enable_dll_pll = true; - } - else - { - if (d_preamble_synchronized == true) - { - // continue extended coherent correlation - // Compute the next buffer length based on the period of the PRN sequence and the code phase error estimation - double T_chip_seconds = 1.0 / d_code_freq_chips; - double T_prn_seconds = T_chip_seconds * GPS_L1_CA_CODE_LENGTH_CHIPS; - double T_prn_samples = T_prn_seconds * static_cast(d_fs_in); - int32_t K_prn_samples = round(T_prn_samples); - double K_T_prn_error_samples = K_prn_samples - T_prn_samples; - - d_rem_code_phase_samples = d_rem_code_phase_samples - K_T_prn_error_samples; - d_rem_code_phase_integer_samples = round(d_rem_code_phase_samples); // round to a discrete number of samples - d_correlation_length_samples = K_prn_samples + d_rem_code_phase_integer_samples; - d_rem_code_phase_samples = d_rem_code_phase_samples - d_rem_code_phase_integer_samples; - // code phase step (Code resampler phase increment per sample) [chips/sample] - d_code_phase_step_chips = d_code_freq_chips / static_cast(d_fs_in); - // remnant code phase [chips] - d_rem_code_phase_chips = d_rem_code_phase_samples * (d_code_freq_chips / static_cast(d_fs_in)); - d_rem_carrier_phase_rad = fmod(d_rem_carrier_phase_rad + d_carrier_phase_step_rad * static_cast(d_correlation_length_samples), GPS_TWO_PI); - - // UPDATE ACCUMULATED CARRIER PHASE - CORRECTED_INTEGRATION_TIME_S = (static_cast(d_correlation_length_samples) / static_cast(d_fs_in)); - d_acc_carrier_phase_cycles -= d_carrier_phase_step_rad * d_correlation_length_samples / GPS_TWO_PI; - - // disable tracking loop and inform telemetry decoder - enable_dll_pll = false; - } - else - { - // perform basic (1ms) correlation - // UPDATE INTEGRATION TIME - CURRENT_INTEGRATION_TIME_S = static_cast(d_correlation_length_samples) / static_cast(d_fs_in); - enable_dll_pll = true; - } - } - } - else - { - // UPDATE INTEGRATION TIME - CURRENT_INTEGRATION_TIME_S = static_cast(d_correlation_length_samples) / static_cast(d_fs_in); - enable_dll_pll = true; - } - - if (enable_dll_pll == true) - { - // ################## PLL ########################################################## - // Update PLL discriminator [rads/Ti -> Secs/Ti] - d_carr_phase_error_secs_Ti = pll_cloop_two_quadrant_atan(std::complex(d_correlator_outs_16sc[1].real(), d_correlator_outs_16sc[1].imag())) / GPS_TWO_PI; //prompt output - - // Carrier discriminator filter - // NOTICE: The carrier loop filter includes the Carrier Doppler accumulator, as described in Kaplan - // Input [s/Ti] -> output [Hz] - d_carrier_doppler_hz = d_carrier_loop_filter.get_carrier_error(0.0, d_carr_phase_error_secs_Ti, CURRENT_INTEGRATION_TIME_S); - // PLL to DLL assistance [Secs/Ti] - d_pll_to_dll_assist_secs_Ti = (d_carrier_doppler_hz * CURRENT_INTEGRATION_TIME_S) / GPS_L1_FREQ_HZ; - // code Doppler frequency update - d_code_freq_chips = GPS_L1_CA_CODE_RATE_HZ + ((d_carrier_doppler_hz * GPS_L1_CA_CODE_RATE_HZ) / GPS_L1_FREQ_HZ); - - // ################## DLL ########################################################## - // DLL discriminator - d_code_error_chips_Ti = dll_nc_e_minus_l_normalized(std::complex(d_correlator_outs_16sc[0].real(), d_correlator_outs_16sc[0].imag()), std::complex(d_correlator_outs_16sc[2].real(), d_correlator_outs_16sc[2].imag())); // [chips/Ti] //early and late - // Code discriminator filter - d_code_error_filt_chips_s = d_code_loop_filter.get_code_nco(d_code_error_chips_Ti); // input [chips/Ti] -> output [chips/second] - d_code_error_filt_chips_Ti = d_code_error_filt_chips_s * CURRENT_INTEGRATION_TIME_S; - code_error_filt_secs_Ti = d_code_error_filt_chips_Ti / d_code_freq_chips; // [s/Ti] - - // ################## CARRIER AND CODE NCO BUFFER ALIGNMENT ####################### - // keep alignment parameters for the next input buffer - // Compute the next buffer length based in the new period of the PRN sequence and the code phase error estimation - double T_chip_seconds = 1.0 / d_code_freq_chips; - double T_prn_seconds = T_chip_seconds * GPS_L1_CA_CODE_LENGTH_CHIPS; - double T_prn_samples = T_prn_seconds * static_cast(d_fs_in); - double K_prn_samples = round(T_prn_samples); - double K_T_prn_error_samples = K_prn_samples - T_prn_samples; - - d_rem_code_phase_samples = d_rem_code_phase_samples - K_T_prn_error_samples + code_error_filt_secs_Ti * static_cast(d_fs_in); //(code_error_filt_secs_Ti + d_pll_to_dll_assist_secs_Ti) * static_cast(d_fs_in); - d_rem_code_phase_integer_samples = round(d_rem_code_phase_samples); // round to a discrete number of samples - d_correlation_length_samples = K_prn_samples + d_rem_code_phase_integer_samples; - d_rem_code_phase_samples = d_rem_code_phase_samples - d_rem_code_phase_integer_samples; - - //################### PLL COMMANDS ################################################# - //carrier phase step (NCO phase increment per sample) [rads/sample] - d_carrier_phase_step_rad = GPS_TWO_PI * d_carrier_doppler_hz / static_cast(d_fs_in); - d_acc_carrier_phase_cycles -= d_carrier_phase_step_rad * d_correlation_length_samples / GPS_TWO_PI; - // UPDATE ACCUMULATED CARRIER PHASE - CORRECTED_INTEGRATION_TIME_S = (static_cast(d_correlation_length_samples) / static_cast(d_fs_in)); - //remnant carrier phase [rad] - d_rem_carrier_phase_rad = fmod(d_rem_carrier_phase_rad + GPS_TWO_PI * d_carrier_doppler_hz * CORRECTED_INTEGRATION_TIME_S, GPS_TWO_PI); - - //################### DLL COMMANDS ################################################# - //code phase step (Code resampler phase increment per sample) [chips/sample] - d_code_phase_step_chips = d_code_freq_chips / static_cast(d_fs_in); - //remnant code phase [chips] - d_rem_code_phase_chips = d_rem_code_phase_samples * (d_code_freq_chips / static_cast(d_fs_in)); - - // ####### CN0 ESTIMATION AND LOCK DETECTORS ####################################### - if (d_cn0_estimation_counter < FLAGS_cn0_samples) - { - // fill buffer with prompt correlator output values - d_Prompt_buffer[d_cn0_estimation_counter] = lv_cmake(static_cast(d_correlator_outs_16sc[1].real()), static_cast(d_correlator_outs_16sc[1].imag())); // prompt - d_cn0_estimation_counter++; - } - else - { - d_cn0_estimation_counter = 0; - // Code lock indicator - d_CN0_SNV_dB_Hz = cn0_svn_estimator(d_Prompt_buffer, FLAGS_cn0_samples, GPS_L1_CA_CODE_PERIOD); - // Carrier lock indicator - d_carrier_lock_test = carrier_lock_detector(d_Prompt_buffer, FLAGS_cn0_samples); - // Loss of lock detection - if (d_carrier_lock_test < d_carrier_lock_threshold or d_CN0_SNV_dB_Hz < FLAGS_cn0_min) - { - d_carrier_lock_fail_counter++; - } - else - { - if (d_carrier_lock_fail_counter > 0) - { - d_carrier_lock_fail_counter--; - } - } - if (d_carrier_lock_fail_counter > FLAGS_max_lock_fail) - { - std::cout << "Loss of lock in channel " << d_channel << "!" << std::endl; - LOG(INFO) << "Loss of lock in channel " << d_channel << "!"; - this->message_port_pub(pmt::mp("events"), pmt::from_long(3)); //3 -> loss of lock - d_carrier_lock_fail_counter = 0; - d_enable_tracking = false; // TODO: check if disabling tracking is consistent with the channel state machine - } - } - // ########### Output the tracking data to navigation and PVT ########## - current_synchro_data.Prompt_I = static_cast((d_correlator_outs_16sc[1]).real()); - current_synchro_data.Prompt_Q = static_cast((d_correlator_outs_16sc[1]).imag()); - // Tracking_timestamp_secs is aligned with the CURRENT PRN start sample (Hybridization OK!) - current_synchro_data.Tracking_sample_counter = d_sample_counter + static_cast(d_correlation_length_samples); - current_synchro_data.Code_phase_samples = d_rem_code_phase_samples; - current_synchro_data.Carrier_phase_rads = GPS_TWO_PI * d_acc_carrier_phase_cycles; - current_synchro_data.Carrier_Doppler_hz = d_carrier_doppler_hz; - current_synchro_data.CN0_dB_hz = d_CN0_SNV_dB_Hz; - current_synchro_data.Flag_valid_symbol_output = true; - if (d_preamble_synchronized == true) - { - current_synchro_data.correlation_length_ms = d_extend_correlation_ms; - } - else - { - current_synchro_data.correlation_length_ms = 1; - } - } - else - { - current_synchro_data.Prompt_I = static_cast((d_correlator_outs_16sc[1]).real()); - current_synchro_data.Prompt_Q = static_cast((d_correlator_outs_16sc[1]).imag()); - current_synchro_data.Tracking_sample_counter = d_sample_counter + static_cast(d_correlation_length_samples); - current_synchro_data.Code_phase_samples = d_rem_code_phase_samples; - current_synchro_data.Carrier_phase_rads = GPS_TWO_PI * d_acc_carrier_phase_cycles; - current_synchro_data.Carrier_Doppler_hz = d_carrier_doppler_hz; // todo: project the carrier doppler - current_synchro_data.CN0_dB_hz = d_CN0_SNV_dB_Hz; - } - } - else - { - for (int32_t n = 0; n < d_n_correlator_taps; n++) - { - d_correlator_outs_16sc[n] = lv_cmake(0, 0); - } - - current_synchro_data.System = {'G'}; - current_synchro_data.Tracking_sample_counter = d_sample_counter + static_cast(d_correlation_length_samples); - } - current_synchro_data.fs = d_fs_in; - *out[0] = current_synchro_data; - if (d_dump) - { - // MULTIPLEXED FILE RECORDING - Record results to file - float prompt_I; - float prompt_Q; - float tmp_E, tmp_P, tmp_L; - float tmp_VE = 0.0; - float tmp_VL = 0.0; - float tmp_float; - prompt_I = d_correlator_outs_16sc[1].real(); - prompt_Q = d_correlator_outs_16sc[1].imag(); - tmp_E = std::abs(gr_complex(d_correlator_outs_16sc[0].real(), d_correlator_outs_16sc[0].imag())); - tmp_P = std::abs(gr_complex(d_correlator_outs_16sc[1].real(), d_correlator_outs_16sc[1].imag())); - tmp_L = std::abs(gr_complex(d_correlator_outs_16sc[2].real(), d_correlator_outs_16sc[2].imag())); - try - { - // Dump correlators output - d_dump_file.write(reinterpret_cast(&tmp_VE), sizeof(float)); - d_dump_file.write(reinterpret_cast(&tmp_E), sizeof(float)); - d_dump_file.write(reinterpret_cast(&tmp_P), sizeof(float)); - d_dump_file.write(reinterpret_cast(&tmp_L), sizeof(float)); - d_dump_file.write(reinterpret_cast(&tmp_VL), sizeof(float)); - // PROMPT I and Q (to analyze navigation symbols) - d_dump_file.write(reinterpret_cast(&prompt_I), sizeof(float)); - d_dump_file.write(reinterpret_cast(&prompt_Q), sizeof(float)); - // PRN start sample stamp - d_dump_file.write(reinterpret_cast(&d_sample_counter), sizeof(uint64_t)); - // accumulated carrier phase - tmp_float = d_acc_carrier_phase_cycles * GPS_TWO_PI; - d_dump_file.write(reinterpret_cast(&tmp_float), sizeof(float)); - // carrier and code frequency - tmp_float = d_carrier_doppler_hz; - d_dump_file.write(reinterpret_cast(&tmp_float), sizeof(float)); - tmp_float = d_code_freq_chips; - d_dump_file.write(reinterpret_cast(&tmp_float), sizeof(float)); - // PLL commands - tmp_float = 1.0 / (d_carr_phase_error_secs_Ti * CURRENT_INTEGRATION_TIME_S); - d_dump_file.write(reinterpret_cast(&tmp_float), sizeof(float)); - tmp_float = 1.0 / (d_code_error_filt_chips_Ti * CURRENT_INTEGRATION_TIME_S); - d_dump_file.write(reinterpret_cast(&tmp_float), sizeof(float)); - // DLL commands - tmp_float = d_code_error_chips_Ti * CURRENT_INTEGRATION_TIME_S; - d_dump_file.write(reinterpret_cast(&tmp_float), sizeof(float)); - tmp_float = d_code_error_filt_chips_Ti; - d_dump_file.write(reinterpret_cast(&tmp_float), sizeof(float)); - // CN0 and carrier lock test - tmp_float = d_CN0_SNV_dB_Hz; - d_dump_file.write(reinterpret_cast(&tmp_float), sizeof(float)); - tmp_float = d_carrier_lock_test; - d_dump_file.write(reinterpret_cast(&tmp_float), sizeof(float)); - // AUX vars (for debug purposes) - tmp_float = d_code_error_chips_Ti * CURRENT_INTEGRATION_TIME_S; - d_dump_file.write(reinterpret_cast(&tmp_float), sizeof(float)); - auto tmp_double = static_cast(d_sample_counter + d_correlation_length_samples); - d_dump_file.write(reinterpret_cast(&tmp_double), sizeof(double)); - // PRN - uint32_t prn_ = d_acquisition_gnss_synchro->PRN; - d_dump_file.write(reinterpret_cast(&prn_), sizeof(uint32_t)); - } - catch (const std::ifstream::failure &e) - { - LOG(WARNING) << "Exception writing trk dump file " << e.what(); - } - } - - consume_each(d_correlation_length_samples); // this is necessary in gr::block derivates - d_sample_counter += d_correlation_length_samples; //count for the processed samples - - if (d_enable_tracking) - { - return 1; - } - - return 0; -} diff --git a/src/algorithms/tracking/gnuradio_blocks/gps_l1_ca_dll_pll_c_aid_tracking_sc.h b/src/algorithms/tracking/gnuradio_blocks/gps_l1_ca_dll_pll_c_aid_tracking_sc.h deleted file mode 100644 index 9aec25252..000000000 --- a/src/algorithms/tracking/gnuradio_blocks/gps_l1_ca_dll_pll_c_aid_tracking_sc.h +++ /dev/null @@ -1,201 +0,0 @@ -/*! - * \file gps_l1_ca_dll_pll_c_aid_tracking_sc.h - * \brief Interface of a code DLL + carrier PLL tracking block - * \author Carlos Aviles, 2010. carlos.avilesr(at)googlemail.com - * Javier Arribas, 2011. jarribas(at)cttc.es - * - * Code DLL + carrier PLL according to the algorithms described in: - * K.Borre, D.M.Akos, N.Bertelsen, P.Rinder, and S.H.Jensen, - * A Software-Defined GPS and Galileo Receiver. A Single-Frequency Approach, - * Birkhauser, 2007 - * - * ------------------------------------------------------------------------- - * - * Copyright (C) 2010-2018 (see AUTHORS file for a list of contributors) - * - * GNSS-SDR is a software defined Global Navigation - * Satellite Systems receiver - * - * This file is part of GNSS-SDR. - * - * GNSS-SDR is free software: you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * GNSS-SDR is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - * GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with GNSS-SDR. If not, see . - * - * ------------------------------------------------------------------------- - */ - -#ifndef GNSS_SDR_GPS_L1_CA_DLL_PLL_C_AID_TRACKING_SC_H -#define GNSS_SDR_GPS_L1_CA_DLL_PLL_C_AID_TRACKING_SC_H - -#include "cpu_multicorrelator_16sc.h" -#include "gnss_synchro.h" -#include "gps_sdr_signal_processing.h" -#include "tracking_2nd_DLL_filter.h" -#include "tracking_FLL_PLL_filter.h" -#include -#include -#include -#include -#include -#include -#include - -class gps_l1_ca_dll_pll_c_aid_tracking_sc; - -using gps_l1_ca_dll_pll_c_aid_tracking_sc_sptr = boost::shared_ptr; - -gps_l1_ca_dll_pll_c_aid_tracking_sc_sptr -gps_l1_ca_dll_pll_c_aid_make_tracking_sc( - int64_t fs_in, uint32_t vector_length, - bool dump, - std::string dump_filename, - float pll_bw_hz, - float dll_bw_hz, - float pll_bw_narrow_hz, - float dll_bw_narrow_hz, - int32_t extend_correlation_ms, - float early_late_space_chips); - - -/*! - * \brief This class implements a DLL + PLL tracking loop block - */ -class gps_l1_ca_dll_pll_c_aid_tracking_sc : public gr::block -{ -public: - ~gps_l1_ca_dll_pll_c_aid_tracking_sc(); - - void set_channel(uint32_t channel); - void set_gnss_synchro(Gnss_Synchro* p_gnss_synchro); - void start_tracking(); - - int general_work(int noutput_items, gr_vector_int& ninput_items, - gr_vector_const_void_star& input_items, gr_vector_void_star& output_items); - - void forecast(int noutput_items, gr_vector_int& ninput_items_required); - -private: - friend gps_l1_ca_dll_pll_c_aid_tracking_sc_sptr - gps_l1_ca_dll_pll_c_aid_make_tracking_sc( - int64_t fs_in, uint32_t vector_length, - bool dump, - std::string dump_filename, - float pll_bw_hz, - float dll_bw_hz, - float pll_bw_narrow_hz, - float dll_bw_narrow_hz, - int32_t extend_correlation_ms, - float early_late_space_chips); - - gps_l1_ca_dll_pll_c_aid_tracking_sc( - int64_t fs_in, uint32_t vector_length, - bool dump, - std::string dump_filename, - float pll_bw_hz, - float dll_bw_hz, - float pll_bw_narrow_hz, - float dll_bw_narrow_hz, - int32_t extend_correlation_ms, - float early_late_space_chips); - - // tracking configuration vars - uint32_t d_vector_length; - bool d_dump; - - Gnss_Synchro* d_acquisition_gnss_synchro; - uint32_t d_channel; - - int64_t d_fs_in; - - double d_early_late_spc_chips; - int32_t d_n_correlator_taps; - - gr_complex* d_ca_code; - lv_16sc_t* d_ca_code_16sc; - float* d_local_code_shift_chips; - //gr_complex* d_correlator_outs; - lv_16sc_t* d_correlator_outs_16sc; - //cpu_multicorrelator multicorrelator_cpu; - Cpu_Multicorrelator_16sc multicorrelator_cpu_16sc; - - // remaining code phase and carrier phase between tracking loops - double d_rem_code_phase_samples; - double d_rem_code_phase_chips; - double d_rem_carrier_phase_rad; - int32_t d_rem_code_phase_integer_samples; - - // PLL and DLL filter library - Tracking_2nd_DLL_filter d_code_loop_filter; - Tracking_FLL_PLL_filter d_carrier_loop_filter; - - // acquisition - double d_acq_code_phase_samples; - double d_acq_carrier_doppler_hz; - - // tracking vars - float d_dll_bw_hz; - float d_pll_bw_hz; - float d_dll_bw_narrow_hz; - float d_pll_bw_narrow_hz; - double d_code_freq_chips; - double d_code_phase_step_chips; - double d_carrier_doppler_hz; - double d_carrier_phase_step_rad; - double d_acc_carrier_phase_cycles; - double d_code_phase_samples; - double d_pll_to_dll_assist_secs_Ti; - double d_carr_phase_error_secs_Ti; - double d_code_error_chips_Ti; - double d_preamble_timestamp_s; - int32_t d_extend_correlation_ms; - bool d_enable_extended_integration; - bool d_preamble_synchronized; - double d_code_error_filt_chips_s; - double d_code_error_filt_chips_Ti; - void msg_handler_preamble_index(pmt::pmt_t msg); - - // symbol history to detect bit transition - std::deque d_E_history; - std::deque d_P_history; - std::deque d_L_history; - - //Integration period in samples - int32_t d_correlation_length_samples; - - //processing samples counters - uint64_t d_sample_counter; - uint64_t d_acq_sample_stamp; - - // CN0 estimation and lock detector - int32_t d_cn0_estimation_counter; - gr_complex* d_Prompt_buffer; - double d_carrier_lock_test; - double d_CN0_SNV_dB_Hz; - double d_carrier_lock_threshold; - int32_t d_carrier_lock_fail_counter; - - // control vars - bool d_enable_tracking; - bool d_pull_in; - - // file dump - std::string d_dump_filename; - std::ofstream d_dump_file; - - std::map systemName; - std::string sys; - - int32_t save_matfile(); -}; - -#endif //GNSS_SDR_GPS_L1_CA_DLL_PLL_C_AID_TRACKING_SC_H diff --git a/src/algorithms/tracking/libs/CMakeLists.txt b/src/algorithms/tracking/libs/CMakeLists.txt index 5950f8ad1..fb816d0d8 100644 --- a/src/algorithms/tracking/libs/CMakeLists.txt +++ b/src/algorithms/tracking/libs/CMakeLists.txt @@ -102,12 +102,20 @@ if(Boost_VERSION VERSION_GREATER "106599") ) endif() +# Fix for Boost Asio < 1.70 if(OS_IS_MACOSX) - if(CMAKE_CXX_COMPILER_ID STREQUAL "Clang") # not AppleClang - target_compile_definitions(tracking_libs - PUBLIC - -DBOOST_ASIO_HAS_STD_STRING_VIEW - ) + if((CMAKE_CXX_COMPILER_ID MATCHES "Clang") AND (${Boost_VERSION} VERSION_LESS 107000)) + if(${has_string_view}) + target_compile_definitions(tracking_libs + PUBLIC + -DBOOST_ASIO_HAS_STD_STRING_VIEW=1 + ) + else() + target_compile_definitions(tracking_libs + PUBLIC + -DBOOST_ASIO_HAS_STD_STRING_VIEW=0 + ) + endif() endif() endif() diff --git a/src/algorithms/tracking/libs/lock_detectors.h b/src/algorithms/tracking/libs/lock_detectors.h index 81d54b651..3f1750e15 100644 --- a/src/algorithms/tracking/libs/lock_detectors.h +++ b/src/algorithms/tracking/libs/lock_detectors.h @@ -64,7 +64,7 @@ * * The SNR value is converted to CN0 [dB-Hz], taking to account the coherent integration time, using the following formula: * \f{equation} - * CN0_{dB}=10*log(\hat{\rho})-10*log(2 * T_{int}), + * CN0_{dB}=10*log(\hat{\rho})-10*log(T_{int}), * \f} * where \f$T_{int}\f$ is the coherent integration time, in seconds. * Ref: Marco Pini, Emanuela Falletti and Maurizio Fantino, "Performance diff --git a/src/core/monitor/CMakeLists.txt b/src/core/monitor/CMakeLists.txt index aa8ee4daa..7fb4008dd 100644 --- a/src/core/monitor/CMakeLists.txt +++ b/src/core/monitor/CMakeLists.txt @@ -68,15 +68,24 @@ if(Boost_VERSION VERSION_GREATER "106599") endif() +# Fix for Boost Asio < 1.70 if(OS_IS_MACOSX) - if(CMAKE_CXX_COMPILER_ID STREQUAL "Clang") # not AppleClang - target_compile_definitions(core_monitor - PUBLIC - -DBOOST_ASIO_HAS_STD_STRING_VIEW - ) + if((CMAKE_CXX_COMPILER_ID MATCHES "Clang") AND (${Boost_VERSION} VERSION_LESS 107000)) + if(${has_string_view}) + target_compile_definitions(core_monitor + PUBLIC + -DBOOST_ASIO_HAS_STD_STRING_VIEW=1 + ) + else() + target_compile_definitions(core_monitor + PUBLIC + -DBOOST_ASIO_HAS_STD_STRING_VIEW=0 + ) + endif() endif() endif() + if(ENABLE_CLANG_TIDY) if(CLANG_TIDY_EXE) set_target_properties(core_monitor diff --git a/src/core/receiver/CMakeLists.txt b/src/core/receiver/CMakeLists.txt index 4cfca1f29..121b4ab75 100644 --- a/src/core/receiver/CMakeLists.txt +++ b/src/core/receiver/CMakeLists.txt @@ -162,12 +162,20 @@ target_link_libraries(core_receiver pvt_adapters ) +# Fix for Boost Asio < 1.70 if(OS_IS_MACOSX) - if(CMAKE_CXX_COMPILER_ID STREQUAL "Clang") # not AppleClang - target_compile_definitions(core_receiver - PUBLIC - -DBOOST_ASIO_HAS_STD_STRING_VIEW - ) + if((CMAKE_CXX_COMPILER_ID MATCHES "Clang") AND (${Boost_VERSION} VERSION_LESS 107000)) + if(${has_string_view}) + target_compile_definitions(core_receiver + PUBLIC + -DBOOST_ASIO_HAS_STD_STRING_VIEW=1 + ) + else() + target_compile_definitions(core_receiver + PUBLIC + -DBOOST_ASIO_HAS_STD_STRING_VIEW=0 + ) + endif() endif() endif() diff --git a/src/core/receiver/gnss_block_factory.cc b/src/core/receiver/gnss_block_factory.cc index 32de09a96..b4ede27ac 100644 --- a/src/core/receiver/gnss_block_factory.cc +++ b/src/core/receiver/gnss_block_factory.cc @@ -73,7 +73,6 @@ #include "glonass_l2_ca_pcps_acquisition.h" #include "glonass_l2_ca_telemetry_decoder.h" #include "gnss_block_interface.h" -#include "gps_l1_ca_dll_pll_c_aid_tracking.h" #include "gps_l1_ca_dll_pll_tracking.h" #include "gps_l1_ca_kf_tracking.h" #include "gps_l1_ca_pcps_acquisition.h" @@ -1720,12 +1719,6 @@ std::unique_ptr GNSSBlockFactory::GetBlock( out_streams)); block = std::move(block_); } - else if (implementation == "GPS_L1_CA_DLL_PLL_C_Aid_Tracking") - { - std::unique_ptr block_(new GpsL1CaDllPllCAidTracking(configuration.get(), role, in_streams, - out_streams)); - block = std::move(block_); - } #if ENABLE_FPGA else if (implementation == "GPS_L1_CA_DLL_PLL_Tracking_Fpga") { @@ -2138,12 +2131,6 @@ std::unique_ptr GNSSBlockFactory::GetTrkBlock( out_streams)); block = std::move(block_); } - else if (implementation == "GPS_L1_CA_DLL_PLL_C_Aid_Tracking") - { - std::unique_ptr block_(new GpsL1CaDllPllCAidTracking(configuration.get(), role, in_streams, - out_streams)); - block = std::move(block_); - } #if ENABLE_FPGA else if (implementation == "GPS_L1_CA_DLL_PLL_Tracking_Fpga") { diff --git a/src/main/CMakeLists.txt b/src/main/CMakeLists.txt index 4561b7119..96e1d3c97 100644 --- a/src/main/CMakeLists.txt +++ b/src/main/CMakeLists.txt @@ -19,10 +19,15 @@ add_executable(gnss-sdr ${CMAKE_CURRENT_SOURCE_DIR}/main.cc) +if(${FILESYSTEM_FOUND}) + target_compile_definitions(gnss-sdr PRIVATE -DHAS_STD_FILESYSTEM=1) + target_link_libraries(gnss-sdr PRIVATE std::filesystem) +else() + target_link_libraries(gnss-sdr PRIVATE Boost::filesystem Boost::system) +endif() + target_link_libraries(gnss-sdr PUBLIC - Boost::filesystem - Boost::system Gflags::gflags Glog::glog Threads::Threads diff --git a/src/main/main.cc b/src/main/main.cc index 696ff412b..cf01b30b5 100644 --- a/src/main/main.cc +++ b/src/main/main.cc @@ -45,23 +45,35 @@ #include "gps_acq_assist.h" #include // for diagnostic_informatio #include // for exception -#include // for create_directories, exists -#include // for path, operator<< -#include // for error_code #include // for thread_resource_error -#include // for ShutDownCommandLineFlags -#include // for FLAGS_log_dir -#include // for time_point -#include // for exception -#include // for operator<<, endl -#include // for unique_ptr -#include // for string +#if HAS_STD_FILESYSTEM +#include +#include +#else +#include // for create_directories, exists +#include // for path, operator<< +#include // for error_code +#endif +#include // for ShutDownCommandLineFlags +#include // for FLAGS_log_dir +#include // for time_point +#include // for exception +#include // for operator<<, endl +#include // for unique_ptr +#include // for string #if CUDA_GPU_ACCEL // For the CUDA runtime routines (prefixed with "cuda_") #include #endif +#if HAS_STD_FILESYSTEM +namespace fs = std::filesystem; +namespace errorlib = std; +#else +namespace fs = boost::filesystem; +namespace errorlib = boost::system; +#endif /* * Concurrent queues that communicates the Telemetry Decoder @@ -103,22 +115,22 @@ int main(int argc, char** argv) if (FLAGS_log_dir.empty()) { std::cout << "Logging will be written at " - << boost::filesystem::temp_directory_path() + << fs::temp_directory_path() << std::endl << "Use gnss-sdr --log_dir=/path/to/log to change that." << std::endl; } else { - const boost::filesystem::path p(FLAGS_log_dir); - if (!boost::filesystem::exists(p)) + const fs::path p(FLAGS_log_dir); + if (!fs::exists(p)) { std::cout << "The path " << FLAGS_log_dir << " does not exist, attempting to create it." << std::endl; - boost::system::error_code ec; - if (!boost::filesystem::create_directory(p, ec)) + errorlib::error_code ec; + if (!fs::create_directory(p, ec)) { std::cerr << "Could not create the " << FLAGS_log_dir << " folder. GNSS-SDR program ended." << std::endl; google::ShutDownCommandLineFlags(); diff --git a/src/tests/CMakeLists.txt b/src/tests/CMakeLists.txt index 51e67077f..2ace1a4b5 100644 --- a/src/tests/CMakeLists.txt +++ b/src/tests/CMakeLists.txt @@ -237,7 +237,7 @@ if(ENABLE_UNIT_TESTING_EXTRA OR ENABLE_SYSTEM_TESTING_EXTRA OR ENABLE_FPGA) if(NOT GPSTK_FOUND OR ENABLE_OWN_GPSTK) message(STATUS " GPSTk v${GNSSSDR_GPSTK_LOCAL_VERSION} will be automatically downloaded and built when doing 'make'.") if("${TOOLCHAIN_ARG}" STREQUAL "") - set(TOOLCHAIN_ARG "-DCMAKE_CXX_FLAGS=\"-Wno-deprecated\"") + set(TOOLCHAIN_ARG "-DCMAKE_CXX_FLAGS=-Wno-deprecated") set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wno-deprecated") endif() include(GNUInstallDirs) @@ -354,11 +354,15 @@ include_directories(${LIST_INCLUDE_DIRS}) ################################################################################ if(ENABLE_UNIT_TESTING) add_executable(run_tests ${CMAKE_CURRENT_SOURCE_DIR}/test_main.cc) + if(${FILESYSTEM_FOUND}) + target_compile_definitions(run_tests PRIVATE -DHAS_STD_FILESYSTEM=1) + target_link_libraries(run_tests PRIVATE std::filesystem) + else() + target_link_libraries(run_tests PRIVATE Boost::filesystem Boost::system) + endif() target_link_libraries(run_tests PUBLIC - Boost::filesystem - Boost::system Boost::thread Armadillo::armadillo Gflags::gflags @@ -441,11 +445,15 @@ if(ENABLE_FPGA) ${CMAKE_CURRENT_SOURCE_DIR}/single_test_main.cc ${CMAKE_CURRENT_SOURCE_DIR}/unit-tests/signal-processing-blocks/tracking/gps_l1_ca_dll_pll_tracking_test_fpga.cc ) + if(${FILESYSTEM_FOUND}) + target_compile_definitions(gps_l1_ca_dll_pll_tracking_test_fpga PRIVATE -DHAS_STD_FILESYSTEM=1) + target_link_libraries(gps_l1_ca_dll_pll_tracking_test_fpga PRIVATE std::filesystem) + else() + target_link_libraries(gps_l1_ca_dll_pll_tracking_test_fpga PRIVATE Boost::filesystem Boost::system) + endif() target_link_libraries(gps_l1_ca_dll_pll_tracking_test_fpga PUBLIC Armadillo::armadillo - Boost::filesystem - Boost::system Boost::thread Gflags::gflags Glog::glog @@ -482,6 +490,12 @@ function(add_system_test executable) execute_process(COMMAND ${CMAKE_COMMAND} -E touch ${SYSTEM_TEST_SOURCES}) endif() add_executable(${executable} ${SYSTEM_TEST_SOURCES}) + if(${FILESYSTEM_FOUND}) + target_compile_definitions(${executable} PRIVATE -DHAS_STD_FILESYSTEM=1) + target_link_libraries(${executable} PRIVATE std::filesystem) + else() + target_link_libraries(${executable} PRIVATE Boost::filesystem Boost::system) + endif() target_include_directories(${executable} PUBLIC ${OPT_INCLUDES_} ${CMAKE_SOURCES_DIR}/src/algorithms/libs) target_link_libraries(${executable} PUBLIC ${OPT_LIBS_} algorithms_libs) @@ -521,7 +535,7 @@ if(ENABLE_SYSTEM_TESTING) add_definitions(-DHOST_SYSTEM="${HOST_SYSTEM}") #### TTFF - set(OPT_LIBS_ Boost::filesystem Boost::system Boost::thread Boost::date_time + set(OPT_LIBS_ Boost::thread Boost::date_time Threads::Threads Gflags::gflags Glog::glog Gnuradio::runtime GTest::GTest GTest::Main Gnuradio::blocks Gnuradio::filter @@ -532,7 +546,7 @@ if(ENABLE_SYSTEM_TESTING) if(ENABLE_SYSTEM_TESTING_EXTRA) #### POSITION_TEST - set(OPT_LIBS_ Boost::filesystem Boost::system Boost::thread + set(OPT_LIBS_ Boost::thread Threads::Threads Gflags::gflags Glog::glog GTest::GTest GTest::Main Gnuradio::runtime Gnuradio::blocks Gnuradio::filter @@ -569,11 +583,14 @@ if(NOT ENABLE_PACKAGING AND NOT ENABLE_FPGA) ${CMAKE_CURRENT_SOURCE_DIR}/single_test_main.cc ${CMAKE_CURRENT_SOURCE_DIR}/unit-tests/control-plane/gnss_flowgraph_test.cc ) - + if(${FILESYSTEM_FOUND}) + target_compile_definitions(flowgraph_test PRIVATE -DHAS_STD_FILESYSTEM=1) + target_link_libraries(flowgraph_test PRIVATE std::filesystem) + else() + target_link_libraries(flowgraph_test PRIVATE Boost::filesystem Boost::system) + endif() target_link_libraries(flowgraph_test PUBLIC - Boost::filesystem - Boost::system Boost::thread Gflags::gflags Glog::glog @@ -615,11 +632,14 @@ if(NOT ENABLE_PACKAGING AND NOT ENABLE_FPGA) ${CMAKE_CURRENT_SOURCE_DIR}/unit-tests/signal-processing-blocks/adapter/adapter_test.cc ${CMAKE_CURRENT_SOURCE_DIR}/unit-tests/control-plane/gnss_block_factory_test.cc ) - + if(${FILESYSTEM_FOUND}) + target_compile_definitions(gnss_block_test PRIVATE -DHAS_STD_FILESYSTEM=1) + target_link_libraries(gnss_block_test PRIVATE std::filesystem) + else() + target_link_libraries(gnss_block_test PRIVATE Boost::filesystem Boost::system) + endif() target_link_libraries(gnss_block_test PUBLIC - Boost::filesystem - Boost::system Boost::thread Gflags::gflags Glog::glog @@ -659,11 +679,14 @@ if(NOT ENABLE_PACKAGING AND NOT ENABLE_FPGA) ${CMAKE_CURRENT_SOURCE_DIR}/single_test_main.cc ${CMAKE_CURRENT_SOURCE_DIR}/unit-tests/signal-processing-blocks/sources/unpack_2bit_samples_test.cc ) - + if(${FILESYSTEM_FOUND}) + target_compile_definitions(gnuradio_block_test PRIVATE -DHAS_STD_FILESYSTEM=1) + target_link_libraries(gnuradio_block_test PRIVATE std::filesystem) + else() + target_link_libraries(gnuradio_block_test PRIVATE Boost::filesystem Boost::system) + endif() target_link_libraries(gnuradio_block_test PUBLIC - Boost::filesystem - Boost::system Boost::thread Gflags::gflags Glog::glog @@ -715,11 +738,14 @@ if(NOT ENABLE_PACKAGING AND NOT ENABLE_FPGA) ${CMAKE_CURRENT_SOURCE_DIR}/single_test_main.cc ${CMAKE_CURRENT_SOURCE_DIR}/unit-tests/signal-processing-blocks/acquisition/gps_l1_ca_pcps_acquisition_test.cc ) - + if(${FILESYSTEM_FOUND}) + target_compile_definitions(acq_test PRIVATE -DHAS_STD_FILESYSTEM=1) + target_link_libraries(acq_test PRIVATE std::filesystem) + else() + target_link_libraries(acq_test PRIVATE Boost::filesystem Boost::system) + endif() target_link_libraries(acq_test PUBLIC - Boost::filesystem - Boost::system Boost::thread Gflags::gflags Glog::glog @@ -757,11 +783,15 @@ if(NOT ENABLE_PACKAGING AND NOT ENABLE_FPGA) ${CMAKE_CURRENT_SOURCE_DIR}/unit-tests/signal-processing-blocks/tracking/bayesian_estimation_test.cc ${CMAKE_CURRENT_SOURCE_DIR}/unit-tests/signal-processing-blocks/tracking/cubature_filter_test.cc ) + if(${FILESYSTEM_FOUND}) + target_compile_definitions(trk_test PRIVATE -DHAS_STD_FILESYSTEM=1) + target_link_libraries(trk_test PRIVATE std::filesystem) + else() + target_link_libraries(trk_test PRIVATE Boost::filesystem Boost::system) + endif() target_link_libraries(trk_test PUBLIC - Boost::filesystem - Boost::system Boost::thread Gflags::gflags Glog::glog @@ -794,11 +824,15 @@ if(NOT ENABLE_PACKAGING AND NOT ENABLE_FPGA) ${CMAKE_CURRENT_SOURCE_DIR}/unit-tests/control-plane/control_message_factory_test.cc ${CMAKE_CURRENT_SOURCE_DIR}/unit-tests/control-plane/control_thread_test.cc ) + if(${FILESYSTEM_FOUND}) + target_compile_definitions(control_thread_test PRIVATE -DHAS_STD_FILESYSTEM=1) + target_link_libraries(control_thread_test PRIVATE std::filesystem) + else() + target_link_libraries(control_thread_test PRIVATE Boost::filesystem Boost::system) + endif() target_link_libraries(control_thread_test PUBLIC - Boost::filesystem - Boost::system Boost::thread Gflags::gflags Glog::glog diff --git a/src/tests/system-tests/position_test.cc b/src/tests/system-tests/position_test.cc index 1365b4302..364553dab 100644 --- a/src/tests/system-tests/position_test.cc +++ b/src/tests/system-tests/position_test.cc @@ -48,7 +48,6 @@ #include "test_flags.h" #include "tracking_tests_flags.h" //acquisition resampler #include -#include #include #include #include @@ -59,6 +58,14 @@ #include #include +#if HAS_STD_FILESYSTEM +#include +namespace fs = std::filesystem; +#else +#include +namespace fs = boost::filesystem; +#endif + // For GPS NAVIGATION (L1) Concurrent_Queue global_gps_acq_assist_queue; Concurrent_Map global_gps_acq_assist_map; @@ -843,8 +850,8 @@ void PositionSystemTest::print_results(const arma::mat& R_eb_enu) try { - boost::filesystem::path p(gnuplot_executable); - boost::filesystem::path dir = p.parent_path(); + fs::path p(gnuplot_executable); + fs::path dir = p.parent_path(); const std::string& gnuplot_path = dir.native(); Gnuplot::set_GNUPlotPath(gnuplot_path); diff --git a/src/tests/unit-tests/arithmetic/fft_length_test.cc b/src/tests/unit-tests/arithmetic/fft_length_test.cc index c8eb8354d..5b2583758 100644 --- a/src/tests/unit-tests/arithmetic/fft_length_test.cc +++ b/src/tests/unit-tests/arithmetic/fft_length_test.cc @@ -31,13 +31,19 @@ #include "gnuplot_i.h" #include "test_flags.h" -#include #include #include #include #include #include +#if HAS_STD_FILESYSTEM +#include +namespace fs = std::filesystem; +#else +#include +namespace fs = boost::filesystem; +#endif DEFINE_int32(fft_iterations_test, 1000, "Number of averaged iterations in FFT length timing test"); DEFINE_bool(plot_fft_length_test, false, "Plots results of FFTLengthTest with gnuplot"); @@ -110,8 +116,8 @@ TEST(FFTLengthTest, MeasureExecutionTime) { try { - boost::filesystem::path p(gnuplot_executable); - boost::filesystem::path dir = p.parent_path(); + fs::path p(gnuplot_executable); + fs::path dir = p.parent_path(); const std::string& gnuplot_path = dir.native(); Gnuplot::set_GNUPlotPath(gnuplot_path); diff --git a/src/tests/unit-tests/control-plane/control_thread_test.cc b/src/tests/unit-tests/control-plane/control_thread_test.cc index 0155cb227..781a5af76 100644 --- a/src/tests/unit-tests/control-plane/control_thread_test.cc +++ b/src/tests/unit-tests/control-plane/control_thread_test.cc @@ -31,8 +31,8 @@ */ -#include "control_message_factory.h" #include "control_thread.h" +#include "control_message_factory.h" #include "in_memory_configuration.h" #include #include @@ -170,7 +170,7 @@ TEST_F(ControlThreadTest /*unused*/, InstantiateRunControlMessages2 /*unused*/) config->set_property("Acquisition_1C.threshold", "1"); config->set_property("Acquisition_1C.doppler_max", "5000"); config->set_property("Acquisition_1C.doppler_min", "-5000"); - config->set_property("Tracking_1C.implementation", "GPS_L1_CA_DLL_PLL_C_Aid_Tracking"); + config->set_property("Tracking_1C.implementation", "GPS_L1_CA_DLL_PLL_Tracking"); config->set_property("Tracking_1C.item_type", "gr_complex"); config->set_property("TelemetryDecoder_1C.implementation", "GPS_L1_CA_Telemetry_Decoder"); config->set_property("TelemetryDecoder_1C.item_type", "gr_complex"); @@ -234,7 +234,7 @@ TEST_F(ControlThreadTest /*unused*/, StopReceiverProgrammatically /*unused*/) config->set_property("Acquisition_1C.threshold", "1"); config->set_property("Acquisition_1C.doppler_max", "5000"); config->set_property("Acquisition_1C.doppler_min", "-5000"); - config->set_property("Tracking_1C.implementation", "GPS_L1_CA_DLL_PLL_C_Aid_Tracking"); + config->set_property("Tracking_1C.implementation", "GPS_L1_CA_DLL_PLL_Tracking"); config->set_property("Tracking_1C.item_type", "gr_complex"); config->set_property("TelemetryDecoder_1C.implementation", "GPS_L1_CA_Telemetry_Decoder"); config->set_property("TelemetryDecoder_1C.item_type", "gr_complex"); diff --git a/src/tests/unit-tests/control-plane/gnss_block_factory_test.cc b/src/tests/unit-tests/control-plane/gnss_block_factory_test.cc index 9eff70397..0af18c4e1 100644 --- a/src/tests/unit-tests/control-plane/gnss_block_factory_test.cc +++ b/src/tests/unit-tests/control-plane/gnss_block_factory_test.cc @@ -33,9 +33,9 @@ * ------------------------------------------------------------------------- */ +#include "gnss_block_factory.h" #include "acquisition_interface.h" #include "channel.h" -#include "gnss_block_factory.h" #include "gnss_block_interface.h" #include "in_memory_configuration.h" #include "observables_interface.h" @@ -251,18 +251,6 @@ TEST(GNSSBlockFactoryTest, InstantiateGalileoE1PcpsAmbiguousAcquisition) } -TEST(GNSSBlockFactoryTest, InstantiateGpsL1CaDllPllCAidTracking) -{ - std::shared_ptr configuration = std::make_shared(); - configuration->set_property("Tracking.implementation", "GPS_L1_CA_DLL_PLL_C_Aid_Tracking"); - std::unique_ptr factory; - std::shared_ptr trk_ = factory->GetBlock(configuration, "Tracking", "GPS_L1_CA_DLL_PLL_C_Aid_Tracking", 1, 1); - std::shared_ptr tracking = std::dynamic_pointer_cast(trk_); - EXPECT_STREQ("Tracking", tracking->role().c_str()); - EXPECT_STREQ("GPS_L1_CA_DLL_PLL_C_Aid_Tracking", tracking->implementation().c_str()); -} - - TEST(GNSSBlockFactoryTest, InstantiateGpsL1CaDllPllTracking) { std::shared_ptr configuration = std::make_shared(); @@ -316,7 +304,7 @@ TEST(GNSSBlockFactoryTest, InstantiateChannels) configuration->set_property("Channels_1C.count", "2"); configuration->set_property("Channels_1E.count", "0"); configuration->set_property("Channels.in_acquisition", "2"); - configuration->set_property("Tracking_1C.implementation", "GPS_L1_CA_DLL_PLL_C_Aid_Tracking"); + configuration->set_property("Tracking_1C.implementation", "GPS_L1_CA_DLL_PLL_Tracking"); configuration->set_property("TelemetryDecoder_1C.implementation", "GPS_L1_CA_Telemetry_Decoder"); configuration->set_property("Channel0.item_type", "gr_complex"); configuration->set_property("Acquisition_1C.implementation", "GPS_L1_CA_PCPS_Acquisition"); diff --git a/src/tests/unit-tests/signal-processing-blocks/acquisition/acq_performance_test.cc b/src/tests/unit-tests/signal-processing-blocks/acquisition/acq_performance_test.cc index e30e4fe5b..82b0fdcfd 100644 --- a/src/tests/unit-tests/signal-processing-blocks/acquisition/acq_performance_test.cc +++ b/src/tests/unit-tests/signal-processing-blocks/acquisition/acq_performance_test.cc @@ -47,7 +47,6 @@ #include "test_flags.h" #include "tracking_true_obs_reader.h" #include "true_observables_reader.h" -#include #include #include #include @@ -55,6 +54,17 @@ #include #include +#if HAS_STD_FILESYSTEM +#include +#include +namespace fs = std::filesystem; +namespace errorlib = std; +#else +#include +#include +namespace fs = boost::filesystem; +namespace errorlib = boost::system; +#endif DEFINE_string(config_file_ptest, std::string(""), "File containing alternative configuration parameters for the acquisition performance test."); DEFINE_string(acq_test_input_file, std::string(""), "File containing raw signal data, must be in int8_t format. The signal generator will not be used."); @@ -692,8 +702,8 @@ void AcquisitionPerformanceTest::plot_results() { try { - boost::filesystem::path p(gnuplot_executable); - boost::filesystem::path dir = p.parent_path(); + fs::path p(gnuplot_executable); + fs::path dir = p.parent_path(); const std::string& gnuplot_path = dir.native(); Gnuplot::set_GNUPlotPath(gnuplot_path); @@ -782,12 +792,12 @@ TEST_F(AcquisitionPerformanceTest, ROC) { Tracking_True_Obs_Reader true_trk_data; - if (boost::filesystem::exists(path_str)) + if (fs::exists(path_str)) { - boost::filesystem::remove_all(path_str); + fs::remove_all(path_str); } - boost::system::error_code ec; - ASSERT_TRUE(boost::filesystem::create_directory(path_str, ec)) << "Could not create the " << path_str << " folder."; + errorlib::error_code ec; + ASSERT_TRUE(fs::create_directory(path_str, ec)) << "Could not create the " << path_str << " folder."; unsigned int cn0_index = 0; for (double it : cn0_vector) diff --git a/src/tests/unit-tests/signal-processing-blocks/acquisition/beidou_b1i_pcps_acquisition_test.cc b/src/tests/unit-tests/signal-processing-blocks/acquisition/beidou_b1i_pcps_acquisition_test.cc index be0214766..efb923137 100644 --- a/src/tests/unit-tests/signal-processing-blocks/acquisition/beidou_b1i_pcps_acquisition_test.cc +++ b/src/tests/unit-tests/signal-processing-blocks/acquisition/beidou_b1i_pcps_acquisition_test.cc @@ -41,7 +41,6 @@ #include "gnuplot_i.h" #include "in_memory_configuration.h" #include "test_flags.h" -#include #include #include #include @@ -52,12 +51,20 @@ #include #include #include + #ifdef GR_GREATER_38 #include #else #include #endif +#if HAS_STD_FILESYSTEM +#include +namespace fs = std::filesystem; +#else +#include +namespace fs = boost::filesystem; +#endif // ######## GNURADIO BLOCK MESSAGE RECEVER ######### class BeidouB1iPcpsAcquisitionTest_msg_rx; @@ -200,8 +207,8 @@ void BeidouB1iPcpsAcquisitionTest::plot_grid() std::cout << "Plotting the acquisition grid. This can take a while..." << std::endl; try { - boost::filesystem::path p(gnuplot_executable); - boost::filesystem::path dir = p.parent_path(); + fs::path p(gnuplot_executable); + fs::path dir = p.parent_path(); const std::string &gnuplot_path = dir.native(); Gnuplot::set_GNUPlotPath(gnuplot_path); @@ -229,9 +236,9 @@ void BeidouB1iPcpsAcquisitionTest::plot_grid() } } std::string data_str = "./tmp-acq-bds-b1i"; - if (boost::filesystem::exists(data_str)) + if (fs::exists(data_str)) { - boost::filesystem::remove_all(data_str); + fs::remove_all(data_str); } } @@ -290,11 +297,11 @@ TEST_F(BeidouB1iPcpsAcquisitionTest, ValidationOfResults) if (FLAGS_plot_acq_grid == true) { std::string data_str = "./tmp-acq-bds-b1i"; - if (boost::filesystem::exists(data_str)) + if (fs::exists(data_str)) { - boost::filesystem::remove_all(data_str); + fs::remove_all(data_str); } - boost::filesystem::create_directory(data_str); + fs::create_directory(data_str); } std::shared_ptr acquisition = std::make_shared(config.get(), "Acquisition_B1", 1, 0); diff --git a/src/tests/unit-tests/signal-processing-blocks/acquisition/beidou_b3i_pcps_acquisition_test.cc b/src/tests/unit-tests/signal-processing-blocks/acquisition/beidou_b3i_pcps_acquisition_test.cc index d80ca6e66..8d39ac2ff 100644 --- a/src/tests/unit-tests/signal-processing-blocks/acquisition/beidou_b3i_pcps_acquisition_test.cc +++ b/src/tests/unit-tests/signal-processing-blocks/acquisition/beidou_b3i_pcps_acquisition_test.cc @@ -33,15 +33,14 @@ #include "Beidou_B3I.h" #include "acquisition_dump_reader.h" +#include "beidou_b3i_pcps_acquisition.h" #include "gnss_block_factory.h" #include "gnss_block_interface.h" #include "gnss_sdr_valve.h" #include "gnss_synchro.h" #include "gnuplot_i.h" -#include "beidou_b3i_pcps_acquisition.h" #include "in_memory_configuration.h" #include "test_flags.h" -#include #include #include #include @@ -52,12 +51,20 @@ #include #include #include + #ifdef GR_GREATER_38 #include #else #include #endif +#if HAS_STD_FILESYSTEM +#include +namespace fs = std::filesystem; +#else +#include +namespace fs = boost::filesystem; +#endif // ######## GNURADIO BLOCK MESSAGE RECEVER ######### class BeidouB3iPcpsAcquisitionTest_msg_rx; @@ -199,8 +206,8 @@ void BeidouB3iPcpsAcquisitionTest::plot_grid() std::cout << "Plotting the acquisition grid. This can take a while..." << std::endl; try { - boost::filesystem::path p(gnuplot_executable); - boost::filesystem::path dir = p.parent_path(); + fs::path p(gnuplot_executable); + fs::path dir = p.parent_path(); const std::string &gnuplot_path = dir.native(); Gnuplot::set_GNUPlotPath(gnuplot_path); @@ -228,9 +235,9 @@ void BeidouB3iPcpsAcquisitionTest::plot_grid() } } std::string data_str = "./tmp-acq-bds-b3i"; - if (boost::filesystem::exists(data_str)) + if (fs::exists(data_str)) { - boost::filesystem::remove_all(data_str); + fs::remove_all(data_str); } } @@ -289,11 +296,11 @@ TEST_F(BeidouB3iPcpsAcquisitionTest, ValidationOfResults) if (FLAGS_plot_acq_grid == true) { std::string data_str = "./tmp-acq-bds-b3i"; - if (boost::filesystem::exists(data_str)) + if (fs::exists(data_str)) { - boost::filesystem::remove_all(data_str); + fs::remove_all(data_str); } - boost::filesystem::create_directory(data_str); + fs::create_directory(data_str); } std::shared_ptr acquisition = std::make_shared(config.get(), "Acquisition_B3", 1, 0); diff --git a/src/tests/unit-tests/signal-processing-blocks/acquisition/galileo_e1_pcps_ambiguous_acquisition_test.cc b/src/tests/unit-tests/signal-processing-blocks/acquisition/galileo_e1_pcps_ambiguous_acquisition_test.cc index c31937d37..204acbb14 100644 --- a/src/tests/unit-tests/signal-processing-blocks/acquisition/galileo_e1_pcps_ambiguous_acquisition_test.cc +++ b/src/tests/unit-tests/signal-processing-blocks/acquisition/galileo_e1_pcps_ambiguous_acquisition_test.cc @@ -52,12 +52,21 @@ #include #include #include + #ifdef GR_GREATER_38 #include #else #include #endif +#if HAS_STD_FILESYSTEM +#include +namespace fs = std::filesystem; +#else +#include +namespace fs = boost::filesystem; +#endif + // ######## GNURADIO BLOCK MESSAGE RECEVER ######### class GalileoE1PcpsAmbiguousAcquisitionTest_msg_rx; @@ -199,8 +208,8 @@ void GalileoE1PcpsAmbiguousAcquisitionTest::plot_grid() std::cout << "Plotting the acquisition grid. This can take a while..." << std::endl; try { - boost::filesystem::path p(gnuplot_executable); - boost::filesystem::path dir = p.parent_path(); + fs::path p(gnuplot_executable); + fs::path dir = p.parent_path(); const std::string& gnuplot_path = dir.native(); Gnuplot::set_GNUPlotPath(gnuplot_path); @@ -228,9 +237,9 @@ void GalileoE1PcpsAmbiguousAcquisitionTest::plot_grid() } } std::string data_str = "./tmp-acq-gal1"; - if (boost::filesystem::exists(data_str)) + if (fs::exists(data_str)) { - boost::filesystem::remove_all(data_str); + fs::remove_all(data_str); } } @@ -283,11 +292,11 @@ TEST_F(GalileoE1PcpsAmbiguousAcquisitionTest, ValidationOfResults) if (FLAGS_plot_acq_grid == true) { std::string data_str = "./tmp-acq-gal1"; - if (boost::filesystem::exists(data_str)) + if (fs::exists(data_str)) { - boost::filesystem::remove_all(data_str); + fs::remove_all(data_str); } - boost::filesystem::create_directory(data_str); + fs::create_directory(data_str); } double expected_delay_samples = 2920; //18250; diff --git a/src/tests/unit-tests/signal-processing-blocks/acquisition/gps_l1_ca_pcps_acquisition_test.cc b/src/tests/unit-tests/signal-processing-blocks/acquisition/gps_l1_ca_pcps_acquisition_test.cc index 8e6876aa9..42fe90a6b 100644 --- a/src/tests/unit-tests/signal-processing-blocks/acquisition/gps_l1_ca_pcps_acquisition_test.cc +++ b/src/tests/unit-tests/signal-processing-blocks/acquisition/gps_l1_ca_pcps_acquisition_test.cc @@ -41,7 +41,6 @@ #include "gps_l1_ca_pcps_acquisition.h" #include "in_memory_configuration.h" #include "test_flags.h" -#include #include #include #include @@ -52,12 +51,21 @@ #include #include #include + #ifdef GR_GREATER_38 #include #else #include #endif +#if HAS_STD_FILESYSTEM +#include +namespace fs = std::filesystem; +#else +#include +namespace fs = boost::filesystem; +#endif + // ######## GNURADIO BLOCK MESSAGE RECEVER ######### class GpsL1CaPcpsAcquisitionTest_msg_rx; @@ -200,8 +208,8 @@ void GpsL1CaPcpsAcquisitionTest::plot_grid() std::cout << "Plotting the acquisition grid. This can take a while..." << std::endl; try { - boost::filesystem::path p(gnuplot_executable); - boost::filesystem::path dir = p.parent_path(); + fs::path p(gnuplot_executable); + fs::path dir = p.parent_path(); const std::string &gnuplot_path = dir.native(); Gnuplot::set_GNUPlotPath(gnuplot_path); @@ -229,9 +237,9 @@ void GpsL1CaPcpsAcquisitionTest::plot_grid() } } std::string data_str = "./tmp-acq-gps1"; - if (boost::filesystem::exists(data_str)) + if (fs::exists(data_str)) { - boost::filesystem::remove_all(data_str); + fs::remove_all(data_str); } } @@ -290,11 +298,11 @@ TEST_F(GpsL1CaPcpsAcquisitionTest, ValidationOfResults) if (FLAGS_plot_acq_grid == true) { std::string data_str = "./tmp-acq-gps1"; - if (boost::filesystem::exists(data_str)) + if (fs::exists(data_str)) { - boost::filesystem::remove_all(data_str); + fs::remove_all(data_str); } - boost::filesystem::create_directory(data_str); + fs::create_directory(data_str); } std::shared_ptr acquisition = std::make_shared(config.get(), "Acquisition_1C", 1, 0); diff --git a/src/tests/unit-tests/signal-processing-blocks/acquisition/gps_l1_ca_pcps_opencl_acquisition_gsoc2013_test.cc b/src/tests/unit-tests/signal-processing-blocks/acquisition/gps_l1_ca_pcps_opencl_acquisition_gsoc2013_test.cc index 2eecb0e53..b28e72aec 100644 --- a/src/tests/unit-tests/signal-processing-blocks/acquisition/gps_l1_ca_pcps_opencl_acquisition_gsoc2013_test.cc +++ b/src/tests/unit-tests/signal-processing-blocks/acquisition/gps_l1_ca_pcps_opencl_acquisition_gsoc2013_test.cc @@ -60,16 +60,16 @@ class GpsL1CaPcpsOpenClAcquisitionGSoC2013Test_msg_rx; typedef boost::shared_ptr GpsL1CaPcpsOpenClAcquisitionGSoC2013Test_msg_rx_sptr; -GpsL1CaPcpsOpenClAcquisitionGSoC2013Test_msg_rx_sptr GpsL1CaPcpsOpenClAcquisitionGSoC2013Test_msg_rx_make(concurrent_queue& queue); +GpsL1CaPcpsOpenClAcquisitionGSoC2013Test_msg_rx_sptr GpsL1CaPcpsOpenClAcquisitionGSoC2013Test_msg_rx_make(Concurrent_Queue& queue); class GpsL1CaPcpsOpenClAcquisitionGSoC2013Test_msg_rx : public gr::block { private: - friend GpsL1CaPcpsOpenClAcquisitionGSoC2013Test_msg_rx_sptr GpsL1CaPcpsOpenClAcquisitionGSoC2013Test_msg_rx_make(concurrent_queue& queue); + friend GpsL1CaPcpsOpenClAcquisitionGSoC2013Test_msg_rx_sptr GpsL1CaPcpsOpenClAcquisitionGSoC2013Test_msg_rx_make(Concurrent_Queue& queue); void msg_handler_events(pmt::pmt_t msg); - GpsL1CaPcpsOpenClAcquisitionGSoC2013Test_msg_rx(concurrent_queue& queue); - concurrent_queue& channel_internal_queue; + GpsL1CaPcpsOpenClAcquisitionGSoC2013Test_msg_rx(Concurrent_Queue& queue); + Concurrent_Queue& channel_internal_queue; public: int rx_message; @@ -77,7 +77,7 @@ public: }; -GpsL1CaPcpsOpenClAcquisitionGSoC2013Test_msg_rx_sptr GpsL1CaPcpsOpenClAcquisitionGSoC2013Test_msg_rx_make(concurrent_queue& queue) +GpsL1CaPcpsOpenClAcquisitionGSoC2013Test_msg_rx_sptr GpsL1CaPcpsOpenClAcquisitionGSoC2013Test_msg_rx_make(Concurrent_Queue& queue) { return GpsL1CaPcpsOpenClAcquisitionGSoC2013Test_msg_rx_sptr(new GpsL1CaPcpsOpenClAcquisitionGSoC2013Test_msg_rx(queue)); } @@ -99,7 +99,7 @@ void GpsL1CaPcpsOpenClAcquisitionGSoC2013Test_msg_rx::msg_handler_events(pmt::pm } -GpsL1CaPcpsOpenClAcquisitionGSoC2013Test_msg_rx::GpsL1CaPcpsOpenClAcquisitionGSoC2013Test_msg_rx(concurrent_queue& queue) : gr::block("GpsL1CaPcpsOpenClAcquisitionGSoC2013Test_msg_rx", gr::io_signature::make(0, 0, 0), gr::io_signature::make(0, 0, 0)), channel_internal_queue(queue) +GpsL1CaPcpsOpenClAcquisitionGSoC2013Test_msg_rx::GpsL1CaPcpsOpenClAcquisitionGSoC2013Test_msg_rx(Concurrent_Queue& queue) : gr::block("GpsL1CaPcpsOpenClAcquisitionGSoC2013Test_msg_rx", gr::io_signature::make(0, 0, 0), gr::io_signature::make(0, 0, 0)), channel_internal_queue(queue) { this->message_port_register_in(pmt::mp("events")); this->set_msg_handler(pmt::mp("events"), boost::bind(&GpsL1CaPcpsOpenClAcquisitionGSoC2013Test_msg_rx::msg_handler_events, this, _1)); @@ -139,7 +139,7 @@ protected: void process_message(); void stop_queue(); - concurrent_queue channel_internal_queue; + Concurrent_Queue channel_internal_queue; gr::msg_queue::sptr queue; gr::top_block_sptr top_block; std::shared_ptr acquisition; diff --git a/src/tests/unit-tests/signal-processing-blocks/acquisition/gps_l2_m_pcps_acquisition_test.cc b/src/tests/unit-tests/signal-processing-blocks/acquisition/gps_l2_m_pcps_acquisition_test.cc index 0ade6eb89..ae50d3bb0 100644 --- a/src/tests/unit-tests/signal-processing-blocks/acquisition/gps_l2_m_pcps_acquisition_test.cc +++ b/src/tests/unit-tests/signal-processing-blocks/acquisition/gps_l2_m_pcps_acquisition_test.cc @@ -41,7 +41,6 @@ #include "gps_l2_m_pcps_acquisition.h" #include "in_memory_configuration.h" #include "test_flags.h" -#include #include #include #include @@ -53,12 +52,21 @@ #include #include #include + #ifdef GR_GREATER_38 #include #else #include #endif +#if HAS_STD_FILESYSTEM +#include +namespace fs = std::filesystem; +#else +#include +namespace fs = boost::filesystem; +#endif + // ######## GNURADIO BLOCK MESSAGE RECEVER ######### class GpsL2MPcpsAcquisitionTest_msg_rx; @@ -203,8 +211,8 @@ void GpsL2MPcpsAcquisitionTest::plot_grid() std::cout << "Plotting the acquisition grid. This can take a while..." << std::endl; try { - boost::filesystem::path p(gnuplot_executable); - boost::filesystem::path dir = p.parent_path(); + fs::path p(gnuplot_executable); + fs::path dir = p.parent_path(); const std::string &gnuplot_path = dir.native(); Gnuplot::set_GNUPlotPath(gnuplot_path); @@ -232,9 +240,9 @@ void GpsL2MPcpsAcquisitionTest::plot_grid() } } std::string data_str = "./tmp-acq-gps2"; - if (boost::filesystem::exists(data_str)) + if (fs::exists(data_str)) { - boost::filesystem::remove_all(data_str); + fs::remove_all(data_str); } } @@ -289,11 +297,11 @@ TEST_F(GpsL2MPcpsAcquisitionTest, ValidationOfResults) if (FLAGS_plot_acq_grid == true) { std::string data_str = "./tmp-acq-gps2"; - if (boost::filesystem::exists(data_str)) + if (fs::exists(data_str)) { - boost::filesystem::remove_all(data_str); + fs::remove_all(data_str); } - boost::filesystem::create_directory(data_str); + fs::create_directory(data_str); } init(); diff --git a/src/tests/unit-tests/signal-processing-blocks/telemetry_decoder/gps_l1_ca_telemetry_decoder_test.cc b/src/tests/unit-tests/signal-processing-blocks/telemetry_decoder/gps_l1_ca_telemetry_decoder_test.cc index 9271f669b..0998bb035 100644 --- a/src/tests/unit-tests/signal-processing-blocks/telemetry_decoder/gps_l1_ca_telemetry_decoder_test.cc +++ b/src/tests/unit-tests/signal-processing-blocks/telemetry_decoder/gps_l1_ca_telemetry_decoder_test.cc @@ -48,7 +48,6 @@ #include "gnss_block_factory.h" #include "gnss_block_interface.h" #include "gnss_synchro.h" -#include "gps_l1_ca_dll_pll_c_aid_tracking.h" #include "gps_l1_ca_dll_pll_tracking.h" #include "gps_l1_ca_telemetry_decoder.h" #include "in_memory_configuration.h" diff --git a/src/tests/unit-tests/signal-processing-blocks/tracking/gps_l1_ca_dll_pll_tracking_test.cc b/src/tests/unit-tests/signal-processing-blocks/tracking/gps_l1_ca_dll_pll_tracking_test.cc index 1bce1e6b8..3e33bc3bf 100644 --- a/src/tests/unit-tests/signal-processing-blocks/tracking/gps_l1_ca_dll_pll_tracking_test.cc +++ b/src/tests/unit-tests/signal-processing-blocks/tracking/gps_l1_ca_dll_pll_tracking_test.cc @@ -41,7 +41,6 @@ #include "tracking_tests_flags.h" #include "tracking_true_obs_reader.h" #include -#include #include #include #include @@ -54,12 +53,21 @@ #include #include #include + #ifdef GR_GREATER_38 #include #else #include #endif +#if HAS_STD_FILESYSTEM +#include +namespace fs = std::filesystem; +#else +#include +namespace fs = boost::filesystem; +#endif + // ######## GNURADIO BLOCK MESSAGE RECEVER ######### class GpsL1CADllPllTrackingTest_msg_rx; @@ -125,7 +133,7 @@ public: std::string p4; std::string p5; std::string p6; - std::string implementation = "GPS_L1_CA_DLL_PLL_Tracking"; //"GPS_L1_CA_DLL_PLL_C_Aid_Tracking"; + std::string implementation = "GPS_L1_CA_DLL_PLL_Tracking"; const int baseband_sampling_freq = FLAGS_fs_gen_sps; @@ -807,8 +815,8 @@ TEST_F(GpsL1CADllPllTrackingTest, ValidationOfResults) { try { - boost::filesystem::path p(gnuplot_executable); - boost::filesystem::path dir = p.parent_path(); + fs::path p(gnuplot_executable); + fs::path dir = p.parent_path(); const std::string& gnuplot_path = dir.native(); Gnuplot::set_GNUPlotPath(gnuplot_path); auto decimate = static_cast(FLAGS_plot_decimate); diff --git a/src/tests/unit-tests/signal-processing-blocks/tracking/gps_l1_ca_dll_pll_tracking_test_fpga.cc b/src/tests/unit-tests/signal-processing-blocks/tracking/gps_l1_ca_dll_pll_tracking_test_fpga.cc index 9ca2cd870..747e4cbc5 100644 --- a/src/tests/unit-tests/signal-processing-blocks/tracking/gps_l1_ca_dll_pll_tracking_test_fpga.cc +++ b/src/tests/unit-tests/signal-processing-blocks/tracking/gps_l1_ca_dll_pll_tracking_test_fpga.cc @@ -209,8 +209,8 @@ GpsL1CADllPllTrackingTestFpga_msg_rx::GpsL1CADllPllTrackingTestFpga_msg_rx() : g this->message_port_register_in(pmt::mp("events")); this->set_msg_handler(pmt::mp("events"), boost::bind( - &GpsL1CADllPllTrackingTestFpga_msg_rx::msg_handler_events, - this, _1)); + &GpsL1CADllPllTrackingTestFpga_msg_rx::msg_handler_events, + this, _1)); rx_message = 0; } @@ -320,8 +320,6 @@ void GpsL1CADllPllTrackingTestFpga::configure_receiver() config->set_property("GNSS-SDR.internal_fs_sps", std::to_string(baseband_sampling_freq)); // Set Tracking - //config->set_property("Tracking_1C.implementation", - // "GPS_L1_CA_DLL_PLL_C_Aid_Tracking_Fpga"); config->set_property("Tracking_1C.implementation", "GPS_L1_CA_DLL_PLL_Tracking_Fpga"); config->set_property("Tracking_1C.item_type", "cshort"); diff --git a/src/tests/unit-tests/signal-processing-blocks/tracking/gps_l1_ca_kf_tracking_test.cc b/src/tests/unit-tests/signal-processing-blocks/tracking/gps_l1_ca_kf_tracking_test.cc index 7422aa286..0b16279f7 100644 --- a/src/tests/unit-tests/signal-processing-blocks/tracking/gps_l1_ca_kf_tracking_test.cc +++ b/src/tests/unit-tests/signal-processing-blocks/tracking/gps_l1_ca_kf_tracking_test.cc @@ -41,7 +41,6 @@ #include "tracking_interface.h" #include "tracking_true_obs_reader.h" #include -#include #include #include #include @@ -53,12 +52,21 @@ #include #include #include + #ifdef GR_GREATER_38 #include #else #include #endif +#if HAS_STD_FILESYSTEM +#include +namespace fs = std::filesystem; +#else +#include +namespace fs = boost::filesystem; +#endif + DEFINE_bool(plot_gps_l1_kf_tracking_test, false, "Plots results of GpsL1CAKfTrackingTest with gnuplot"); @@ -525,8 +533,8 @@ TEST_F(GpsL1CAKfTrackingTest, ValidationOfResults) { try { - boost::filesystem::path p(gnuplot_executable); - boost::filesystem::path dir = p.parent_path(); + fs::path p(gnuplot_executable); + fs::path dir = p.parent_path(); const std::string& gnuplot_path = dir.native(); Gnuplot::set_GNUPlotPath(gnuplot_path); diff --git a/src/tests/unit-tests/signal-processing-blocks/tracking/tracking_pull-in_test.cc b/src/tests/unit-tests/signal-processing-blocks/tracking/tracking_pull-in_test.cc index 05787d5bd..21567e373 100644 --- a/src/tests/unit-tests/signal-processing-blocks/tracking/tracking_pull-in_test.cc +++ b/src/tests/unit-tests/signal-processing-blocks/tracking/tracking_pull-in_test.cc @@ -55,7 +55,6 @@ #include "tracking_tests_flags.h" #include "tracking_true_obs_reader.h" #include -#include #include #include #include @@ -69,12 +68,21 @@ #include #include #include + #ifdef GR_GREATER_38 #include #else #include #endif +#if HAS_STD_FILESYSTEM +#include +namespace fs = std::filesystem; +#else +#include +namespace fs = boost::filesystem; +#endif + // ######## GNURADIO TRACKING BLOCK MESSAGE RECEVER ######### class TrackingPullInTest_msg_rx; @@ -965,8 +973,8 @@ TEST_F(TrackingPullInTest, ValidationOfResults) { try { - boost::filesystem::path p(gnuplot_executable); - boost::filesystem::path dir = p.parent_path(); + fs::path p(gnuplot_executable); + fs::path dir = p.parent_path(); const std::string& gnuplot_path = dir.native(); Gnuplot::set_GNUPlotPath(gnuplot_path); auto decimate = static_cast(FLAGS_plot_decimate); diff --git a/src/utils/front-end-cal/CMakeLists.txt b/src/utils/front-end-cal/CMakeLists.txt index a8d0e244e..80f05cc2b 100644 --- a/src/utils/front-end-cal/CMakeLists.txt +++ b/src/utils/front-end-cal/CMakeLists.txt @@ -56,6 +56,13 @@ endif() add_executable(front-end-cal ${CMAKE_CURRENT_SOURCE_DIR}/main.cc) +if(${FILESYSTEM_FOUND}) + target_compile_definitions(front-end-cal PRIVATE -DHAS_STD_FILESYSTEM=1) + target_link_libraries(front-end-cal PRIVATE std::filesystem) +else() + target_link_libraries(front-end-cal PRIVATE Boost::filesystem Boost::system) +endif() + target_link_libraries(front-end-cal PUBLIC Volkgnsssdr::volkgnsssdr ${ORC_LIBRARIES} @@ -64,7 +71,6 @@ target_link_libraries(front-end-cal front_end_cal_lib gnss_sdr_flags PRIVATE - Boost::filesystem Gflags::gflags Glog::glog ) diff --git a/src/utils/front-end-cal/main.cc b/src/utils/front-end-cal/main.cc index 989ba2348..83b664362 100644 --- a/src/utils/front-end-cal/main.cc +++ b/src/utils/front-end-cal/main.cc @@ -51,7 +51,6 @@ #include // for bad_any_cast #include #include -#include #include #include #include @@ -83,6 +82,14 @@ #include #include +#if HAS_STD_FILESYSTEM +#include +namespace fs = std::filesystem; +#else +#include +namespace fs = boost::filesystem; +#endif + DECLARE_string(log_dir); Concurrent_Map global_gps_ephemeris_map; @@ -284,14 +291,14 @@ int main(int argc, char** argv) } else { - const boost::filesystem::path p(FLAGS_log_dir); - if (!boost::filesystem::exists(p)) + const fs::path p(FLAGS_log_dir); + if (!fs::exists(p)) { std::cout << "The path " << FLAGS_log_dir << " does not exist, attempting to create it" << std::endl; - boost::filesystem::create_directory(p); + fs::create_directory(p); } std::cout << "Logging with be done at " << FLAGS_log_dir << std::endl; diff --git a/src/utils/rinex2assist/CMakeLists.txt b/src/utils/rinex2assist/CMakeLists.txt index d42b379b5..312462ea1 100644 --- a/src/utils/rinex2assist/CMakeLists.txt +++ b/src/utils/rinex2assist/CMakeLists.txt @@ -55,8 +55,8 @@ find_program(UNCOMPRESS_EXECUTABLE uncompress ) if(Boost_FOUND) + set(CMAKE_CXX_STANDARD 11) set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wno-deprecated") - add_executable(rinex2assist ${CMAKE_CURRENT_SOURCE_DIR}/main.cc) target_link_libraries(rinex2assist