1
0
mirror of https://github.com/gnss-sdr/gnss-sdr synced 2024-12-12 19:20:32 +00:00

Merge with next and enabling KF VTL experimental tracking

This commit is contained in:
Javier Arribas 2021-02-24 11:41:27 +01:00
commit 56943fc12d
161 changed files with 7617 additions and 7396 deletions

41
.github/DCO.txt vendored Normal file
View File

@ -0,0 +1,41 @@
Developer Certificate of Origin
Version 1.1
SPDX-License-Identifier: GPL-3.0-or-later
Copyright (C) 2021 Centre Tecnològic de Telecomunicacions de Catalunya (CTTC)
and its contributors.
Parc Mediterrani de la Tecnologia (PMT)
Building B4
Av. Carl Friedrich Gauss 7
08860 - Castelldefels (Spain)
Everyone is permitted to copy and distribute verbatim copies of this
license document, but changing it is not allowed.
Developer's Certificate of Origin 1.1
By making a contribution to this project, I certify that:
(a) The contribution was created in whole or in part by me and I
have the right to submit it under the open source license
indicated in the file; or
(b) The contribution is based upon previous work that, to the best
of my knowledge, is covered under an appropriate open source
license and I have the right under that license to submit that
work with modifications, whether created in whole or in part
by me, under the same open source license (unless I am
permitted to submit under a different license), as indicated
in the file; or
(c) The contribution was provided directly to me by some other
person who certified (a), (b) or (c) and I have not modified
it.
(d) I understand and agree that this project and the contribution
are public and that a record of the contribution (including all
personal information I submit with it, including my sign-off) is
maintained indefinitely and may be redistributed consistent with
this project or the open source license(s) involved.

View File

@ -7,25 +7,35 @@ SPDX-License-Identifier: GPL-3.0-or-later
)
[comment]: # (
SPDX-FileCopyrightText: 2011-2020 Carles Fernandez-Prades <carles.fernandez@cttc.es>
SPDX-FileCopyrightText: 2011-2021 Carles Fernandez-Prades <carles.fernandez@cttc.es>
)
<!-- prettier-ignore-end -->
Any code contributions going into GNSS-SDR will become part of a GPL-licensed,
open source repository. It is therefore imperative that code submissions belong
to the authors, and that submitters have the authority to merge that code into
the public GNSS-SDR codebase.
For that purpose, we use the
[Developer's Certificate of Origin](https://github.com/gnss-sdr/gnss-sdr/blob/next/.github/DCO.txt).
It is the same document used by other projects. Signing the DCO states that
there are no legal reasons to not merge your code.
To sign the DCO, suffix your git commits with a `Signed-off-by:` line. When
using the command line, you can use `git commit -s` to automatically add this
line. If there were multiple authors of the code, or other types of
stakeholders, make sure that all are listed, each with a separate
`Signed-off-by:` line.
Before submitting your pull request, please make sure the following is done:
1. You undertake the
[Contributor Covenant Code of Conduct](https://github.com/gnss-sdr/gnss-sdr/blob/master/CODE_OF_CONDUCT.md).
2. If you are a first-time contributor, after your pull request you will be
asked to sign an Individual Contributor License Agreement
([CLA](https://en.wikipedia.org/wiki/Contributor_License_Agreement)) before
your code gets accepted into `master`. This license is for your protection
as a Contributor as well as for the protection of
[CTTC](http://www.cttc.es/); it does not change your rights to use your own
contributions for any other purpose. Except for the license granted therein
to CTTC and recipients of software distributed by CTTC, you reserve all
right, title, and interest in and to your contributions. The information you
provide in that CLA will be maintained in accordance with
[CTTC's privacy policy](http://www.cttc.es/privacy/).
2. You have read the
[Developer's Certificate of Origin](https://github.com/gnss-sdr/gnss-sdr/blob/next/.github/DCO.txt)
and
[signed your commits](https://gnss-sdr.org/docs/tutorials/using-git/#sign-your-commits)
as an indication of fulfillment.
3. You have read the
[Contributing Guidelines](https://github.com/gnss-sdr/gnss-sdr/blob/master/CONTRIBUTING.md).
4. You have read the [coding style guide](https://gnss-sdr.org/coding-style/).

View File

@ -51,6 +51,7 @@ David Pubill david.pubill@cttc.cat Contributor
Fran Fabra fabra@ice.csic.es Contributor
Gabriel Araujo gabriel.araujo.5000@gmail.com Contributor
Gerald LaMountain gerald@gece.neu.edu Contributor
Jim Melton jim.melton@sncorp.com Contributor
Josh Schindehette jschindehette@geontech.com Contributor
Leonardo Tonetto tonetto.dev@gmail.com Contributor
Mara Branzanti mara.branzanti@gmail.com Contributor

View File

@ -332,7 +332,7 @@ set(GNSSSDR_GNSS_SIM_LOCAL_VERSION "master")
set(GNSSSDR_GPSTK_LOCAL_VERSION "8.0.0")
set(GNSSSDR_MATIO_LOCAL_VERSION "1.5.19")
set(GNSSSDR_PUGIXML_LOCAL_VERSION "1.11.4")
set(GNSSSDR_PROTOCOLBUFFERS_LOCAL_VERSION "3.14.0")
set(GNSSSDR_PROTOCOLBUFFERS_LOCAL_VERSION "3.15.0")
set(GNSSSDR_BENCHMARK_LOCAL_VERSION "1.5.2")
set(GNSSSDR_MATHJAX_EXTERNAL_VERSION "2.7.7")

View File

@ -6,7 +6,7 @@ SPDX-License-Identifier: GPL-3.0-or-later
)
[comment]: # (
SPDX-FileCopyrightText: 2011-2020 Carles Fernandez-Prades <carles.fernandez@cttc.es>
SPDX-FileCopyrightText: 2011-2021 Carles Fernandez-Prades <carles.fernandez@cttc.es>
)
<!-- prettier-ignore-end -->
@ -116,8 +116,11 @@ $ git checkout -b my_feature
```
Now you can do changes, add files, do commits (please take a look at
[how to write good commit messages](https://chris.beams.io/posts/git-commit/)!)
and push them to your repository:
[how to write good commit messages](https://chris.beams.io/posts/git-commit/),
and do not forget to
[sign your commits](https://gnss-sdr.org/docs/tutorials/using-git/#sign-your-commits)
if you plan to submit your code to the upstream repository in a pull-request,
see below) and push them to your repository:
```
$ git push origin my_feature
@ -133,6 +136,24 @@ $ git pull --rebase upstream next
### How to submit a pull request
Any code contributions going into GNSS-SDR will become part of a GPL-licensed,
open source repository. It is therefore imperative that code submissions belong
to the authors, and that submitters have the authority to merge that code into
the public GNSS-SDR codebase.
For that purpose, we use the
[Developer's Certificate of Origin](https://github.com/gnss-sdr/gnss-sdr/blob/next/.github/DCO.txt).
It is the same document used by other projects. Signing the DCO states that
there are no legal reasons to not merge your code.
To sign the DCO, suffix your git commits with a `Signed-off-by:` line. When
using the command line, you can use `git commit -s` to automatically add this
line. If there were multiple authors of the code, or other types of
stakeholders, make sure that all are listed, each with a separate
`Signed-off-by:` line. See
[how to sign commits](https://gnss-sdr.org/docs/tutorials/using-git/#sign-your-commits)
for details on how to tell Git to sign commits by default.
Before submitting your code, please be sure to
[apply clang-format](https://gnss-sdr.org/coding-style/#use-tools-for-automated-code-formatting).
@ -147,6 +168,7 @@ discuss potential modifications, and even push follow-up commits if necessary.
Some things that will increase the chance that your pull request is accepted:
- Your commits must be signed.
- Avoid platform-dependent code. If your code require external dependencies,
they must be available as packages in
[Debian OldStable](https://wiki.debian.org/DebianOldStable).

View File

@ -122,7 +122,10 @@ endif()
# 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"))
if((CMAKE_CXX_COMPILER_ID STREQUAL "GNU") AND (CMAKE_CXX_COMPILER_VERSION VERSION_GREATER "8.0.0"))
if(CMAKE_CXX_COMPILER_VERSION VERSION_LESS "8.99")
set(UNDEFINED_BEHAVIOR_WITHOUT_LINKING TRUE)
endif()
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"))
@ -207,9 +210,10 @@ if(CXX_FILESYSTEM_HAVE_FS)
]] 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 UNDEFINED_BEHAVIOR_WITHOUT_LINKING)
check_cxx_source_compiles("${code}" CXX_FILESYSTEM_NO_LINK_NEEDED)
set(can_link ${CXX_FILESYSTEM_NO_LINK_NEEDED})
endif()
if(NOT CXX_FILESYSTEM_NO_LINK_NEEDED)
set(prev_libraries ${CMAKE_REQUIRED_LIBRARIES})

View File

@ -22,14 +22,29 @@ SPDX-FileCopyrightText: 2011-2021 Carles Fernandez-Prades <carles.fernandez@cttc
- Fix building when using the Xcode generator, Xcode >= 12 and CMake >= 3.19.
- Fix building of FPGA blocks when linking against GNU Radio >= 3.9 and/or
Boost >= 1.74.
- Fix linking of the `<filesystem>` library when using GCC 8.x and GNU Radio >=
3.8.
### Improvements in Maintainability:
- The Contributor License Agreement (CLA) signing for new contributors has been
replaced by a
[Developer's Certificate of Origin (DCO)](https://github.com/gnss-sdr/gnss-sdr/blob/next/.github/DCO.txt),
which implies that contributed commits in a pull request need to be signed as
a manifestation that contributors have the right to submit their work under
the open source license indicated in the contributed file(s) (instead of
asking them to sign the CLA document).
- Improved handling of change in GNU Radio 3.9 FFT API.
- Improved handling of the filesystem library.
- Added an abstract class `SignalSourceInterface` and a common base class
`SignalSourceBase`, which allow to remove a lot of duplicated code in Signal
Source blocks, and further abstract file-based interfaces behind them.
- Do not apply clang-tidy fixes to protobuf-generated headers.
- Refactored private implementation of flow graph connection and disconnection
for improved source code readability.
- Added a base class for GNSS ephemeris, saving some duplicated code and
providing a common nomenclature for ephemeris' parameters. New generated XML
files make use of the new parameters' name.
### Improvements in Usability:
@ -37,6 +52,9 @@ SPDX-FileCopyrightText: 2011-2021 Carles Fernandez-Prades <carles.fernandez@cttc
some common inconsistencies in the configuration file.
- Provide hints to the user in case of failed flow graph connection due to
inconsistencies in the configuration file.
- Fix segmentation fault if the RINEX output was disabled.
- Added a feature that optionally enables the remote monitoring of GPS and
Galileo ephemeris using UDP and protobuffers.
&nbsp;

View File

@ -105,9 +105,10 @@ Google submitted KML (formerly Keyhole Markup Language) to the Open Geospatial C
The C++ programming language is standardized by the International Organization for Standardization (ISO), with the latest standard version ratified and published by ISO in December 2017 as ISO/IEC 14882:2017 (informally known as C++17). The list of supported C++ standards (the highest available is automatically selected by the CMake script):
<ul>
<li><strong>Draft C++20</strong>: Check the <a href="https://github.com/cplusplus/draft" target="_blank">C++ standard draft sources at GitHub</a>.</li>
<li><strong>C++17</strong>: The current ISO C++ standard is officially known as <em>ISO International Standard ISO/IEC 14882:2017 Programming languages C++</em>. You can get it from <a href="https://www.iso.org/standard/68564.html" target="_blank">ISO</a>, <a href="https://webstore.iec.ch/publication/62162" target="_blank">IEC</a> or <a href="https://webstore.ansi.org/Standards/ISO/ISOIEC148822017" target="_blank">ANSI</a>. The closest free working document available is <a href="http://www.open-std.org/jtc1/sc22/wg21/docs/papers/2017/n4659.pdf" target="_blank">N4659</a>.</li>
<li><strong>C++14</strong>: The former ISO C++ standard was officially known as <em>ISO International Standard ISO/IEC 14882:2014 Programming languages C++</em>. You can get it from <a href="https://www.iso.org/standard/64029.html" target="_blank">ISO</a> or <a href="https://webstore.ansi.org/RecordDetail.aspx?sku=INCITS/ISO/IEC+14882:2014+(2016)" target="_blank">ANSI</a>. The closest free working document available is <a href="http://www.open-std.org/jtc1/sc22/wg21/docs/papers/2014/n4296.pdf" target="_blank">N4296</a>.</li>
<li><strong>Draft C++23</strong>: Check the <a href="https://github.com/cplusplus/draft" target="_blank">C++ standard draft sources at GitHub</a>.</li>
<li><strong>C++20</strong>: The current ISO C++ standard is officially known as <em>ISO International Standard ISO/IEC 14882:2020(E) Programming languages C++</em>. You can get it from <a href="https://www.iso.org/standard/79358.html" target="_blank">ISO</a>, <a href="https://webstore.iec.ch/publication/68285" target="_blank">IEC</a> or <a href="https://webstore.ansi.org/Standards/ISO/ISOIEC148822020" target="_blank">ANSI</a>. The closest free working document available is <a href="https://github.com/cplusplus/draft/releases/download/n4868/n4868.pdf" target="_blank">N4868</a>.</li>
<li><strong>C++17</strong>: A former ISO C++ standard was officially known as <em>ISO International Standard ISO/IEC 14882:2017 Programming languages C++</em>. You can get it from <a href="https://www.iso.org/standard/68564.html" target="_blank">ISO</a>, <a href="https://webstore.iec.ch/publication/62162" target="_blank">IEC</a> or <a href="https://webstore.ansi.org/Standards/ISO/ISOIEC148822017" target="_blank">ANSI</a>. The closest free working document available is <a href="http://www.open-std.org/jtc1/sc22/wg21/docs/papers/2017/n4659.pdf" target="_blank">N4659</a>.</li>
<li><strong>C++14</strong>: A former ISO C++ standard was officially known as <em>ISO International Standard ISO/IEC 14882:2014 Programming languages C++</em>. You can get it from <a href="https://www.iso.org/standard/64029.html" target="_blank">ISO</a> or <a href="https://webstore.ansi.org/RecordDetail.aspx?sku=INCITS/ISO/IEC+14882:2014+(2016)" target="_blank">ANSI</a>. The closest free working document available is <a href="http://www.open-std.org/jtc1/sc22/wg21/docs/papers/2014/n4296.pdf" target="_blank">N4296</a>.</li>
<li><strong>C++11</strong>: An older ISO C++ standard was ISO/IEC 14882:2011. You can get it from <a href="https://www.iso.org/standard/50372.html" target="_blank">ISO</a>. The closest free working document available is <a href="http://www.open-std.org/jtc1/sc22/wg21/docs/papers/2012/n3337.pdf" target="_blank">N3337</a>.</li>
</ul>

View File

@ -0,0 +1,53 @@
// SPDX-License-Identifier: BSD-3-Clause
// SPDX-FileCopyrightText: 2018-2021 Carles Fernandez-Prades <carles.fernandez@cttc.es>
syntax = "proto3";
package gnss_sdr;
message GalileoEphemeris {
int32 PRN = 1; // SV ID
double M_0 = 2; // Mean anomaly at reference time [semi-circles]
double delta_n = 3; // Mean motion difference from computed value [semi-circles/sec]
double ecc = 4; // Eccentricity
double sqrtA = 5; // Square root of the semi-major axis [meters^1/2]
double OMEGA_0 = 6; // Longitude of ascending node of orbital plane at weekly epoch [semi-circles]
double i_0 = 7; // Inclination angle at reference time [semi-circles]
double omega = 8; // Argument of perigee [semi-circles]
double OMEGAdot = 9; // Rate of right ascension [semi-circles/sec]
double idot = 10; // Rate of inclination angle [semi-circles/sec]
double Cuc = 11; // Amplitude of the cosine harmonic correction term to the argument of latitude [radians]
double Cus = 12; // Amplitude of the sine harmonic correction term to the argument of latitude [radians]
double Crc = 13; // Amplitude of the cosine harmonic correction term to the orbit radius [meters]
double Crs = 14; // Amplitude of the sine harmonic correction term to the orbit radius [meters]
double Cic = 15; // Amplitude of the cosine harmonic correction term to the angle of inclination [radians]
double Cis = 16; // Amplitude of the sine harmonic correction term to the angle of inclination [radians]
int32 toe = 17; // Ephemeris reference time [s]
// Clock correction parameters
int32 toc = 18; // Clock correction data reference Time of Week [sec]
double af0 = 19; // SV clock bias correction coefficient [s]
double af1 = 20; // SV clock drift correction coefficient [s/s]
double af2 = 21; // SV clock drift rate correction coefficient [s/s^2]
double satClkDrift = 22; // SV clock drift
double dtr = 23; // Relativistic clock correction term
// Time
int32 WN = 24; // Week number
int32 tow = 25; // Time of Week
// Galileo-specific parameters
int32 IOD_ephemeris = 26;
int32 IOD_nav = 27;
// SV status
int32 SISA = 28; // Signal in space accuracy index
int32 E5a_HS = 29; // E5a Signal Health Status
int32 E5b_HS = 30; // E5b Signal Health Status
int32 E1B_HS = 31; // E1B Signal Health Status
bool E5a_DVS = 32; // E5a Data Validity Status
bool E5b_DVS = 33; // E5b Data Validity Status
bool E1B_DVS = 34; // E1B Data Validity Status
double BGD_E1E5a = 35; // E1-E5a Broadcast Group Delay [s]
double BGD_E1E5b = 36; // E1-E5b Broadcast Group Delay [s]
}

View File

@ -0,0 +1,57 @@
// SPDX-License-Identifier: BSD-3-Clause
// SPDX-FileCopyrightText: 2018-2021 Carles Fernandez-Prades <carles.fernandez@cttc.es>
syntax = "proto3";
package gnss_sdr;
message GpsEphemeris {
int32 PRN = 1; // SV ID
double M_0 = 2; // Mean anomaly at reference time [semi-circles]
double delta_n = 3; // Mean motion difference from computed value [semi-circles/sec]
double ecc = 4; // Eccentricity
double sqrtA = 5; // Square root of the semi-major axis [meters^1/2]
double OMEGA_0 = 6; // Longitude of ascending node of orbital plane at weekly epoch [semi-circles]
double i_0 = 7; // Inclination angle at reference time [semi-circles]
double omega = 8; // Argument of perigee [semi-circles]
double OMEGAdot = 9; // Rate of right ascension [semi-circles/sec]
double idot = 10; // Rate of inclination angle [semi-circles/sec]
double Cuc = 11; // Amplitude of the cosine harmonic correction term to the argument of latitude [radians]
double Cus = 12; // Amplitude of the sine harmonic correction term to the argument of latitude [radians]
double Crc = 13; // Amplitude of the cosine harmonic correction term to the orbit radius [meters]
double Crs = 14; // Amplitude of the sine harmonic correction term to the orbit radius [meters]
double Cic = 15; // Amplitude of the cosine harmonic correction term to the angle of inclination [radians]
double Cis = 16; // Amplitude of the sine harmonic correction term to the angle of inclination [radians]
int32 toe = 17; // Ephemeris reference time [s]
// Clock correction parameters
int32 toc = 18; // Clock correction data reference Time of Week [sec]
double af0 = 19; // SV clock bias correction coefficient [s]
double af1 = 20; // SV clock drift correction coefficient [s/s]
double af2 = 21; // SV clock drift rate correction coefficient [s/s^2]
double satClkDrift = 22; // SV clock drift
double dtr = 23; // Relativistic clock correction term
// Time
int32 WN = 24; // Week number
int32 tow = 25; // Time of Week
// GPS-specific parameters
int32 code_on_L2 = 26; // If 1, P code ON in L2; if 2, C/A code ON in L2;
bool L2_P_data_flag = 27; // When true, indicates that the NAV data stream was commanded OFF on the P-code of the L2 channel
int32 SV_accuracy = 28; // User Range Accuracy (URA) index of the SV (reference paragraph 6.2.1) for the standard positioning service user (Ref 20.3.3.3.1.3 IS-GPS-200L)
int32 SV_health = 29; // Satellite heath status
double TGD = 30; // Estimated Group Delay Differential: L1-L2 correction term only for the benefit of "L1 P(Y)" or "L2 P(Y)" s users [s]
int32 IODC = 31; // Issue of Data, Clock
int32 IODE_SF2 = 32; // Issue of Data, Ephemeris (IODE), subframe 2
int32 IODE_SF3 = 33; // Issue of Data, Ephemeris (IODE), subframe 3
int32 AODO = 34; // Age of Data Offset (AODO) term for the navigation message correction table (NMCT) contained in subframe 4 (reference paragraph 20.3.3.5.1.9) [s]
bool fit_interval_flag = 35; // indicates the curve-fit interval used by the CS (Block II/IIA/IIR/IIR-M/IIF) and SS (Block IIIA) in determining the ephemeris parameters, as follows: 0 = 4 hours, 1 = greater than 4 hours.
double spare1 = 36;
double spare2 = 37;
bool integrity_status_flag = 38;
bool alert_flag = 39; // If true, indicates that the SV URA may be worse than indicated in d_SV_accuracy, use that SV at our own risk.
bool antispoofing_flag = 40; // If true, the AntiSpoofing mode is ON in that SV
}

View File

@ -6,7 +6,7 @@ SPDX-License-Identifier: GPL-3.0-or-later
)
[comment]: # (
SPDX-FileCopyrightText: 2011-2020 Carles Fernandez-Prades <carles.fernandez@cttc.es>
SPDX-FileCopyrightText: 2011-2021 Carles Fernandez-Prades <carles.fernandez@cttc.es>
)
<!-- prettier-ignore-end -->
@ -33,6 +33,8 @@ elements in an XML document.
- [cnav_ephemeris_map.xsd](./cnav_ephemeris_map.xsd) - GPS CNAV message
ephemeris parameters.
- [cnav_utc_model.xsd](./cnav_utc_model.xsd) - GPS CNAV message UTC model
parameters.
## Galileo

View File

@ -1,6 +1,6 @@
<xs:schema attributeFormDefault="unqualified" elementFormDefault="qualified" xmlns:xs="http://www.w3.org/2001/XMLSchema">
<!-- SPDX-License-Identifier: BSD-3-Clause -->
<!-- SPDX-FileCopyrightText: 2018-2020 Carles Fernandez-Prades <carles.fernandez@cttc.es> -->
<!-- SPDX-FileCopyrightText: 2018-2021 Carles Fernandez-Prades <carles.fernandez@cttc.es> -->
<xs:element name="boost_serialization">
<xs:complexType>
<xs:sequence>
@ -16,38 +16,46 @@
<xs:element name="second">
<xs:complexType>
<xs:sequence>
<xs:element type="xs:byte" name="i_satellite_PRN"/>
<xs:element type="xs:int" name="d_TOW"/>
<xs:element type="xs:float" name="d_Crs"/>
<xs:element type="xs:float" name="d_M_0"/>
<xs:element type="xs:float" name="d_Cuc"/>
<xs:element type="xs:float" name="d_e_eccentricity"/>
<xs:element type="xs:float" name="d_Cus"/>
<xs:element type="xs:int" name="d_Toe1"/>
<xs:element type="xs:int" name="d_Toe2"/>
<xs:element type="xs:byte" name="d_Toc"/>
<xs:element type="xs:float" name="d_Cic"/>
<xs:element type="xs:float" name="d_OMEGA0"/>
<xs:element type="xs:float" name="d_Cis"/>
<xs:element type="xs:float" name="d_i_0"/>
<xs:element type="xs:float" name="d_Crc"/>
<xs:element type="xs:float" name="d_OMEGA"/>
<xs:element type="xs:float" name="d_IDOT"/>
<xs:element type="xs:short" name="i_GPS_week"/>
<xs:element type="xs:float" name="d_TGD"/>
<xs:element type="xs:float" name="d_ISCL1"/>
<xs:element type="xs:float" name="d_ISCL2"/>
<xs:element type="xs:float" name="d_ISCL5I"/>
<xs:element type="xs:float" name="d_ISCL5Q"/>
<xs:element type="xs:float" name="d_DELTA_A"/>
<xs:element type="xs:float" name="d_A_DOT"/>
<xs:element type="xs:float" name="d_DELTA_OMEGA_DOT"/>
<xs:element type="xs:float" name="d_A_f0"/>
<xs:element type="xs:float" name="d_A_f1"/>
<xs:element type="xs:float" name="d_A_f2"/>
<xs:element type="xs:byte" name="b_integrity_status_flag"/>
<xs:element type="xs:byte" name="b_alert_flag"/>
<xs:element type="xs:byte" name="b_antispoofing_flag"/>
<xs:element type="xs:byte" name="PRN"/>
<xs:element type="xs:float" name="M_0"/>
<xs:element type="xs:float" name="delta_n"/>
<xs:element type="xs:float" name="ecc"/>
<xs:element type="xs:float" name="sqrtA"/>
<xs:element type="xs:float" name="OMEGA_0"/>
<xs:element type="xs:float" name="i_0"/>
<xs:element type="xs:float" name="omega"/>
<xs:element type="xs:float" name="OMEGAdot"/>
<xs:element type="xs:float" name="idot"/>
<xs:element type="xs:float" name="Cuc"/>
<xs:element type="xs:float" name="Cus"/>
<xs:element type="xs:float" name="Crc"/>
<xs:element type="xs:float" name="Crs"/>
<xs:element type="xs:float" name="Cic"/>
<xs:element type="xs:float" name="Cis"/>
<xs:element type="xs:int" name="toe"/>
<xs:element type="xs:int" name="toc"/>
<xs:element type="xs:float" name="af0"/>
<xs:element type="xs:float" name="af1"/>
<xs:element type="xs:float" name="af2"/>
<xs:element type="xs:short" name="WN"/>
<xs:element type="xs:int" name="tow"/>
<xs:element type="xs:float" name="satClkDrift"/>
<xs:element type="xs:float" name="dtr"/>
<xs:element type="xs:byte" name="IODE_SF2"/>
<xs:element type="xs:byte" name="IODE_SF3"/>
<xs:element type="xs:byte" name="code_on_L2"/>
<xs:element type="xs:byte" name="L2_P_data_flag"/>
<xs:element type="xs:byte" name="SV_accuracy"/>
<xs:element type="xs:byte" name="SV_health"/>
<xs:element type="xs:float" name="TGD"/>
<xs:element type="xs:byte" name="IODC"/>
<xs:element type="xs:short" name="AODO"/>
<xs:element type="xs:byte" name="fit_interval_flag"/>
<xs:element type="xs:float" name="spare1"/>
<xs:element type="xs:float" name="spare2"/>
<xs:element type="xs:byte" name="integrity_status_flag"/>
<xs:element type="xs:byte" name="alert_flag"/>
<xs:element type="xs:byte" name="antispoofing_flag"/>
</xs:sequence>
<xs:attribute type="xs:byte" name="class_id" use="optional"/>
<xs:attribute type="xs:byte" name="tracking_level" use="optional"/>

View File

@ -0,0 +1,31 @@
<xs:schema attributeFormDefault="unqualified" elementFormDefault="qualified" xmlns:xs="http://www.w3.org/2001/XMLSchema">
<!-- SPDX-License-Identifier: BSD-3-Clause -->
<!-- SPDX-FileCopyrightText: 2018-2021 Carles Fernandez-Prades <carles.fernandez@cttc.es> -->
<xs:element name="boost_serialization">
<xs:complexType>
<xs:sequence>
<xs:element name="GNSS-SDR_cnav_utc_model">
<xs:complexType>
<xs:sequence>
<xs:element type="xs:float" name="A0"/>
<xs:element type="xs:float" name="A1"/>
<xs:element type="xs:float" name="A2"/>
<xs:element type="xs:int" name="tot"/>
<xs:element type="xs:short" name="WN_T"/>
<xs:element type="xs:byte" name="DeltaT_LS"/>
<xs:element type="xs:short" name="WN_LSF"/>
<xs:element type="xs:byte" name="DN"/>
<xs:element type="xs:byte" name="DeltaT_LSF"/>
<xs:element type="xs:byte" name="valid"/>
</xs:sequence>
<xs:attribute type="xs:byte" name="class_id"/>
<xs:attribute type="xs:byte" name="tracking_level"/>
<xs:attribute type="xs:byte" name="version"/>
</xs:complexType>
</xs:element>
</xs:sequence>
<xs:attribute type="xs:string" name="signature"/>
<xs:attribute type="xs:byte" name="version"/>
</xs:complexType>
</xs:element>
</xs:schema>

View File

@ -1,6 +1,6 @@
<xs:schema attributeFormDefault="unqualified" elementFormDefault="qualified" xmlns:xs="http://www.w3.org/2001/XMLSchema">
IODE_SF<xs:schema attributeFormDefault="unqualified" elementFormDefault="qualified" xmlns:xs="http://www.w3.org/2001/XMLSchema">
<!-- SPDX-License-Identifier: BSD-3-Clause -->
<!-- SPDX-FileCopyrightText: 2018-2020 Carles Fernandez-Prades <carles.fernandez@cttc.es> -->
<!-- SPDX-FileCopyrightText: 2018-2021 Carles Fernandez-Prades <carles.fernandez@cttc.es> -->
<xs:element name="boost_serialization">
<xs:complexType>
<xs:sequence>
@ -16,44 +16,44 @@
<xs:element name="second">
<xs:complexType>
<xs:sequence>
<xs:element type="xs:byte" name="i_satellite_PRN"/>
<xs:element type="xs:int" name="d_TOW"/>
<xs:element type="xs:byte" name="d_IODE_SF2"/>
<xs:element type="xs:byte" name="d_IODE_SF3"/>
<xs:element type="xs:float" name="d_Crs"/>
<xs:element type="xs:float" name="d_Delta_n"/>
<xs:element type="xs:float" name="d_M_0"/>
<xs:element type="xs:float" name="d_Cuc"/>
<xs:element type="xs:float" name="d_e_eccentricity"/>
<xs:element type="xs:float" name="d_Cus"/>
<xs:element type="xs:float" name="d_sqrt_A"/>
<xs:element type="xs:int" name="d_Toe"/>
<xs:element type="xs:int" name="d_Toc"/>
<xs:element type="xs:float" name="d_Cic"/>
<xs:element type="xs:float" name="d_OMEGA0"/>
<xs:element type="xs:float" name="d_Cis"/>
<xs:element type="xs:float" name="d_i_0"/>
<xs:element type="xs:float" name="d_Crc"/>
<xs:element type="xs:float" name="d_OMEGA"/>
<xs:element type="xs:float" name="d_OMEGA_DOT"/>
<xs:element type="xs:float" name="d_IDOT"/>
<xs:element type="xs:byte" name="i_code_on_L2"/>
<xs:element type="xs:short" name="i_GPS_week"/>
<xs:element type="xs:byte" name="b_L2_P_data_flag"/>
<xs:element type="xs:byte" name="i_SV_accuracy"/>
<xs:element type="xs:byte" name="i_SV_health"/>
<xs:element type="xs:float" name="d_TGD"/>
<xs:element type="xs:byte" name="d_IODC"/>
<xs:element type="xs:short" name="i_AODO"/>
<xs:element type="xs:byte" name="b_fit_interval_flag"/>
<xs:element type="xs:float" name="d_spare1"/>
<xs:element type="xs:float" name="d_spare2"/>
<xs:element type="xs:float" name="d_A_f0"/>
<xs:element type="xs:float" name="d_A_f1"/>
<xs:element type="xs:float" name="d_A_f2"/>
<xs:element type="xs:byte" name="b_integrity_status_flag"/>
<xs:element type="xs:byte" name="b_alert_flag"/>
<xs:element type="xs:byte" name="b_antispoofing_flag"/>
<xs:element type="xs:byte" name="PRN"/>
<xs:element type="xs:int" name="tow"/>
<xs:element type="xs:byte" name="IODE_SF2"/>
<xs:element type="xs:byte" name="IODE_SF3"/>
<xs:element type="xs:float" name="Crs"/>
<xs:element type="xs:float" name="delta_n"/>
<xs:element type="xs:float" name="M_0"/>
<xs:element type="xs:float" name="Cuc"/>
<xs:element type="xs:float" name="ecc"/>
<xs:element type="xs:float" name="Cus"/>
<xs:element type="xs:float" name="sqrtA"/>
<xs:element type="xs:int" name="toe"/>
<xs:element type="xs:int" name="toc"/>
<xs:element type="xs:float" name="Cic"/>
<xs:element type="xs:float" name="OMEGA_0"/>
<xs:element type="xs:float" name="Cis"/>
<xs:element type="xs:float" name="i_0"/>
<xs:element type="xs:float" name="Crc"/>
<xs:element type="xs:float" name="omega"/>
<xs:element type="xs:float" name="OMEGAdot"/>
<xs:element type="xs:float" name="idot"/>
<xs:element type="xs:byte" name="code_on_L2"/>
<xs:element type="xs:short" name="WN"/>
<xs:element type="xs:byte" name="L2_P_data_flag"/>
<xs:element type="xs:byte" name="SV_accuracy"/>
<xs:element type="xs:byte" name="SV_health"/>
<xs:element type="xs:float" name="TGD"/>
<xs:element type="xs:byte" name="IODC"/>
<xs:element type="xs:short" name="AODO"/>
<xs:element type="xs:byte" name="fit_interval_flag"/>
<xs:element type="xs:float" name="spare1"/>
<xs:element type="xs:float" name="spare2"/>
<xs:element type="xs:float" name="af0"/>
<xs:element type="xs:float" name="af1"/>
<xs:element type="xs:float" name="af2"/>
<xs:element type="xs:byte" name="integrity_status_flag"/>
<xs:element type="xs:byte" name="alert_flag"/>
<xs:element type="xs:byte" name="antispoofing_flag"/>
</xs:sequence>
<xs:attribute type="xs:byte" name="class_id" use="optional"/>
<xs:attribute type="xs:byte" name="tracking_level" use="optional"/>

View File

@ -1,6 +1,6 @@
<xs:schema attributeFormDefault="unqualified" elementFormDefault="qualified" xmlns:xs="http://www.w3.org/2001/XMLSchema">
<!-- SPDX-License-Identifier: BSD-3-Clause -->
<!-- SPDX-FileCopyrightText: 2018-2020 Carles Fernandez-Prades <carles.fernandez@cttc.es> -->
<!-- SPDX-FileCopyrightText: 2018-2021 Carles Fernandez-Prades <carles.fernandez@cttc.es> -->
<xs:element name="boost_serialization">
<xs:complexType>
<xs:sequence>
@ -16,19 +16,19 @@
<xs:element name="second">
<xs:complexType>
<xs:sequence>
<xs:element type="xs:byte" name="i_satellite_PRN"/>
<xs:element type="xs:int" name="i_Toa"/>
<xs:element type="xs:byte" name="i_WNa"/>
<xs:element type="xs:byte" name="i_IODa"/>
<xs:element type="xs:float" name="d_Delta_i"/>
<xs:element type="xs:float" name="d_M_0"/>
<xs:element type="xs:float" name="d_e_eccentricity"/>
<xs:element type="xs:float" name="d_Delta_sqrt_A"/>
<xs:element type="xs:float" name="d_OMEGA0"/>
<xs:element type="xs:float" name="d_OMEGA"/>
<xs:element type="xs:float" name="d_OMEGA_DOT"/>
<xs:element type="xs:float" name="d_A_f0"/>
<xs:element type="xs:float" name="d_A_f1"/>
<xs:element type="xs:byte" name="PRN"/>
<xs:element type="xs:int" name="toa"/>
<xs:element type="xs:byte" name="WNa"/>
<xs:element type="xs:byte" name="IODa"/>
<xs:element type="xs:float" name="delta_i"/>
<xs:element type="xs:float" name="M_0"/>
<xs:element type="xs:float" name="ecc"/>
<xs:element type="xs:float" name="delta_sqrtA"/>
<xs:element type="xs:float" name="OMEGA_0"/>
<xs:element type="xs:float" name="omega"/>
<xs:element type="xs:float" name="OMEGAdot"/>
<xs:element type="xs:float" name="af0"/>
<xs:element type="xs:float" name="af1"/>
<xs:element type="xs:byte" name="E5b_HS"/>
<xs:element type="xs:byte" name="E1B_HS"/>
<xs:element type="xs:byte" name="E5a_HS"/>

View File

@ -1,6 +1,6 @@
<xs:schema attributeFormDefault="unqualified" elementFormDefault="qualified" xmlns:xs="http://www.w3.org/2001/XMLSchema">
<!-- SPDX-License-Identifier: BSD-3-Clause -->
<!-- SPDX-FileCopyrightText: 2018-2020 Carles Fernandez-Prades <carles.fernandez@cttc.es> -->
<!-- SPDX-FileCopyrightText: 2018-2021 Carles Fernandez-Prades <carles.fernandez@cttc.es> -->
<xs:element name="boost_serialization">
<xs:complexType>
<xs:sequence>
@ -16,43 +16,42 @@
<xs:element name="second">
<xs:complexType>
<xs:sequence>
<xs:element type="xs:byte" name="i_satellite_PRN"/>
<xs:element type="xs:float" name="M0_1"/>
<xs:element type="xs:float" name="delta_n_3"/>
<xs:element type="xs:float" name="e_1"/>
<xs:element type="xs:float" name="A_1"/>
<xs:element type="xs:float" name="OMEGA_0_2"/>
<xs:element type="xs:float" name="i_0_2"/>
<xs:element type="xs:float" name="omega_2"/>
<xs:element type="xs:float" name="OMEGA_dot_3"/>
<xs:element type="xs:float" name="iDot_2"/>
<xs:element type="xs:float" name="C_uc_3"/>
<xs:element type="xs:float" name="C_us_3"/>
<xs:element type="xs:float" name="C_rc_3"/>
<xs:element type="xs:float" name="C_rs_3"/>
<xs:element type="xs:float" name="C_ic_4"/>
<xs:element type="xs:float" name="C_is_4"/>
<xs:element type="xs:int" name="t0e_1"/>
<xs:element type="xs:int" name="t0c_4"/>
<xs:element type="xs:float" name="af0_4"/>
<xs:element type="xs:float" name="af1_4"/>
<xs:element type="xs:float" name="af2_4"/>
<xs:element type="xs:short" name="WN_5"/>
<xs:element type="xs:int" name="TOW_5"/>
<xs:element type="xs:float" name="Galileo_satClkDrift"/>
<xs:element type="xs:float" name="Galileo_dtr"/>
<xs:element type="xs:byte" name="PRN"/>
<xs:element type="xs:float" name="M_0"/>
<xs:element type="xs:float" name="delta_n"/>
<xs:element type="xs:float" name="ecc"/>
<xs:element type="xs:float" name="sqrtA"/>
<xs:element type="xs:float" name="OMEGA_0"/>
<xs:element type="xs:float" name="i_0"/>
<xs:element type="xs:float" name="omega"/>
<xs:element type="xs:float" name="OMEGAdot"/>
<xs:element type="xs:float" name="idot"/>
<xs:element type="xs:float" name="Cuc"/>
<xs:element type="xs:float" name="Cus"/>
<xs:element type="xs:float" name="Crc"/>
<xs:element type="xs:float" name="Crs"/>
<xs:element type="xs:float" name="Cic"/>
<xs:element type="xs:float" name="Cis"/>
<xs:element type="xs:int" name="toe"/>
<xs:element type="xs:int" name="toc"/>
<xs:element type="xs:float" name="af0"/>
<xs:element type="xs:float" name="af1"/>
<xs:element type="xs:float" name="af2"/>
<xs:element type="xs:short" name="WN"/>
<xs:element type="xs:int" name="tow"/>
<xs:element type="xs:float" name="satClkDrift"/>
<xs:element type="xs:float" name="dtr"/>
<xs:element type="xs:byte" name="IOD_ephemeris"/>
<xs:element type="xs:byte" name="IOD_nav_1"/>
<xs:element type="xs:byte" name="SISA_3"/>
<xs:element type="xs:byte" name="IOD_nav"/>
<xs:element type="xs:byte" name="SISA"/>
<xs:element type="xs:byte" name="E5a_HS"/>
<xs:element type="xs:byte" name="E5b_HS_5"/>
<xs:element type="xs:byte" name="E1B_HS_5"/>
<xs:element type="xs:byte" name="E5b_HS"/>
<xs:element type="xs:byte" name="E1B_HS"/>
<xs:element type="xs:byte" name="E5a_DVS"/>
<xs:element type="xs:byte" name="E5b_DVS_5"/>
<xs:element type="xs:byte" name="E1B_DVS_5"/>
<xs:element type="xs:float" name="BGD_E1E5a_5"/>
<xs:element type="xs:float" name="BGD_E1E5b_5"/>
<xs:element type="xs:byte" name="E5b_DVS"/>
<xs:element type="xs:byte" name="E1B_DVS"/>
<xs:element type="xs:float" name="BGD_E1E5a"/>
<xs:element type="xs:float" name="BGD_E1E5b"/>
<xs:element type="xs:byte" name="flag_all_ephemeris"/>
</xs:sequence>
<xs:attribute type="xs:byte" name="class_id" use="optional"/>

View File

@ -1,22 +1,22 @@
<xs:schema attributeFormDefault="unqualified" elementFormDefault="qualified" xmlns:xs="http://www.w3.org/2001/XMLSchema">
<!-- SPDX-License-Identifier: BSD-3-Clause -->
<!-- SPDX-FileCopyrightText: 2018-2020 Carles Fernandez-Prades <carles.fernandez@cttc.es> -->
<!-- SPDX-FileCopyrightText: 2018-2021 Carles Fernandez-Prades <carles.fernandez@cttc.es> -->
<xs:element name="boost_serialization">
<xs:complexType>
<xs:sequence>
<xs:element name="GNSS-SDR_gal_iono_model">
<xs:complexType>
<xs:sequence>
<xs:element type="xs:float" name="ai0_5"/>
<xs:element type="xs:float" name="ai1_5"/>
<xs:element type="xs:float" name="ai2_5"/>
<xs:element type="xs:int" name="TOW_5"/>
<xs:element type="xs:short" name="WN_5"/>
<xs:element type="xs:byte" name="Region1_flag_5"/>
<xs:element type="xs:byte" name="Region2_flag_5"/>
<xs:element type="xs:byte" name="Region3_flag_5"/>
<xs:element type="xs:byte" name="Region4_flag_5"/>
<xs:element type="xs:byte" name="Region5_flag_5"/>
<xs:element type="xs:float" name="ai0"/>
<xs:element type="xs:float" name="ai1"/>
<xs:element type="xs:float" name="ai2"/>
<xs:element type="xs:int" name="tow"/>
<xs:element type="xs:short" name="WN"/>
<xs:element type="xs:byte" name="Region1_flag"/>
<xs:element type="xs:byte" name="Region2_flag"/>
<xs:element type="xs:byte" name="Region3_flag"/>
<xs:element type="xs:byte" name="Region4_flag"/>
<xs:element type="xs:byte" name="Region5_flag"/>
</xs:sequence>
<xs:attribute type="xs:byte" name="class_id"/>
<xs:attribute type="xs:byte" name="tracking_level"/>

View File

@ -1,20 +1,20 @@
<xs:schema attributeFormDefault="unqualified" elementFormDefault="qualified" xmlns:xs="http://www.w3.org/2001/XMLSchema">
<!-- SPDX-License-Identifier: BSD-3-Clause -->
<!-- SPDX-FileCopyrightText: 2018-2020 Carles Fernandez-Prades <carles.fernandez@cttc.es> -->
<!-- SPDX-FileCopyrightText: 2018-2021 Carles Fernandez-Prades <carles.fernandez@cttc.es> -->
<xs:element name="boost_serialization">
<xs:complexType>
<xs:sequence>
<xs:element name="GNSS-SDR_gal_utc_model">
<xs:complexType>
<xs:sequence>
<xs:element type="xs:float" name="A0_6"/>
<xs:element type="xs:float" name="A1_6"/>
<xs:element type="xs:byte" name="Delta_tLS_6"/>
<xs:element type="xs:int" name="t0t_6"/>
<xs:element type="xs:short" name="WNot_6"/>
<xs:element type="xs:short" name="WN_LSF_6"/>
<xs:element type="xs:byte" name="DN_6"/>
<xs:element type="xs:byte" name="Delta_tLSF_6"/>
<xs:element type="xs:float" name="A0"/>
<xs:element type="xs:float" name="A1"/>
<xs:element type="xs:byte" name="Delta_tLS"/>
<xs:element type="xs:int" name="tot"/>
<xs:element type="xs:short" name="WNot"/>
<xs:element type="xs:short" name="WN_LSF"/>
<xs:element type="xs:byte" name="DN"/>
<xs:element type="xs:byte" name="Delta_tLSF"/>
<xs:element type="xs:byte" name="flag_utc_model"/>
</xs:sequence>
<xs:attribute type="xs:byte" name="class_id"/>

View File

@ -1,6 +1,6 @@
<xs:schema attributeFormDefault="unqualified" elementFormDefault="qualified" xmlns:xs="http://www.w3.org/2001/XMLSchema">
<!-- SPDX-License-Identifier: BSD-3-Clause -->
<!-- SPDX-FileCopyrightText: 2018-2020 Carles Fernandez-Prades <carles.fernandez@cttc.es> -->
<!-- SPDX-FileCopyrightText: 2018-2021 Carles Fernandez-Prades <carles.fernandez@cttc.es> -->
<xs:element name="boost_serialization">
<xs:complexType>
<xs:sequence>
@ -16,20 +16,20 @@
<xs:element name="second">
<xs:complexType>
<xs:sequence>
<xs:element type="xs:byte" name="i_satellite_PRN"/>
<xs:element type="xs:float" name="d_Delta_i"/>
<xs:element type="xs:byte" name="i_Toa"/>
<xs:element type="xs:byte" name="i_WNa"/>
<xs:element type="xs:float" name="d_M_0"/>
<xs:element type="xs:float" name="d_e_eccentricity"/>
<xs:element type="xs:float" name="d_sqrt_A"/>
<xs:element type="xs:float" name="d_OMEGA0"/>
<xs:element type="xs:float" name="d_OMEGA"/>
<xs:element type="xs:float" name="d_OMEGA_DOT"/>
<xs:element type="xs:byte" name="i_SV_health"/>
<xs:element type="xs:byte" name="i_AS_status"/>
<xs:element type="xs:float" name="d_A_f0"/>
<xs:element type="xs:float" name="d_A_f1"/>
<xs:element type="xs:byte" name="PRN"/>
<xs:element type="xs:float" name="delta_i"/>
<xs:element type="xs:byte" name="toa"/>
<xs:element type="xs:byte" name="WNa"/>
<xs:element type="xs:float" name="M_0"/>
<xs:element type="xs:float" name="ecc"/>
<xs:element type="xs:float" name="sqrtA"/>
<xs:element type="xs:float" name="OMEGA_0"/>
<xs:element type="xs:float" name="omega"/>
<xs:element type="xs:float" name="OMEGAdot"/>
<xs:element type="xs:byte" name="SV_health"/>
<xs:element type="xs:byte" name="AS_status"/>
<xs:element type="xs:float" name="af0"/>
<xs:element type="xs:float" name="af1"/>
</xs:sequence>
<xs:attribute type="xs:byte" name="class_id" use="optional"/>
<xs:attribute type="xs:byte" name="tracking_level" use="optional"/>

View File

@ -1,20 +1,20 @@
<xs:schema attributeFormDefault="unqualified" elementFormDefault="qualified" xmlns:xs="http://www.w3.org/2001/XMLSchema">
<!-- SPDX-License-Identifier: BSD-3-Clause -->
<!-- SPDX-FileCopyrightText: 2018-2020 Carles Fernandez-Prades <carles.fernandez@cttc.es> -->
<!-- SPDX-FileCopyrightText: 2018-2021 Carles Fernandez-Prades <carles.fernandez@cttc.es> -->
<xs:element name="boost_serialization">
<xs:complexType>
<xs:sequence>
<xs:element name="GNSS-SDR_iono_model">
<xs:complexType>
<xs:sequence>
<xs:element type="xs:float" name="d_alpha0"/>
<xs:element type="xs:float" name="d_alpha1"/>
<xs:element type="xs:float" name="d_alpha2"/>
<xs:element type="xs:float" name="d_alpha3"/>
<xs:element type="xs:float" name="d_beta0"/>
<xs:element type="xs:float" name="d_beta1"/>
<xs:element type="xs:float" name="d_beta2"/>
<xs:element type="xs:float" name="d_beta3"/>
<xs:element type="xs:float" name="alpha0"/>
<xs:element type="xs:float" name="alpha1"/>
<xs:element type="xs:float" name="alpha2"/>
<xs:element type="xs:float" name="alpha3"/>
<xs:element type="xs:float" name="beta0"/>
<xs:element type="xs:float" name="beta1"/>
<xs:element type="xs:float" name="beta2"/>
<xs:element type="xs:float" name="beta3"/>
</xs:sequence>
<xs:attribute type="xs:byte" name="class_id"/>
<xs:attribute type="xs:byte" name="tracking_level"/>

View File

@ -1,20 +1,21 @@
<xs:schema attributeFormDefault="unqualified" elementFormDefault="qualified" xmlns:xs="http://www.w3.org/2001/XMLSchema">
<!-- SPDX-License-Identifier: BSD-3-Clause -->
<!-- SPDX-FileCopyrightText: 2018-2020 Carles Fernandez-Prades <carles.fernandez@cttc.es> -->
<!-- SPDX-FileCopyrightText: 2018-2021 Carles Fernandez-Prades <carles.fernandez@cttc.es> -->
<xs:element name="boost_serialization">
<xs:complexType>
<xs:sequence>
<xs:element name="GNSS-SDR_utc_model">
<xs:complexType>
<xs:sequence>
<xs:element type="xs:float" name="d_A1"/>
<xs:element type="xs:float" name="d_A0"/>
<xs:element type="xs:int" name="d_t_OT"/>
<xs:element type="xs:short" name="i_WN_T"/>
<xs:element type="xs:byte" name="d_DeltaT_LS"/>
<xs:element type="xs:short" name="i_WN_LSF"/>
<xs:element type="xs:byte" name="i_DN"/>
<xs:element type="xs:byte" name="d_DeltaT_LSF"/>
<xs:element type="xs:float" name="A0"/>
<xs:element type="xs:float" name="A1"/>
<xs:element type="xs:float" name="A2"/>
<xs:element type="xs:int" name="tot"/>
<xs:element type="xs:short" name="WN_T"/>
<xs:element type="xs:byte" name="DeltaT_LS"/>
<xs:element type="xs:short" name="WN_LSF"/>
<xs:element type="xs:byte" name="DN"/>
<xs:element type="xs:byte" name="DeltaT_LSF"/>
<xs:element type="xs:byte" name="valid"/>
</xs:sequence>
<xs:attribute type="xs:byte" name="class_id"/>

View File

@ -804,6 +804,11 @@ Rtklib_Pvt::Rtklib_Pvt(const ConfigurationInterface* configuration,
pvt_output_parameters.protobuf_enabled = true;
}
// Read EPHEMERIS MONITOR Configuration
pvt_output_parameters.monitor_ephemeris_enabled = configuration->property(role + ".enable_monitor_ephemeris", false);
pvt_output_parameters.udp_eph_addresses = configuration->property(role + ".monitor_ephemeris_client_addresses", std::string("127.0.0.1"));
pvt_output_parameters.udp_eph_port = configuration->property(role + ".monitor_ephemeris_udp_port", 1234);
// Show time in local zone
pvt_output_parameters.show_local_time_zone = configuration->property(role + ".show_local_time_zone", false);

View File

@ -43,6 +43,7 @@
#include "gps_utc_model.h"
#include "gpx_printer.h"
#include "kml_printer.h"
#include "monitor_ephemeris_udp_sink.h"
#include "monitor_pvt.h"
#include "monitor_pvt_udp_sink.h"
#include "nmea_printer.h"
@ -399,6 +400,22 @@ rtklib_pvt_gs::rtklib_pvt_gs(uint32_t nchannels,
d_udp_sink_ptr = nullptr;
}
// EPHEMERIS MONITOR
d_flag_monitor_ephemeris_enabled = conf_.monitor_ephemeris_enabled;
if (d_flag_monitor_ephemeris_enabled)
{
std::string address_string = conf_.udp_eph_addresses;
std::vector<std::string> udp_addr_vec = split_string(address_string, '_');
std::sort(udp_addr_vec.begin(), udp_addr_vec.end());
udp_addr_vec.erase(std::unique(udp_addr_vec.begin(), udp_addr_vec.end()), udp_addr_vec.end());
d_eph_udp_sink_ptr = std::make_unique<Monitor_Ephemeris_Udp_Sink>(udp_addr_vec, conf_.udp_eph_port, conf_.protobuf_enabled);
}
else
{
d_eph_udp_sink_ptr = nullptr;
}
// Create Sys V message queue
d_first_fix = true;
d_sysv_msg_key = 1101;
@ -653,7 +670,7 @@ rtklib_pvt_gs::~rtklib_pvt_gs()
// Save Galileo UTC model parameters
file_name = d_xml_base_path + "gal_utc_model.xml";
if (d_internal_pvt_solver->galileo_utc_model.Delta_tLS_6 != 0.0)
if (d_internal_pvt_solver->galileo_utc_model.Delta_tLS != 0.0)
{
std::ofstream ofs;
try
@ -743,7 +760,7 @@ rtklib_pvt_gs::~rtklib_pvt_gs()
// Save Galileo iono parameters
file_name = d_xml_base_path + "gal_iono.xml";
if (d_internal_pvt_solver->galileo_iono.ai0_5 != 0.0)
if (d_internal_pvt_solver->galileo_iono.ai0 != 0.0)
{
std::ofstream ofs;
try
@ -1060,21 +1077,28 @@ void rtklib_pvt_gs::msg_handler_telemetry(const pmt::pmt_t& msg)
// ### GPS EPHEMERIS ###
const auto gps_eph = boost::any_cast<std::shared_ptr<Gps_Ephemeris>>(pmt::any_ref(msg));
DLOG(INFO) << "Ephemeris record has arrived from SAT ID "
<< gps_eph->i_satellite_PRN << " (Block "
<< gps_eph->satelliteBlock[gps_eph->i_satellite_PRN] << ")"
<< "inserted with Toe=" << gps_eph->d_Toe << " and GPS Week="
<< gps_eph->i_GPS_week;
<< gps_eph->PRN << " (Block "
<< gps_eph->satelliteBlock[gps_eph->PRN] << ")"
<< "inserted with Toe=" << gps_eph->toe << " and GPS Week="
<< gps_eph->WN;
// todo: Send only new sets of ephemeris (new TOE), not sent to the client
// send the new eph to the eph monitor (if enabled)
if (d_flag_monitor_ephemeris_enabled)
{
d_eph_udp_sink_ptr->write_gps_ephemeris(gps_eph);
}
// update/insert new ephemeris record to the global ephemeris map
if (d_rp->is_rinex_header_written()) // The header is already written, we can now log the navigation message data
if (d_rinex_output_enabled && d_rp->is_rinex_header_written()) // The header is already written, we can now log the navigation message data
{
bool new_annotation = false;
if (d_internal_pvt_solver->gps_ephemeris_map.find(gps_eph->i_satellite_PRN) == d_internal_pvt_solver->gps_ephemeris_map.cend())
if (d_internal_pvt_solver->gps_ephemeris_map.find(gps_eph->PRN) == d_internal_pvt_solver->gps_ephemeris_map.cend())
{
new_annotation = true;
}
else
{
if (d_internal_pvt_solver->gps_ephemeris_map[gps_eph->i_satellite_PRN].d_Toe != gps_eph->d_Toe)
if (d_internal_pvt_solver->gps_ephemeris_map[gps_eph->PRN].toe != gps_eph->toe)
{
new_annotation = true;
}
@ -1083,14 +1107,14 @@ void rtklib_pvt_gs::msg_handler_telemetry(const pmt::pmt_t& msg)
{
// New record!
std::map<int32_t, Gps_Ephemeris> new_eph;
new_eph[gps_eph->i_satellite_PRN] = *gps_eph;
new_eph[gps_eph->PRN] = *gps_eph;
d_rp->log_rinex_nav_gps_nav(d_type_of_rx, new_eph);
}
}
d_internal_pvt_solver->gps_ephemeris_map[gps_eph->i_satellite_PRN] = *gps_eph;
d_internal_pvt_solver->gps_ephemeris_map[gps_eph->PRN] = *gps_eph;
if (d_enable_rx_clock_correction == true)
{
d_user_pvt_solver->gps_ephemeris_map[gps_eph->i_satellite_PRN] = *gps_eph;
d_user_pvt_solver->gps_ephemeris_map[gps_eph->PRN] = *gps_eph;
}
}
else if (msg_type_hash_code == d_gps_iono_sptr_type_hash_code)
@ -1120,16 +1144,16 @@ void rtklib_pvt_gs::msg_handler_telemetry(const pmt::pmt_t& msg)
// ### GPS CNAV message ###
const auto gps_cnav_ephemeris = boost::any_cast<std::shared_ptr<Gps_CNAV_Ephemeris>>(pmt::any_ref(msg));
// update/insert new ephemeris record to the global ephemeris map
if (d_rp->is_rinex_header_written()) // The header is already written, we can now log the navigation message data
if (d_rinex_output_enabled && d_rp->is_rinex_header_written()) // The header is already written, we can now log the navigation message data
{
bool new_annotation = false;
if (d_internal_pvt_solver->gps_cnav_ephemeris_map.find(gps_cnav_ephemeris->i_satellite_PRN) == d_internal_pvt_solver->gps_cnav_ephemeris_map.cend())
if (d_internal_pvt_solver->gps_cnav_ephemeris_map.find(gps_cnav_ephemeris->PRN) == d_internal_pvt_solver->gps_cnav_ephemeris_map.cend())
{
new_annotation = true;
}
else
{
if (d_internal_pvt_solver->gps_cnav_ephemeris_map[gps_cnav_ephemeris->i_satellite_PRN].d_Toe1 != gps_cnav_ephemeris->d_Toe1)
if (d_internal_pvt_solver->gps_cnav_ephemeris_map[gps_cnav_ephemeris->PRN].toe1 != gps_cnav_ephemeris->toe1)
{
new_annotation = true;
}
@ -1138,14 +1162,14 @@ void rtklib_pvt_gs::msg_handler_telemetry(const pmt::pmt_t& msg)
{
// New record!
std::map<int32_t, Gps_CNAV_Ephemeris> new_cnav_eph;
new_cnav_eph[gps_cnav_ephemeris->i_satellite_PRN] = *gps_cnav_ephemeris;
new_cnav_eph[gps_cnav_ephemeris->PRN] = *gps_cnav_ephemeris;
d_rp->log_rinex_nav_gps_cnav(d_type_of_rx, new_cnav_eph);
}
}
d_internal_pvt_solver->gps_cnav_ephemeris_map[gps_cnav_ephemeris->i_satellite_PRN] = *gps_cnav_ephemeris;
d_internal_pvt_solver->gps_cnav_ephemeris_map[gps_cnav_ephemeris->PRN] = *gps_cnav_ephemeris;
if (d_enable_rx_clock_correction == true)
{
d_user_pvt_solver->gps_cnav_ephemeris_map[gps_cnav_ephemeris->i_satellite_PRN] = *gps_cnav_ephemeris;
d_user_pvt_solver->gps_cnav_ephemeris_map[gps_cnav_ephemeris->PRN] = *gps_cnav_ephemeris;
}
DLOG(INFO) << "New GPS CNAV ephemeris record has arrived ";
}
@ -1175,10 +1199,10 @@ void rtklib_pvt_gs::msg_handler_telemetry(const pmt::pmt_t& msg)
{
// ### GPS ALMANAC ###
const auto gps_almanac = boost::any_cast<std::shared_ptr<Gps_Almanac>>(pmt::any_ref(msg));
d_internal_pvt_solver->gps_almanac_map[gps_almanac->i_satellite_PRN] = *gps_almanac;
d_internal_pvt_solver->gps_almanac_map[gps_almanac->PRN] = *gps_almanac;
if (d_enable_rx_clock_correction == true)
{
d_user_pvt_solver->gps_almanac_map[gps_almanac->i_satellite_PRN] = *gps_almanac;
d_user_pvt_solver->gps_almanac_map[gps_almanac->PRN] = *gps_almanac;
}
DLOG(INFO) << "New GPS almanac record has arrived ";
}
@ -1189,20 +1213,26 @@ void rtklib_pvt_gs::msg_handler_telemetry(const pmt::pmt_t& msg)
// ### Galileo EPHEMERIS ###
const auto galileo_eph = boost::any_cast<std::shared_ptr<Galileo_Ephemeris>>(pmt::any_ref(msg));
// insert new ephemeris record
DLOG(INFO) << "Galileo New Ephemeris record inserted in global map with TOW =" << galileo_eph->TOW_5
<< ", GALILEO Week Number =" << galileo_eph->WN_5
DLOG(INFO) << "Galileo New Ephemeris record inserted in global map with TOW =" << galileo_eph->tow
<< ", GALILEO Week Number =" << galileo_eph->WN
<< " and Ephemeris IOD = " << galileo_eph->IOD_ephemeris;
// todo: Send only new sets of ephemeris (new TOE), not sent to the client
// send the new eph to the eph monitor (if enabled)
if (d_flag_monitor_ephemeris_enabled)
{
d_eph_udp_sink_ptr->write_galileo_ephemeris(galileo_eph);
}
// update/insert new ephemeris record to the global ephemeris map
if (d_rp->is_rinex_header_written()) // The header is already written, we can now log the navigation message data
if (d_rinex_output_enabled && d_rp->is_rinex_header_written()) // The header is already written, we can now log the navigation message data
{
bool new_annotation = false;
if (d_internal_pvt_solver->galileo_ephemeris_map.find(galileo_eph->i_satellite_PRN) == d_internal_pvt_solver->galileo_ephemeris_map.cend())
if (d_internal_pvt_solver->galileo_ephemeris_map.find(galileo_eph->PRN) == d_internal_pvt_solver->galileo_ephemeris_map.cend())
{
new_annotation = true;
}
else
{
if (d_internal_pvt_solver->galileo_ephemeris_map[galileo_eph->i_satellite_PRN].t0e_1 != galileo_eph->t0e_1)
if (d_internal_pvt_solver->galileo_ephemeris_map[galileo_eph->PRN].toe != galileo_eph->toe)
{
new_annotation = true;
}
@ -1211,14 +1241,14 @@ void rtklib_pvt_gs::msg_handler_telemetry(const pmt::pmt_t& msg)
{
// New record!
std::map<int32_t, Galileo_Ephemeris> new_gal_eph;
new_gal_eph[galileo_eph->i_satellite_PRN] = *galileo_eph;
new_gal_eph[galileo_eph->PRN] = *galileo_eph;
d_rp->log_rinex_nav_gal_nav(d_type_of_rx, new_gal_eph);
}
}
d_internal_pvt_solver->galileo_ephemeris_map[galileo_eph->i_satellite_PRN] = *galileo_eph;
d_internal_pvt_solver->galileo_ephemeris_map[galileo_eph->PRN] = *galileo_eph;
if (d_enable_rx_clock_correction == true)
{
d_user_pvt_solver->galileo_ephemeris_map[galileo_eph->i_satellite_PRN] = *galileo_eph;
d_user_pvt_solver->galileo_ephemeris_map[galileo_eph->PRN] = *galileo_eph;
}
}
else if (msg_type_hash_code == d_galileo_iono_sptr_type_hash_code)
@ -1251,28 +1281,28 @@ void rtklib_pvt_gs::msg_handler_telemetry(const pmt::pmt_t& msg)
const Galileo_Almanac sv2 = galileo_almanac_helper->get_almanac(2);
const Galileo_Almanac sv3 = galileo_almanac_helper->get_almanac(3);
if (sv1.i_satellite_PRN != 0)
if (sv1.PRN != 0)
{
d_internal_pvt_solver->galileo_almanac_map[sv1.i_satellite_PRN] = sv1;
d_internal_pvt_solver->galileo_almanac_map[sv1.PRN] = sv1;
if (d_enable_rx_clock_correction == true)
{
d_user_pvt_solver->galileo_almanac_map[sv1.i_satellite_PRN] = sv1;
d_user_pvt_solver->galileo_almanac_map[sv1.PRN] = sv1;
}
}
if (sv2.i_satellite_PRN != 0)
if (sv2.PRN != 0)
{
d_internal_pvt_solver->galileo_almanac_map[sv2.i_satellite_PRN] = sv2;
d_internal_pvt_solver->galileo_almanac_map[sv2.PRN] = sv2;
if (d_enable_rx_clock_correction == true)
{
d_user_pvt_solver->galileo_almanac_map[sv2.i_satellite_PRN] = sv2;
d_user_pvt_solver->galileo_almanac_map[sv2.PRN] = sv2;
}
}
if (sv3.i_satellite_PRN != 0)
if (sv3.PRN != 0)
{
d_internal_pvt_solver->galileo_almanac_map[sv3.i_satellite_PRN] = sv3;
d_internal_pvt_solver->galileo_almanac_map[sv3.PRN] = sv3;
if (d_enable_rx_clock_correction == true)
{
d_user_pvt_solver->galileo_almanac_map[sv3.i_satellite_PRN] = sv3;
d_user_pvt_solver->galileo_almanac_map[sv3.PRN] = sv3;
}
}
DLOG(INFO) << "New Galileo Almanac data have arrived ";
@ -1282,10 +1312,10 @@ void rtklib_pvt_gs::msg_handler_telemetry(const pmt::pmt_t& msg)
// ### Galileo Almanac ###
const auto galileo_alm = boost::any_cast<std::shared_ptr<Galileo_Almanac>>(pmt::any_ref(msg));
// update/insert new almanac record to the global almanac map
d_internal_pvt_solver->galileo_almanac_map[galileo_alm->i_satellite_PRN] = *galileo_alm;
d_internal_pvt_solver->galileo_almanac_map[galileo_alm->PRN] = *galileo_alm;
if (d_enable_rx_clock_correction == true)
{
d_user_pvt_solver->galileo_almanac_map[galileo_alm->i_satellite_PRN] = *galileo_alm;
d_user_pvt_solver->galileo_almanac_map[galileo_alm->PRN] = *galileo_alm;
}
}
@ -1301,16 +1331,16 @@ void rtklib_pvt_gs::msg_handler_telemetry(const pmt::pmt_t& msg)
<< " and Ephemeris IOD in UTC = " << glonass_gnav_eph->compute_GLONASS_time(glonass_gnav_eph->d_t_b)
<< " from SV = " << glonass_gnav_eph->i_satellite_slot_number;
// update/insert new ephemeris record to the global ephemeris map
if (d_rp->is_rinex_header_written()) // The header is already written, we can now log the navigation message data
if (d_rinex_output_enabled && d_rp->is_rinex_header_written()) // The header is already written, we can now log the navigation message data
{
bool new_annotation = false;
if (d_internal_pvt_solver->glonass_gnav_ephemeris_map.find(glonass_gnav_eph->i_satellite_PRN) == d_internal_pvt_solver->glonass_gnav_ephemeris_map.cend())
if (d_internal_pvt_solver->glonass_gnav_ephemeris_map.find(glonass_gnav_eph->PRN) == d_internal_pvt_solver->glonass_gnav_ephemeris_map.cend())
{
new_annotation = true;
}
else
{
if (d_internal_pvt_solver->glonass_gnav_ephemeris_map[glonass_gnav_eph->i_satellite_PRN].d_t_b != glonass_gnav_eph->d_t_b)
if (d_internal_pvt_solver->glonass_gnav_ephemeris_map[glonass_gnav_eph->PRN].d_t_b != glonass_gnav_eph->d_t_b)
{
new_annotation = true;
}
@ -1319,14 +1349,14 @@ void rtklib_pvt_gs::msg_handler_telemetry(const pmt::pmt_t& msg)
{
// New record!
std::map<int32_t, Glonass_Gnav_Ephemeris> new_glo_eph;
new_glo_eph[glonass_gnav_eph->i_satellite_PRN] = *glonass_gnav_eph;
new_glo_eph[glonass_gnav_eph->PRN] = *glonass_gnav_eph;
d_rp->log_rinex_nav_glo_gnav(d_type_of_rx, new_glo_eph);
}
}
d_internal_pvt_solver->glonass_gnav_ephemeris_map[glonass_gnav_eph->i_satellite_PRN] = *glonass_gnav_eph;
d_internal_pvt_solver->glonass_gnav_ephemeris_map[glonass_gnav_eph->PRN] = *glonass_gnav_eph;
if (d_enable_rx_clock_correction == true)
{
d_user_pvt_solver->glonass_gnav_ephemeris_map[glonass_gnav_eph->i_satellite_PRN] = *glonass_gnav_eph;
d_user_pvt_solver->glonass_gnav_ephemeris_map[glonass_gnav_eph->PRN] = *glonass_gnav_eph;
}
}
else if (msg_type_hash_code == d_glonass_gnav_utc_model_sptr_type_hash_code)
@ -1359,21 +1389,21 @@ void rtklib_pvt_gs::msg_handler_telemetry(const pmt::pmt_t& msg)
// ### Beidou EPHEMERIS ###
const auto bds_dnav_eph = boost::any_cast<std::shared_ptr<Beidou_Dnav_Ephemeris>>(pmt::any_ref(msg));
DLOG(INFO) << "Ephemeris record has arrived from SAT ID "
<< bds_dnav_eph->i_satellite_PRN << " (Block "
<< bds_dnav_eph->satelliteBlock[bds_dnav_eph->i_satellite_PRN] << ")"
<< "inserted with Toe=" << bds_dnav_eph->d_Toe << " and BDS Week="
<< bds_dnav_eph->i_BEIDOU_week;
<< bds_dnav_eph->PRN << " (Block "
<< bds_dnav_eph->satelliteBlock[bds_dnav_eph->PRN] << ")"
<< "inserted with Toe=" << bds_dnav_eph->toe << " and BDS Week="
<< bds_dnav_eph->WN;
// update/insert new ephemeris record to the global ephemeris map
if (d_rp->is_rinex_header_written()) // The header is already written, we can now log the navigation message data
if (d_rinex_output_enabled && d_rp->is_rinex_header_written()) // The header is already written, we can now log the navigation message data
{
bool new_annotation = false;
if (d_internal_pvt_solver->beidou_dnav_ephemeris_map.find(bds_dnav_eph->i_satellite_PRN) == d_internal_pvt_solver->beidou_dnav_ephemeris_map.cend())
if (d_internal_pvt_solver->beidou_dnav_ephemeris_map.find(bds_dnav_eph->PRN) == d_internal_pvt_solver->beidou_dnav_ephemeris_map.cend())
{
new_annotation = true;
}
else
{
if (d_internal_pvt_solver->beidou_dnav_ephemeris_map[bds_dnav_eph->i_satellite_PRN].d_Toc != bds_dnav_eph->d_Toc)
if (d_internal_pvt_solver->beidou_dnav_ephemeris_map[bds_dnav_eph->PRN].toc != bds_dnav_eph->toc)
{
new_annotation = true;
}
@ -1382,14 +1412,14 @@ void rtklib_pvt_gs::msg_handler_telemetry(const pmt::pmt_t& msg)
{
// New record!
std::map<int32_t, Beidou_Dnav_Ephemeris> new_bds_eph;
new_bds_eph[bds_dnav_eph->i_satellite_PRN] = *bds_dnav_eph;
new_bds_eph[bds_dnav_eph->PRN] = *bds_dnav_eph;
d_rp->log_rinex_nav_bds_dnav(d_type_of_rx, new_bds_eph);
}
}
d_internal_pvt_solver->beidou_dnav_ephemeris_map[bds_dnav_eph->i_satellite_PRN] = *bds_dnav_eph;
d_internal_pvt_solver->beidou_dnav_ephemeris_map[bds_dnav_eph->PRN] = *bds_dnav_eph;
if (d_enable_rx_clock_correction == true)
{
d_user_pvt_solver->beidou_dnav_ephemeris_map[bds_dnav_eph->i_satellite_PRN] = *bds_dnav_eph;
d_user_pvt_solver->beidou_dnav_ephemeris_map[bds_dnav_eph->PRN] = *bds_dnav_eph;
}
}
else if (msg_type_hash_code == d_beidou_dnav_iono_sptr_type_hash_code)
@ -1418,10 +1448,10 @@ void rtklib_pvt_gs::msg_handler_telemetry(const pmt::pmt_t& msg)
{
// ### BeiDou ALMANAC ###
const auto bds_dnav_almanac = boost::any_cast<std::shared_ptr<Beidou_Dnav_Almanac>>(pmt::any_ref(msg));
d_internal_pvt_solver->beidou_dnav_almanac_map[bds_dnav_almanac->i_satellite_PRN] = *bds_dnav_almanac;
d_internal_pvt_solver->beidou_dnav_almanac_map[bds_dnav_almanac->PRN] = *bds_dnav_almanac;
if (d_enable_rx_clock_correction == true)
{
d_user_pvt_solver->beidou_dnav_almanac_map[bds_dnav_almanac->i_satellite_PRN] = *bds_dnav_almanac;
d_user_pvt_solver->beidou_dnav_almanac_map[bds_dnav_almanac->PRN] = *bds_dnav_almanac;
}
DLOG(INFO) << "New BeiDou DNAV almanac record has arrived ";
}
@ -1807,7 +1837,7 @@ int rtklib_pvt_gs::work(int noutput_items, gr_vector_const_void_star& input_item
if (tmp_eph_iter_gps != d_internal_pvt_solver->gps_ephemeris_map.cend())
{
const uint32_t prn_aux = tmp_eph_iter_gps->second.i_satellite_PRN;
const uint32_t prn_aux = tmp_eph_iter_gps->second.PRN;
if ((prn_aux == in[i][epoch].PRN) and (std::string(in[i][epoch].Signal) == "1C"))
{
store_valid_observable = true;
@ -1815,7 +1845,7 @@ int rtklib_pvt_gs::work(int noutput_items, gr_vector_const_void_star& input_item
}
if (tmp_eph_iter_gal != d_internal_pvt_solver->galileo_ephemeris_map.cend())
{
const uint32_t prn_aux = tmp_eph_iter_gal->second.i_satellite_PRN;
const uint32_t prn_aux = tmp_eph_iter_gal->second.PRN;
if ((prn_aux == in[i][epoch].PRN) and ((std::string(in[i][epoch].Signal) == "1B") or (std::string(in[i][epoch].Signal) == "5X") or (std::string(in[i][epoch].Signal) == "7X")))
{
store_valid_observable = true;
@ -1823,7 +1853,7 @@ int rtklib_pvt_gs::work(int noutput_items, gr_vector_const_void_star& input_item
}
if (tmp_eph_iter_cnav != d_internal_pvt_solver->gps_cnav_ephemeris_map.cend())
{
const uint32_t prn_aux = tmp_eph_iter_cnav->second.i_satellite_PRN;
const uint32_t prn_aux = tmp_eph_iter_cnav->second.PRN;
if ((prn_aux == in[i][epoch].PRN) and ((std::string(in[i][epoch].Signal) == "2S") or (std::string(in[i][epoch].Signal) == "L5")))
{
store_valid_observable = true;
@ -1831,7 +1861,7 @@ int rtklib_pvt_gs::work(int noutput_items, gr_vector_const_void_star& input_item
}
if (tmp_eph_iter_glo_gnav != d_internal_pvt_solver->glonass_gnav_ephemeris_map.cend())
{
const uint32_t prn_aux = tmp_eph_iter_glo_gnav->second.i_satellite_PRN;
const uint32_t prn_aux = tmp_eph_iter_glo_gnav->second.PRN;
if ((prn_aux == in[i][epoch].PRN) and ((std::string(in[i][epoch].Signal) == "1G") or (std::string(in[i][epoch].Signal) == "2G")))
{
store_valid_observable = true;
@ -1839,7 +1869,7 @@ int rtklib_pvt_gs::work(int noutput_items, gr_vector_const_void_star& input_item
}
if (tmp_eph_iter_bds_dnav != d_internal_pvt_solver->beidou_dnav_ephemeris_map.cend())
{
const uint32_t prn_aux = tmp_eph_iter_bds_dnav->second.i_satellite_PRN;
const uint32_t prn_aux = tmp_eph_iter_bds_dnav->second.PRN;
if ((prn_aux == in[i][epoch].PRN) and ((std::string(in[i][epoch].Signal) == "B1") or (std::string(in[i][epoch].Signal) == "B3")))
{
store_valid_observable = true;

View File

@ -52,6 +52,7 @@ class Gps_Ephemeris;
class Gpx_Printer;
class Kml_Printer;
class Monitor_Pvt_Udp_Sink;
class Monitor_Ephemeris_Udp_Sink;
class Nmea_Printer;
class Pvt_Conf;
class Rinex_Printer;
@ -168,6 +169,7 @@ private:
std::unique_ptr<GeoJSON_Printer> d_geojson_printer;
std::unique_ptr<Rtcm_Printer> d_rtcm_printer;
std::unique_ptr<Monitor_Pvt_Udp_Sink> d_udp_sink_ptr;
std::unique_ptr<Monitor_Ephemeris_Udp_Sink> d_eph_udp_sink_ptr;
std::chrono::time_point<std::chrono::system_clock> d_start;
std::chrono::time_point<std::chrono::system_clock> d_end;
@ -260,6 +262,7 @@ private:
bool d_first_fix;
bool d_xml_storage;
bool d_flag_monitor_pvt_enabled;
bool d_flag_monitor_ephemeris_enabled;
bool d_show_local_time_zone;
bool d_waiting_obs_block_rx_clock_offset_correction_msg;
bool d_enable_rx_clock_correction;

View File

@ -5,6 +5,8 @@
# SPDX-License-Identifier: BSD-3-Clause
protobuf_generate_cpp(PROTO_SRCS PROTO_HDRS ${CMAKE_SOURCE_DIR}/docs/protobuf/monitor_pvt.proto)
protobuf_generate_cpp(PROTO_SRCS2 PROTO_HDRS2 ${CMAKE_SOURCE_DIR}/docs/protobuf/gps_ephemeris.proto)
protobuf_generate_cpp(PROTO_SRCS3 PROTO_HDRS3 ${CMAKE_SOURCE_DIR}/docs/protobuf/galileo_ephemeris.proto)
set(PVT_LIB_SOURCES
pvt_conf.cc
@ -18,6 +20,7 @@ set(PVT_LIB_SOURCES
rtcm.cc
rtklib_solver.cc
monitor_pvt_udp_sink.cc
monitor_ephemeris_udp_sink.cc
)
set(PVT_LIB_HEADERS
@ -34,6 +37,9 @@ set(PVT_LIB_HEADERS
monitor_pvt_udp_sink.h
monitor_pvt.h
serdes_monitor_pvt.h
serdes_galileo_eph.h
serdes_gps_eph.h
monitor_ephemeris_udp_sink.h
)
list(SORT PVT_LIB_HEADERS)
@ -44,14 +50,27 @@ if(USE_CMAKE_TARGET_SOURCES)
target_sources(pvt_libs
PRIVATE
${PROTO_SRCS}
${PROTO_SRCS2}
${PROTO_SRCS3}
${PROTO_HDRS}
${PROTO_HDRS2}
${PROTO_HDRS3}
${PVT_LIB_SOURCES}
PUBLIC
${PVT_LIB_HEADERS}
)
else()
source_group(Headers FILES ${PVT_LIB_HEADERS} ${PROTO_HDRS})
add_library(pvt_libs ${PVT_LIB_SOURCES} ${PROTO_SRCS} ${PVT_LIB_HEADERS} ${PROTO_HDRS})
source_group(Headers FILES ${PVT_LIB_HEADERS} ${PROTO_HDRS} ${PROTO_HDRS2} ${PROTO_HDRS3})
add_library(pvt_libs
${PVT_LIB_SOURCES}
${PROTO_SRCS}
${PROTO_SRCS2}
${PROTO_SRCS3}
${PVT_LIB_HEADERS}
${PROTO_HDRS}
${PROTO_HDRS2}
${PROTO_HDRS3}
)
endif()
target_link_libraries(pvt_libs

View File

@ -0,0 +1,112 @@
/*!
* \file monitor_ephemeris_udp_sink.cc
* \brief Interface of a class that sends serialized Gps_Ephemeris and
* Galileo_Ephemeris objects over udp to one or multiple endpoints.
* \author Javier Arribas, 2021. jarribas(at)cttc.es
*
* -----------------------------------------------------------------------------
*
* GNSS-SDR is a Global Navigation Satellite System software-defined receiver.
* This file is part of GNSS-SDR.
*
* Copyright (C) 2010-2021 (see AUTHORS file for a list of contributors)
* SPDX-License-Identifier: GPL-3.0-or-later
*
* -----------------------------------------------------------------------------
*/
#include "monitor_ephemeris_udp_sink.h"
#include <boost/archive/binary_oarchive.hpp>
#include <iostream>
#include <sstream>
Monitor_Ephemeris_Udp_Sink::Monitor_Ephemeris_Udp_Sink(const std::vector<std::string>& addresses, const uint16_t& port, bool protobuf_enabled) : socket{io_context}
{
for (const auto& address : addresses)
{
boost::asio::ip::udp::endpoint endpoint(boost::asio::ip::address::from_string(address, error), port);
endpoints.push_back(endpoint);
}
use_protobuf = protobuf_enabled;
if (use_protobuf)
{
serdes_gal = Serdes_Galileo_Eph();
serdes_gps = Serdes_Gps_Eph();
}
}
bool Monitor_Ephemeris_Udp_Sink::write_galileo_ephemeris(const std::shared_ptr<Galileo_Ephemeris>& monitor_gal_eph)
{
std::string outbound_data;
if (use_protobuf == false)
{
std::ostringstream archive_stream;
boost::archive::binary_oarchive oa{archive_stream};
oa << *monitor_gal_eph;
outbound_data = archive_stream.str();
}
else
{
outbound_data = "E";
outbound_data.append(serdes_gal.createProtobuffer(monitor_gal_eph));
}
for (const auto& endpoint : endpoints)
{
socket.open(endpoint.protocol(), error);
socket.connect(endpoint, error);
try
{
if (socket.send(boost::asio::buffer(outbound_data)) == 0)
{
return false;
}
}
catch (boost::system::system_error const& e)
{
return false;
}
}
return true;
}
bool Monitor_Ephemeris_Udp_Sink::write_gps_ephemeris(const std::shared_ptr<Gps_Ephemeris>& monitor_gps_eph)
{
std::string outbound_data;
if (use_protobuf == false)
{
std::ostringstream archive_stream;
boost::archive::binary_oarchive oa{archive_stream};
oa << *monitor_gps_eph;
outbound_data = archive_stream.str();
}
else
{
outbound_data = "G";
outbound_data.append(serdes_gps.createProtobuffer(monitor_gps_eph));
}
for (const auto& endpoint : endpoints)
{
socket.open(endpoint.protocol(), error);
socket.connect(endpoint, error);
try
{
if (socket.send(boost::asio::buffer(outbound_data)) == 0)
{
return false;
}
}
catch (boost::system::system_error const& e)
{
return false;
}
}
return true;
}

View File

@ -0,0 +1,62 @@
/*!
* \file monitor_ephemeris_udp_sink.h
* \brief Interface of a class that sends serialized Gps_Ephemeris and
* Galileo_Ephemeris objects over udp to one or multiple endpoints.
* \author Javier Arribas, 2021. jarribas(at)cttc.es
*
* -----------------------------------------------------------------------------
*
* GNSS-SDR is a Global Navigation Satellite System software-defined receiver.
* This file is part of GNSS-SDR.
*
* Copyright (C) 2010-2021 (see AUTHORS file for a list of contributors)
* SPDX-License-Identifier: GPL-3.0-or-later
*
* -----------------------------------------------------------------------------
*/
#ifndef GNSS_SDR_MONITOR_EPHEMERIS_UDP_SINK_H
#define GNSS_SDR_MONITOR_EPHEMERIS_UDP_SINK_H
#include "galileo_ephemeris.h"
#include "gps_ephemeris.h"
#include "serdes_galileo_eph.h"
#include "serdes_gps_eph.h"
#include <boost/asio.hpp>
#include <memory>
#include <string>
#include <vector>
/** \addtogroup PVT
* \{ */
/** \addtogroup PVT_libs
* \{ */
#if USE_BOOST_ASIO_IO_CONTEXT
using b_io_context = boost::asio::io_context;
#else
using b_io_context = boost::asio::io_service;
#endif
class Monitor_Ephemeris_Udp_Sink
{
public:
Monitor_Ephemeris_Udp_Sink(const std::vector<std::string>& addresses, const uint16_t& port, bool protobuf_enabled);
bool write_gps_ephemeris(const std::shared_ptr<Gps_Ephemeris>& monitor_gps_eph);
bool write_galileo_ephemeris(const std::shared_ptr<Galileo_Ephemeris>& monitor_gal_eph);
private:
Serdes_Galileo_Eph serdes_gal;
Serdes_Gps_Eph serdes_gps;
b_io_context io_context;
boost::asio::ip::udp::socket socket;
std::vector<boost::asio::ip::udp::endpoint> endpoints;
boost::system::error_code error;
bool use_protobuf;
};
/** \} */
/** \} */
#endif // GNSS_SDR_MONITOR_EPHEMERIS_UDP_SINK_H

View File

@ -29,7 +29,7 @@ Pvt_Conf::Pvt_Conf()
max_obs_block_rx_clock_offset_ms = 40;
rinex_version = 0;
rinexobs_rate_ms = 0;
rinex_name = "-";
rinex_name = std::string("-");
dump = false;
dump_mat = true;
@ -61,8 +61,10 @@ Pvt_Conf::Pvt_Conf()
enable_rx_clock_correction = true;
monitor_enabled = false;
monitor_ephemeris_enabled = false;
protobuf_enabled = true;
udp_port = 0;
udp_eph_port = 0;
pre_2009_file = false;
show_local_time_zone = false;
}

View File

@ -48,6 +48,7 @@ public:
std::string xml_output_path;
std::string rtcm_output_file_path;
std::string udp_addresses;
std::string udp_eph_addresses;
uint32_t type_of_receiver;
int32_t output_rate_ms;
@ -60,6 +61,7 @@ public:
int32_t rinexobs_rate_ms;
int32_t max_obs_block_rx_clock_offset_ms;
int udp_port;
int udp_eph_port;
uint16_t rtcm_tcp_port;
uint16_t rtcm_station_id;
@ -76,6 +78,7 @@ public:
bool xml_output_enabled;
bool rtcm_output_file_enabled;
bool monitor_enabled;
bool monitor_ephemeris_enabled;
bool protobuf_enabled;
bool enable_rx_clock_correction;
bool show_local_time_zone;

File diff suppressed because it is too large Load Diff

View File

@ -1625,95 +1625,95 @@ int32_t Rtcm::read_MT1019(const std::string& message, Gps_Ephemeris& gps_eph) co
}
// Fill Gps Ephemeris with message data content
gps_eph.i_satellite_PRN = static_cast<uint32_t>(Rtcm::bin_to_uint(message_bin.substr(index, 6)));
gps_eph.PRN = static_cast<uint32_t>(Rtcm::bin_to_uint(message_bin.substr(index, 6)));
index += 6;
gps_eph.i_GPS_week = static_cast<int32_t>(Rtcm::bin_to_uint(message_bin.substr(index, 10)));
gps_eph.WN = static_cast<int32_t>(Rtcm::bin_to_uint(message_bin.substr(index, 10)));
index += 10;
gps_eph.i_SV_accuracy = static_cast<int32_t>(Rtcm::bin_to_uint(message_bin.substr(index, 4)));
gps_eph.SV_accuracy = static_cast<int32_t>(Rtcm::bin_to_uint(message_bin.substr(index, 4)));
index += 4;
gps_eph.i_code_on_L2 = static_cast<int32_t>(Rtcm::bin_to_uint(message_bin.substr(index, 2)));
gps_eph.code_on_L2 = static_cast<int32_t>(Rtcm::bin_to_uint(message_bin.substr(index, 2)));
index += 2;
gps_eph.d_IDOT = static_cast<double>(Rtcm::bin_to_int(message_bin.substr(index, 14))) * I_DOT_LSB;
gps_eph.idot = static_cast<double>(Rtcm::bin_to_int(message_bin.substr(index, 14))) * I_DOT_LSB;
index += 14;
gps_eph.d_IODE_SF2 = static_cast<double>(Rtcm::bin_to_uint(message_bin.substr(index, 8)));
gps_eph.d_IODE_SF3 = static_cast<double>(Rtcm::bin_to_uint(message_bin.substr(index, 8)));
gps_eph.IODE_SF2 = static_cast<double>(Rtcm::bin_to_uint(message_bin.substr(index, 8)));
gps_eph.IODE_SF3 = static_cast<double>(Rtcm::bin_to_uint(message_bin.substr(index, 8)));
index += 8;
gps_eph.d_Toc = static_cast<double>(Rtcm::bin_to_uint(message_bin.substr(index, 16))) * T_OC_LSB;
gps_eph.toc = static_cast<double>(Rtcm::bin_to_uint(message_bin.substr(index, 16))) * T_OC_LSB;
index += 16;
gps_eph.d_A_f2 = static_cast<double>(Rtcm::bin_to_int(message_bin.substr(index, 8))) * A_F2_LSB;
gps_eph.af2 = static_cast<double>(Rtcm::bin_to_int(message_bin.substr(index, 8))) * A_F2_LSB;
index += 8;
gps_eph.d_A_f1 = static_cast<double>(Rtcm::bin_to_int(message_bin.substr(index, 16))) * A_F1_LSB;
gps_eph.af1 = static_cast<double>(Rtcm::bin_to_int(message_bin.substr(index, 16))) * A_F1_LSB;
index += 16;
gps_eph.d_A_f0 = static_cast<double>(Rtcm::bin_to_int(message_bin.substr(index, 22))) * A_F0_LSB;
gps_eph.af0 = static_cast<double>(Rtcm::bin_to_int(message_bin.substr(index, 22))) * A_F0_LSB;
index += 22;
gps_eph.d_IODC = static_cast<double>(Rtcm::bin_to_uint(message_bin.substr(index, 10)));
gps_eph.IODC = static_cast<double>(Rtcm::bin_to_uint(message_bin.substr(index, 10)));
index += 10;
gps_eph.d_Crs = static_cast<double>(Rtcm::bin_to_int(message_bin.substr(index, 16))) * C_RS_LSB;
gps_eph.Crs = static_cast<double>(Rtcm::bin_to_int(message_bin.substr(index, 16))) * C_RS_LSB;
index += 16;
gps_eph.d_Delta_n = static_cast<double>(Rtcm::bin_to_int(message_bin.substr(index, 16))) * DELTA_N_LSB;
gps_eph.delta_n = static_cast<double>(Rtcm::bin_to_int(message_bin.substr(index, 16))) * DELTA_N_LSB;
index += 16;
gps_eph.d_M_0 = static_cast<double>(Rtcm::bin_to_int(message_bin.substr(index, 32))) * M_0_LSB;
gps_eph.M_0 = static_cast<double>(Rtcm::bin_to_int(message_bin.substr(index, 32))) * M_0_LSB;
index += 32;
gps_eph.d_Cuc = static_cast<double>(Rtcm::bin_to_int(message_bin.substr(index, 16))) * C_UC_LSB;
gps_eph.Cuc = static_cast<double>(Rtcm::bin_to_int(message_bin.substr(index, 16))) * C_UC_LSB;
index += 16;
gps_eph.d_e_eccentricity = static_cast<double>(Rtcm::bin_to_uint(message_bin.substr(index, 32))) * ECCENTRICITY_LSB;
gps_eph.ecc = static_cast<double>(Rtcm::bin_to_uint(message_bin.substr(index, 32))) * ECCENTRICITY_LSB;
index += 32;
gps_eph.d_Cus = static_cast<double>(Rtcm::bin_to_int(message_bin.substr(index, 16))) * C_US_LSB;
gps_eph.Cus = static_cast<double>(Rtcm::bin_to_int(message_bin.substr(index, 16))) * C_US_LSB;
index += 16;
gps_eph.d_sqrt_A = static_cast<double>(Rtcm::bin_to_uint(message_bin.substr(index, 32))) * SQRT_A_LSB;
gps_eph.sqrtA = static_cast<double>(Rtcm::bin_to_uint(message_bin.substr(index, 32))) * SQRT_A_LSB;
index += 32;
gps_eph.d_Toe = static_cast<double>(Rtcm::bin_to_uint(message_bin.substr(index, 16))) * T_OE_LSB;
gps_eph.toe = static_cast<double>(Rtcm::bin_to_uint(message_bin.substr(index, 16))) * T_OE_LSB;
index += 16;
gps_eph.d_Cic = static_cast<double>(Rtcm::bin_to_int(message_bin.substr(index, 16))) * C_IC_LSB;
gps_eph.Cic = static_cast<double>(Rtcm::bin_to_int(message_bin.substr(index, 16))) * C_IC_LSB;
index += 16;
gps_eph.d_OMEGA0 = static_cast<double>(Rtcm::bin_to_int(message_bin.substr(index, 32))) * OMEGA_0_LSB;
gps_eph.OMEGA_0 = static_cast<double>(Rtcm::bin_to_int(message_bin.substr(index, 32))) * OMEGA_0_LSB;
index += 32;
gps_eph.d_Cis = static_cast<double>(Rtcm::bin_to_int(message_bin.substr(index, 16))) * C_IS_LSB;
gps_eph.Cis = static_cast<double>(Rtcm::bin_to_int(message_bin.substr(index, 16))) * C_IS_LSB;
index += 16;
gps_eph.d_i_0 = static_cast<double>(Rtcm::bin_to_int(message_bin.substr(index, 32))) * I_0_LSB;
gps_eph.i_0 = static_cast<double>(Rtcm::bin_to_int(message_bin.substr(index, 32))) * I_0_LSB;
index += 32;
gps_eph.d_Crc = static_cast<double>(Rtcm::bin_to_int(message_bin.substr(index, 16))) * C_RC_LSB;
gps_eph.Crc = static_cast<double>(Rtcm::bin_to_int(message_bin.substr(index, 16))) * C_RC_LSB;
index += 16;
gps_eph.d_OMEGA = static_cast<double>(Rtcm::bin_to_int(message_bin.substr(index, 32))) * OMEGA_LSB;
gps_eph.omega = static_cast<double>(Rtcm::bin_to_int(message_bin.substr(index, 32))) * OMEGA_LSB;
index += 32;
gps_eph.d_OMEGA_DOT = static_cast<double>(Rtcm::bin_to_int(message_bin.substr(index, 24))) * OMEGA_DOT_LSB;
gps_eph.OMEGAdot = static_cast<double>(Rtcm::bin_to_int(message_bin.substr(index, 24))) * OMEGA_DOT_LSB;
index += 24;
gps_eph.d_TGD = static_cast<double>(Rtcm::bin_to_int(message_bin.substr(index, 8))) * T_GD_LSB;
gps_eph.TGD = static_cast<double>(Rtcm::bin_to_int(message_bin.substr(index, 8))) * T_GD_LSB;
index += 8;
gps_eph.i_SV_health = static_cast<int32_t>(Rtcm::bin_to_uint(message_bin.substr(index, 6)));
gps_eph.SV_health = static_cast<int32_t>(Rtcm::bin_to_uint(message_bin.substr(index, 6)));
index += 6;
gps_eph.b_L2_P_data_flag = static_cast<bool>(Rtcm::bin_to_uint(message_bin.substr(index, 1)));
gps_eph.L2_P_data_flag = static_cast<bool>(Rtcm::bin_to_uint(message_bin.substr(index, 1)));
index += 1;
gps_eph.b_fit_interval_flag = static_cast<bool>(Rtcm::bin_to_uint(message_bin.substr(index, 1)));
gps_eph.fit_interval_flag = static_cast<bool>(Rtcm::bin_to_uint(message_bin.substr(index, 1)));
return 0;
}
@ -2162,79 +2162,79 @@ int32_t Rtcm::read_MT1045(const std::string& message, Galileo_Ephemeris& gal_eph
}
// Fill Galileo Ephemeris with message data content
gal_eph.i_satellite_PRN = static_cast<uint32_t>(Rtcm::bin_to_uint(message_bin.substr(index, 6)));
gal_eph.PRN = static_cast<uint32_t>(Rtcm::bin_to_uint(message_bin.substr(index, 6)));
index += 6;
gal_eph.WN_5 = static_cast<double>(Rtcm::bin_to_uint(message_bin.substr(index, 12)));
gal_eph.WN = static_cast<double>(Rtcm::bin_to_uint(message_bin.substr(index, 12)));
index += 12;
gal_eph.IOD_nav_1 = static_cast<int32_t>(Rtcm::bin_to_uint(message_bin.substr(index, 10)));
gal_eph.IOD_nav = static_cast<int32_t>(Rtcm::bin_to_uint(message_bin.substr(index, 10)));
index += 10;
gal_eph.SISA_3 = static_cast<double>(Rtcm::bin_to_uint(message_bin.substr(index, 8)));
gal_eph.SISA = static_cast<double>(Rtcm::bin_to_uint(message_bin.substr(index, 8)));
index += 8;
gal_eph.iDot_2 = static_cast<double>(Rtcm::bin_to_int(message_bin.substr(index, 14))) * I_DOT_2_LSB;
gal_eph.idot = static_cast<double>(Rtcm::bin_to_int(message_bin.substr(index, 14))) * I_DOT_2_LSB;
index += 14;
gal_eph.t0c_4 = static_cast<double>(Rtcm::bin_to_uint(message_bin.substr(index, 14))) * T0C_4_LSB;
gal_eph.toc = static_cast<double>(Rtcm::bin_to_uint(message_bin.substr(index, 14))) * T0C_4_LSB;
index += 14;
gal_eph.af2_4 = static_cast<double>(Rtcm::bin_to_int(message_bin.substr(index, 6))) * AF2_4_LSB;
gal_eph.af2 = static_cast<double>(Rtcm::bin_to_int(message_bin.substr(index, 6))) * AF2_4_LSB;
index += 6;
gal_eph.af1_4 = static_cast<double>(Rtcm::bin_to_int(message_bin.substr(index, 21))) * AF1_4_LSB;
gal_eph.af1 = static_cast<double>(Rtcm::bin_to_int(message_bin.substr(index, 21))) * AF1_4_LSB;
index += 21;
gal_eph.af0_4 = static_cast<double>(Rtcm::bin_to_int(message_bin.substr(index, 31))) * AF0_4_LSB;
gal_eph.af0 = static_cast<double>(Rtcm::bin_to_int(message_bin.substr(index, 31))) * AF0_4_LSB;
index += 31;
gal_eph.C_rs_3 = static_cast<double>(Rtcm::bin_to_int(message_bin.substr(index, 16))) * C_RS_3_LSB;
gal_eph.Crs = static_cast<double>(Rtcm::bin_to_int(message_bin.substr(index, 16))) * C_RS_3_LSB;
index += 16;
gal_eph.delta_n_3 = static_cast<double>(Rtcm::bin_to_int(message_bin.substr(index, 16))) * DELTA_N_3_LSB;
gal_eph.delta_n = static_cast<double>(Rtcm::bin_to_int(message_bin.substr(index, 16))) * DELTA_N_3_LSB;
index += 16;
gal_eph.M0_1 = static_cast<double>(Rtcm::bin_to_int(message_bin.substr(index, 32))) * M0_1_LSB;
gal_eph.M_0 = static_cast<double>(Rtcm::bin_to_int(message_bin.substr(index, 32))) * M0_1_LSB;
index += 32;
gal_eph.C_uc_3 = static_cast<double>(Rtcm::bin_to_int(message_bin.substr(index, 16))) * C_UC_3_LSB;
gal_eph.Cuc = static_cast<double>(Rtcm::bin_to_int(message_bin.substr(index, 16))) * C_UC_3_LSB;
index += 16;
gal_eph.e_1 = static_cast<double>(Rtcm::bin_to_uint(message_bin.substr(index, 32))) * E_1_LSB;
gal_eph.ecc = static_cast<double>(Rtcm::bin_to_uint(message_bin.substr(index, 32))) * E_1_LSB;
index += 32;
gal_eph.C_us_3 = static_cast<double>(Rtcm::bin_to_int(message_bin.substr(index, 16))) * C_US_3_LSB;
gal_eph.Cus = static_cast<double>(Rtcm::bin_to_int(message_bin.substr(index, 16))) * C_US_3_LSB;
index += 16;
gal_eph.A_1 = static_cast<double>(Rtcm::bin_to_uint(message_bin.substr(index, 32))) * A_1_LSB_GAL;
gal_eph.sqrtA = static_cast<double>(Rtcm::bin_to_uint(message_bin.substr(index, 32))) * A_1_LSB_GAL;
index += 32;
gal_eph.t0e_1 = static_cast<double>(Rtcm::bin_to_uint(message_bin.substr(index, 14))) * T0E_1_LSB;
gal_eph.toe = static_cast<double>(Rtcm::bin_to_uint(message_bin.substr(index, 14))) * T0E_1_LSB;
index += 14;
gal_eph.C_ic_4 = static_cast<double>(Rtcm::bin_to_int(message_bin.substr(index, 16))) * C_IC_4_LSB;
gal_eph.Cic = static_cast<double>(Rtcm::bin_to_int(message_bin.substr(index, 16))) * C_IC_4_LSB;
index += 16;
gal_eph.OMEGA_0_2 = static_cast<double>(Rtcm::bin_to_int(message_bin.substr(index, 32))) * OMEGA_0_2_LSB;
gal_eph.OMEGA_0 = static_cast<double>(Rtcm::bin_to_int(message_bin.substr(index, 32))) * OMEGA_0_2_LSB;
index += 32;
gal_eph.C_is_4 = static_cast<double>(Rtcm::bin_to_int(message_bin.substr(index, 16))) * C_IS_4_LSB;
gal_eph.Cis = static_cast<double>(Rtcm::bin_to_int(message_bin.substr(index, 16))) * C_IS_4_LSB;
index += 16;
gal_eph.i_0_2 = static_cast<double>(Rtcm::bin_to_int(message_bin.substr(index, 32))) * I_0_2_LSB;
gal_eph.i_0 = static_cast<double>(Rtcm::bin_to_int(message_bin.substr(index, 32))) * I_0_2_LSB;
index += 32;
gal_eph.C_rc_3 = static_cast<double>(Rtcm::bin_to_int(message_bin.substr(index, 16))) * C_RC_3_LSB;
gal_eph.Crc = static_cast<double>(Rtcm::bin_to_int(message_bin.substr(index, 16))) * C_RC_3_LSB;
index += 16;
gal_eph.omega_2 = static_cast<double>(Rtcm::bin_to_int(message_bin.substr(index, 32))) * OMEGA_2_LSB;
gal_eph.omega = static_cast<double>(Rtcm::bin_to_int(message_bin.substr(index, 32))) * OMEGA_2_LSB;
index += 32;
gal_eph.OMEGA_dot_3 = static_cast<double>(Rtcm::bin_to_int(message_bin.substr(index, 24))) * OMEGA_DOT_3_LSB;
gal_eph.OMEGAdot = static_cast<double>(Rtcm::bin_to_int(message_bin.substr(index, 24))) * OMEGA_DOT_3_LSB;
index += 24;
gal_eph.BGD_E1E5a_5 = static_cast<double>(Rtcm::bin_to_int(message_bin.substr(index, 10)));
gal_eph.BGD_E1E5a = static_cast<double>(Rtcm::bin_to_int(message_bin.substr(index, 10)));
index += 10;
gal_eph.E5a_HS = static_cast<uint32_t>(Rtcm::bin_to_uint(message_bin.substr(index, 2)));
@ -2266,23 +2266,23 @@ std::string Rtcm::print_MSM_1(const Gps_Ephemeris& gps_eph,
bool more_messages)
{
uint32_t msg_number = 0;
if (gps_eph.i_satellite_PRN != 0)
if (gps_eph.PRN != 0)
{
msg_number = 1071;
}
if (gps_cnav_eph.i_satellite_PRN != 0)
if (gps_cnav_eph.PRN != 0)
{
msg_number = 1071;
}
if (glo_gnav_eph.i_satellite_PRN != 0)
if (glo_gnav_eph.PRN != 0)
{
msg_number = 1081;
}
if (gal_eph.i_satellite_PRN != 0)
if (gal_eph.PRN != 0)
{
msg_number = 1091;
}
if (((gps_eph.i_satellite_PRN != 0) || (gps_cnav_eph.i_satellite_PRN != 0)) && (gal_eph.i_satellite_PRN != 0) && (glo_gnav_eph.i_satellite_PRN != 0))
if (((gps_eph.PRN != 0) || (gps_cnav_eph.PRN != 0)) && (gal_eph.PRN != 0) && (glo_gnav_eph.PRN != 0))
{
LOG(WARNING) << "MSM messages for observables from different systems are not defined"; // print two messages?
}
@ -2463,23 +2463,23 @@ std::string Rtcm::print_MSM_2(const Gps_Ephemeris& gps_eph,
bool more_messages)
{
uint32_t msg_number = 0;
if (gps_eph.i_satellite_PRN != 0)
if (gps_eph.PRN != 0)
{
msg_number = 1072;
}
if (gps_cnav_eph.i_satellite_PRN != 0)
if (gps_cnav_eph.PRN != 0)
{
msg_number = 1072;
}
if (glo_gnav_eph.i_satellite_PRN != 0)
if (glo_gnav_eph.PRN != 0)
{
msg_number = 1082;
}
if (gal_eph.i_satellite_PRN != 0)
if (gal_eph.PRN != 0)
{
msg_number = 1092;
}
if (((gps_eph.i_satellite_PRN != 0) || (gps_cnav_eph.i_satellite_PRN != 0)) && (gal_eph.i_satellite_PRN != 0) && (glo_gnav_eph.i_satellite_PRN != 0))
if (((gps_eph.PRN != 0) || (gps_cnav_eph.PRN != 0)) && (gal_eph.PRN != 0) && (glo_gnav_eph.PRN != 0))
{
LOG(WARNING) << "MSM messages for observables from different systems are not defined"; // print two messages?
}
@ -2577,23 +2577,23 @@ std::string Rtcm::print_MSM_3(const Gps_Ephemeris& gps_eph,
bool more_messages)
{
uint32_t msg_number = 0;
if (gps_eph.i_satellite_PRN != 0)
if (gps_eph.PRN != 0)
{
msg_number = 1073;
}
if (gps_cnav_eph.i_satellite_PRN != 0)
if (gps_cnav_eph.PRN != 0)
{
msg_number = 1073;
}
if (glo_gnav_eph.i_satellite_PRN != 0)
if (glo_gnav_eph.PRN != 0)
{
msg_number = 1083;
}
if (gal_eph.i_satellite_PRN != 0)
if (gal_eph.PRN != 0)
{
msg_number = 1093;
}
if (((gps_eph.i_satellite_PRN != 0) || (gps_cnav_eph.i_satellite_PRN != 0)) && (gal_eph.i_satellite_PRN != 0) && (glo_gnav_eph.i_satellite_PRN != 0))
if (((gps_eph.PRN != 0) || (gps_cnav_eph.PRN != 0)) && (gal_eph.PRN != 0) && (glo_gnav_eph.PRN != 0))
{
LOG(WARNING) << "MSM messages for observables from different systems are not defined"; // print two messages?
}
@ -2694,23 +2694,23 @@ std::string Rtcm::print_MSM_4(const Gps_Ephemeris& gps_eph,
bool more_messages)
{
uint32_t msg_number = 0;
if (gps_eph.i_satellite_PRN != 0)
if (gps_eph.PRN != 0)
{
msg_number = 1074;
}
if (gps_cnav_eph.i_satellite_PRN != 0)
if (gps_cnav_eph.PRN != 0)
{
msg_number = 1074;
}
if (glo_gnav_eph.i_satellite_PRN != 0)
if (glo_gnav_eph.PRN != 0)
{
msg_number = 1084;
}
if (gal_eph.i_satellite_PRN != 0)
if (gal_eph.PRN != 0)
{
msg_number = 1094;
}
if (((gps_eph.i_satellite_PRN != 0) || (gps_cnav_eph.i_satellite_PRN != 0)) && (gal_eph.i_satellite_PRN != 0) && (glo_gnav_eph.i_satellite_PRN != 0))
if (((gps_eph.PRN != 0) || (gps_cnav_eph.PRN != 0)) && (gal_eph.PRN != 0) && (glo_gnav_eph.PRN != 0))
{
LOG(WARNING) << "MSM messages for observables from different systems are not defined"; // print two messages?
}
@ -2857,23 +2857,23 @@ std::string Rtcm::print_MSM_5(const Gps_Ephemeris& gps_eph,
bool more_messages)
{
uint32_t msg_number = 0;
if (gps_eph.i_satellite_PRN != 0)
if (gps_eph.PRN != 0)
{
msg_number = 1075;
}
if (gps_cnav_eph.i_satellite_PRN != 0)
if (gps_cnav_eph.PRN != 0)
{
msg_number = 1075;
}
if (glo_gnav_eph.i_satellite_PRN != 0)
if (glo_gnav_eph.PRN != 0)
{
msg_number = 1085;
}
if (gal_eph.i_satellite_PRN != 0)
if (gal_eph.PRN != 0)
{
msg_number = 1095;
}
if (((gps_eph.i_satellite_PRN != 0) || (gps_cnav_eph.i_satellite_PRN != 0)) && (gal_eph.i_satellite_PRN != 0) && (glo_gnav_eph.i_satellite_PRN != 0))
if (((gps_eph.PRN != 0) || (gps_cnav_eph.PRN != 0)) && (gal_eph.PRN != 0) && (glo_gnav_eph.PRN != 0))
{
LOG(WARNING) << "MSM messages for observables from different systems are not defined"; // print two messages?
}
@ -3029,23 +3029,23 @@ std::string Rtcm::print_MSM_6(const Gps_Ephemeris& gps_eph,
bool more_messages)
{
uint32_t msg_number = 0;
if (gps_eph.i_satellite_PRN != 0)
if (gps_eph.PRN != 0)
{
msg_number = 1076;
}
if (gps_cnav_eph.i_satellite_PRN != 0)
if (gps_cnav_eph.PRN != 0)
{
msg_number = 1076;
}
if (glo_gnav_eph.i_satellite_PRN != 0)
if (glo_gnav_eph.PRN != 0)
{
msg_number = 1086;
}
if (gal_eph.i_satellite_PRN != 0)
if (gal_eph.PRN != 0)
{
msg_number = 1096;
}
if (((gps_eph.i_satellite_PRN != 0) || (gps_cnav_eph.i_satellite_PRN != 0)) && (gal_eph.i_satellite_PRN != 0) && (glo_gnav_eph.i_satellite_PRN != 0))
if (((gps_eph.PRN != 0) || (gps_cnav_eph.PRN != 0)) && (gal_eph.PRN != 0) && (glo_gnav_eph.PRN != 0))
{
LOG(WARNING) << "MSM messages for observables from different systems are not defined"; // print two messages?
}
@ -3149,23 +3149,23 @@ std::string Rtcm::print_MSM_7(const Gps_Ephemeris& gps_eph,
bool more_messages)
{
uint32_t msg_number = 0;
if (gps_eph.i_satellite_PRN != 0)
if (gps_eph.PRN != 0)
{
msg_number = 1077;
}
if (gps_cnav_eph.i_satellite_PRN != 0)
if (gps_cnav_eph.PRN != 0)
{
msg_number = 1077;
}
if (glo_gnav_eph.i_satellite_PRN != 0)
if (glo_gnav_eph.PRN != 0)
{
msg_number = 1087;
}
if (gal_eph.i_satellite_PRN != 0)
if (gal_eph.PRN != 0)
{
msg_number = 1097;
}
if (((gps_eph.i_satellite_PRN != 0) || (gps_cnav_eph.i_satellite_PRN != 0)) && (glo_gnav_eph.i_satellite_PRN != 0) && (gal_eph.i_satellite_PRN != 0))
if (((gps_eph.PRN != 0) || (gps_cnav_eph.PRN != 0)) && (glo_gnav_eph.PRN != 0) && (gal_eph.PRN != 0))
{
LOG(WARNING) << "MSM messages for observables from different systems are not defined"; // print two messages?
}
@ -3391,9 +3391,9 @@ std::map<std::string, int> Rtcm::galileo_signal_map = [] {
boost::posix_time::ptime Rtcm::compute_GPS_time(const Gps_Ephemeris& eph, double obs_time) const
{
const double gps_t = obs_time;
const boost::posix_time::time_duration t_duration = boost::posix_time::milliseconds(static_cast<long>((gps_t + 604800 * static_cast<double>(eph.i_GPS_week)) * 1000)); // NOLINT(google-runtime-int)
const boost::posix_time::time_duration t_duration = boost::posix_time::milliseconds(static_cast<long>((gps_t + 604800 * static_cast<double>(eph.WN)) * 1000)); // NOLINT(google-runtime-int)
if (eph.i_GPS_week < 512)
if (eph.WN < 512)
{
boost::posix_time::ptime p_time(boost::gregorian::date(2019, 4, 7), t_duration);
return p_time;
@ -3407,7 +3407,7 @@ boost::posix_time::ptime Rtcm::compute_GPS_time(const Gps_Ephemeris& eph, double
boost::posix_time::ptime Rtcm::compute_GPS_time(const Gps_CNAV_Ephemeris& eph, double obs_time) const
{
const double gps_t = obs_time;
const boost::posix_time::time_duration t_duration = boost::posix_time::milliseconds(static_cast<long>((gps_t + 604800 * static_cast<double>(eph.i_GPS_week)) * 1000)); // NOLINT(google-runtime-int)
const boost::posix_time::time_duration t_duration = boost::posix_time::milliseconds(static_cast<long>((gps_t + 604800 * static_cast<double>(eph.WN)) * 1000)); // NOLINT(google-runtime-int)
boost::posix_time::ptime p_time(boost::gregorian::date(1999, 8, 22), t_duration);
return p_time;
}
@ -3416,7 +3416,7 @@ boost::posix_time::ptime Rtcm::compute_GPS_time(const Gps_CNAV_Ephemeris& eph, d
boost::posix_time::ptime Rtcm::compute_Galileo_time(const Galileo_Ephemeris& eph, double obs_time) const
{
const double galileo_t = obs_time;
const boost::posix_time::time_duration t_duration = boost::posix_time::milliseconds(static_cast<long>((galileo_t + 604800 * static_cast<double>(eph.WN_5)) * 1000)); // NOLINT(google-runtime-int)
const boost::posix_time::time_duration t_duration = boost::posix_time::milliseconds(static_cast<long>((galileo_t + 604800 * static_cast<double>(eph.WN)) * 1000)); // NOLINT(google-runtime-int)
boost::posix_time::ptime p_time(boost::gregorian::date(1999, 8, 22), t_duration);
return p_time;
}
@ -3778,7 +3778,7 @@ int32_t Rtcm::set_DF009(const Gnss_Synchro& gnss_synchro)
int32_t Rtcm::set_DF009(const Gps_Ephemeris& gps_eph)
{
const uint32_t prn_ = gps_eph.i_satellite_PRN;
const uint32_t prn_ = gps_eph.PRN;
if (prn_ > 32)
{
LOG(WARNING) << "GPS satellite ID must be between 1 and 32, but PRN " << prn_ << " was found";
@ -4201,9 +4201,9 @@ int32_t Rtcm::set_DF050(const Gnss_Synchro& gnss_synchro)
int32_t Rtcm::set_DF051(const Gps_Ephemeris& gps_eph, double obs_time)
{
const double gps_t = obs_time;
const boost::posix_time::time_duration t_duration = boost::posix_time::milliseconds(static_cast<int64_t>((gps_t + 604800 * static_cast<double>(gps_eph.i_GPS_week)) * 1000));
const boost::posix_time::time_duration t_duration = boost::posix_time::milliseconds(static_cast<int64_t>((gps_t + 604800 * static_cast<double>(gps_eph.WN)) * 1000));
std::string now_ptime;
if (gps_eph.i_GPS_week < 512)
if (gps_eph.WN < 512)
{
boost::posix_time::ptime p_time(boost::gregorian::date(2019, 4, 7), t_duration);
now_ptime = to_iso_string(p_time);
@ -4224,9 +4224,9 @@ int32_t Rtcm::set_DF051(const Gps_Ephemeris& gps_eph, double obs_time)
int32_t Rtcm::set_DF052(const Gps_Ephemeris& gps_eph, double obs_time)
{
const double gps_t = obs_time;
const boost::posix_time::time_duration t_duration = boost::posix_time::milliseconds(static_cast<int64_t>((gps_t + 604800 * static_cast<double>(gps_eph.i_GPS_week)) * 1000));
const boost::posix_time::time_duration t_duration = boost::posix_time::milliseconds(static_cast<int64_t>((gps_t + 604800 * static_cast<double>(gps_eph.WN)) * 1000));
std::string now_ptime;
if (gps_eph.i_GPS_week < 512)
if (gps_eph.WN < 512)
{
boost::posix_time::ptime p_time(boost::gregorian::date(2019, 4, 7), t_duration);
now_ptime = to_iso_string(p_time);
@ -4248,7 +4248,7 @@ int32_t Rtcm::set_DF052(const Gps_Ephemeris& gps_eph, double obs_time)
int32_t Rtcm::set_DF071(const Gps_Ephemeris& gps_eph)
{
const auto iode = static_cast<uint32_t>(gps_eph.d_IODE_SF2);
const auto iode = static_cast<uint32_t>(gps_eph.IODE_SF2);
DF071 = std::bitset<8>(iode);
return 0;
}
@ -4256,7 +4256,7 @@ int32_t Rtcm::set_DF071(const Gps_Ephemeris& gps_eph)
int32_t Rtcm::set_DF076(const Gps_Ephemeris& gps_eph)
{
const auto week_number = static_cast<uint32_t>(gps_eph.i_GPS_week);
const auto week_number = static_cast<uint32_t>(gps_eph.WN);
DF076 = std::bitset<10>(week_number);
return 0;
}
@ -4264,7 +4264,7 @@ int32_t Rtcm::set_DF076(const Gps_Ephemeris& gps_eph)
int32_t Rtcm::set_DF077(const Gps_Ephemeris& gps_eph)
{
const auto ura = static_cast<uint16_t>(gps_eph.i_SV_accuracy);
const auto ura = static_cast<uint16_t>(gps_eph.SV_accuracy);
DF077 = std::bitset<4>(ura);
return 0;
}
@ -4272,7 +4272,7 @@ int32_t Rtcm::set_DF077(const Gps_Ephemeris& gps_eph)
int32_t Rtcm::set_DF078(const Gps_Ephemeris& gps_eph)
{
const auto code_on_L2 = static_cast<uint16_t>(gps_eph.i_code_on_L2);
const auto code_on_L2 = static_cast<uint16_t>(gps_eph.code_on_L2);
DF078 = std::bitset<2>(code_on_L2);
return 0;
}
@ -4280,7 +4280,7 @@ int32_t Rtcm::set_DF078(const Gps_Ephemeris& gps_eph)
int32_t Rtcm::set_DF079(const Gps_Ephemeris& gps_eph)
{
const auto idot = static_cast<uint32_t>(std::round(gps_eph.d_IDOT / I_DOT_LSB));
const auto idot = static_cast<uint32_t>(std::round(gps_eph.idot / I_DOT_LSB));
DF079 = std::bitset<14>(idot);
return 0;
}
@ -4288,7 +4288,7 @@ int32_t Rtcm::set_DF079(const Gps_Ephemeris& gps_eph)
int32_t Rtcm::set_DF080(const Gps_Ephemeris& gps_eph)
{
const auto iode = static_cast<uint16_t>(gps_eph.d_IODE_SF2);
const auto iode = static_cast<uint16_t>(gps_eph.IODE_SF2);
DF080 = std::bitset<8>(iode);
return 0;
}
@ -4296,7 +4296,7 @@ int32_t Rtcm::set_DF080(const Gps_Ephemeris& gps_eph)
int32_t Rtcm::set_DF081(const Gps_Ephemeris& gps_eph)
{
const auto toc = static_cast<uint32_t>(std::round(gps_eph.d_Toc / T_OC_LSB));
const auto toc = static_cast<uint32_t>(std::round(gps_eph.toc / T_OC_LSB));
DF081 = std::bitset<16>(toc);
return 0;
}
@ -4304,7 +4304,7 @@ int32_t Rtcm::set_DF081(const Gps_Ephemeris& gps_eph)
int32_t Rtcm::set_DF082(const Gps_Ephemeris& gps_eph)
{
const auto af2 = static_cast<int16_t>(std::round(gps_eph.d_A_f2 / A_F2_LSB));
const auto af2 = static_cast<int16_t>(std::round(gps_eph.af2 / A_F2_LSB));
DF082 = std::bitset<8>(af2);
return 0;
}
@ -4312,7 +4312,7 @@ int32_t Rtcm::set_DF082(const Gps_Ephemeris& gps_eph)
int32_t Rtcm::set_DF083(const Gps_Ephemeris& gps_eph)
{
const auto af1 = static_cast<int32_t>(std::round(gps_eph.d_A_f1 / A_F1_LSB));
const auto af1 = static_cast<int32_t>(std::round(gps_eph.af1 / A_F1_LSB));
DF083 = std::bitset<16>(af1);
return 0;
}
@ -4320,7 +4320,7 @@ int32_t Rtcm::set_DF083(const Gps_Ephemeris& gps_eph)
int32_t Rtcm::set_DF084(const Gps_Ephemeris& gps_eph)
{
const auto af0 = static_cast<int64_t>(std::round(gps_eph.d_A_f0 / A_F0_LSB));
const auto af0 = static_cast<int64_t>(std::round(gps_eph.af0 / A_F0_LSB));
DF084 = std::bitset<22>(af0);
return 0;
}
@ -4328,7 +4328,7 @@ int32_t Rtcm::set_DF084(const Gps_Ephemeris& gps_eph)
int32_t Rtcm::set_DF085(const Gps_Ephemeris& gps_eph)
{
const auto iodc = static_cast<uint32_t>(gps_eph.d_IODC);
const auto iodc = static_cast<uint32_t>(gps_eph.IODC);
DF085 = std::bitset<10>(iodc);
return 0;
}
@ -4336,7 +4336,7 @@ int32_t Rtcm::set_DF085(const Gps_Ephemeris& gps_eph)
int32_t Rtcm::set_DF086(const Gps_Ephemeris& gps_eph)
{
const auto crs = static_cast<int32_t>(std::round(gps_eph.d_Crs / C_RS_LSB));
const auto crs = static_cast<int32_t>(std::round(gps_eph.Crs / C_RS_LSB));
DF086 = std::bitset<16>(crs);
return 0;
}
@ -4344,7 +4344,7 @@ int32_t Rtcm::set_DF086(const Gps_Ephemeris& gps_eph)
int32_t Rtcm::set_DF087(const Gps_Ephemeris& gps_eph)
{
const auto delta_n = static_cast<int32_t>(std::round(gps_eph.d_Delta_n / DELTA_N_LSB));
const auto delta_n = static_cast<int32_t>(std::round(gps_eph.delta_n / DELTA_N_LSB));
DF087 = std::bitset<16>(delta_n);
return 0;
}
@ -4352,7 +4352,7 @@ int32_t Rtcm::set_DF087(const Gps_Ephemeris& gps_eph)
int32_t Rtcm::set_DF088(const Gps_Ephemeris& gps_eph)
{
const auto m0 = static_cast<int64_t>(std::round(gps_eph.d_M_0 / M_0_LSB));
const auto m0 = static_cast<int64_t>(std::round(gps_eph.M_0 / M_0_LSB));
DF088 = std::bitset<32>(m0);
return 0;
}
@ -4360,14 +4360,14 @@ int32_t Rtcm::set_DF088(const Gps_Ephemeris& gps_eph)
int32_t Rtcm::set_DF089(const Gps_Ephemeris& gps_eph)
{
const auto cuc = static_cast<int32_t>(std::round(gps_eph.d_Cuc / C_UC_LSB));
const auto cuc = static_cast<int32_t>(std::round(gps_eph.Cuc / C_UC_LSB));
DF089 = std::bitset<16>(cuc);
return 0;
}
int32_t Rtcm::set_DF090(const Gps_Ephemeris& gps_eph)
{
const auto ecc = static_cast<uint64_t>(std::round(gps_eph.d_e_eccentricity / ECCENTRICITY_LSB));
const auto ecc = static_cast<uint64_t>(std::round(gps_eph.ecc / ECCENTRICITY_LSB));
DF090 = std::bitset<32>(ecc);
return 0;
}
@ -4375,7 +4375,7 @@ int32_t Rtcm::set_DF090(const Gps_Ephemeris& gps_eph)
int32_t Rtcm::set_DF091(const Gps_Ephemeris& gps_eph)
{
const auto cus = static_cast<int32_t>(std::round(gps_eph.d_Cus / C_US_LSB));
const auto cus = static_cast<int32_t>(std::round(gps_eph.Cus / C_US_LSB));
DF091 = std::bitset<16>(cus);
return 0;
}
@ -4383,7 +4383,7 @@ int32_t Rtcm::set_DF091(const Gps_Ephemeris& gps_eph)
int32_t Rtcm::set_DF092(const Gps_Ephemeris& gps_eph)
{
const auto sqr_a = static_cast<uint64_t>(std::round(gps_eph.d_sqrt_A / SQRT_A_LSB));
const auto sqr_a = static_cast<uint64_t>(std::round(gps_eph.sqrtA / SQRT_A_LSB));
DF092 = std::bitset<32>(sqr_a);
return 0;
}
@ -4391,7 +4391,7 @@ int32_t Rtcm::set_DF092(const Gps_Ephemeris& gps_eph)
int32_t Rtcm::set_DF093(const Gps_Ephemeris& gps_eph)
{
const auto toe = static_cast<uint32_t>(std::round(gps_eph.d_Toe / T_OE_LSB));
const auto toe = static_cast<uint32_t>(std::round(gps_eph.toe / T_OE_LSB));
DF093 = std::bitset<16>(toe);
return 0;
}
@ -4399,7 +4399,7 @@ int32_t Rtcm::set_DF093(const Gps_Ephemeris& gps_eph)
int32_t Rtcm::set_DF094(const Gps_Ephemeris& gps_eph)
{
const auto cic = static_cast<int32_t>(std::round(gps_eph.d_Cic / C_IC_LSB));
const auto cic = static_cast<int32_t>(std::round(gps_eph.Cic / C_IC_LSB));
DF094 = std::bitset<16>(cic);
return 0;
}
@ -4407,7 +4407,7 @@ int32_t Rtcm::set_DF094(const Gps_Ephemeris& gps_eph)
int32_t Rtcm::set_DF095(const Gps_Ephemeris& gps_eph)
{
const auto Omega0 = static_cast<int64_t>(std::round(gps_eph.d_OMEGA0 / OMEGA_0_LSB));
const auto Omega0 = static_cast<int64_t>(std::round(gps_eph.OMEGA_0 / OMEGA_0_LSB));
DF095 = std::bitset<32>(Omega0);
return 0;
}
@ -4415,7 +4415,7 @@ int32_t Rtcm::set_DF095(const Gps_Ephemeris& gps_eph)
int32_t Rtcm::set_DF096(const Gps_Ephemeris& gps_eph)
{
const auto cis = static_cast<int32_t>(std::round(gps_eph.d_Cis / C_IS_LSB));
const auto cis = static_cast<int32_t>(std::round(gps_eph.Cis / C_IS_LSB));
DF096 = std::bitset<16>(cis);
return 0;
}
@ -4423,7 +4423,7 @@ int32_t Rtcm::set_DF096(const Gps_Ephemeris& gps_eph)
int32_t Rtcm::set_DF097(const Gps_Ephemeris& gps_eph)
{
const auto i0 = static_cast<int64_t>(std::round(gps_eph.d_i_0 / I_0_LSB));
const auto i0 = static_cast<int64_t>(std::round(gps_eph.i_0 / I_0_LSB));
DF097 = std::bitset<32>(i0);
return 0;
}
@ -4431,7 +4431,7 @@ int32_t Rtcm::set_DF097(const Gps_Ephemeris& gps_eph)
int32_t Rtcm::set_DF098(const Gps_Ephemeris& gps_eph)
{
const auto crc = static_cast<int32_t>(std::round(gps_eph.d_Crc / C_RC_LSB));
const auto crc = static_cast<int32_t>(std::round(gps_eph.Crc / C_RC_LSB));
DF098 = std::bitset<16>(crc);
return 0;
}
@ -4439,7 +4439,7 @@ int32_t Rtcm::set_DF098(const Gps_Ephemeris& gps_eph)
int32_t Rtcm::set_DF099(const Gps_Ephemeris& gps_eph)
{
const auto omega = static_cast<int64_t>(std::round(gps_eph.d_OMEGA / OMEGA_LSB));
const auto omega = static_cast<int64_t>(std::round(gps_eph.omega / OMEGA_LSB));
DF099 = std::bitset<32>(omega);
return 0;
}
@ -4447,7 +4447,7 @@ int32_t Rtcm::set_DF099(const Gps_Ephemeris& gps_eph)
int32_t Rtcm::set_DF100(const Gps_Ephemeris& gps_eph)
{
const auto omegadot = static_cast<int64_t>(std::round(gps_eph.d_OMEGA_DOT / OMEGA_DOT_LSB));
const auto omegadot = static_cast<int64_t>(std::round(gps_eph.OMEGAdot / OMEGA_DOT_LSB));
DF100 = std::bitset<24>(omegadot);
return 0;
}
@ -4455,7 +4455,7 @@ int32_t Rtcm::set_DF100(const Gps_Ephemeris& gps_eph)
int32_t Rtcm::set_DF101(const Gps_Ephemeris& gps_eph)
{
const auto tgd = static_cast<int16_t>(std::round(gps_eph.d_TGD / T_GD_LSB));
const auto tgd = static_cast<int16_t>(std::round(gps_eph.TGD / T_GD_LSB));
DF101 = std::bitset<8>(tgd);
return 0;
}
@ -4463,7 +4463,7 @@ int32_t Rtcm::set_DF101(const Gps_Ephemeris& gps_eph)
int32_t Rtcm::set_DF102(const Gps_Ephemeris& gps_eph)
{
const auto sv_heath = static_cast<uint16_t>(gps_eph.i_SV_health);
const auto sv_heath = static_cast<uint16_t>(gps_eph.SV_health);
DF102 = std::bitset<6>(sv_heath);
return 0;
}
@ -4471,7 +4471,7 @@ int32_t Rtcm::set_DF102(const Gps_Ephemeris& gps_eph)
int32_t Rtcm::set_DF103(const Gps_Ephemeris& gps_eph)
{
DF103 = std::bitset<1>(gps_eph.b_L2_P_data_flag);
DF103 = std::bitset<1>(gps_eph.L2_P_data_flag);
return 0;
}
@ -4789,7 +4789,7 @@ int32_t Rtcm::set_DF136(const Glonass_Gnav_Ephemeris& glonass_gnav_eph)
int32_t Rtcm::set_DF137(const Gps_Ephemeris& gps_eph)
{
DF137 = std::bitset<1>(gps_eph.b_fit_interval_flag);
DF137 = std::bitset<1>(gps_eph.fit_interval_flag);
return 0;
}
@ -4810,7 +4810,7 @@ int32_t Rtcm::set_DF248(double obs_time)
int32_t Rtcm::set_DF252(const Galileo_Ephemeris& gal_eph)
{
const uint32_t prn_ = gal_eph.i_satellite_PRN;
const uint32_t prn_ = gal_eph.PRN;
if (prn_ > 63)
{
LOG(WARNING) << "Galileo satellite ID must be between 0 and 63, but PRN " << prn_ << " was found";
@ -4822,7 +4822,7 @@ int32_t Rtcm::set_DF252(const Galileo_Ephemeris& gal_eph)
int32_t Rtcm::set_DF289(const Galileo_Ephemeris& gal_eph)
{
const auto galileo_week_number = static_cast<uint32_t>(gal_eph.WN_5);
const auto galileo_week_number = static_cast<uint32_t>(gal_eph.WN);
if (galileo_week_number > 4095)
{
LOG(WARNING) << "Error decoding Galileo week number (it has a 4096 roll-off, but " << galileo_week_number << " was detected)";
@ -4834,7 +4834,7 @@ int32_t Rtcm::set_DF289(const Galileo_Ephemeris& gal_eph)
int32_t Rtcm::set_DF290(const Galileo_Ephemeris& gal_eph)
{
const auto iod_nav = static_cast<uint32_t>(gal_eph.IOD_nav_1);
const auto iod_nav = static_cast<uint32_t>(gal_eph.IOD_nav);
if (iod_nav > 1023)
{
LOG(WARNING) << "Error decoding Galileo IODnav (it has a max of 1023, but " << iod_nav << " was detected)";
@ -4846,7 +4846,7 @@ int32_t Rtcm::set_DF290(const Galileo_Ephemeris& gal_eph)
int32_t Rtcm::set_DF291(const Galileo_Ephemeris& gal_eph)
{
const auto SISA = static_cast<uint16_t>(gal_eph.SISA_3);
const auto SISA = static_cast<uint16_t>(gal_eph.SISA);
// SISA = 0; // SIS Accuracy, data content definition not given in Galileo OS SIS ICD, Issue 1.1, Sept 2010
DF291 = std::bitset<8>(SISA);
return 0;
@ -4855,7 +4855,7 @@ int32_t Rtcm::set_DF291(const Galileo_Ephemeris& gal_eph)
int32_t Rtcm::set_DF292(const Galileo_Ephemeris& gal_eph)
{
const auto idot = static_cast<int32_t>(std::round(gal_eph.iDot_2 / FNAV_IDOT_2_LSB));
const auto idot = static_cast<int32_t>(std::round(gal_eph.idot / FNAV_IDOT_2_LSB));
DF292 = std::bitset<14>(idot);
return 0;
}
@ -4863,7 +4863,7 @@ int32_t Rtcm::set_DF292(const Galileo_Ephemeris& gal_eph)
int32_t Rtcm::set_DF293(const Galileo_Ephemeris& gal_eph)
{
const auto toc = static_cast<uint32_t>(gal_eph.t0c_4);
const auto toc = static_cast<uint32_t>(gal_eph.toc);
if (toc > 604740)
{
LOG(WARNING) << "Error decoding Galileo ephemeris time (max of 604740, but " << toc << " was detected)";
@ -4875,7 +4875,7 @@ int32_t Rtcm::set_DF293(const Galileo_Ephemeris& gal_eph)
int32_t Rtcm::set_DF294(const Galileo_Ephemeris& gal_eph)
{
const auto af2 = static_cast<int16_t>(std::round(gal_eph.af2_4 / FNAV_AF2_1_LSB));
const auto af2 = static_cast<int16_t>(std::round(gal_eph.af2 / FNAV_AF2_1_LSB));
DF294 = std::bitset<6>(af2);
return 0;
}
@ -4883,7 +4883,7 @@ int32_t Rtcm::set_DF294(const Galileo_Ephemeris& gal_eph)
int32_t Rtcm::set_DF295(const Galileo_Ephemeris& gal_eph)
{
const auto af1 = static_cast<int64_t>(std::round(gal_eph.af1_4 / FNAV_AF1_1_LSB));
const auto af1 = static_cast<int64_t>(std::round(gal_eph.af1 / FNAV_AF1_1_LSB));
DF295 = std::bitset<21>(af1);
return 0;
}
@ -4891,7 +4891,7 @@ int32_t Rtcm::set_DF295(const Galileo_Ephemeris& gal_eph)
int32_t Rtcm::set_DF296(const Galileo_Ephemeris& gal_eph)
{
const int64_t af0 = static_cast<uint32_t>(std::round(gal_eph.af0_4 / FNAV_AF0_1_LSB));
const int64_t af0 = static_cast<uint32_t>(std::round(gal_eph.af0 / FNAV_AF0_1_LSB));
DF296 = std::bitset<31>(af0);
return 0;
}
@ -4899,7 +4899,7 @@ int32_t Rtcm::set_DF296(const Galileo_Ephemeris& gal_eph)
int32_t Rtcm::set_DF297(const Galileo_Ephemeris& gal_eph)
{
const auto crs = static_cast<int32_t>(std::round(gal_eph.C_rs_3 / FNAV_CRS_3_LSB));
const auto crs = static_cast<int32_t>(std::round(gal_eph.Crs / FNAV_CRS_3_LSB));
DF297 = std::bitset<16>(crs);
return 0;
}
@ -4907,7 +4907,7 @@ int32_t Rtcm::set_DF297(const Galileo_Ephemeris& gal_eph)
int32_t Rtcm::set_DF298(const Galileo_Ephemeris& gal_eph)
{
const auto delta_n = static_cast<int32_t>(std::round(gal_eph.delta_n_3 / FNAV_DELTAN_3_LSB));
const auto delta_n = static_cast<int32_t>(std::round(gal_eph.delta_n / FNAV_DELTAN_3_LSB));
DF298 = std::bitset<16>(delta_n);
return 0;
}
@ -4915,7 +4915,7 @@ int32_t Rtcm::set_DF298(const Galileo_Ephemeris& gal_eph)
int32_t Rtcm::set_DF299(const Galileo_Ephemeris& gal_eph)
{
const auto m0 = static_cast<int64_t>(std::round(gal_eph.M0_1 / FNAV_M0_2_LSB));
const auto m0 = static_cast<int64_t>(std::round(gal_eph.M_0 / FNAV_M0_2_LSB));
DF299 = std::bitset<32>(m0);
return 0;
}
@ -4923,7 +4923,7 @@ int32_t Rtcm::set_DF299(const Galileo_Ephemeris& gal_eph)
int32_t Rtcm::set_DF300(const Galileo_Ephemeris& gal_eph)
{
const int32_t cuc = static_cast<uint32_t>(std::round(gal_eph.C_uc_3 / FNAV_CUC_3_LSB));
const int32_t cuc = static_cast<uint32_t>(std::round(gal_eph.Cuc / FNAV_CUC_3_LSB));
DF300 = std::bitset<16>(cuc);
return 0;
}
@ -4931,7 +4931,7 @@ int32_t Rtcm::set_DF300(const Galileo_Ephemeris& gal_eph)
int32_t Rtcm::set_DF301(const Galileo_Ephemeris& gal_eph)
{
const auto ecc = static_cast<uint64_t>(std::round(gal_eph.e_1 / FNAV_E_2_LSB));
const auto ecc = static_cast<uint64_t>(std::round(gal_eph.ecc / FNAV_E_2_LSB));
DF301 = std::bitset<32>(ecc);
return 0;
}
@ -4939,7 +4939,7 @@ int32_t Rtcm::set_DF301(const Galileo_Ephemeris& gal_eph)
int32_t Rtcm::set_DF302(const Galileo_Ephemeris& gal_eph)
{
const auto cus = static_cast<int32_t>(std::round(gal_eph.C_us_3 / FNAV_CUS_3_LSB));
const auto cus = static_cast<int32_t>(std::round(gal_eph.Cus / FNAV_CUS_3_LSB));
DF302 = std::bitset<16>(cus);
return 0;
}
@ -4947,7 +4947,7 @@ int32_t Rtcm::set_DF302(const Galileo_Ephemeris& gal_eph)
int32_t Rtcm::set_DF303(const Galileo_Ephemeris& gal_eph)
{
const auto sqr_a = static_cast<uint64_t>(std::round(gal_eph.A_1 / FNAV_A12_2_LSB));
const auto sqr_a = static_cast<uint64_t>(std::round(gal_eph.sqrtA / FNAV_A12_2_LSB));
DF303 = std::bitset<32>(sqr_a);
return 0;
}
@ -4955,7 +4955,7 @@ int32_t Rtcm::set_DF303(const Galileo_Ephemeris& gal_eph)
int32_t Rtcm::set_DF304(const Galileo_Ephemeris& gal_eph)
{
const auto toe = static_cast<uint32_t>(std::round(gal_eph.t0e_1 / FNAV_T0E_3_LSB));
const auto toe = static_cast<uint32_t>(std::round(gal_eph.toe / FNAV_T0E_3_LSB));
DF304 = std::bitset<14>(toe);
return 0;
}
@ -4963,7 +4963,7 @@ int32_t Rtcm::set_DF304(const Galileo_Ephemeris& gal_eph)
int32_t Rtcm::set_DF305(const Galileo_Ephemeris& gal_eph)
{
const auto cic = static_cast<int32_t>(std::round(gal_eph.C_ic_4 / FNAV_CIC_4_LSB));
const auto cic = static_cast<int32_t>(std::round(gal_eph.Cic / FNAV_CIC_4_LSB));
DF305 = std::bitset<16>(cic);
return 0;
}
@ -4971,7 +4971,7 @@ int32_t Rtcm::set_DF305(const Galileo_Ephemeris& gal_eph)
int32_t Rtcm::set_DF306(const Galileo_Ephemeris& gal_eph)
{
const auto Omega0 = static_cast<int64_t>(std::round(gal_eph.OMEGA_0_2 / FNAV_OMEGA0_2_LSB));
const auto Omega0 = static_cast<int64_t>(std::round(gal_eph.OMEGA_0 / FNAV_OMEGA0_2_LSB));
DF306 = std::bitset<32>(Omega0);
return 0;
}
@ -4979,7 +4979,7 @@ int32_t Rtcm::set_DF306(const Galileo_Ephemeris& gal_eph)
int32_t Rtcm::set_DF307(const Galileo_Ephemeris& gal_eph)
{
const auto cis = static_cast<int32_t>(std::round(gal_eph.C_is_4 / FNAV_CIS_4_LSB));
const auto cis = static_cast<int32_t>(std::round(gal_eph.Cis / FNAV_CIS_4_LSB));
DF307 = std::bitset<16>(cis);
return 0;
}
@ -4987,7 +4987,7 @@ int32_t Rtcm::set_DF307(const Galileo_Ephemeris& gal_eph)
int32_t Rtcm::set_DF308(const Galileo_Ephemeris& gal_eph)
{
const auto i0 = static_cast<int64_t>(std::round(gal_eph.i_0_2 / FNAV_I0_3_LSB));
const auto i0 = static_cast<int64_t>(std::round(gal_eph.i_0 / FNAV_I0_3_LSB));
DF308 = std::bitset<32>(i0);
return 0;
}
@ -4995,7 +4995,7 @@ int32_t Rtcm::set_DF308(const Galileo_Ephemeris& gal_eph)
int32_t Rtcm::set_DF309(const Galileo_Ephemeris& gal_eph)
{
const int32_t crc = static_cast<uint32_t>(std::round(gal_eph.C_rc_3 / FNAV_CRC_3_LSB));
const int32_t crc = static_cast<uint32_t>(std::round(gal_eph.Crc / FNAV_CRC_3_LSB));
DF309 = std::bitset<16>(crc);
return 0;
}
@ -5003,7 +5003,7 @@ int32_t Rtcm::set_DF309(const Galileo_Ephemeris& gal_eph)
int32_t Rtcm::set_DF310(const Galileo_Ephemeris& gal_eph)
{
const auto omega = static_cast<int32_t>(std::round(gal_eph.omega_2 / FNAV_OMEGA0_2_LSB));
const auto omega = static_cast<int32_t>(std::round(gal_eph.omega / FNAV_OMEGA0_2_LSB));
DF310 = std::bitset<32>(omega);
return 0;
}
@ -5011,7 +5011,7 @@ int32_t Rtcm::set_DF310(const Galileo_Ephemeris& gal_eph)
int32_t Rtcm::set_DF311(const Galileo_Ephemeris& gal_eph)
{
const auto Omegadot = static_cast<int64_t>(std::round(gal_eph.OMEGA_dot_3 / FNAV_OMEGADOT_2_LSB));
const auto Omegadot = static_cast<int64_t>(std::round(gal_eph.OMEGAdot / FNAV_OMEGADOT_2_LSB));
DF311 = std::bitset<24>(Omegadot);
return 0;
}
@ -5019,7 +5019,7 @@ int32_t Rtcm::set_DF311(const Galileo_Ephemeris& gal_eph)
int32_t Rtcm::set_DF312(const Galileo_Ephemeris& gal_eph)
{
const auto bdg_E1_E5a = static_cast<int32_t>(std::round(gal_eph.BGD_E1E5a_5 / FNAV_BGD_1_LSB));
const auto bdg_E1_E5a = static_cast<int32_t>(std::round(gal_eph.BGD_E1E5a / FNAV_BGD_1_LSB));
DF312 = std::bitset<10>(bdg_E1_E5a);
return 0;
}
@ -5027,7 +5027,7 @@ int32_t Rtcm::set_DF312(const Galileo_Ephemeris& gal_eph)
int32_t Rtcm::set_DF313(const Galileo_Ephemeris& gal_eph)
{
const auto bdg_E5b_E1 = static_cast<uint32_t>(std::round(gal_eph.BGD_E1E5b_5));
const auto bdg_E5b_E1 = static_cast<uint32_t>(std::round(gal_eph.BGD_E1E5b));
// bdg_E5b_E1 = 0; // reserved
DF313 = std::bitset<10>(bdg_E5b_E1);
return 0;

View File

@ -457,7 +457,7 @@ bool Rtklib_Solver::get_PVT(const std::map<int, Gnss_Synchro> &gnss_observables_
obsd_t newobs{};
obs_data[valid_obs + glo_valid_obs] = insert_obs_to_rtklib(newobs,
gnss_observables_iter->second,
galileo_ephemeris_iter->second.WN_5,
galileo_ephemeris_iter->second.WN,
0);
valid_obs++;
}
@ -481,7 +481,7 @@ bool Rtklib_Solver::get_PVT(const std::map<int, Gnss_Synchro> &gnss_observables_
{
obs_data[i + glo_valid_obs] = insert_obs_to_rtklib(obs_data[i + glo_valid_obs],
gnss_observables_iter->second,
galileo_ephemeris_iter->second.WN_5,
galileo_ephemeris_iter->second.WN,
2); // Band 3 (L5/E5)
found_E1_obs = true;
break;
@ -499,7 +499,7 @@ bool Rtklib_Solver::get_PVT(const std::map<int, Gnss_Synchro> &gnss_observables_
{}, {0.0, 0.0, 0.0}, {}};
obs_data[valid_obs + glo_valid_obs] = insert_obs_to_rtklib(newobs,
gnss_observables_iter->second,
galileo_ephemeris_iter->second.WN_5,
galileo_ephemeris_iter->second.WN,
2); // Band 3 (L5/E5)
valid_obs++;
}
@ -527,7 +527,7 @@ bool Rtklib_Solver::get_PVT(const std::map<int, Gnss_Synchro> &gnss_observables_
obsd_t newobs{};
obs_data[valid_obs + glo_valid_obs] = insert_obs_to_rtklib(newobs,
gnss_observables_iter->second,
gps_ephemeris_iter->second.i_GPS_week,
gps_ephemeris_iter->second.WN,
0,
this->is_pre_2009());
valid_obs++;
@ -576,7 +576,7 @@ bool Rtklib_Solver::get_PVT(const std::map<int, Gnss_Synchro> &gnss_observables_
{}, {0.0, 0.0, 0.0}, {}};
obs_data[valid_obs + glo_valid_obs] = insert_obs_to_rtklib(newobs,
gnss_observables_iter->second,
gps_cnav_ephemeris_iter->second.i_GPS_week,
gps_cnav_ephemeris_iter->second.WN,
1); // Band 2 (L2)
valid_obs++;
}
@ -605,7 +605,7 @@ bool Rtklib_Solver::get_PVT(const std::map<int, Gnss_Synchro> &gnss_observables_
eph_data[i] = eph_to_rtklib(gps_cnav_ephemeris_iter->second);
obs_data[i + glo_valid_obs] = insert_obs_to_rtklib(obs_data[i],
gnss_observables_iter->second,
gps_cnav_ephemeris_iter->second.i_GPS_week,
gps_cnav_ephemeris_iter->second.WN,
2); // Band 3 (L5)
break;
}
@ -623,7 +623,7 @@ bool Rtklib_Solver::get_PVT(const std::map<int, Gnss_Synchro> &gnss_observables_
{}, {0.0, 0.0, 0.0}, {}};
obs_data[valid_obs + glo_valid_obs] = insert_obs_to_rtklib(newobs,
gnss_observables_iter->second,
gps_cnav_ephemeris_iter->second.i_GPS_week,
gps_cnav_ephemeris_iter->second.WN,
2); // Band 3 (L5)
valid_obs++;
}
@ -717,7 +717,7 @@ bool Rtklib_Solver::get_PVT(const std::map<int, Gnss_Synchro> &gnss_observables_
obsd_t newobs{};
obs_data[valid_obs + glo_valid_obs] = insert_obs_to_rtklib(newobs,
gnss_observables_iter->second,
beidou_ephemeris_iter->second.i_BEIDOU_week + BEIDOU_DNAV_BDT2GPST_WEEK_NUM_OFFSET,
beidou_ephemeris_iter->second.WN + BEIDOU_DNAV_BDT2GPST_WEEK_NUM_OFFSET,
0);
valid_obs++;
}
@ -739,7 +739,7 @@ bool Rtklib_Solver::get_PVT(const std::map<int, Gnss_Synchro> &gnss_observables_
{
obs_data[i + glo_valid_obs] = insert_obs_to_rtklib(obs_data[i + glo_valid_obs],
gnss_observables_iter->second,
beidou_ephemeris_iter->second.i_BEIDOU_week + BEIDOU_DNAV_BDT2GPST_WEEK_NUM_OFFSET,
beidou_ephemeris_iter->second.WN + BEIDOU_DNAV_BDT2GPST_WEEK_NUM_OFFSET,
2); // Band 3 (L2/G2/B3)
found_B1I_obs = true;
break;
@ -757,7 +757,7 @@ bool Rtklib_Solver::get_PVT(const std::map<int, Gnss_Synchro> &gnss_observables_
{}, {0.0, 0.0, 0.0}, {}};
obs_data[valid_obs + glo_valid_obs] = insert_obs_to_rtklib(newobs,
gnss_observables_iter->second,
beidou_ephemeris_iter->second.i_BEIDOU_week + BEIDOU_DNAV_BDT2GPST_WEEK_NUM_OFFSET,
beidou_ephemeris_iter->second.WN + BEIDOU_DNAV_BDT2GPST_WEEK_NUM_OFFSET,
2); // Band 2 (L2/G2)
valid_obs++;
}
@ -791,59 +791,59 @@ bool Rtklib_Solver::get_PVT(const std::map<int, Gnss_Synchro> &gnss_observables_
nav_data.ng = glo_valid_obs;
if (gps_iono.valid)
{
nav_data.ion_gps[0] = gps_iono.d_alpha0;
nav_data.ion_gps[1] = gps_iono.d_alpha1;
nav_data.ion_gps[2] = gps_iono.d_alpha2;
nav_data.ion_gps[3] = gps_iono.d_alpha3;
nav_data.ion_gps[4] = gps_iono.d_beta0;
nav_data.ion_gps[5] = gps_iono.d_beta1;
nav_data.ion_gps[6] = gps_iono.d_beta2;
nav_data.ion_gps[7] = gps_iono.d_beta3;
nav_data.ion_gps[0] = gps_iono.alpha0;
nav_data.ion_gps[1] = gps_iono.alpha1;
nav_data.ion_gps[2] = gps_iono.alpha2;
nav_data.ion_gps[3] = gps_iono.alpha3;
nav_data.ion_gps[4] = gps_iono.beta0;
nav_data.ion_gps[5] = gps_iono.beta1;
nav_data.ion_gps[6] = gps_iono.beta2;
nav_data.ion_gps[7] = gps_iono.beta3;
}
if (!(gps_iono.valid) and gps_cnav_iono.valid)
{
nav_data.ion_gps[0] = gps_cnav_iono.d_alpha0;
nav_data.ion_gps[1] = gps_cnav_iono.d_alpha1;
nav_data.ion_gps[2] = gps_cnav_iono.d_alpha2;
nav_data.ion_gps[3] = gps_cnav_iono.d_alpha3;
nav_data.ion_gps[4] = gps_cnav_iono.d_beta0;
nav_data.ion_gps[5] = gps_cnav_iono.d_beta1;
nav_data.ion_gps[6] = gps_cnav_iono.d_beta2;
nav_data.ion_gps[7] = gps_cnav_iono.d_beta3;
nav_data.ion_gps[0] = gps_cnav_iono.alpha0;
nav_data.ion_gps[1] = gps_cnav_iono.alpha1;
nav_data.ion_gps[2] = gps_cnav_iono.alpha2;
nav_data.ion_gps[3] = gps_cnav_iono.alpha3;
nav_data.ion_gps[4] = gps_cnav_iono.beta0;
nav_data.ion_gps[5] = gps_cnav_iono.beta1;
nav_data.ion_gps[6] = gps_cnav_iono.beta2;
nav_data.ion_gps[7] = gps_cnav_iono.beta3;
}
if (galileo_iono.ai0_5 != 0.0)
if (galileo_iono.ai0 != 0.0)
{
nav_data.ion_gal[0] = galileo_iono.ai0_5;
nav_data.ion_gal[1] = galileo_iono.ai1_5;
nav_data.ion_gal[2] = galileo_iono.ai2_5;
nav_data.ion_gal[0] = galileo_iono.ai0;
nav_data.ion_gal[1] = galileo_iono.ai1;
nav_data.ion_gal[2] = galileo_iono.ai2;
nav_data.ion_gal[3] = 0.0;
}
if (beidou_dnav_iono.valid)
{
nav_data.ion_cmp[0] = beidou_dnav_iono.d_alpha0;
nav_data.ion_cmp[1] = beidou_dnav_iono.d_alpha1;
nav_data.ion_cmp[2] = beidou_dnav_iono.d_alpha2;
nav_data.ion_cmp[3] = beidou_dnav_iono.d_alpha3;
nav_data.ion_cmp[4] = beidou_dnav_iono.d_beta0;
nav_data.ion_cmp[5] = beidou_dnav_iono.d_beta0;
nav_data.ion_cmp[6] = beidou_dnav_iono.d_beta0;
nav_data.ion_cmp[7] = beidou_dnav_iono.d_beta3;
nav_data.ion_cmp[0] = beidou_dnav_iono.alpha0;
nav_data.ion_cmp[1] = beidou_dnav_iono.alpha1;
nav_data.ion_cmp[2] = beidou_dnav_iono.alpha2;
nav_data.ion_cmp[3] = beidou_dnav_iono.alpha3;
nav_data.ion_cmp[4] = beidou_dnav_iono.beta0;
nav_data.ion_cmp[5] = beidou_dnav_iono.beta0;
nav_data.ion_cmp[6] = beidou_dnav_iono.beta0;
nav_data.ion_cmp[7] = beidou_dnav_iono.beta3;
}
if (gps_utc_model.valid)
{
nav_data.utc_gps[0] = gps_utc_model.d_A0;
nav_data.utc_gps[1] = gps_utc_model.d_A1;
nav_data.utc_gps[2] = gps_utc_model.d_t_OT;
nav_data.utc_gps[3] = gps_utc_model.i_WN_T;
nav_data.leaps = gps_utc_model.d_DeltaT_LS;
nav_data.utc_gps[0] = gps_utc_model.A0;
nav_data.utc_gps[1] = gps_utc_model.A1;
nav_data.utc_gps[2] = gps_utc_model.tot;
nav_data.utc_gps[3] = gps_utc_model.WN_T;
nav_data.leaps = gps_utc_model.DeltaT_LS;
}
if (!(gps_utc_model.valid) and gps_cnav_utc_model.valid)
{
nav_data.utc_gps[0] = gps_cnav_utc_model.d_A0;
nav_data.utc_gps[1] = gps_cnav_utc_model.d_A1;
nav_data.utc_gps[2] = gps_cnav_utc_model.d_t_OT;
nav_data.utc_gps[3] = gps_cnav_utc_model.i_WN_T;
nav_data.leaps = gps_cnav_utc_model.d_DeltaT_LS;
nav_data.utc_gps[0] = gps_cnav_utc_model.A0;
nav_data.utc_gps[1] = gps_cnav_utc_model.A1;
nav_data.utc_gps[2] = gps_cnav_utc_model.tot;
nav_data.utc_gps[3] = gps_cnav_utc_model.WN_T;
nav_data.leaps = gps_cnav_utc_model.DeltaT_LS;
}
if (glonass_gnav_utc_model.valid)
{
@ -852,21 +852,21 @@ bool Rtklib_Solver::get_PVT(const std::map<int, Gnss_Synchro> &gnss_observables_
nav_data.utc_glo[2] = 0.0; // ??
nav_data.utc_glo[3] = 0.0; // ??
}
if (galileo_utc_model.A0_6 != 0.0)
if (galileo_utc_model.A0 != 0.0)
{
nav_data.utc_gal[0] = galileo_utc_model.A0_6;
nav_data.utc_gal[1] = galileo_utc_model.A1_6;
nav_data.utc_gal[2] = galileo_utc_model.t0t_6;
nav_data.utc_gal[3] = galileo_utc_model.WNot_6;
nav_data.leaps = galileo_utc_model.Delta_tLS_6;
nav_data.utc_gal[0] = galileo_utc_model.A0;
nav_data.utc_gal[1] = galileo_utc_model.A1;
nav_data.utc_gal[2] = galileo_utc_model.tot;
nav_data.utc_gal[3] = galileo_utc_model.WNot;
nav_data.leaps = galileo_utc_model.Delta_tLS;
}
if (beidou_dnav_utc_model.valid)
{
nav_data.utc_cmp[0] = beidou_dnav_utc_model.d_A0_UTC;
nav_data.utc_cmp[1] = beidou_dnav_utc_model.d_A1_UTC;
nav_data.utc_cmp[0] = beidou_dnav_utc_model.A0_UTC;
nav_data.utc_cmp[1] = beidou_dnav_utc_model.A1_UTC;
nav_data.utc_cmp[2] = 0.0; // ??
nav_data.utc_cmp[3] = 0.0; // ??
nav_data.leaps = beidou_dnav_utc_model.i_DeltaT_LS;
nav_data.leaps = beidou_dnav_utc_model.DeltaT_LS;
}
/* update carrier wave length using native function call in RTKlib */

View File

@ -0,0 +1,179 @@
/*!
* \file serdes_galileo_eph.h
* \brief Serialization / Deserialization of Galileo_Ephemeris objects using
* Protocol Buffers
* \author Javier Arribas, 2021. jarribas(at)cttc.es
*
* -----------------------------------------------------------------------------
*
* GNSS-SDR is a Global Navigation Satellite System software-defined receiver.
* This file is part of GNSS-SDR.
*
* Copyright (C) 2010-2021 (see AUTHORS file for a list of contributors)
* SPDX-License-Identifier: GPL-3.0-or-later
*
* -----------------------------------------------------------------------------
*/
#ifndef GNSS_SDR_SERDES_GALILEO_EPH_H
#define GNSS_SDR_SERDES_GALILEO_EPH_H
#include "galileo_ephemeris.h"
#include "galileo_ephemeris.pb.h" // file created by Protocol Buffers at compile time
#include <memory>
#include <string>
#include <utility>
/** \addtogroup PVT
* \{ */
/** \addtogroup PVT_libs
* \{ */
/*!
* \brief This class implements serialization and deserialization of
* Galileo_Ephemeris using Protocol Buffers.
*/
class Serdes_Galileo_Eph
{
public:
Serdes_Galileo_Eph()
{
// Verify that the version of the library that we linked against is
// compatible with the version of the headers we compiled against.
GOOGLE_PROTOBUF_VERIFY_VERSION;
}
~Serdes_Galileo_Eph()
{
// google::protobuf::ShutdownProtobufLibrary();
}
inline Serdes_Galileo_Eph(const Serdes_Galileo_Eph& other) noexcept //!< Copy constructor
{
this->monitor_ = other.monitor_;
}
inline Serdes_Galileo_Eph& operator=(const Serdes_Galileo_Eph& rhs) noexcept //!< Copy assignment operator
{
this->monitor_ = rhs.monitor_;
return *this;
}
inline Serdes_Galileo_Eph(Serdes_Galileo_Eph&& other) noexcept //!< Move constructor
{
this->monitor_ = std::move(other.monitor_);
}
inline Serdes_Galileo_Eph& operator=(Serdes_Galileo_Eph&& other) noexcept //!< Move assignment operator
{
if (this != &other)
{
this->monitor_ = std::move(other.monitor_);
}
return *this;
}
inline std::string createProtobuffer(const std::shared_ptr<Galileo_Ephemeris> monitor) //!< Serialization into a string
{
monitor_.Clear();
std::string data;
monitor_.set_prn(monitor->PRN);
monitor_.set_m_0(monitor->M_0);
monitor_.set_delta_n(monitor->delta_n);
monitor_.set_ecc(monitor->ecc);
monitor_.set_sqrta(monitor->sqrtA);
monitor_.set_omega_0(monitor->OMEGA_0);
monitor_.set_i_0(monitor->i_0);
monitor_.set_omega(monitor->omega);
monitor_.set_omegadot(monitor->OMEGAdot);
monitor_.set_idot(monitor->idot);
monitor_.set_cuc(monitor->Cuc);
monitor_.set_cus(monitor->Cus);
monitor_.set_crc(monitor->Crc);
monitor_.set_crs(monitor->Crs);
monitor_.set_cic(monitor->Cic);
monitor_.set_cis(monitor->Cis);
monitor_.set_toe(monitor->toe);
monitor_.set_toc(monitor->toc);
monitor_.set_af0(monitor->af0);
monitor_.set_af1(monitor->af1);
monitor_.set_af2(monitor->af2);
monitor_.set_satclkdrift(monitor->satClkDrift);
monitor_.set_dtr(monitor->dtr);
monitor_.set_wn(monitor->WN);
monitor_.set_tow(monitor->tow);
// Galileo-specific parameters
monitor_.set_iod_ephemeris(monitor->IOD_ephemeris);
monitor_.set_iod_nav(monitor->IOD_nav);
monitor_.set_sisa(monitor->SISA);
monitor_.set_e5a_hs(monitor->E5a_HS);
monitor_.set_e5b_hs(monitor->E5b_HS);
monitor_.set_e1b_hs(monitor->E1B_HS);
monitor_.set_e5a_dvs(monitor->E5a_DVS);
monitor_.set_e5b_dvs(monitor->E5b_DVS);
monitor_.set_e1b_dvs(monitor->E1B_DVS);
monitor_.set_bgd_e1e5a(monitor->BGD_E1E5a);
monitor_.set_bgd_e1e5b(monitor->BGD_E1E5b);
monitor_.SerializeToString(&data);
return data;
}
inline Galileo_Ephemeris readProtobuffer(const gnss_sdr::GalileoEphemeris& mon) const //!< Deserialization
{
Galileo_Ephemeris monitor;
monitor.PRN = mon.prn();
monitor.M_0 = mon.m_0();
monitor.delta_n = mon.delta_n();
monitor.ecc = mon.ecc();
monitor.sqrtA = mon.sqrta();
monitor.OMEGA_0 = mon.omega_0();
monitor.i_0 = mon.i_0();
monitor.omega = mon.omega();
monitor.OMEGAdot = mon.omegadot();
monitor.idot = mon.idot();
monitor.Cuc = mon.cuc();
monitor.Cus = mon.cus();
monitor.Crc = mon.crc();
monitor.Crs = mon.crs();
monitor.Cic = mon.cic();
monitor.Cis = mon.cis();
monitor.toe = mon.toe();
monitor.toc = mon.toc();
monitor.af0 = mon.af0();
monitor.af1 = mon.af1();
monitor.af2 = mon.af2();
monitor.satClkDrift = mon.satclkdrift();
monitor.dtr = mon.dtr();
monitor.WN = mon.wn();
monitor.tow = mon.tow();
// Galileo-specific parameters
monitor.IOD_ephemeris = mon.iod_ephemeris();
monitor.IOD_nav = mon.iod_nav();
monitor.SISA = mon.sisa();
monitor.E5a_HS = mon.e5a_hs();
monitor.E5b_HS = mon.e5b_hs();
monitor.E1B_HS = mon.e1b_hs();
monitor.E5a_DVS = mon.e5a_dvs();
monitor.E5b_DVS = mon.e5b_dvs();
monitor.E1B_DVS = mon.e1b_dvs();
monitor.BGD_E1E5a = mon.bgd_e1e5a();
monitor.BGD_E1E5b = mon.bgd_e1e5b();
return monitor;
}
private:
gnss_sdr::GalileoEphemeris monitor_{};
};
/** \} */
/** \} */
#endif // GGNSS_SDR_SERDES_GALILEO_EPH_H

View File

@ -0,0 +1,185 @@
/*!
* \file serdes_gps_eph.h
* \brief Serialization / Deserialization of Gps_Ephemeris objects using
* Protocol Buffers
* \author Javier Arribas, 2021. jarribas(at)cttc.es
*
* -----------------------------------------------------------------------------
*
* GNSS-SDR is a Global Navigation Satellite System software-defined receiver.
* This file is part of GNSS-SDR.
*
* Copyright (C) 2010-2021 (see AUTHORS file for a list of contributors)
* SPDX-License-Identifier: GPL-3.0-or-later
*
* -----------------------------------------------------------------------------
*/
#ifndef GNSS_SDR_SERDES_GPS_EPH_H
#define GNSS_SDR_SERDES_GPS_EPH_H
#include "gps_ephemeris.h"
#include "gps_ephemeris.pb.h" // file created by Protocol Buffers at compile time
#include <memory>
#include <string>
#include <utility>
/** \addtogroup PVT
* \{ */
/** \addtogroup PVT_libs
* \{ */
/*!
* \brief This class implements serialization and deserialization of
* Gps_Ephemeris objects using Protocol Buffers.
*/
class Serdes_Gps_Eph
{
public:
Serdes_Gps_Eph()
{
// Verify that the version of the library that we linked against is
// compatible with the version of the headers we compiled against.
GOOGLE_PROTOBUF_VERIFY_VERSION;
}
~Serdes_Gps_Eph()
{
// google::protobuf::ShutdownProtobufLibrary();
}
inline Serdes_Gps_Eph(const Serdes_Gps_Eph& other) noexcept //!< Copy constructor
{
this->monitor_ = other.monitor_;
}
inline Serdes_Gps_Eph& operator=(const Serdes_Gps_Eph& rhs) noexcept //!< Copy assignment operator
{
this->monitor_ = rhs.monitor_;
return *this;
}
inline Serdes_Gps_Eph(Serdes_Gps_Eph&& other) noexcept //!< Move constructor
{
this->monitor_ = std::move(other.monitor_);
}
inline Serdes_Gps_Eph& operator=(Serdes_Gps_Eph&& other) noexcept //!< Move assignment operator
{
if (this != &other)
{
this->monitor_ = std::move(other.monitor_);
}
return *this;
}
inline std::string createProtobuffer(const std::shared_ptr<Gps_Ephemeris> monitor) //!< Serialization into a string
{
monitor_.Clear();
std::string data;
monitor_.set_prn(monitor->PRN);
monitor_.set_m_0(monitor->M_0);
monitor_.set_delta_n(monitor->delta_n);
monitor_.set_ecc(monitor->ecc);
monitor_.set_sqrta(monitor->sqrtA);
monitor_.set_omega_0(monitor->OMEGA_0);
monitor_.set_i_0(monitor->i_0);
monitor_.set_omega(monitor->omega);
monitor_.set_omegadot(monitor->OMEGAdot);
monitor_.set_idot(monitor->idot);
monitor_.set_cuc(monitor->Cuc);
monitor_.set_cus(monitor->Cus);
monitor_.set_crc(monitor->Crc);
monitor_.set_crs(monitor->Crs);
monitor_.set_cic(monitor->Cic);
monitor_.set_cis(monitor->Cis);
monitor_.set_toe(monitor->toe);
monitor_.set_toc(monitor->toc);
monitor_.set_af0(monitor->af0);
monitor_.set_af1(monitor->af1);
monitor_.set_af2(monitor->af2);
monitor_.set_satclkdrift(monitor->satClkDrift);
monitor_.set_dtr(monitor->dtr);
monitor_.set_wn(monitor->WN);
monitor_.set_tow(monitor->tow);
// GPS-specific parameters
monitor_.set_code_on_l2(monitor->code_on_L2);
monitor_.set_l2_p_data_flag(monitor->L2_P_data_flag);
monitor_.set_sv_accuracy(monitor->SV_accuracy);
monitor_.set_sv_health(monitor->SV_health);
monitor_.set_tgd(monitor->TGD);
monitor_.set_iodc(monitor->IODC);
monitor_.set_iode_sf2(monitor->IODE_SF2);
monitor_.set_iode_sf3(monitor->IODE_SF3);
monitor_.set_aodo(monitor->AODO);
monitor_.set_fit_interval_flag(monitor->fit_interval_flag);
monitor_.set_spare1(monitor->spare1);
monitor_.set_spare2(monitor->spare2);
monitor_.set_integrity_status_flag(monitor->integrity_status_flag);
monitor_.set_alert_flag(monitor->alert_flag);
monitor_.set_antispoofing_flag(monitor->antispoofing_flag);
monitor_.SerializeToString(&data);
return data;
}
inline Gps_Ephemeris readProtobuffer(const gnss_sdr::GpsEphemeris& mon) const //!< Deserialization
{
Gps_Ephemeris monitor;
monitor.PRN = mon.prn();
monitor.M_0 = mon.m_0();
monitor.delta_n = mon.delta_n();
monitor.ecc = mon.ecc();
monitor.sqrtA = mon.sqrta();
monitor.OMEGA_0 = mon.omega_0();
monitor.i_0 = mon.i_0();
monitor.omega = mon.omega();
monitor.OMEGAdot = mon.omegadot();
monitor.idot = mon.idot();
monitor.Cuc = mon.cuc();
monitor.Cus = mon.cus();
monitor.Crc = mon.crc();
monitor.Crs = mon.crs();
monitor.Cic = mon.cic();
monitor.Cis = mon.cis();
monitor.toe = mon.toe();
monitor.toc = mon.toc();
monitor.af0 = mon.af0();
monitor.af1 = mon.af1();
monitor.af2 = mon.af2();
monitor.satClkDrift = mon.satclkdrift();
monitor.dtr = mon.dtr();
monitor.WN = mon.wn();
monitor.tow = mon.tow();
// GPS-specific parameters
monitor.code_on_L2 = mon.code_on_l2();
monitor.L2_P_data_flag = mon.l2_p_data_flag();
monitor.SV_accuracy = mon.sv_accuracy();
monitor.SV_health = mon.sv_health();
monitor.TGD = mon.tgd();
monitor.IODC = mon.iodc();
monitor.IODE_SF2 = mon.iode_sf2();
monitor.IODE_SF3 = mon.iode_sf3();
monitor.AODO = mon.aodo();
monitor.fit_interval_flag = mon.fit_interval_flag();
monitor.spare1 = mon.spare1();
monitor.spare2 = mon.spare2();
monitor.integrity_status_flag = mon.integrity_status_flag();
monitor.alert_flag = mon.alert_flag();
monitor.antispoofing_flag = mon.antispoofing_flag();
return monitor;
}
private:
gnss_sdr::GpsEphemeris monitor_{};
};
/** \} */
/** \} */
#endif // GNSS_SDR_SERDES_GPS_EPH_H

View File

@ -162,13 +162,13 @@ void pcps_assisted_acquisition_cc::get_assistance()
// TODO: use the LO tolerance here
if (gps_acq_assisistance.dopplerUncertainty >= 1000)
{
d_doppler_max = gps_acq_assisistance.d_Doppler0 + gps_acq_assisistance.dopplerUncertainty * 2;
d_doppler_min = gps_acq_assisistance.d_Doppler0 - gps_acq_assisistance.dopplerUncertainty * 2;
d_doppler_max = gps_acq_assisistance.Doppler0 + gps_acq_assisistance.dopplerUncertainty * 2;
d_doppler_min = gps_acq_assisistance.Doppler0 - gps_acq_assisistance.dopplerUncertainty * 2;
}
else
{
d_doppler_max = gps_acq_assisistance.d_Doppler0 + 1000;
d_doppler_min = gps_acq_assisistance.d_Doppler0 - 1000;
d_doppler_max = gps_acq_assisistance.Doppler0 + 1000;
d_doppler_min = gps_acq_assisistance.Doppler0 - 1000;
}
this->d_disable_assist = false;
std::cout << "Acq assist ENABLED for GPS SV " << this->d_gnss_synchro->PRN << " (Doppler max,Doppler min)=("

View File

@ -44,10 +44,9 @@ Acq_Conf::Acq_Conf()
dump = false;
blocking = true;
make_2_steps = false;
dump_filename = "";
dump_channel = 0U;
it_size = sizeof(gr_complex);
item_type = "gr_complex";
item_type = std::string("gr_complex");
blocking_on_standby = false;
use_automatic_resampler = false;
resampler_ratio = 1.0;

View File

@ -179,25 +179,25 @@ gr::basic_block_sptr Channel::get_left_block_trk()
return trk_->get_left_block();
}
gr::basic_block_sptr Channel::get_right_block_trk()
{
return trk_->get_right_block();
}
gr::basic_block_sptr Channel::get_left_block_acq()
{
if (flag_enable_fpga_)
{
LOG(ERROR) << "Enabled FPGA and called get_left_block() in channel interface";
}
return acq_->get_left_block();
}
gr::basic_block_sptr Channel::get_right_block_acq()
{
return acq_->get_right_block();
}
gr::basic_block_sptr Channel::get_right_block()
{
return nav_->get_right_block();

View File

@ -32,6 +32,7 @@ set(GNSS_SPLIBS_SOURCES
trackingcmd.cc
pass_through.cc
short_x2_to_cshort.cc
gnss_sdr_string_literals.cc
)
set(GNSS_SPLIBS_HEADERS
@ -63,6 +64,7 @@ set(GNSS_SPLIBS_HEADERS
trackingcmd.h
pass_through.h
short_x2_to_cshort.h
gnss_sdr_string_literals.h
)
if(ENABLE_OPENCL)

View File

@ -0,0 +1,42 @@
/*!
* \file gnss_sdr_string_literals.cc
* \brief This file implements the ""s operator for std::string in C++11, and
* puts it into the std::string_literals namespace. This is already implemented
* in C++14, so this is only compiled when using C++11. The .cc file is required
* for avoiding the duplication of symbols.
*
* \author Carles Fernandez-Prades, 2021. cfernandez(at)cttc.es
*
*
* -----------------------------------------------------------------------------
*
* GNSS-SDR is a Global Navigation Satellite System software-defined receiver.
* This file is part of GNSS-SDR.
*
* Copyright (C) 2010-2021 (see AUTHORS file for a list of contributors)
* SPDX-License-Identifier: GPL-3.0-or-later
*
* -----------------------------------------------------------------------------
*/
#include "gnss_sdr_string_literals.h"
#if __cplusplus == 201103L
namespace std
{
namespace string_literals
{
std::string operator"" s(const char* str, std::size_t len)
{
return std::string(str, len);
};
} // namespace string_literals
} // namespace std
#else
// Avoid "gnss_sdr_string_literals.cc.o has no symbols" warning in MacOS with a
// dummy symbol so ranlib does not complain
void avoid_no_symbols_warning() {}
#endif // __cplusplus == 201103L

View File

@ -0,0 +1,48 @@
/*!
* \file gnss_sdr_string_literals.h
* \brief This file implements the ""s operator for std::string in C++11, and
* puts it into the std::string_literals namespace. This is already implemented
* in C++14, so this is only compiled when using C++11. The .cc file is required
* for avoiding the duplication of symbols.
*
* \author Carles Fernandez-Prades, 2021. cfernandez(at)cttc.es
*
*
* -----------------------------------------------------------------------------
*
* GNSS-SDR is a Global Navigation Satellite System software-defined receiver.
* This file is part of GNSS-SDR.
*
* Copyright (C) 2010-2021 (see AUTHORS file for a list of contributors)
* SPDX-License-Identifier: GPL-3.0-or-later
*
* -----------------------------------------------------------------------------
*/
#ifndef GNSS_SDR_STRING_LITERALS_H
#define GNSS_SDR_STRING_LITERALS_H
/** \addtogroup Algorithms_Library
* \{ */
/** \addtogroup Algorithm_libs algorithms_libs
* \{ */
#if __cplusplus == 201103L
#include <cstddef>
#include <string>
namespace std
{
namespace string_literals
{
std::string operator"" s(const char* str, std::size_t len);
} // namespace string_literals
} // namespace std
#endif // __cplusplus == 201103L
/** \} */
/** \} */
#endif // GNSS_SDR_STRING_LITERALS_H

View File

@ -186,18 +186,15 @@ const int MAXPRNGAL = 36; //!< max satellite PRN numbe
const int NSATGAL = (MAXPRNGAL - MINPRNGAL + 1); //!< number of Galileo satellites
const int NSYSGAL = 1;
const int MAXPRNQZS = 199; //!< max satellite PRN number of QZSS
const int MINPRNQZS = 193; //!< min satellite PRN number of QZSS
#ifdef ENAQZS
const int MINPRNQZS = 193; //!< min satellite PRN number of QZSS
const int MAXPRNQZS = 199; //!< max satellite PRN number of QZSS
const int MINPRNQZS_S = 183; //!< min satellite PRN number of QZSS SAIF
const int MAXPRNQZS_S = 189; //!< max satellite PRN number of QZSS SAIF
const int NSATQZS = (MAXPRNQZS - MINPRNQZS + 1); //!< number of QZSS satellites
const int NSYSQZS = 1;
#else
const int MINPRNQZS = 0;
const int MAXPRNQZS = 0;
const int MINPRNQZS_S = 0;
const int MAXPRNQZS_S = 0;
const int NSATQZS = 0;
const int NSYSQZS = 0;
#endif
@ -215,26 +212,22 @@ const int NSATBDS = 0;
const int NSYSBDS = 0;
#endif
const int MINPRNIRN = 1; //!< min satellite sat number of IRNSS
const int MAXPRNIRN = 7; //!< max satellite sat number of IRNSS
#ifdef ENAIRN
const int MINPRNIRN = 1; //!< min satellite sat number of IRNSS
const int MAXPRNIRN = 7; //!< max satellite sat number of IRNSS
const int NSATIRN = (MAXPRNIRN - MINPRNIRN + 1); //!< number of IRNSS satellites
const int NSYSIRN = 1;
#else
const int MINPRNIRN = 0;
const int MAXPRNIRN = 0;
const int NSATIRN = 0;
const int NSYSIRN = 0;
#endif
const int MINPRNLEO = 1; //!< min satellite sat number of LEO
const int MAXPRNLEO = 10; //!< max satellite sat number of LEO */
#ifdef ENALEO
const int MINPRNLEO = 1; //!< min satellite sat number of LEO
const int NSATLEO = 10; //!< max satellite sat number of LEO
const int NSATLEO = (MAXPRNLEO - MINPRNLEO + 1); //!< number of LEO satellites
const int NSYSLEO = 1;
#else
const int MINPRNLEO = 0;
const int MAXPRNLEO = 0;
const int NSATLEO = 0;
const int NSYSLEO = 0;
#endif

View File

@ -168,36 +168,36 @@ eph_t eph_to_rtklib(const Galileo_Ephemeris& gal_eph)
eph_t rtklib_sat = {0, 0, 0, 0, 0, 0, 0, 0, {0, 0}, {0, 0}, {0, 0}, 0.0, 0.0, 0.0, 0.0, 0.0,
0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, {}, {}, 0.0, 0.0};
// Galileo is the third satellite system for RTKLIB, so, add the required offset to discriminate Galileo ephemeris
rtklib_sat.sat = gal_eph.i_satellite_PRN + NSATGPS + NSATGLO;
rtklib_sat.A = gal_eph.A_1 * gal_eph.A_1;
rtklib_sat.M0 = gal_eph.M0_1;
rtklib_sat.deln = gal_eph.delta_n_3;
rtklib_sat.OMG0 = gal_eph.OMEGA_0_2;
rtklib_sat.OMGd = gal_eph.OMEGA_dot_3;
rtklib_sat.omg = gal_eph.omega_2;
rtklib_sat.i0 = gal_eph.i_0_2;
rtklib_sat.idot = gal_eph.iDot_2;
rtklib_sat.e = gal_eph.e_1;
rtklib_sat.sat = gal_eph.PRN + NSATGPS + NSATGLO;
rtklib_sat.A = gal_eph.sqrtA * gal_eph.sqrtA;
rtklib_sat.M0 = gal_eph.M_0;
rtklib_sat.deln = gal_eph.delta_n;
rtklib_sat.OMG0 = gal_eph.OMEGA_0;
rtklib_sat.OMGd = gal_eph.OMEGAdot;
rtklib_sat.omg = gal_eph.omega;
rtklib_sat.i0 = gal_eph.i_0;
rtklib_sat.idot = gal_eph.idot;
rtklib_sat.e = gal_eph.ecc;
rtklib_sat.Adot = 0; // only in CNAV;
rtklib_sat.ndot = 0; // only in CNAV;
rtklib_sat.week = gal_eph.WN_5 + 1024; /* week of tow in GPS (not mod-1024) week scale */
rtklib_sat.cic = gal_eph.C_ic_4;
rtklib_sat.cis = gal_eph.C_is_4;
rtklib_sat.cuc = gal_eph.C_uc_3;
rtklib_sat.cus = gal_eph.C_us_3;
rtklib_sat.crc = gal_eph.C_rc_3;
rtklib_sat.crs = gal_eph.C_rs_3;
rtklib_sat.f0 = gal_eph.af0_4;
rtklib_sat.f1 = gal_eph.af1_4;
rtklib_sat.f2 = gal_eph.af2_4;
rtklib_sat.tgd[0] = gal_eph.BGD_E1E5a_5;
rtklib_sat.tgd[1] = gal_eph.BGD_E1E5b_5;
rtklib_sat.week = gal_eph.WN + 1024; /* week of tow in GPS (not mod-1024) week scale */
rtklib_sat.cic = gal_eph.Cic;
rtklib_sat.cis = gal_eph.Cis;
rtklib_sat.cuc = gal_eph.Cuc;
rtklib_sat.cus = gal_eph.Cus;
rtklib_sat.crc = gal_eph.Crc;
rtklib_sat.crs = gal_eph.Crs;
rtklib_sat.f0 = gal_eph.af0;
rtklib_sat.f1 = gal_eph.af1;
rtklib_sat.f2 = gal_eph.af2;
rtklib_sat.tgd[0] = gal_eph.BGD_E1E5a;
rtklib_sat.tgd[1] = gal_eph.BGD_E1E5b;
rtklib_sat.tgd[2] = 0;
rtklib_sat.tgd[3] = 0;
rtklib_sat.toes = gal_eph.t0e_1;
rtklib_sat.toc = gpst2time(rtklib_sat.week, gal_eph.t0c_4);
rtklib_sat.ttr = gpst2time(rtklib_sat.week, gal_eph.TOW_5);
rtklib_sat.toes = gal_eph.toe;
rtklib_sat.toc = gpst2time(rtklib_sat.week, gal_eph.toc);
rtklib_sat.ttr = gpst2time(rtklib_sat.week, gal_eph.tow);
/* adjustment for week handover */
double tow;
@ -226,36 +226,36 @@ eph_t eph_to_rtklib(const Gps_Ephemeris& gps_eph, bool pre_2009_file)
{
eph_t rtklib_sat = {0, 0, 0, 0, 0, 0, 0, 0, {0, 0}, {0, 0}, {0, 0}, 0.0, 0.0, 0.0, 0.0, 0.0,
0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, {}, {}, 0.0, 0.0};
rtklib_sat.sat = gps_eph.i_satellite_PRN;
rtklib_sat.A = gps_eph.d_sqrt_A * gps_eph.d_sqrt_A;
rtklib_sat.M0 = gps_eph.d_M_0;
rtklib_sat.deln = gps_eph.d_Delta_n;
rtklib_sat.OMG0 = gps_eph.d_OMEGA0;
rtklib_sat.OMGd = gps_eph.d_OMEGA_DOT;
rtklib_sat.omg = gps_eph.d_OMEGA;
rtklib_sat.i0 = gps_eph.d_i_0;
rtklib_sat.idot = gps_eph.d_IDOT;
rtklib_sat.e = gps_eph.d_e_eccentricity;
rtklib_sat.sat = gps_eph.PRN;
rtklib_sat.A = gps_eph.sqrtA * gps_eph.sqrtA;
rtklib_sat.M0 = gps_eph.M_0;
rtklib_sat.deln = gps_eph.delta_n;
rtklib_sat.OMG0 = gps_eph.OMEGA_0;
rtklib_sat.OMGd = gps_eph.OMEGAdot;
rtklib_sat.omg = gps_eph.omega;
rtklib_sat.i0 = gps_eph.i_0;
rtklib_sat.idot = gps_eph.idot;
rtklib_sat.e = gps_eph.ecc;
rtklib_sat.Adot = 0; // only in CNAV;
rtklib_sat.ndot = 0; // only in CNAV;
rtklib_sat.week = adjgpsweek(gps_eph.i_GPS_week, pre_2009_file); /* week of tow */
rtklib_sat.cic = gps_eph.d_Cic;
rtklib_sat.cis = gps_eph.d_Cis;
rtklib_sat.cuc = gps_eph.d_Cuc;
rtklib_sat.cus = gps_eph.d_Cus;
rtklib_sat.crc = gps_eph.d_Crc;
rtklib_sat.crs = gps_eph.d_Crs;
rtklib_sat.f0 = gps_eph.d_A_f0;
rtklib_sat.f1 = gps_eph.d_A_f1;
rtklib_sat.f2 = gps_eph.d_A_f2;
rtklib_sat.tgd[0] = gps_eph.d_TGD;
rtklib_sat.week = adjgpsweek(gps_eph.WN, pre_2009_file); /* week of tow */
rtklib_sat.cic = gps_eph.Cic;
rtklib_sat.cis = gps_eph.Cis;
rtklib_sat.cuc = gps_eph.Cuc;
rtklib_sat.cus = gps_eph.Cus;
rtklib_sat.crc = gps_eph.Crc;
rtklib_sat.crs = gps_eph.Crs;
rtklib_sat.f0 = gps_eph.af0;
rtklib_sat.f1 = gps_eph.af1;
rtklib_sat.f2 = gps_eph.af2;
rtklib_sat.tgd[0] = gps_eph.TGD;
rtklib_sat.tgd[1] = 0.0;
rtklib_sat.tgd[2] = 0.0;
rtklib_sat.tgd[3] = 0.0;
rtklib_sat.toes = gps_eph.d_Toe;
rtklib_sat.toc = gpst2time(rtklib_sat.week, gps_eph.d_Toc);
rtklib_sat.ttr = gpst2time(rtklib_sat.week, gps_eph.d_TOW);
rtklib_sat.toes = gps_eph.toe;
rtklib_sat.toc = gpst2time(rtklib_sat.week, gps_eph.toc);
rtklib_sat.ttr = gpst2time(rtklib_sat.week, gps_eph.tow);
/* adjustment for week handover */
double tow;
@ -284,45 +284,45 @@ eph_t eph_to_rtklib(const Beidou_Dnav_Ephemeris& bei_eph)
{
eph_t rtklib_sat = {0, 0, 0, 0, 0, 0, 0, 0, {0, 0}, {0, 0}, {0, 0}, 0.0, 0.0, 0.0, 0.0, 0.0,
0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, {}, {}, 0.0, 0.0};
rtklib_sat.sat = bei_eph.i_satellite_PRN + NSATGPS + NSATGLO + NSATGAL + NSATQZS;
rtklib_sat.A = bei_eph.d_sqrt_A * bei_eph.d_sqrt_A;
rtklib_sat.M0 = bei_eph.d_M_0;
rtklib_sat.deln = bei_eph.d_Delta_n;
rtklib_sat.OMG0 = bei_eph.d_OMEGA0;
rtklib_sat.OMGd = bei_eph.d_OMEGA_DOT;
rtklib_sat.omg = bei_eph.d_OMEGA;
rtklib_sat.i0 = bei_eph.d_i_0;
rtklib_sat.idot = bei_eph.d_IDOT;
rtklib_sat.e = bei_eph.d_eccentricity;
rtklib_sat.sat = bei_eph.PRN + NSATGPS + NSATGLO + NSATGAL + NSATQZS;
rtklib_sat.A = bei_eph.sqrtA * bei_eph.sqrtA;
rtklib_sat.M0 = bei_eph.M_0;
rtklib_sat.deln = bei_eph.delta_n;
rtklib_sat.OMG0 = bei_eph.OMEGA_0;
rtklib_sat.OMGd = bei_eph.OMEGAdot;
rtklib_sat.omg = bei_eph.omega;
rtklib_sat.i0 = bei_eph.i_0;
rtklib_sat.idot = bei_eph.idot;
rtklib_sat.e = bei_eph.ecc;
rtklib_sat.Adot = 0; // only in CNAV;
rtklib_sat.ndot = 0; // only in CNAV;
rtklib_sat.svh = bei_eph.i_SV_health;
rtklib_sat.sva = bei_eph.i_SV_accuracy;
rtklib_sat.svh = bei_eph.SV_health;
rtklib_sat.sva = bei_eph.SV_accuracy;
rtklib_sat.code = bei_eph.i_sig_type; /* B1I data */
rtklib_sat.flag = bei_eph.i_nav_type; /* MEO/IGSO satellite */
rtklib_sat.iode = static_cast<int32_t>(bei_eph.d_AODE); /* AODE */
rtklib_sat.iodc = static_cast<int32_t>(bei_eph.d_AODC); /* AODC */
rtklib_sat.code = bei_eph.sig_type; /* B1I data */
rtklib_sat.flag = bei_eph.nav_type; /* MEO/IGSO satellite */
rtklib_sat.iode = static_cast<int32_t>(bei_eph.AODE); /* AODE */
rtklib_sat.iodc = static_cast<int32_t>(bei_eph.AODC); /* AODC */
rtklib_sat.week = bei_eph.i_BEIDOU_week; /* week of tow */
rtklib_sat.cic = bei_eph.d_Cic;
rtklib_sat.cis = bei_eph.d_Cis;
rtklib_sat.cuc = bei_eph.d_Cuc;
rtklib_sat.cus = bei_eph.d_Cus;
rtklib_sat.crc = bei_eph.d_Crc;
rtklib_sat.crs = bei_eph.d_Crs;
rtklib_sat.f0 = bei_eph.d_A_f0;
rtklib_sat.f1 = bei_eph.d_A_f1;
rtklib_sat.f2 = bei_eph.d_A_f2;
rtklib_sat.tgd[0] = bei_eph.d_TGD1;
rtklib_sat.tgd[1] = bei_eph.d_TGD2;
rtklib_sat.week = bei_eph.WN; /* week of tow */
rtklib_sat.cic = bei_eph.Cic;
rtklib_sat.cis = bei_eph.Cis;
rtklib_sat.cuc = bei_eph.Cuc;
rtklib_sat.cus = bei_eph.Cus;
rtklib_sat.crc = bei_eph.Crc;
rtklib_sat.crs = bei_eph.Crs;
rtklib_sat.f0 = bei_eph.af0;
rtklib_sat.f1 = bei_eph.af1;
rtklib_sat.f2 = bei_eph.af2;
rtklib_sat.tgd[0] = bei_eph.TGD1;
rtklib_sat.tgd[1] = bei_eph.TGD2;
rtklib_sat.tgd[2] = 0.0;
rtklib_sat.tgd[3] = 0.0;
rtklib_sat.toes = bei_eph.d_Toe;
rtklib_sat.toe = bdt2gpst(bdt2time(rtklib_sat.week, bei_eph.d_Toe));
rtklib_sat.toc = bdt2gpst(bdt2time(rtklib_sat.week, bei_eph.d_Toc));
rtklib_sat.ttr = bdt2gpst(bdt2time(rtklib_sat.week, bei_eph.d_TOW));
rtklib_sat.toes = bei_eph.toe;
rtklib_sat.toe = bdt2gpst(bdt2time(rtklib_sat.week, bei_eph.toe));
rtklib_sat.toc = bdt2gpst(bdt2time(rtklib_sat.week, bei_eph.toc));
rtklib_sat.ttr = bdt2gpst(bdt2time(rtklib_sat.week, bei_eph.tow));
/* adjustment for week handover */
double tow;
double toc;
@ -353,44 +353,40 @@ eph_t eph_to_rtklib(const Gps_CNAV_Ephemeris& gps_cnav_eph)
{
eph_t rtklib_sat = {0, 0, 0, 0, 0, 0, 0, 0, {0, 0}, {0, 0}, {0, 0}, 0.0, 0.0, 0.0, 0.0, 0.0,
0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, {}, {}, 0.0, 0.0};
rtklib_sat.sat = gps_cnav_eph.i_satellite_PRN;
const double A_REF = 26559710.0; // See IS-GPS-200L, pp. 161
rtklib_sat.A = A_REF + gps_cnav_eph.d_DELTA_A;
rtklib_sat.M0 = gps_cnav_eph.d_M_0;
rtklib_sat.deln = gps_cnav_eph.d_Delta_n;
rtklib_sat.OMG0 = gps_cnav_eph.d_OMEGA0;
// Compute the angle between the ascending node and the Greenwich meridian
const double OMEGA_DOT_REF = -2.6e-9; // semicircles / s, see IS-GPS-200L pp. 160
double d_OMEGA_DOT = OMEGA_DOT_REF * GNSS_PI + gps_cnav_eph.d_DELTA_OMEGA_DOT;
rtklib_sat.OMGd = d_OMEGA_DOT;
rtklib_sat.omg = gps_cnav_eph.d_OMEGA;
rtklib_sat.i0 = gps_cnav_eph.d_i_0;
rtklib_sat.idot = gps_cnav_eph.d_IDOT;
rtklib_sat.e = gps_cnav_eph.d_e_eccentricity;
rtklib_sat.Adot = gps_cnav_eph.d_A_DOT; // only in CNAV;
rtklib_sat.ndot = gps_cnav_eph.d_DELTA_DOT_N; // only in CNAV;
rtklib_sat.sat = gps_cnav_eph.PRN;
rtklib_sat.A = gps_cnav_eph.sqrtA * gps_cnav_eph.sqrtA;
rtklib_sat.M0 = gps_cnav_eph.M_0;
rtklib_sat.deln = gps_cnav_eph.delta_n;
rtklib_sat.OMG0 = gps_cnav_eph.OMEGA_0;
rtklib_sat.OMGd = gps_cnav_eph.OMEGAdot;
rtklib_sat.omg = gps_cnav_eph.omega;
rtklib_sat.i0 = gps_cnav_eph.i_0;
rtklib_sat.idot = gps_cnav_eph.idot;
rtklib_sat.e = gps_cnav_eph.ecc;
rtklib_sat.Adot = gps_cnav_eph.Adot; // only in CNAV;
rtklib_sat.ndot = gps_cnav_eph.delta_ndot; // only in CNAV;
rtklib_sat.week = adjgpsweek(gps_cnav_eph.i_GPS_week); /* week of tow */
rtklib_sat.cic = gps_cnav_eph.d_Cic;
rtklib_sat.cis = gps_cnav_eph.d_Cis;
rtklib_sat.cuc = gps_cnav_eph.d_Cuc;
rtklib_sat.cus = gps_cnav_eph.d_Cus;
rtklib_sat.crc = gps_cnav_eph.d_Crc;
rtklib_sat.crs = gps_cnav_eph.d_Crs;
rtklib_sat.f0 = gps_cnav_eph.d_A_f0;
rtklib_sat.f1 = gps_cnav_eph.d_A_f1;
rtklib_sat.f2 = gps_cnav_eph.d_A_f2;
rtklib_sat.tgd[0] = gps_cnav_eph.d_TGD;
rtklib_sat.week = adjgpsweek(gps_cnav_eph.WN); /* week of tow */
rtklib_sat.cic = gps_cnav_eph.Cic;
rtklib_sat.cis = gps_cnav_eph.Cis;
rtklib_sat.cuc = gps_cnav_eph.Cuc;
rtklib_sat.cus = gps_cnav_eph.Cus;
rtklib_sat.crc = gps_cnav_eph.Crc;
rtklib_sat.crs = gps_cnav_eph.Crs;
rtklib_sat.f0 = gps_cnav_eph.af0;
rtklib_sat.f1 = gps_cnav_eph.af1;
rtklib_sat.f2 = gps_cnav_eph.af2;
rtklib_sat.tgd[0] = gps_cnav_eph.TGD;
rtklib_sat.tgd[1] = 0.0;
rtklib_sat.tgd[2] = 0.0;
rtklib_sat.tgd[3] = 0.0;
rtklib_sat.isc[0] = gps_cnav_eph.d_ISCL1;
rtklib_sat.isc[1] = gps_cnav_eph.d_ISCL2;
rtklib_sat.isc[2] = gps_cnav_eph.d_ISCL5I;
rtklib_sat.isc[3] = gps_cnav_eph.d_ISCL5Q;
rtklib_sat.toes = gps_cnav_eph.d_Toe1;
rtklib_sat.toc = gpst2time(rtklib_sat.week, gps_cnav_eph.d_Toc);
rtklib_sat.ttr = gpst2time(rtklib_sat.week, gps_cnav_eph.d_TOW);
rtklib_sat.isc[0] = gps_cnav_eph.ISCL1;
rtklib_sat.isc[1] = gps_cnav_eph.ISCL2;
rtklib_sat.isc[2] = gps_cnav_eph.ISCL5I;
rtklib_sat.isc[3] = gps_cnav_eph.ISCL5Q;
rtklib_sat.toes = gps_cnav_eph.toe1;
rtklib_sat.toc = gpst2time(rtklib_sat.week, gps_cnav_eph.toc);
rtklib_sat.ttr = gpst2time(rtklib_sat.week, gps_cnav_eph.tow);
/* adjustment for week handover */
double tow;
@ -421,24 +417,24 @@ alm_t alm_to_rtklib(const Gps_Almanac& gps_alm)
rtklib_alm = {0, 0, 0, 0, {0, 0}, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0};
rtklib_alm.sat = gps_alm.i_satellite_PRN;
rtklib_alm.svh = gps_alm.i_SV_health;
rtklib_alm.svconf = gps_alm.i_AS_status;
rtklib_alm.week = gps_alm.i_WNa;
rtklib_alm.sat = gps_alm.PRN;
rtklib_alm.svh = gps_alm.SV_health;
rtklib_alm.svconf = gps_alm.AS_status;
rtklib_alm.week = gps_alm.WNa;
gtime_t toa;
toa.time = gps_alm.i_Toa;
toa.time = gps_alm.toa;
toa.sec = 0.0;
rtklib_alm.toa = toa;
rtklib_alm.A = gps_alm.d_sqrt_A * gps_alm.d_sqrt_A;
rtklib_alm.e = gps_alm.d_e_eccentricity;
rtklib_alm.i0 = (gps_alm.d_Delta_i + 0.3) * GNSS_PI;
rtklib_alm.OMG0 = gps_alm.d_OMEGA0 * GNSS_PI;
rtklib_alm.OMGd = gps_alm.d_OMEGA_DOT * GNSS_PI;
rtklib_alm.omg = gps_alm.d_OMEGA * GNSS_PI;
rtklib_alm.M0 = gps_alm.d_M_0 * GNSS_PI;
rtklib_alm.f0 = gps_alm.d_A_f0;
rtklib_alm.f1 = gps_alm.d_A_f1;
rtklib_alm.toas = gps_alm.i_Toa;
rtklib_alm.A = gps_alm.sqrtA * gps_alm.sqrtA;
rtklib_alm.e = gps_alm.ecc;
rtklib_alm.i0 = (gps_alm.delta_i + 0.3) * GNSS_PI;
rtklib_alm.OMG0 = gps_alm.OMEGA_0 * GNSS_PI;
rtklib_alm.OMGd = gps_alm.OMEGAdot * GNSS_PI;
rtklib_alm.omg = gps_alm.omega * GNSS_PI;
rtklib_alm.M0 = gps_alm.M_0 * GNSS_PI;
rtklib_alm.f0 = gps_alm.af0;
rtklib_alm.f1 = gps_alm.af1;
rtklib_alm.toas = gps_alm.toa;
return rtklib_alm;
}
@ -450,25 +446,25 @@ alm_t alm_to_rtklib(const Galileo_Almanac& gal_alm)
rtklib_alm = {0, 0, 0, 0, {0, 0}, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0};
rtklib_alm.sat = gal_alm.i_satellite_PRN + NSATGPS + NSATGLO;
rtklib_alm.sat = gal_alm.PRN + NSATGPS + NSATGLO;
rtklib_alm.svh = gal_alm.E1B_HS;
rtklib_alm.svconf = gal_alm.E1B_HS;
rtklib_alm.week = gal_alm.i_WNa;
rtklib_alm.week = gal_alm.WNa;
gtime_t toa;
toa.time = gal_alm.i_Toa;
toa.time = gal_alm.toa;
toa.sec = 0.0;
rtklib_alm.toa = toa;
rtklib_alm.A = 5440.588203494 + gal_alm.d_Delta_sqrt_A;
rtklib_alm.A = 5440.588203494 + gal_alm.delta_sqrtA;
rtklib_alm.A = rtklib_alm.A * rtklib_alm.A;
rtklib_alm.e = gal_alm.d_e_eccentricity;
rtklib_alm.i0 = (gal_alm.d_Delta_i + 56.0 / 180.0) * GNSS_PI;
rtklib_alm.OMG0 = gal_alm.d_OMEGA0 * GNSS_PI;
rtklib_alm.OMGd = gal_alm.d_OMEGA_DOT * GNSS_PI;
rtklib_alm.omg = gal_alm.d_OMEGA * GNSS_PI;
rtklib_alm.M0 = gal_alm.d_M_0 * GNSS_PI;
rtklib_alm.f0 = gal_alm.d_A_f0;
rtklib_alm.f1 = gal_alm.d_A_f1;
rtklib_alm.toas = gal_alm.i_Toa;
rtklib_alm.e = gal_alm.ecc;
rtklib_alm.i0 = (gal_alm.delta_i + 56.0 / 180.0) * GNSS_PI;
rtklib_alm.OMG0 = gal_alm.OMEGA_0 * GNSS_PI;
rtklib_alm.OMGd = gal_alm.OMEGAdot * GNSS_PI;
rtklib_alm.omg = gal_alm.omega * GNSS_PI;
rtklib_alm.M0 = gal_alm.M_0 * GNSS_PI;
rtklib_alm.f0 = gal_alm.af0;
rtklib_alm.f1 = gal_alm.af1;
rtklib_alm.toas = gal_alm.toa;
return rtklib_alm;
}

View File

@ -31,6 +31,7 @@
#include "rtklib_rtkcmn.h"
#include <glog/logging.h>
#include <cassert>
#include <cstring>
#include <dirent.h>
#include <iostream>
@ -273,19 +274,19 @@ int satno(int sys, int prn)
}
return NSATGPS + NSATGLO + NSATGAL + prn - MINPRNQZS + 1;
case SYS_BDS:
if (prn < MINPRNBDS || MAXPRNBDS < prn)
if (MAXPRNBDS < prn)
{
return 0;
}
return NSATGPS + NSATGLO + NSATGAL + NSATQZS + prn - MINPRNBDS + 1;
case SYS_IRN:
if (prn < MINPRNIRN || MAXPRNIRN < prn)
if (MAXPRNIRN < prn)
{
return 0;
}
return NSATGPS + NSATGLO + NSATGAL + NSATQZS + NSATBDS + prn - MINPRNIRN + 1;
case SYS_LEO:
if (prn < MINPRNLEO || MAXPRNLEO < prn)
if (MAXPRNLEO < prn)
{
return 0;
}
@ -442,6 +443,11 @@ int satid2no(const char *id)
default:
return 0;
}
if (prn <= 0 || prn > MAXSAT)
{
return 0;
}
return satno(sys, prn);
}
@ -1417,6 +1423,7 @@ void matfprint(const double A[], int n, int m, int p, int q, FILE *fp)
}
}
void matsprint(const double A[], int n, int m, int p, int q, std::string &buffer)
{
int i;
@ -2689,6 +2696,20 @@ void addpcv(const pcv_t *pcv, pcvs_t *pcvs)
}
/* strncpy without truncation ------------------------------------------------*/
char *strncpy_no_trunc(char *out, size_t outsz, const char *in, size_t insz)
{
assert(outsz > 0);
while (--outsz > 0 && insz > 0 && *in)
{
*out++ = *in++;
insz--;
}
*out = 0;
return out;
}
/* read ngs antenna parameter file -------------------------------------------*/
int readngspcv(const char *file, pcvs_t *pcvs)
{
@ -2718,7 +2739,7 @@ int readngspcv(const char *file, pcvs_t *pcvs)
if (++n == 1)
{
pcv = pcv0;
strncpy(pcv.type, buff, 61);
strncpy_no_trunc(pcv.type, 61, buff, 256);
pcv.type[61] = '\0';
}
else if (n == 2)

View File

@ -59,6 +59,7 @@
#define GNSS_SDR_RTKLIB_RTKCMN_H
#include "rtklib.h"
#include <cstddef>
#include <string>
@ -96,7 +97,7 @@
} \
while (0)
char *strncpy_no_trunc(char *out, size_t outsz, const char *in, size_t insz);
void fatalerr(const char *format, ...);
int satno(int sys, int prn);
int satsys(int sat, int *prn);

View File

@ -232,7 +232,7 @@ void read_results(std::vector<volk_gnsssdr_test_results_t> *results, std::string
if (single_kernel_result.size() == 3)
{
volk_gnsssdr_test_results_t kernel_result;
volk_gnsssdr_test_results_t kernel_result{};
kernel_result.name = std::string(single_kernel_result[0]);
kernel_result.config_name = std::string(single_kernel_result[0]);
kernel_result.best_arch_u = std::string(single_kernel_result[1]);

View File

@ -119,8 +119,11 @@ if(FILESYSTEM_FIND_QUIETLY)
set(CMAKE_REQUIRED_QUIET ${FILESYSTEM_FIND_QUIETLY})
endif()
# All of our tests require C++17 or later
if((CMAKE_CXX_COMPILER_ID STREQUAL "GNU") AND (CMAKE_CXX_COMPILER_VERSION VERSION_GREATER "9.0.0"))
set(CMAKE_CXX_STANDARD 17)
if((CMAKE_CXX_COMPILER_ID STREQUAL "GNU") AND (CMAKE_CXX_COMPILER_VERSION VERSION_GREATER "8.0.0"))
if(CMAKE_CXX_COMPILER_VERSION VERSION_LESS "8.99")
set(UNDEFINED_BEHAVIOR_WITHOUT_LINKING TRUE)
endif()
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"))
@ -205,9 +208,10 @@ if(CXX_FILESYSTEM_HAVE_FS)
]] 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 UNDEFINED_BEHAVIOR_WITHOUT_LINKING)
check_cxx_source_compiles("${code}" CXX_FILESYSTEM_NO_LINK_NEEDED)
set(can_link ${CXX_FILESYSTEM_NO_LINK_NEEDED})
endif()
if(NOT CXX_FILESYSTEM_NO_LINK_NEEDED)
set(prev_libraries ${CMAKE_REQUIRED_LIBRARIES})

View File

@ -20,7 +20,7 @@
Obs_Conf::Obs_Conf()
{
dump_filename = "obs_dump.dat";
dump_filename = std::string("obs_dump.dat");
smoothing_factor = FLAGS_carrier_smoothing_factor;
nchannels_in = 0;
nchannels_out = 0;

View File

@ -100,6 +100,8 @@ endif()
set(SIGNAL_SOURCE_ADAPTER_SOURCES
signal_source_base.cc
file_source_base.cc
file_signal_source.cc
multichannel_file_signal_source.cc
gen_signal_source.cc
@ -114,6 +116,8 @@ set(SIGNAL_SOURCE_ADAPTER_SOURCES
)
set(SIGNAL_SOURCE_ADAPTER_HEADERS
signal_source_base.h
file_source_base.h
file_signal_source.h
multichannel_file_signal_source.h
gen_signal_source.h
@ -164,6 +168,7 @@ target_link_libraries(signal_source_adapters
Gnuradio::blocks
signal_source_gr_blocks
PRIVATE
algorithms_libs
gnss_sdr_flags
core_system_parameters
Glog::glog

View File

@ -25,6 +25,7 @@
#include "ad9361_manager.h"
#include "configuration_interface.h"
#include "gnss_sdr_flags.h"
#include "gnss_sdr_string_literals.h"
#include "uio_fpga.h"
#include <glog/logging.h>
#include <iio.h>
@ -42,9 +43,12 @@
#include <vector>
using namespace std::string_literals;
Ad9361FpgaSignalSource::Ad9361FpgaSignalSource(const ConfigurationInterface *configuration,
const std::string &role, unsigned int in_stream, unsigned int out_stream,
Concurrent_Queue<pmt::pmt_t> *queue __attribute__((unused))) : role_(role), in_stream_(in_stream), out_stream_(out_stream)
Concurrent_Queue<pmt::pmt_t> *queue __attribute__((unused)))
: SignalSourceBase(configuration, role, "Ad9361_Fpga_Signal_Source"s), in_stream_(in_stream), out_stream_(out_stream)
{
const std::string default_gain_mode("slow_attack");
const double default_tx_attenuation_db = -10.0;
@ -98,22 +102,24 @@ Ad9361FpgaSignalSource::Ad9361FpgaSignalSource(const ConfigurationInterface *con
throw std::exception();
}
switch_position = configuration->property(role + ".switch_position", 0);
if (switch_position != 0 && switch_position != 2)
switch_position_ = configuration->property(role + ".switch_position", 0);
if (switch_position_ != 0 && switch_position_ != 2)
{
std::cout << "SignalSource.switch_position configuration parameter must be either 0: read from file(s) via DMA, or 2: read from AD9361\n";
std::cout << "SignalSource.switch_position configuration parameter set to its default value switch_position=0 - read from file(s)\n";
switch_position = 0;
switch_position_ = 0;
}
switch_fpga = std::make_shared<Fpga_Switch>(device_io_name);
switch_fpga->set_switch_position(switch_position);
switch_fpga->set_switch_position(switch_position_);
item_size_ = sizeof(gr_complex);
std::cout << "Sample rate: " << sample_rate_ << " Sps\n";
if (switch_position == 0) // Inject file(s) via DMA
enable_ovf_check_buffer_monitor_active_ = false; // check buffer overflow and buffer monitor disabled by default
if (switch_position_ == 0) // Inject file(s) via DMA
{
enable_DMA_ = true;
const std::string empty_string;
@ -154,7 +160,7 @@ Ad9361FpgaSignalSource::Ad9361FpgaSignalSource(const ConfigurationInterface *con
freq_band = "L1L2";
}
}
if (switch_position == 2) // Real-time via AD9361
if (switch_position_ == 2) // Real-time via AD9361
{
// some basic checks
if ((rf_port_select_ != "A_BALANCED") and (rf_port_select_ != "B_BALANCED") and (rf_port_select_ != "A_N") and (rf_port_select_ != "B_N") and (rf_port_select_ != "B_P") and (rf_port_select_ != "C_N") and (rf_port_select_ != "C_P") and (rf_port_select_ != "TX_MONITOR1") and (rf_port_select_ != "TX_MONITOR2") and (rf_port_select_ != "TX_MONITOR1_2"))
@ -292,6 +298,26 @@ Ad9361FpgaSignalSource::Ad9361FpgaSignalSource(const ConfigurationInterface *con
std::cout << "Exception cached when configuring the TX carrier: " << e.what() << '\n';
}
}
// when the receiver is working in real-time mode via AD9361 perform buffer overflow checking,
// and if dump is enabled perform buffer monitoring
enable_ovf_check_buffer_monitor_active_ = true;
std::string device_io_name_buffer_monitor;
dump_ = configuration->property(role + ".dump", false);
std::string dump_filename = configuration->property(role + ".dump_filename", default_dump_filename);
// find the uio device file corresponding to the buffer monitor
if (find_uio_dev_file_name(device_io_name_buffer_monitor, buffer_monitor_device_name, 0) < 0)
{
std::cout << "Cannot find the FPGA uio device file corresponding to device name " << buffer_monitor_device_name << std::endl;
throw std::exception();
}
uint32_t num_freq_bands = (freq_band.compare("L1L2")) ? 1 : 2;
buffer_monitor_fpga = std::make_shared<Fpga_buffer_monitor>(device_io_name_buffer_monitor, num_freq_bands, dump_, dump_filename);
thread_buffer_monitor = std::thread([&] { run_buffer_monitor_process(); });
}
// dynamic bits selection
@ -331,7 +357,7 @@ Ad9361FpgaSignalSource::Ad9361FpgaSignalSource(const ConfigurationInterface *con
Ad9361FpgaSignalSource::~Ad9361FpgaSignalSource()
{
/* cleanup and exit */
if (switch_position == 0) // read samples from a file via DMA
if (switch_position_ == 0) // read samples from a file via DMA
{
std::unique_lock<std::mutex> lock(dma_mutex);
enable_DMA_ = false; // disable the DMA
@ -342,7 +368,7 @@ Ad9361FpgaSignalSource::~Ad9361FpgaSignalSource()
}
}
if (switch_position == 2) // Real-time via AD9361
if (switch_position_ == 2) // Real-time via AD9361
{
if (rf_shutdown_)
{
@ -363,6 +389,16 @@ Ad9361FpgaSignalSource::~Ad9361FpgaSignalSource()
}
}
}
// disable buffer overflow checking and buffer monitoring
std::unique_lock<std::mutex> lock(buffer_monitor_mutex);
enable_ovf_check_buffer_monitor_active_ = false;
lock.unlock();
if (thread_buffer_monitor.joinable())
{
thread_buffer_monitor.join();
}
}
std::unique_lock<std::mutex> lock(dynamic_bit_selection_mutex);
@ -646,6 +682,25 @@ void Ad9361FpgaSignalSource::run_dynamic_bit_selection_process()
}
}
void Ad9361FpgaSignalSource::run_buffer_monitor_process()
{
bool enable_ovf_check_buffer_monitor_active = true;
std::this_thread::sleep_for(std::chrono::milliseconds(buffer_monitoring_initial_delay_ms));
while (enable_ovf_check_buffer_monitor_active)
{
buffer_monitor_fpga->check_buffer_overflow_and_monitor_buffer_status();
std::this_thread::sleep_for(std::chrono::milliseconds(buffer_monitor_period_ms));
std::unique_lock<std::mutex> lock(buffer_monitor_mutex);
if (enable_ovf_check_buffer_monitor_active_ == false)
{
enable_ovf_check_buffer_monitor_active = false;
}
lock.unlock();
}
}
void Ad9361FpgaSignalSource::connect(gr::top_block_sptr top_block)
{

View File

@ -19,9 +19,11 @@
#define GNSS_SDR_AD9361_FPGA_SIGNAL_SOURCE_H
#include "concurrent_queue.h"
#include "fpga_buffer_monitor.h"
#include "fpga_dynamic_bit_selection.h"
#include "fpga_switch.h"
#include "gnss_block_interface.h"
#include "signal_source_base.h"
#include <pmt/pmt.h>
#include <cstdint>
#include <memory>
@ -38,7 +40,7 @@
class ConfigurationInterface;
class Ad9361FpgaSignalSource : public GNSSBlockInterface
class Ad9361FpgaSignalSource : public SignalSourceBase
{
public:
Ad9361FpgaSignalSource(const ConfigurationInterface *configuration,
@ -49,19 +51,6 @@ public:
void start() override;
inline std::string role() override
{
return role_;
}
/*!
* \brief Returns "Ad9361_Fpga_Signal_Source"
*/
inline std::string implementation() override
{
return "Ad9361_Fpga_Signal_Source";
}
inline size_t item_size() override
{
return item_size_;
@ -74,24 +63,30 @@ public:
private:
const std::string switch_device_name = "AXIS_Switch_v1_0_0"; // Switch UIO device name
const std::string dyn_bit_sel_device_name = "dynamic_bits_selector"; // Switch UIO device name
const std::string dyn_bit_sel_device_name = "dynamic_bits_selector"; // Switch dhnamic bit selector device name
const std::string buffer_monitor_device_name = "buffer_monitor"; // buffer monitor device name
const std::string default_dump_filename = std::string("FPGA_buffer_monitor_dump.dat");
// perform dynamic bit selection every 500 ms by default
static const uint32_t Gain_control_period_ms = 500;
// check buffer overflow and perform buffer monitoring every 1s by default
static const uint32_t buffer_monitor_period_ms = 1000;
// buffer overflow and buffer monitoring initial delay
static const uint32_t buffer_monitoring_initial_delay_ms = 2000;
void run_DMA_process(const std::string &FreqBand,
const std::string &Filename1,
const std::string &Filename2);
void run_dynamic_bit_selection_process();
void run_buffer_monitor_process();
std::thread thread_file_to_dma;
std::thread thread_dynamic_bit_selection;
std::thread thread_buffer_monitor;
std::shared_ptr<Fpga_Switch> switch_fpga;
std::shared_ptr<Fpga_dynamic_bit_selection> dynamic_bit_selection_fpga;
std::string role_;
std::shared_ptr<Fpga_buffer_monitor> buffer_monitor_fpga;
// Front-end settings
std::string gain_mode_rx1_;
@ -106,6 +101,7 @@ private:
std::mutex dma_mutex;
std::mutex dynamic_bit_selection_mutex;
std::mutex buffer_monitor_mutex;
double rf_gain_rx1_;
double rf_gain_rx2_;
@ -125,7 +121,7 @@ private:
size_t item_size_;
uint32_t in_stream_;
uint32_t out_stream_;
int32_t switch_position;
int32_t switch_position_;
bool enable_dds_lo_;
bool filter_auto_;
@ -136,6 +132,9 @@ private:
bool rx2_enable_;
bool enable_DMA_;
bool enable_dynamic_bit_selection_;
bool enable_ovf_check_buffer_monitor_active_;
bool enable_ovf_check_buffer_monitor_;
bool dump_;
bool rf_shutdown_;
};

View File

@ -17,13 +17,17 @@
#include "custom_udp_signal_source.h"
#include "configuration_interface.h"
#include "gnss_sdr_string_literals.h"
#include <glog/logging.h>
#include <iostream>
using namespace std::string_literals;
CustomUDPSignalSource::CustomUDPSignalSource(const ConfigurationInterface* configuration,
const std::string& role, unsigned int in_stream, unsigned int out_stream,
Concurrent_Queue<pmt::pmt_t>* queue __attribute__((unused))) : role_(role), in_stream_(in_stream), out_stream_(out_stream)
Concurrent_Queue<pmt::pmt_t>* queue __attribute__((unused)))
: SignalSourceBase(configuration, role, "Custom_UDP_Signal_Source"s), in_stream_(in_stream), out_stream_(out_stream)
{
// DUMP PARAMETERS
const std::string default_dump_file("./data/signal_source.dat");

View File

@ -19,8 +19,8 @@
#define GNSS_SDR_CUSTOM_UDP_SIGNAL_SOURCE_H
#include "concurrent_queue.h"
#include "gnss_block_interface.h"
#include "gr_complex_ip_packet_source.h"
#include "signal_source_base.h"
#include <gnuradio/blocks/file_sink.h>
#include <gnuradio/blocks/null_sink.h>
#include <pmt/pmt.h>
@ -40,7 +40,7 @@ class ConfigurationInterface;
* \brief This class reads from UDP packets, which streams interleaved
* I/Q samples over a network.
*/
class CustomUDPSignalSource : public GNSSBlockInterface
class CustomUDPSignalSource : public SignalSourceBase
{
public:
CustomUDPSignalSource(const ConfigurationInterface* configuration,
@ -49,19 +49,6 @@ public:
~CustomUDPSignalSource() = default;
inline std::string role() override
{
return role_;
}
/*!
* \brief Returns "Custom_UDP_Signal_Source"
*/
inline std::string implementation() override
{
return "Custom_UDP_Signal_Source";
}
inline size_t item_size() override
{
return item_size_;
@ -78,7 +65,6 @@ private:
std::vector<gnss_shared_ptr<gr::block>> null_sinks_;
std::vector<gnss_shared_ptr<gr::block>> file_sink_;
std::string role_;
std::string item_type_;
std::string dump_filename_;

View File

@ -10,343 +10,29 @@
* GNSS-SDR is a Global Navigation Satellite System software-defined receiver.
* This file is part of GNSS-SDR.
*
* Copyright (C) 2010-2020 (see AUTHORS file for a list of contributors)
* Copyright (C) 2010-2021 (see AUTHORS file for a list of contributors)
* SPDX-License-Identifier: GPL-3.0-or-later
*
* -----------------------------------------------------------------------------
*/
#include "file_signal_source.h"
#include "configuration_interface.h"
#include "gnss_sdr_flags.h"
#include "gnss_sdr_valve.h"
#include "gnss_sdr_string_literals.h"
#include <glog/logging.h>
#include <exception>
#include <fstream>
#include <iomanip>
#include <iostream> // for std::cerr
#include <utility>
using namespace std::string_literals;
FileSignalSource::FileSignalSource(const ConfigurationInterface* configuration,
const std::string& role, unsigned int in_streams, unsigned int out_streams,
Concurrent_Queue<pmt::pmt_t>* queue) : role_(role), in_streams_(in_streams), out_streams_(out_streams)
FileSignalSource::FileSignalSource(ConfigurationInterface const* configuration,
std::string const& role, unsigned int in_streams, unsigned int out_streams,
Concurrent_Queue<pmt::pmt_t>* queue)
: FileSourceBase(configuration, role, "File_Signal_Source"s, queue, "short"s)
{
const std::string default_filename("./example_capture.dat");
const std::string default_item_type("short");
const std::string default_dump_filename("./my_capture.dat");
const double default_seconds_to_skip = 0.0;
samples_ = configuration->property(role + ".samples", static_cast<uint64_t>(0));
sampling_frequency_ = configuration->property(role + ".sampling_frequency", static_cast<int64_t>(0));
filename_ = configuration->property(role + ".filename", default_filename);
// override value with commandline flag, if present
if (FLAGS_signal_source != "-")
{
filename_ = FLAGS_signal_source;
}
if (FLAGS_s != "-")
{
filename_ = FLAGS_s;
}
item_type_ = configuration->property(role + ".item_type", default_item_type);
repeat_ = configuration->property(role + ".repeat", false);
dump_ = configuration->property(role + ".dump", false);
dump_filename_ = configuration->property(role + ".dump_filename", default_dump_filename);
enable_throttle_control_ = configuration->property(role + ".enable_throttle_control", false);
const double seconds_to_skip = configuration->property(role + ".seconds_to_skip", default_seconds_to_skip);
const size_t header_size = configuration->property(role + ".header_size", 0);
int64_t samples_to_skip = 0;
bool is_complex = false;
if (item_type_ == "gr_complex")
{
item_size_ = sizeof(gr_complex);
}
else if (item_type_ == "float")
{
item_size_ = sizeof(float);
}
else if (item_type_ == "short")
{
item_size_ = sizeof(int16_t);
}
else if (item_type_ == "ishort")
{
item_size_ = sizeof(int16_t);
is_complex = true;
}
else if (item_type_ == "byte")
{
item_size_ = sizeof(int8_t);
}
else if (item_type_ == "ibyte")
{
item_size_ = sizeof(int8_t);
is_complex = true;
}
else
{
LOG(WARNING) << item_type_
<< " unrecognized item type. Using gr_complex.";
item_size_ = sizeof(gr_complex);
}
try
{
file_source_ = gr::blocks::file_source::make(item_size_, filename_.c_str(), repeat_);
if (seconds_to_skip > 0)
{
samples_to_skip = static_cast<int64_t>(seconds_to_skip * sampling_frequency_);
if (is_complex)
{
samples_to_skip *= 2;
}
}
if (header_size > 0)
{
samples_to_skip += header_size;
}
if (samples_to_skip > 0)
{
LOG(INFO) << "Skipping " << samples_to_skip << " samples of the input file";
if (not file_source_->seek(samples_to_skip, SEEK_SET))
{
LOG(INFO) << "Error skipping bytes!";
}
}
}
catch (const std::exception& e)
{
if (filename_ == default_filename)
{
std::cerr
<< "The configuration file has not been found.\n"
<< "Please create a configuration file based on the examples at the 'conf/' folder\n"
<< "and then generate your own GNSS Software Defined Receiver by doing:\n"
<< "$ gnss-sdr --config_file=/path/to/my_GNSS_SDR_configuration.conf\n";
}
else
{
std::cerr
<< "The receiver was configured to work with a file signal source\n"
<< "but the specified file is unreachable by GNSS-SDR.\n"
<< "Please modify your configuration file\n"
<< "and point SignalSource.filename to a valid raw data file. Then:\n"
<< "$ gnss-sdr --config_file=/path/to/my_GNSS_SDR_configuration.conf\n"
<< "Examples of configuration files available at:\n"
<< GNSSSDR_INSTALL_DIR "/share/gnss-sdr/conf/\n";
}
LOG(INFO) << "file_signal_source: Unable to open the samples file "
<< filename_.c_str() << ", exiting the program.";
throw(e);
}
DLOG(INFO) << "file_source(" << file_source_->unique_id() << ")";
if (samples_ == 0) // read all file
{
/*!
* BUG workaround: The GNU Radio file source does not stop the receiver after reaching the End of File.
* A possible solution is to compute the file length in samples using file size, excluding the last 100 milliseconds, and enable always the
* valve block
*/
std::ifstream file(filename_.c_str(), std::ios::in | std::ios::binary | std::ios::ate);
std::ifstream::pos_type size;
if (file.is_open())
{
size = file.tellg();
DLOG(INFO) << "Total samples in the file= " << floor(static_cast<double>(size) / static_cast<double>(item_size_));
}
else
{
std::cout << "file_signal_source: Unable to open the samples file " << filename_.c_str() << '\n';
LOG(ERROR) << "file_signal_source: Unable to open the samples file " << filename_.c_str();
}
std::streamsize ss = std::cout.precision();
std::cout << std::setprecision(16);
std::cout << "Processing file " << filename_ << ", which contains " << static_cast<double>(size) << " [bytes]\n";
std::cout.precision(ss);
if (size > 0)
{
const int64_t bytes_to_skip = samples_to_skip * item_size_;
const int64_t bytes_to_process = static_cast<int64_t>(size) - bytes_to_skip;
samples_ = floor(static_cast<double>(bytes_to_process) / static_cast<double>(item_size_) - ceil(0.002 * static_cast<double>(sampling_frequency_))); // process all the samples available in the file excluding at least the last 1 ms
}
}
CHECK(samples_ > 0) << "File does not contain enough samples to process.";
double signal_duration_s = static_cast<double>(samples_) * (1 / static_cast<double>(sampling_frequency_));
if (is_complex)
{
signal_duration_s /= 2.0;
}
DLOG(INFO) << "Total number samples to be processed= " << samples_ << " GNSS signal duration= " << signal_duration_s << " [s]";
std::cout << "GNSS signal recorded time to be processed: " << signal_duration_s << " [s]\n";
valve_ = gnss_sdr_make_valve(item_size_, samples_, queue);
DLOG(INFO) << "valve(" << valve_->unique_id() << ")";
if (dump_)
{
sink_ = gr::blocks::file_sink::make(item_size_, dump_filename_.c_str());
DLOG(INFO) << "file_sink(" << sink_->unique_id() << ")";
}
if (enable_throttle_control_)
{
throttle_ = gr::blocks::throttle::make(item_size_, sampling_frequency_);
}
DLOG(INFO) << "File source filename " << filename_;
DLOG(INFO) << "Samples " << samples_;
DLOG(INFO) << "Sampling frequency " << sampling_frequency_;
DLOG(INFO) << "Item type " << item_type_;
DLOG(INFO) << "Item size " << item_size_;
DLOG(INFO) << "Repeat " << repeat_;
DLOG(INFO) << "Dump " << dump_;
DLOG(INFO) << "Dump filename " << dump_filename_;
if (in_streams_ > 0)
if (in_streams > 0)
{
LOG(ERROR) << "A signal source does not have an input stream";
}
if (out_streams_ > 1)
if (out_streams > 1)
{
LOG(ERROR) << "This implementation only supports one output stream";
}
}
void FileSignalSource::connect(gr::top_block_sptr top_block)
{
if (samples_ > 0)
{
if (enable_throttle_control_ == true)
{
top_block->connect(file_source_, 0, throttle_, 0);
DLOG(INFO) << "connected file source to throttle";
top_block->connect(throttle_, 0, valve_, 0);
DLOG(INFO) << "connected throttle to valve";
if (dump_)
{
top_block->connect(valve_, 0, sink_, 0);
DLOG(INFO) << "connected valve to file sink";
}
}
else
{
top_block->connect(file_source_, 0, valve_, 0);
DLOG(INFO) << "connected file source to valve";
if (dump_)
{
top_block->connect(valve_, 0, sink_, 0);
DLOG(INFO) << "connected valve to file sink";
}
}
}
else
{
if (enable_throttle_control_ == true)
{
top_block->connect(file_source_, 0, throttle_, 0);
DLOG(INFO) << "connected file source to throttle";
if (dump_)
{
top_block->connect(file_source_, 0, sink_, 0);
DLOG(INFO) << "connected file source to sink";
}
}
else
{
if (dump_)
{
top_block->connect(file_source_, 0, sink_, 0);
DLOG(INFO) << "connected file source to sink";
}
}
}
}
void FileSignalSource::disconnect(gr::top_block_sptr top_block)
{
if (samples_ > 0)
{
if (enable_throttle_control_ == true)
{
top_block->disconnect(file_source_, 0, throttle_, 0);
DLOG(INFO) << "disconnected file source to throttle";
top_block->disconnect(throttle_, 0, valve_, 0);
DLOG(INFO) << "disconnected throttle to valve";
if (dump_)
{
top_block->disconnect(valve_, 0, sink_, 0);
DLOG(INFO) << "disconnected valve to file sink";
}
}
else
{
top_block->disconnect(file_source_, 0, valve_, 0);
DLOG(INFO) << "disconnected file source to valve";
if (dump_)
{
top_block->disconnect(valve_, 0, sink_, 0);
DLOG(INFO) << "disconnected valve to file sink";
}
}
}
else
{
if (enable_throttle_control_ == true)
{
top_block->disconnect(file_source_, 0, throttle_, 0);
DLOG(INFO) << "disconnected file source to throttle";
if (dump_)
{
top_block->disconnect(file_source_, 0, sink_, 0);
DLOG(INFO) << "disconnected file source to sink";
}
}
else
{
if (dump_)
{
top_block->disconnect(file_source_, 0, sink_, 0);
DLOG(INFO) << "disconnected file source to sink";
}
}
}
}
gr::basic_block_sptr FileSignalSource::get_left_block()
{
LOG(WARNING) << "Left block of a signal source should not be retrieved";
return gr::blocks::file_source::sptr();
}
gr::basic_block_sptr FileSignalSource::get_right_block()
{
if (samples_ > 0)
{
return valve_;
}
if (enable_throttle_control_ == true)
{
return throttle_;
}
return file_source_;
}

View File

@ -21,15 +21,7 @@
#ifndef GNSS_SDR_FILE_SIGNAL_SOURCE_H
#define GNSS_SDR_FILE_SIGNAL_SOURCE_H
#include "concurrent_queue.h"
#include "gnss_block_interface.h"
#include <gnuradio/blocks/file_sink.h>
#include <gnuradio/blocks/file_source.h>
#include <gnuradio/blocks/throttle.h>
#include <gnuradio/hier_block2.h>
#include <pmt/pmt.h>
#include <cstdint>
#include <string>
#include "file_source_base.h"
/** \addtogroup Signal_Source Signal Source
* Classes for Signal Source management.
@ -45,84 +37,16 @@ class ConfigurationInterface;
* \brief Class that reads signals samples from a file
* and adapts it to a SignalSourceInterface
*/
class FileSignalSource : public GNSSBlockInterface
class FileSignalSource : public FileSourceBase
{
public:
FileSignalSource(const ConfigurationInterface* configuration, const std::string& role,
FileSignalSource(ConfigurationInterface const* configuration, std::string const& role,
unsigned int in_streams, unsigned int out_streams,
Concurrent_Queue<pmt::pmt_t>* queue);
~FileSignalSource() = default;
inline std::string role() override
{
return role_;
}
/*!
* \brief Returns "File_Signal_Source".
*/
inline std::string implementation() override
{
return "File_Signal_Source";
}
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;
inline std::string filename() const
{
return filename_;
}
inline std::string item_type() const
{
return item_type_;
}
inline bool repeat() const
{
return repeat_;
}
inline int64_t sampling_frequency() const
{
return sampling_frequency_;
}
inline uint64_t samples() const
{
return samples_;
}
private:
gr::blocks::file_source::sptr file_source_;
gnss_shared_ptr<gr::block> valve_;
gr::blocks::file_sink::sptr sink_;
gr::blocks::throttle::sptr throttle_;
std::string role_;
std::string item_type_;
std::string filename_;
std::string dump_filename_;
uint64_t samples_;
int64_t sampling_frequency_;
size_t item_size_;
uint32_t in_streams_;
uint32_t out_streams_;
bool enable_throttle_control_;
bool repeat_;
bool dump_;
};

View File

@ -0,0 +1,506 @@
/*!
* \file file_source_base.cc
* \brief Implementation of the base class for file-oriented signal_source GNSS blocks
* \author Jim Melton, 2021. jim.melton(at)sncorp.com
*
* -----------------------------------------------------------------------------
*
* GNSS-SDR is a Global Navigation Satellite System software-defined receiver.
* This file is part of GNSS-SDR.
*
* Copyright (C) 2010-2021 (see AUTHORS file for a list of contributors)
* SPDX-License-Identifier: GPL-3.0-or-later
*
* -----------------------------------------------------------------------------
*/
#include "file_source_base.h"
#include "configuration_interface.h"
#include "gnss_sdr_filesystem.h"
#include "gnss_sdr_flags.h"
#include "gnss_sdr_string_literals.h"
#include "gnss_sdr_valve.h"
#include <glog/logging.h>
#include <cmath> // ceil, floor
#include <fstream>
#include <utility> // move
using namespace std::string_literals;
FileSourceBase::FileSourceBase(ConfigurationInterface const* configuration, std::string const& role, std::string impl,
Concurrent_Queue<pmt::pmt_t>* queue,
std::string default_item_type)
: SignalSourceBase(configuration, role, std::move(impl)), filename_(configuration->property(role + ".filename"s, "../data/example_capture.dat"s)),
file_source_(), // NOLINT
item_type_(configuration->property(role + ".item_type"s, default_item_type)), // NOLINT
item_size_(0),
is_complex_(false),
// apparently, MacOS (LLVM) finds 0UL ambiguous with bool, int64_t, uint64_t, int32_t, int16_t, uint16_t,... float, double
header_size_(configuration->property(role + ".header_size"s, uint64_t(0))),
seconds_to_skip_(configuration->property(role + ".seconds_to_skip"s, 0.0)),
repeat_(configuration->property(role + ".repeat"s, false)),
samples_(configuration->property(role + ".samples"s, uint64_t(0))),
sampling_frequency_(configuration->property(role + ".sampling_frequency"s, int64_t(0))),
valve_(), // NOLINT
queue_(queue),
enable_throttle_control_(configuration->property(role + ".enable_throttle_control"s, false)),
throttle_(), // NOLINT
dump_(configuration->property(role + ".dump"s, false)),
dump_filename_(configuration->property(role + ".dump_filename"s, "../data/my_capture.dat"s)),
sink_() // NOLINT
{
// override value with commandline flag, if present
if (FLAGS_signal_source != "-")
{
filename_ = FLAGS_signal_source;
}
if (FLAGS_s != "-")
{
filename_ = FLAGS_s;
}
}
void FileSourceBase::init()
{
create_file_source();
// At this point, we know that the file exists
samples_ = computeSamplesInFile();
auto signal_duration_s = 1.0 * samples_ / sampling_frequency_;
if (is_complex())
{
signal_duration_s /= 2.0;
}
DLOG(INFO) << "Total number samples to be processed= " << samples_ << " GNSS signal duration= " << signal_duration_s << " [s]";
std::cout << "GNSS signal recorded time to be processed: " << signal_duration_s << " [s]\n";
DLOG(INFO) << "File source filename " << filename_;
DLOG(INFO) << "Samples " << samples_;
DLOG(INFO) << "Sampling frequency " << sampling_frequency_;
DLOG(INFO) << "Item type " << item_type_;
DLOG(INFO) << "Item size " << item_size_;
DLOG(INFO) << "Repeat " << repeat_;
DLOG(INFO) << "Dump " << dump_;
DLOG(INFO) << "Dump filename " << dump_filename_;
create_throttle();
create_valve();
create_sink();
}
void FileSourceBase::connect(gr::top_block_sptr top_block)
{
init();
pre_connect_hook(top_block);
auto input = gr::basic_block_sptr();
auto output = gr::basic_block_sptr();
// THROTTLE
if (throttle())
{
// if we are throttling...
top_block->connect(source(), 0, throttle(), 0);
DLOG(INFO) << "connected file source to throttle";
input = throttle();
}
else
{
// no throttle; let 'er rip
input = source();
}
// VALVE
if (valve())
{
top_block->connect(input, 0, valve(), 0);
DLOG(INFO) << "connected source to valve";
output = valve();
}
else
{
// TODO: dumping a file source is unlikely, but should this be the raw file source or the
// throttle if there is one? I'm leaning towards "output=input"
output = source(); // output = input;
}
// DUMP
if (sink())
{
top_block->connect(output, 0, sink(), 0);
DLOG(INFO) << "connected output to file sink";
}
post_connect_hook(top_block);
}
void FileSourceBase::disconnect(gr::top_block_sptr top_block)
{
auto input = gr::basic_block_sptr();
auto output = gr::basic_block_sptr();
pre_disconnect_hook(top_block);
// THROTTLE
if (throttle())
{
// if we are throttling...
top_block->disconnect(source(), 0, throttle(), 0);
DLOG(INFO) << "disconnected file source from throttle";
input = throttle();
}
else
{
// no throttle; let 'er rip
input = source();
}
// VALVE
if (valve())
{
top_block->disconnect(input, 0, valve(), 0);
DLOG(INFO) << "disconnected source to valve";
output = valve();
}
else
{
// TODO: dumping a file source is unlikely, but should this be the raw file source or the
// throttle if there is one? I'm leaning towards "output=input"
output = source(); // output = input;
}
// DUMP
if (sink())
{
top_block->disconnect(output, 0, sink(), 0);
DLOG(INFO) << "disconnected output to file sink";
}
post_disconnect_hook(top_block);
}
gr::basic_block_sptr FileSourceBase::get_left_block()
{
// TODO: is this right? Shouldn't the left block be a nullptr?
LOG(WARNING) << "Left block of a signal source should not be retrieved";
return gr::blocks::file_source::sptr();
}
gr::basic_block_sptr FileSourceBase::get_right_block()
{
// clang-tidy wants braces around the if-conditions. clang-format wants to break the braces into
// multiple line blocks. It's much more readable this way
// clang-format off
if (valve_) { return valve_; }
if (throttle_) { return throttle_; }
return source();
// clang-format on
}
std::string FileSourceBase::filename() const
{
return filename_;
}
std::string FileSourceBase::item_type() const
{
return item_type_;
}
size_t FileSourceBase::item_size()
{
return item_size_;
}
size_t FileSourceBase::item_size() const
{
return item_size_;
}
bool FileSourceBase::repeat() const
{
return repeat_;
}
int64_t FileSourceBase::sampling_frequency() const
{
return sampling_frequency_;
}
uint64_t FileSourceBase::samples() const
{
return samples_;
}
std::tuple<size_t, bool> FileSourceBase::itemTypeToSize()
{
auto is_complex_t = false;
auto item_size = size_t(0);
if (item_type_ == "gr_complex")
{
item_size = sizeof(gr_complex);
}
else if (item_type_ == "float")
{
item_size = sizeof(float);
}
else if (item_type_ == "short")
{
item_size = sizeof(int16_t);
}
else if (item_type_ == "ishort")
{
item_size = sizeof(int16_t);
is_complex_t = true;
}
else if (item_type_ == "byte")
{
item_size = sizeof(int8_t);
}
else if (item_type_ == "ibyte")
{
item_size = sizeof(int8_t);
is_complex_t = true;
}
else
{
LOG(WARNING) << item_type_
<< " unrecognized item type. Using gr_complex.";
item_size = sizeof(gr_complex);
}
return std::make_tuple(item_size, is_complex_t);
}
// Default case is one decoded packet per one read sample
double FileSourceBase::packetsPerSample() const { return 1.0; }
size_t FileSourceBase::samplesToSkip() const
{
auto samples_to_skip = size_t(0);
if (seconds_to_skip_ > 0)
{
// sampling_frequency is in terms of actual samples (output packets). If this source is
// compressed, there may be multiple packets per file (read) sample. First compute the
// actual number of samples to skip (function of time and sample rate)
samples_to_skip = static_cast<size_t>(seconds_to_skip_ * sampling_frequency_);
// convert from sample to input items, scaling this value to input item space
// (rounding up)
samples_to_skip = std::ceil(samples_to_skip / packetsPerSample());
// complex inputs require two input items for one sample (arguably, packetsPerSample could be scaled by 0.5)
if (is_complex())
{
samples_to_skip *= 2;
}
}
if (header_size_ > 0)
{
samples_to_skip += header_size_;
}
return samples_to_skip;
}
size_t FileSourceBase::computeSamplesInFile() const
{
auto n_samples = size_t(samples());
// if configured with 0 samples (read the whole file), figure out how many samples are in the file, and go from there
if (n_samples == 0)
{
// this could throw, but the existence of the file has been proven before we get here.
auto size = fs::file_size(filename());
// if there is some kind of compression/encoding, figure out the uncompressed number of samples
n_samples = std::floor(packetsPerSample() * size / item_size());
auto to_skip = samplesToSkip();
/*!
* BUG workaround: The GNU Radio file source does not stop the receiver after reaching the End of File.
* A possible solution is to compute the file length in samples using file size, excluding at least
* the last 2 milliseconds, and enable always the valve block
*/
auto tail = static_cast<size_t>(std::ceil(0.002 * sampling_frequency()));
DLOG(INFO) << "Total samples in the file= " << n_samples;
std::cout << "Processing file " << filename() << ", which contains " << n_samples << " samples (" << size << " bytes)\n";
if (n_samples > (to_skip + tail))
{
// process all the samples available in the file excluding up to the last 2 ms
n_samples -= to_skip + tail;
}
else
{
// this will terminate the program
LOG(FATAL) << "Skipping " << to_skip << " samples from the front and truncating 2ms (" << tail << " samples)\n"
<< "is greater than the number of samples in the file (" << n_samples << ")";
}
}
return n_samples;
}
size_t FileSourceBase::source_item_size() const
{
// delegate the size of the source to the source() object, so sub-classes have less work to do
DLOG(INFO) << "source_item_size is " << source()->output_signature()->sizeof_stream_item(0);
return source()->output_signature()->sizeof_stream_item(0);
}
bool FileSourceBase::is_complex() const { return is_complex_; }
// Simple accessors
gnss_shared_ptr<gr::block> FileSourceBase::source() const { return file_source(); }
gnss_shared_ptr<gr::block> FileSourceBase::file_source() const { return file_source_; }
gnss_shared_ptr<gr::block> FileSourceBase::valve() const { return valve_; }
gnss_shared_ptr<gr::block> FileSourceBase::throttle() const { return throttle_; }
gnss_shared_ptr<gr::block> FileSourceBase::sink() const { return sink_; }
gr::blocks::file_source::sptr FileSourceBase::create_file_source()
{
auto item_tuple = itemTypeToSize();
item_size_ = std::get<0>(item_tuple);
is_complex_ = std::get<1>(item_tuple);
try
{
// TODO: why are we manually seeking, instead of passing the samples_to_skip to the file_source factory?
auto samples_to_skip = samplesToSkip();
file_source_ = gr::blocks::file_source::make(item_size(), filename().data(), repeat());
if (samples_to_skip > 0)
{
LOG(INFO) << "Skipping " << samples_to_skip << " samples of the input file";
if (not file_source_->seek(samples_to_skip, SEEK_SET))
{
LOG(ERROR) << "Error skipping bytes!";
}
}
}
catch (const std::exception& e)
{
std::cerr
<< "The receiver was configured to work with a file-based signal source\n"
<< "but the specified file is unreachable by GNSS-SDR.\n"
<< "[" << filename() << "]\n"
<< "\n"
<< "Please modify your configuration file\n"
<< "and point SignalSource.filename to a valid raw data file. Then:\n"
<< "$ gnss-sdr --config_file=/path/to/my_GNSS_SDR_configuration.conf\n"
<< "Examples of configuration files available at:\n"
<< GNSSSDR_INSTALL_DIR "/share/gnss-sdr/conf/\n"
<< std::endl;
LOG(ERROR) << "file_signal_source: Unable to open the samples file "
<< filename() << ", exiting the program.";
throw;
}
DLOG(INFO) << implementation() << "(" << file_source_->unique_id() << ")";
// enable subclass hooks
create_file_source_hook();
return file_source_;
}
gr::blocks::throttle::sptr FileSourceBase::create_throttle()
{
if (enable_throttle_control_)
{
// if we are throttling...
throttle_ = gr::blocks::throttle::make(source_item_size(), sampling_frequency());
DLOG(INFO) << "throttle(" << throttle_->unique_id() << ")";
// enable subclass hooks
create_throttle_hook();
}
return throttle_;
}
gnss_shared_ptr<gr::block> FileSourceBase::create_valve()
{
if (samples() > 0)
{
// if a number of samples is specified, honor it by creating a valve
// In practice, this is always true
valve_ = gnss_sdr_make_valve(source_item_size(), samples(), queue_);
DLOG(INFO) << "valve(" << valve_->unique_id() << ")";
// enable subclass hooks
create_valve_hook();
}
return valve_;
}
gr::blocks::file_sink::sptr FileSourceBase::create_sink()
{
if (dump_)
{
sink_ = gr::blocks::file_sink::make(source_item_size(), dump_filename_.c_str());
DLOG(INFO) << "file_sink(" << sink_->unique_id() << ")";
// enable subclass hooks
create_sink_hook();
}
return sink_;
}
// Subclass hooks to augment created objects, as required
void FileSourceBase::create_file_source_hook() {}
void FileSourceBase::create_throttle_hook() {}
void FileSourceBase::create_valve_hook() {}
void FileSourceBase::create_sink_hook() {}
// Subclass hooks for connection/disconnectino
void FileSourceBase::pre_connect_hook(gr::top_block_sptr top_block [[maybe_unused]]) {}
void FileSourceBase::post_connect_hook(gr::top_block_sptr top_block [[maybe_unused]]) {}
void FileSourceBase::pre_disconnect_hook(gr::top_block_sptr top_block [[maybe_unused]]) {}
void FileSourceBase::post_disconnect_hook(gr::top_block_sptr top_block [[maybe_unused]]) {}

View File

@ -0,0 +1,186 @@
/*!
* \file file_source_base.h
* \brief Header file of the base class to file-oriented signal_source GNSS blocks.
* \author Jim Melton, 2021. jim.melton(at)sncorp.com
*
*
* -----------------------------------------------------------------------------
*
* GNSS-SDR is a Global Navigation Satellite System software-defined receiver.
* This file is part of GNSS-SDR.
*
* Copyright (C) 2010-2021 (see AUTHORS file for a list of contributors)
* SPDX-License-Identifier: GPL-3.0-or-later
*
* -----------------------------------------------------------------------------
*/
#ifndef GNSS_SDR_FILE_SOURCE_BASE_H
#define GNSS_SDR_FILE_SOURCE_BASE_H
#include "concurrent_queue.h"
#include "signal_source_base.h"
#include <gnuradio/blocks/file_source.h>
#include <gnuradio/blocks/throttle.h>
#include <pmt/pmt.h>
#include <tuple>
// for dump
#include <gnuradio/blocks/file_sink.h>
#include <cstddef>
#include <string>
class ConfigurationInterface;
//! \brief Base class to file-oriented SignalSourceBase GNSS blocks.
//!
//! This class supports the following properties:
//!
//! .filename - the path to the input file
//! - may be overridden by the -signal_source or -s command-line arguments
//!
//! .samples - number of samples to process (default 0)
//! - if not specified or 0, read the entire file; otherwise stop after that many samples
//!
//! .sampling_frequency - the frequency of the sampled data (samples/second)
//!
//! .item_type - data type of the samples (default "short")
//!
//! .header_size - the size of a prefixed header to skip in "samples" (default 0)
//!
//! .seconds_to_skip - number of seconds of lead-in data to skip over (default 0)
//!
//! .enable_throttle_control - whether to stop reading if the upstream buffer is full (default false)
//!
//! .repeat - whether to rewind and continue at end of file (default false)
//!
//! (probably abstracted to the base class)
//!
//! .dump - whether to archive input data
//!
//! .dump_filename - if dumping, path to file for output
class FileSourceBase : public SignalSourceBase
{
public:
// Virtual overrides
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;
//! The file to read
std::string filename() const;
//! The item type
std::string item_type() const;
//! The configured size of each item
size_t item_size() override;
virtual size_t item_size() const; // what the interface **should** have declared
//! Whether to repeat reading after end-of-file
bool repeat() const;
//! The sampling frequency of the source file
int64_t sampling_frequency() const;
//! The number of samples in the file
uint64_t samples() const;
protected:
//! \brief Constructor
//!
//! Subclasses may want to assert default item types that are appropriate to the specific file
//! type supported. Rather than require the item type to be specified in the config file, allow
//! sub-classes to impose their will
FileSourceBase(ConfigurationInterface const* configuration, std::string const& role, std::string impl,
Concurrent_Queue<pmt::pmt_t>* queue,
std::string default_item_type = "short");
//! Perform post-construction initialization
void init();
//! Compute the item size, from the item_type(). Subclasses may constrain types that don't make
// sense. The return of this method is a tuple of item_size and is_complex
virtual std::tuple<size_t, bool> itemTypeToSize();
//! The number of (possibly unpacked) samples in a (raw) file sample (default=1)
virtual double packetsPerSample() const;
//! Compute the number of samples to skip
virtual size_t samplesToSkip() const;
//! Compute the number of samples in the file
size_t computeSamplesInFile() const;
//! Abstracted front-end source. Sub-classes may override if they create specialized chains to
//! decode source files into a usable format
virtual gnss_shared_ptr<gr::block> source() const;
//! For complex source chains, the size of the file item may not be the same as the size of the
// "source" (decoded) item. This method allows subclasses to handle these differences
virtual size_t source_item_size() const;
bool is_complex() const;
// Generic access to created objects
gnss_shared_ptr<gr::block> file_source() const;
gnss_shared_ptr<gr::block> valve() const;
gnss_shared_ptr<gr::block> throttle() const;
gnss_shared_ptr<gr::block> sink() const;
// The methods create the various blocks, if enabled, and return access to them. The created
// object is also held in this class
gr::blocks::file_source::sptr create_file_source();
gr::blocks::throttle::sptr create_throttle();
gnss_shared_ptr<gr::block> create_valve();
gr::blocks::file_sink::sptr create_sink();
// Subclass hooks to augment created objects, as required
virtual void create_file_source_hook();
virtual void create_throttle_hook();
virtual void create_valve_hook();
virtual void create_sink_hook();
// Subclass hooks for connection/disconnection
virtual void pre_connect_hook(gr::top_block_sptr top_block);
virtual void post_connect_hook(gr::top_block_sptr top_block);
virtual void pre_disconnect_hook(gr::top_block_sptr top_block);
virtual void post_disconnect_hook(gr::top_block_sptr top_block);
private:
std::string filename_;
gr::blocks::file_source::sptr file_source_;
std::string item_type_;
size_t item_size_;
bool is_complex_; // a misnomer; if I/Q are interleaved as integer values
size_t header_size_; // length (in samples) of the header (if any)
double seconds_to_skip_;
bool repeat_;
// The valve allows only the configured number of samples through, then it closes.
// The framework passes the queue as a naked pointer, rather than a shared pointer, so this
// class has two choices: construct the valve in the ctor, or hold onto the pointer, possibly
// beyond its lifetime. Fortunately, the queue is only used to create the valve, so the
// likelihood of holding a stale pointer is mitigated
uint64_t samples_;
int64_t sampling_frequency_; // why is this signed
gnss_shared_ptr<gr::block> valve_;
Concurrent_Queue<pmt::pmt_t>* queue_;
bool enable_throttle_control_;
gr::blocks::throttle::sptr throttle_;
bool dump_;
std::string dump_filename_;
gr::blocks::file_sink::sptr sink_;
};
#endif

View File

@ -18,17 +18,21 @@
#include "flexiband_signal_source.h"
#include "configuration_interface.h"
#include "gnss_sdr_string_literals.h"
#include <glog/logging.h>
#include <gnuradio/blocks/file_sink.h>
#include <teleorbit/frontend.h>
#include <utility>
using namespace std::string_literals;
FlexibandSignalSource::FlexibandSignalSource(const ConfigurationInterface* configuration,
const std::string& role,
unsigned int in_stream,
unsigned int out_stream,
Concurrent_Queue<pmt::pmt_t>* queue __attribute__((unused))) : role_(role), in_stream_(in_stream), out_stream_(out_stream)
Concurrent_Queue<pmt::pmt_t>* queue __attribute__((unused)))
: SignalSourceBase(configuration, role, "Flexiband_Signal_Source"s), in_stream_(in_stream), out_stream_(out_stream)
{
const std::string default_item_type("byte");
item_type_ = configuration->property(role + ".item_type", default_item_type);

View File

@ -21,7 +21,7 @@
#define GNSS_SDR_FLEXIBAND_SIGNAL_SOURCE_H
#include "concurrent_queue.h"
#include "gnss_block_interface.h"
#include "signal_source_base.h"
#include <gnuradio/blocks/char_to_float.h>
#include <gnuradio/blocks/file_sink.h>
#include <gnuradio/blocks/float_to_complex.h>
@ -45,7 +45,7 @@ class ConfigurationInterface;
* \brief This class configures and reads samples from Teleorbit Flexiband front-end.
* This software requires a Flexiband GNU Radio driver installed (not included with GNSS-SDR).
*/
class FlexibandSignalSource : public GNSSBlockInterface
class FlexibandSignalSource : public SignalSourceBase
{
public:
FlexibandSignalSource(const ConfigurationInterface* configuration,
@ -54,19 +54,6 @@ public:
~FlexibandSignalSource() = default;
inline std::string role() override
{
return role_;
}
/*!
* \brief Returns "Flexiband_Signal_Source".
*/
inline std::string implementation() override
{
return "Flexiband_Signal_Source";
}
inline size_t item_size() override
{
return item_size_;
@ -85,7 +72,6 @@ private:
std::vector<boost::shared_ptr<gr::block>> float_to_complex_;
std::vector<gr::blocks::null_sink::sptr> null_sinks_;
std::string role_;
std::string item_type_;
std::string firmware_filename_;
std::string signal_file;

View File

@ -22,6 +22,7 @@
#include "ad9361_manager.h"
#include "configuration_interface.h"
#include "gnss_sdr_flags.h"
#include "gnss_sdr_string_literals.h"
#include "gnss_sdr_valve.h"
#include <glog/logging.h>
#include <algorithm> // for max
@ -29,10 +30,12 @@
#include <iostream>
#include <utility>
using namespace std::string_literals;
Fmcomms2SignalSource::Fmcomms2SignalSource(const ConfigurationInterface *configuration,
const std::string &role, unsigned int in_stream, unsigned int out_stream,
Concurrent_Queue<pmt::pmt_t> *queue) : role_(role), in_stream_(in_stream), out_stream_(out_stream)
Concurrent_Queue<pmt::pmt_t> *queue)
: SignalSourceBase(configuration, role, "Fmcomms2_Signal_Source"s), in_stream_(in_stream), out_stream_(out_stream)
{
const std::string default_item_type("gr_complex");
const std::string default_dump_file("./data/signal_source.dat");

View File

@ -20,7 +20,7 @@
#ifndef GNSS_SDR_FMCOMMS2_SIGNAL_SOURCE_H
#define GNSS_SDR_FMCOMMS2_SIGNAL_SOURCE_H
#include "gnss_block_interface.h"
#include "signal_source_base.h"
#include <gnuradio/blocks/file_sink.h>
#if GRIIO_INCLUDE_HAS_GNURADIO
#include <gnuradio/iio/fmcomms2_source.h>
@ -41,7 +41,7 @@
class ConfigurationInterface;
class Fmcomms2SignalSource : public GNSSBlockInterface
class Fmcomms2SignalSource : public SignalSourceBase
{
public:
Fmcomms2SignalSource(const ConfigurationInterface* configuration,
@ -50,19 +50,6 @@ public:
~Fmcomms2SignalSource();
inline std::string role() override
{
return role_;
}
/*!
* \brief Returns "Fmcomms2_Signal_Source"
*/
inline std::string implementation() override
{
return "Fmcomms2_Signal_Source";
}
inline size_t item_size() override
{
return item_size_;
@ -78,7 +65,6 @@ private:
gnss_shared_ptr<gr::block> valve_;
gr::blocks::file_sink::sptr file_sink_;
std::string role_;
std::string item_type_;
std::string dump_filename_;

View File

@ -22,6 +22,7 @@
#include "concurrent_queue.h"
#include "gnss_block_interface.h"
#include "signal_source_interface.h"
#include <pmt/pmt.h>
#include <memory>
#include <string>
@ -37,16 +38,13 @@
* \brief This class wraps blocks that generates synthesized GNSS signal and
* filters the signal.
*/
class GenSignalSource : public GNSSBlockInterface
class GenSignalSource : public SignalSourceInterface
{
public:
//! Constructor
GenSignalSource(std::shared_ptr<GNSSBlockInterface> signal_generator, std::shared_ptr<GNSSBlockInterface> filter,
std::string role, Concurrent_Queue<pmt::pmt_t> *queue);
//! Virtual destructor
virtual ~GenSignalSource() = default;
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;
@ -56,6 +54,8 @@ public:
//! Returns "Signal Source"
inline std::string implementation() override { return "Signal Source"; }
inline size_t item_size() override { return 0; }
inline size_t getRfChannels() const final { return 0; }
inline std::shared_ptr<GNSSBlockInterface> signal_generator() const { return signal_generator_; }
private:

View File

@ -16,16 +16,20 @@
#include "gn3s_signal_source.h"
#include "configuration_interface.h"
#include "gnss_sdr_string_literals.h"
#include <glog/logging.h>
#include <gnuradio/blocks/file_sink.h>
#include <gn3s/gn3s_source_cc.h>
using namespace std::string_literals;
Gn3sSignalSource::Gn3sSignalSource(const ConfigurationInterface* configuration,
std::string role,
unsigned int in_stream,
unsigned int out_stream,
Concurrent_Queue<pmt::pmt_t>* queue) : role_(role), in_stream_(in_stream), out_stream_(out_stream)
Concurrent_Queue<pmt::pmt_t>* queue)
: SignalSourceBase(configuration, role, "Gn3s_Signal_Source"s), in_stream_(in_stream), out_stream_(out_stream)
{
const std::string default_item_type("short");
const std::string default_dump_file("./data/gn3s_source.dat");

View File

@ -19,7 +19,7 @@
#define GNSS_SDR_GN3S_SIGNAL_SOURCE_H
#include "concurrent_queue.h"
#include "gnss_block_interface.h"
#include "signal_source_base.h"
#include <gnuradio/blocks/file_sink.h>
#include <gnuradio/hier_block2.h>
#include <pmt/pmt.h>
@ -38,7 +38,7 @@ class ConfigurationInterface;
/*!
* \brief This class reads samples from a GN3S USB dongle, a RF front-end signal sampler
*/
class Gn3sSignalSource : public GNSSBlockInterface
class Gn3sSignalSource : public SignalSourceBase
{
public:
Gn3sSignalSource(const ConfigurationInterface* configuration,
@ -47,19 +47,6 @@ public:
~Gn3sSignalSource() = default;
inline std::string role() override
{
return role_;
}
/*!
* \brief Returns "Gn3s_Signal_Source".
*/
inline std::string implementation() override
{
return "Gn3s_Signal_Source";
}
inline size_t item_size() override
{
return item_size_;
@ -73,11 +60,10 @@ public:
private:
gr::block_sptr gn3s_source_;
gr::blocks::file_sink::sptr file_sink_;
std::string role_;
std::string item_type_;
std::string dump_filename_;
size_t item_size_;
int64_t samples_;
[[maybe_unused]] int64_t samples_;
unsigned int in_stream_;
unsigned int out_stream_;
bool dump_;

View File

@ -16,14 +16,15 @@
#include "labsat_signal_source.h"
#include "configuration_interface.h"
#include "gnss_sdr_string_literals.h"
#include "labsat23_source.h"
#include <glog/logging.h>
#include <cstdint>
#include <utility>
using namespace std::string_literals;
LabsatSignalSource::LabsatSignalSource(const ConfigurationInterface* configuration,
const std::string& role, unsigned int in_stream, unsigned int out_stream, Concurrent_Queue<pmt::pmt_t>* queue) : role_(role), in_stream_(in_stream), out_stream_(out_stream)
const std::string& role, unsigned int in_stream, unsigned int out_stream, Concurrent_Queue<pmt::pmt_t>* queue)
: SignalSourceBase(configuration, role, "Labsat_Signal_Source"s), in_stream_(in_stream), out_stream_(out_stream)
{
const std::string default_item_type("gr_complex");
const std::string default_dump_file("./labsat_output.dat");

View File

@ -20,6 +20,7 @@
#include "concurrent_queue.h"
#include "gnss_block_interface.h"
#include "signal_source_base.h"
#include <gnuradio/blocks/file_sink.h>
#include <gnuradio/blocks/throttle.h>
#include <gnuradio/hier_block2.h>
@ -38,7 +39,7 @@ class ConfigurationInterface;
/*!
* \brief This class reads samples stored by a LabSat 2 or LabSat 3 device
*/
class LabsatSignalSource : public GNSSBlockInterface
class LabsatSignalSource : public SignalSourceBase
{
public:
LabsatSignalSource(const ConfigurationInterface* configuration,
@ -47,19 +48,6 @@ public:
~LabsatSignalSource() = default;
inline std::string role() override
{
return role_;
}
/*!
* \brief Returns "Labsat_Signal_Source".
*/
inline std::string implementation() override
{
return "Labsat_Signal_Source";
}
inline size_t item_size() override
{
return item_size_;
@ -75,7 +63,6 @@ private:
gr::blocks::file_sink::sptr file_sink_;
gr::blocks::throttle::sptr throttle_;
std::string role_;
std::string item_type_;
std::string filename_;
std::string dump_filename_;

View File

@ -18,6 +18,7 @@
#include "multichannel_file_signal_source.h"
#include "configuration_interface.h"
#include "gnss_sdr_flags.h"
#include "gnss_sdr_string_literals.h"
#include "gnss_sdr_valve.h"
#include <glog/logging.h>
#include <exception>
@ -27,18 +28,21 @@
#include <utility>
using namespace std::string_literals;
MultichannelFileSignalSource::MultichannelFileSignalSource(const ConfigurationInterface* configuration,
const std::string& role, unsigned int in_streams, unsigned int out_streams,
Concurrent_Queue<pmt::pmt_t>* queue) : role_(role), in_streams_(in_streams), out_streams_(out_streams)
Concurrent_Queue<pmt::pmt_t>* queue)
: SignalSourceBase(configuration, role, "Multichannel_File_Signal_Source"s), in_streams_(in_streams), out_streams_(out_streams)
{
const std::string default_filename("./example_capture.dat");
const std::string default_item_type("short");
const std::string default_dump_filename("./my_capture.dat");
const std::string default_filename("./example_capture.dat"s);
const std::string default_item_type("short"s);
const std::string default_dump_filename("./my_capture.dat"s);
const double default_seconds_to_skip = 0.0;
samples_ = configuration->property(role + ".samples", static_cast<uint64_t>(0));
sampling_frequency_ = configuration->property(role + ".sampling_frequency", static_cast<int64_t>(0));
n_channels_ = configuration->property(role + ".total_channels", 1);
samples_ = configuration->property(role + ".samples"s, static_cast<uint64_t>(0));
sampling_frequency_ = configuration->property(role + ".sampling_frequency"s, static_cast<int64_t>(0));
n_channels_ = configuration->property(role + ".total_channels"s, 1);
for (int32_t n = 0; n < n_channels_; n++)
{

View File

@ -23,6 +23,7 @@
#include "concurrent_queue.h"
#include "gnss_block_interface.h"
#include "signal_source_base.h"
#include <gnuradio/blocks/file_sink.h>
#include <gnuradio/blocks/file_source.h>
#include <gnuradio/blocks/throttle.h>
@ -45,7 +46,7 @@ class ConfigurationInterface;
* \brief Class that reads signals samples from files at different frequency bands
* and adapts it to a SignalSourceInterface
*/
class MultichannelFileSignalSource : public GNSSBlockInterface
class MultichannelFileSignalSource : public SignalSourceBase
{
public:
MultichannelFileSignalSource(const ConfigurationInterface* configuration, const std::string& role,
@ -54,19 +55,6 @@ public:
~MultichannelFileSignalSource() = default;
inline std::string role() override
{
return role_;
}
/*!
* \brief Returns "Multichannel_File_Signal_Source".
*/
inline std::string implementation() override
{
return "Multichannel_File_Signal_Source";
}
inline size_t item_size() override
{
return item_size_;
@ -109,7 +97,6 @@ private:
std::vector<gr::blocks::throttle::sptr> throttle_vec_;
std::vector<std::string> filename_vec_;
std::string item_type_;
std::string role_;
uint64_t samples_;
int64_t sampling_frequency_;
size_t item_size_;

View File

@ -10,286 +10,69 @@
* GNSS-SDR is a Global Navigation Satellite System software-defined receiver.
* This file is part of GNSS-SDR.
*
* Copyright (C) 2010-2020 (see AUTHORS file for a list of contributors)
* Copyright (C) 2010-2021 (see AUTHORS file for a list of contributors)
* SPDX-License-Identifier: GPL-3.0-or-later
*
* -----------------------------------------------------------------------------
*/
#include "nsr_file_signal_source.h"
#include "configuration_interface.h"
#include "gnss_sdr_flags.h"
#include "gnss_sdr_valve.h"
#include "gnss_sdr_string_literals.h"
#include <glog/logging.h>
#include <exception>
#include <fstream>
#include <iomanip>
#include <iostream>
#include <utility>
using namespace std::string_literals;
NsrFileSignalSource::NsrFileSignalSource(const ConfigurationInterface* configuration,
const std::string& role, unsigned int in_streams, unsigned int out_streams,
Concurrent_Queue<pmt::pmt_t>* queue) : role_(role), in_streams_(in_streams), out_streams_(out_streams)
Concurrent_Queue<pmt::pmt_t>* queue)
: FileSourceBase(configuration, role, "Nsr_File_Signal_Source"s, queue, "byte"s)
{
const std::string default_filename("../data/my_capture.dat");
const std::string default_item_type("byte");
const std::string default_dump_filename("../data/my_capture_dump.dat");
samples_ = configuration->property(role + ".samples", static_cast<uint64_t>(0));
sampling_frequency_ = configuration->property(role + ".sampling_frequency", static_cast<int64_t>(0));
filename_ = configuration->property(role + ".filename", default_filename);
// override value with commandline flag, if present
if (FLAGS_signal_source != "-")
{
filename_ = FLAGS_signal_source;
}
if (FLAGS_s != "-")
{
filename_ = FLAGS_s;
}
item_type_ = configuration->property(role + ".item_type", default_item_type);
repeat_ = configuration->property(role + ".repeat", false);
dump_ = configuration->property(role + ".dump", false);
dump_filename_ = configuration->property(role + ".dump_filename", default_dump_filename);
enable_throttle_control_ = configuration->property(role + ".enable_throttle_control", false);
if (item_type_ == "byte")
{
item_size_ = sizeof(char);
}
else
{
LOG(WARNING) << item_type_ << " unrecognized item type. Using byte.";
item_size_ = sizeof(char);
}
try
{
file_source_ = gr::blocks::file_source::make(item_size_, filename_.c_str(), repeat_);
unpack_byte_ = make_unpack_byte_2bit_samples();
}
catch (const std::exception& e)
{
std::cerr
<< "The receiver was configured to work with a file signal source\n"
<< "but the specified file is unreachable by GNSS-SDR.\n"
<< "Please modify your configuration file\n"
<< "and point SignalSource.filename to a valid raw data file. Then:\n"
<< "$ gnss-sdr --config_file=/path/to/my_GNSS_SDR_configuration.conf\n"
<< "Examples of configuration files available at:\n"
<< GNSSSDR_INSTALL_DIR "/share/gnss-sdr/conf/\n";
LOG(WARNING) << "file_signal_source: Unable to open the samples file "
<< filename_.c_str() << ", exiting the program.";
throw(e);
}
DLOG(INFO) << "file_source(" << file_source_->unique_id() << ")";
if (samples_ == 0) // read all file
{
/*!
* BUG workaround: The GNU Radio file source does not stop the receiver after reaching the End of File.
* A possible solution is to compute the file length in samples using file size, excluding the last 2 milliseconds, and enable always the
* valve block
*/
std::ifstream file(filename_.c_str(), std::ios::in | std::ios::binary | std::ios::ate);
std::ifstream::pos_type size;
if (file.is_open())
{
size = file.tellg();
LOG(INFO) << "Total samples in the file= " << floor(static_cast<double>(size) / static_cast<double>(item_size()));
}
else
{
std::cout << "file_signal_source: Unable to open the samples file " << filename_.c_str() << '\n';
LOG(ERROR) << "file_signal_source: Unable to open the samples file " << filename_.c_str();
}
std::streamsize ss = std::cout.precision();
std::cout << std::setprecision(16);
std::cout << "Processing file " << filename_ << ", which contains " << size << " [bytes]\n";
std::cout.precision(ss);
if (size > 0)
{
int sample_packet_factor = 4; // 1 byte -> 4 samples
samples_ = floor(static_cast<double>(size) / static_cast<double>(item_size())) * sample_packet_factor;
samples_ = samples_ - ceil(0.002 * static_cast<double>(sampling_frequency_)); // process all the samples available in the file excluding the last 2 ms
}
}
CHECK(samples_ > 0) << "File does not contain enough samples to process.";
const double signal_duration_s = static_cast<double>(samples_) * (1 / static_cast<double>(sampling_frequency_));
LOG(INFO) << "Total number samples to be processed= " << samples_ << " GNSS signal duration= " << signal_duration_s << " [s]";
std::cout << "GNSS signal recorded time to be processed: " << signal_duration_s << " [s]\n";
valve_ = gnss_sdr_make_valve(sizeof(float), samples_, queue);
DLOG(INFO) << "valve(" << valve_->unique_id() << ")";
if (dump_)
{
// sink_ = gr_make_file_sink(item_size_, dump_filename_.c_str());
sink_ = gr::blocks::file_sink::make(sizeof(float), dump_filename_.c_str());
DLOG(INFO) << "file_sink(" << sink_->unique_id() << ")";
}
if (enable_throttle_control_)
{
throttle_ = gr::blocks::throttle::make(sizeof(float), sampling_frequency_);
}
DLOG(INFO) << "File source filename " << filename_;
DLOG(INFO) << "Samples " << samples_;
DLOG(INFO) << "Sampling frequency " << sampling_frequency_;
DLOG(INFO) << "Item type " << item_type_;
DLOG(INFO) << "Item size " << item_size_;
DLOG(INFO) << "Repeat " << repeat_;
DLOG(INFO) << "Dump " << dump_;
DLOG(INFO) << "Dump filename " << dump_filename_;
if (in_streams_ > 0)
if (in_streams > 0)
{
LOG(ERROR) << "A signal source does not have an input stream";
}
if (out_streams_ > 1)
if (out_streams > 1)
{
LOG(ERROR) << "This implementation only supports one output stream";
}
}
void NsrFileSignalSource::connect(gr::top_block_sptr top_block)
std::tuple<size_t, bool> NsrFileSignalSource::itemTypeToSize()
{
if (samples_ > 0)
auto is_complex = false;
auto item_size = size_t(sizeof(char)); // default
if (item_type() == "byte")
{
if (enable_throttle_control_ == true)
{
top_block->connect(file_source_, 0, unpack_byte_, 0);
top_block->connect(unpack_byte_, 0, throttle_, 0);
DLOG(INFO) << "connected file source to throttle";
top_block->connect(throttle_, 0, valve_, 0);
DLOG(INFO) << "connected throttle to valve";
if (dump_)
{
top_block->connect(valve_, 0, sink_, 0);
DLOG(INFO) << "connected valve to file sink";
}
}
else
{
top_block->connect(file_source_, 0, unpack_byte_, 0);
top_block->connect(unpack_byte_, 0, valve_, 0);
DLOG(INFO) << "connected file source to valve";
if (dump_)
{
top_block->connect(valve_, 0, sink_, 0);
DLOG(INFO) << "connected valve to file sink";
}
}
item_size = sizeof(char);
}
else
{
if (enable_throttle_control_ == true)
{
top_block->connect(file_source_, 0, unpack_byte_, 0);
top_block->connect(unpack_byte_, 0, throttle_, 0);
DLOG(INFO) << "connected file source to throttle";
if (dump_)
{
top_block->connect(throttle_, 0, sink_, 0);
DLOG(INFO) << "connected file source to sink";
}
}
else
{
if (dump_)
{
top_block->connect(file_source_, 0, unpack_byte_, 0);
top_block->connect(unpack_byte_, 0, sink_, 0);
DLOG(INFO) << "connected file source to sink";
}
}
LOG(WARNING) << item_type() << " unrecognized item type. Using byte.";
}
return std::make_tuple(item_size, is_complex);
}
// 1 byte -> 4 samples
double NsrFileSignalSource::packetsPerSample() const { return 4.0; }
gnss_shared_ptr<gr::block> NsrFileSignalSource::source() const { return unpack_byte_; }
void NsrFileSignalSource::disconnect(gr::top_block_sptr top_block)
void NsrFileSignalSource::create_file_source_hook()
{
if (samples_ > 0)
{
if (enable_throttle_control_ == true)
{
top_block->disconnect(file_source_, 0, unpack_byte_, 0);
DLOG(INFO) << "disconnected file source to unpack_byte_";
top_block->connect(unpack_byte_, 0, throttle_, 0);
DLOG(INFO) << "disconnected unpack_byte_ to throttle_";
top_block->disconnect(throttle_, 0, valve_, 0);
DLOG(INFO) << "disconnected throttle to valve";
if (dump_)
{
top_block->disconnect(valve_, 0, sink_, 0);
DLOG(INFO) << "disconnected valve to file sink";
}
}
else
{
top_block->disconnect(file_source_, 0, unpack_byte_, 0);
DLOG(INFO) << "disconnected file source to unpack_byte_";
top_block->disconnect(unpack_byte_, 0, valve_, 0);
DLOG(INFO) << "disconnected unpack_byte_ to valve";
if (dump_)
{
top_block->disconnect(valve_, 0, sink_, 0);
DLOG(INFO) << "disconnected valve to file sink";
}
}
}
else
{
if (enable_throttle_control_ == true)
{
top_block->disconnect(file_source_, 0, unpack_byte_, 0);
DLOG(INFO) << "disconnected file source to unpack_byte_";
top_block->disconnect(unpack_byte_, 0, throttle_, 0);
DLOG(INFO) << "disconnected unpack_byte_ to throttle";
if (dump_)
{
top_block->disconnect(unpack_byte_, 0, sink_, 0);
DLOG(INFO) << "disconnected funpack_byte_ to sink";
}
}
else
{
if (dump_)
{
top_block->disconnect(file_source_, 0, unpack_byte_, 0);
DLOG(INFO) << "disconnected file source to unpack_byte_";
top_block->disconnect(unpack_byte_, 0, sink_, 0);
DLOG(INFO) << "disconnected unpack_byte_ to sink";
}
}
}
unpack_byte_ = make_unpack_byte_2bit_samples();
DLOG(INFO) << "unpack_byte_2bit_samples(" << unpack_byte_->unique_id() << ")";
}
gr::basic_block_sptr NsrFileSignalSource::get_left_block()
void NsrFileSignalSource::pre_connect_hook(gr::top_block_sptr top_block)
{
LOG(WARNING) << "Left block of a signal source should not be retrieved";
// return gr_block_sptr();
return gr::blocks::file_source::sptr();
top_block->connect(file_source(), 0, unpack_byte_, 0);
DLOG(INFO) << "connected file_source to unpacker";
}
gr::basic_block_sptr NsrFileSignalSource::get_right_block()
void NsrFileSignalSource::pre_disconnect_hook(gr::top_block_sptr top_block)
{
if (samples_ > 0)
{
return valve_;
}
if (enable_throttle_control_ == true)
{
return throttle_;
}
return unpack_byte_;
top_block->disconnect(file_source(), 0, unpack_byte_, 0);
DLOG(INFO) << "disconnected file_source from unpacker";
}

View File

@ -12,7 +12,7 @@
* GNSS-SDR is a Global Navigation Satellite System software-defined receiver.
* This file is part of GNSS-SDR.
*
* Copyright (C) 2010-2020 (see AUTHORS file for a list of contributors)
* Copyright (C) 2010-2021 (see AUTHORS file for a list of contributors)
* SPDX-License-Identifier: GPL-3.0-or-later
*
* -----------------------------------------------------------------------------
@ -21,15 +21,8 @@
#ifndef GNSS_SDR_NSR_FILE_SIGNAL_SOURCE_H
#define GNSS_SDR_NSR_FILE_SIGNAL_SOURCE_H
#include "concurrent_queue.h"
#include "gnss_block_interface.h"
#include "file_source_base.h"
#include "unpack_byte_2bit_samples.h"
#include <gnuradio/blocks/file_sink.h>
#include <gnuradio/blocks/file_source.h>
#include <gnuradio/blocks/throttle.h>
#include <gnuradio/hier_block2.h>
#include <pmt/pmt.h>
#include <string>
/** \addtogroup Signal_Source
* \{ */
@ -42,7 +35,7 @@ class ConfigurationInterface;
* \brief Class that reads signals samples from a file
* and adapts it to a SignalSourceInterface
*/
class NsrFileSignalSource : public GNSSBlockInterface
class NsrFileSignalSource : public FileSourceBase
{
public:
NsrFileSignalSource(const ConfigurationInterface* configuration, const std::string& role,
@ -50,73 +43,17 @@ public:
Concurrent_Queue<pmt::pmt_t>* queue);
~NsrFileSignalSource() = default;
inline std::string role() override
{
return role_;
}
/*!
* \brief Returns "Nsr_File_Signal_Source".
*/
inline std::string implementation() override
{
return "Nsr_File_Signal_Source";
}
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;
inline std::string filename() const
{
return filename_;
}
inline std::string item_type() const
{
return item_type_;
}
inline bool repeat() const
{
return repeat_;
}
inline int64_t sampling_frequency() const
{
return sampling_frequency_;
}
inline uint64_t samples() const
{
return samples_;
}
protected:
std::tuple<size_t, bool> itemTypeToSize() override;
double packetsPerSample() const override;
gnss_shared_ptr<gr::block> source() const override;
void create_file_source_hook() override;
void pre_connect_hook(gr::top_block_sptr top_block) override;
void pre_disconnect_hook(gr::top_block_sptr top_block) override;
private:
gr::blocks::file_source::sptr file_source_;
unpack_byte_2bit_samples_sptr unpack_byte_;
gnss_shared_ptr<gr::block> valve_;
gr::blocks::file_sink::sptr sink_;
gr::blocks::throttle::sptr throttle_;
uint64_t samples_;
int64_t sampling_frequency_;
size_t item_size_;
std::string filename_;
std::string item_type_;
std::string dump_filename_;
std::string role_;
uint32_t in_streams_;
uint32_t out_streams_;
bool repeat_;
bool dump_;
// Throttle control
bool enable_throttle_control_;
};

View File

@ -18,6 +18,7 @@
#include "osmosdr_signal_source.h"
#include "GPS_L1_CA.h"
#include "configuration_interface.h"
#include "gnss_sdr_string_literals.h"
#include "gnss_sdr_valve.h"
#include <glog/logging.h>
#include <gnuradio/blocks/file_sink.h>
@ -25,9 +26,13 @@
#include <utility>
using namespace std::string_literals;
OsmosdrSignalSource::OsmosdrSignalSource(const ConfigurationInterface* configuration,
const std::string& role, unsigned int in_stream, unsigned int out_stream,
Concurrent_Queue<pmt::pmt_t>* queue) : role_(role), in_stream_(in_stream), out_stream_(out_stream)
Concurrent_Queue<pmt::pmt_t>* queue)
: SignalSourceBase(configuration, role, "Osmosdr_Signal_Source"s), in_stream_(in_stream), out_stream_(out_stream)
{
// DUMP PARAMETERS
const std::string empty;

View File

@ -20,7 +20,7 @@
#define GNSS_SDR_OSMOSDR_SIGNAL_SOURCE_H
#include "concurrent_queue.h"
#include "gnss_block_interface.h"
#include "signal_source_base.h"
#include <gnuradio/blocks/file_sink.h>
#include <pmt/pmt.h>
#include <cstdint>
@ -42,7 +42,7 @@ class ConfigurationInterface;
* HackRF or Realtek's RTL2832U-based USB dongle DVB-T receivers
* (see https://osmocom.org/projects/rtl-sdr/wiki)
*/
class OsmosdrSignalSource : public GNSSBlockInterface
class OsmosdrSignalSource : public SignalSourceBase
{
public:
OsmosdrSignalSource(const ConfigurationInterface* configuration,
@ -51,19 +51,6 @@ public:
~OsmosdrSignalSource() = default;
inline std::string role() override
{
return role_;
}
/*!
* \brief Returns "Osmosdr_Signal_Source"
*/
inline std::string implementation() override
{
return "Osmosdr_Signal_Source";
}
inline size_t item_size() override
{
return item_size_;
@ -81,7 +68,6 @@ private:
gnss_shared_ptr<gr::block> valve_;
gr::blocks::file_sink::sptr file_sink_;
std::string role_;
std::string item_type_;
std::string dump_filename_;
std::string osmosdr_args_;

View File

@ -18,15 +18,20 @@
#include "plutosdr_signal_source.h"
#include "GPS_L1_CA.h"
#include "configuration_interface.h"
#include "gnss_sdr_string_literals.h"
#include "gnss_sdr_valve.h"
#include <glog/logging.h>
#include <iostream>
#include <utility>
using namespace std::string_literals;
PlutosdrSignalSource::PlutosdrSignalSource(const ConfigurationInterface* configuration,
const std::string& role, unsigned int in_stream, unsigned int out_stream,
Concurrent_Queue<pmt::pmt_t>* queue) : role_(role), in_stream_(in_stream), out_stream_(out_stream)
Concurrent_Queue<pmt::pmt_t>* queue)
: SignalSourceBase(configuration, role, "Plutosdr_Signal_Source"s), in_stream_(in_stream), out_stream_(out_stream)
{
const std::string default_item_type("gr_complex");
const std::string default_dump_file("./data/signal_source.dat");

View File

@ -19,7 +19,7 @@
#ifndef GNSS_SDR_PLUTOSDR_SIGNAL_SOURCE_H
#define GNSS_SDR_PLUTOSDR_SIGNAL_SOURCE_H
#include "gnss_block_interface.h"
#include "signal_source_base.h"
#include <gnuradio/blocks/file_sink.h>
#if GRIIO_INCLUDE_HAS_GNURADIO
#include <gnuradio/iio/pluto_source.h>
@ -42,7 +42,7 @@ class ConfigurationInterface;
/*!
*/
class PlutosdrSignalSource : public GNSSBlockInterface
class PlutosdrSignalSource : public SignalSourceBase
{
public:
PlutosdrSignalSource(const ConfigurationInterface* configuration,
@ -51,18 +51,6 @@ public:
~PlutosdrSignalSource() = default;
std::string role() override
{
return role_;
}
/*!
* \brief Returns "Plutosdr_Signal_Source"
*/
std::string implementation() override
{
return "Plutosdr_Signal_Source";
}
size_t item_size() override
{
return item_size_;
@ -79,7 +67,6 @@ private:
gnss_shared_ptr<gr::block> valve_;
gr::blocks::file_sink::sptr file_sink_;
std::string role_;
std::string dump_filename_;
// Front-end settings

View File

@ -17,14 +17,18 @@
#include "raw_array_signal_source.h"
#include "concurrent_queue.h"
#include "configuration_interface.h"
#include "gnss_sdr_string_literals.h"
#include <glog/logging.h>
#include <gnuradio/blocks/file_sink.h>
#include <pmt/pmt.h>
#include <dbfcttc/raw_array.h>
using namespace std::string_literals;
RawArraySignalSource::RawArraySignalSource(const ConfigurationInterface* configuration,
std::string role, unsigned int in_stream, unsigned int out_stream, Concurrent_Queue<pmt::pmt_t>* queue) : role_(role), in_stream_(in_stream), out_stream_(out_stream)
std::string role, unsigned int in_stream, unsigned int out_stream, Concurrent_Queue<pmt::pmt_t>* queue)
: SignalSourceBase(configuration, role, "Raw_Array_Signal_Source"s), in_stream_(in_stream), out_stream_(out_stream)
{
const std::string default_item_type("gr_complex");
const std::string default_dump_file("./data/raw_array_source.dat");

View File

@ -19,7 +19,7 @@
#define GNSS_SDR_RAW_ARRAY_SIGNAL_SOURCE_H
#include "concurrent_queue.h"
#include "gnss_block_interface.h"
#include "signal_source_base.h"
#include <gnuradio/blocks/file_sink.h>
#include <gnuradio/hier_block2.h>
#include <pmt/pmt.h>
@ -39,7 +39,7 @@ class ConfigurationInterface;
/*!
* \brief This class reads samples from a GN3S USB dongle, a RF front-end signal sampler
*/
class RawArraySignalSource : public GNSSBlockInterface
class RawArraySignalSource : public SignalSourceBase
{
public:
RawArraySignalSource(const ConfigurationInterface* configuration,
@ -48,19 +48,6 @@ public:
~RawArraySignalSource() = default;
inline std::string role() override
{
return role_;
}
/*!
* \brief Returns "RawArraySignalSource".
*/
inline std::string implementation() override
{
return "Raw_Array_Signal_Source";
}
inline size_t item_size() override
{
return item_size_;
@ -74,12 +61,11 @@ public:
private:
gr::block_sptr raw_array_source_;
gr::blocks::file_sink::sptr file_sink_;
std::string role_;
std::string item_type_;
std::string dump_filename_;
std::string eth_device_;
size_t item_size_;
int64_t samples_;
[[maybe_unused]] int64_t samples_;
unsigned int in_stream_;
unsigned int out_stream_;
bool dump_;

View File

@ -19,20 +19,21 @@
#include "rtl_tcp_signal_source.h"
#include "GPS_L1_CA.h"
#include "configuration_interface.h"
#include "gnss_sdr_string_literals.h"
#include "gnss_sdr_valve.h"
#include <glog/logging.h>
#include <cstdint>
#include <iostream>
#include <utility>
using namespace std::string_literals;
RtlTcpSignalSource::RtlTcpSignalSource(const ConfigurationInterface* configuration,
const std::string& role,
unsigned int in_stream,
unsigned int out_stream,
Concurrent_Queue<pmt::pmt_t>* queue) : role_(role),
in_stream_(in_stream),
out_stream_(out_stream)
Concurrent_Queue<pmt::pmt_t>* queue)
: SignalSourceBase(configuration, role, "RtlTcp_Signal_Source"s), in_stream_(in_stream), out_stream_(out_stream)
{
// DUMP PARAMETERS
const std::string default_dump_file("./data/signal_source.dat");

View File

@ -19,8 +19,8 @@
#define GNSS_SDR_RTL_TCP_SIGNAL_SOURCE_H
#include "concurrent_queue.h"
#include "gnss_block_interface.h"
#include "rtl_tcp_signal_source_c.h"
#include "signal_source_base.h"
#include <gnuradio/blocks/deinterleave.h>
#include <gnuradio/blocks/file_sink.h>
#include <gnuradio/blocks/float_to_complex.h>
@ -42,7 +42,7 @@ class ConfigurationInterface;
* I/Q samples over TCP.
* (see https://osmocom.org/projects/rtl-sdr/wiki)
*/
class RtlTcpSignalSource : public GNSSBlockInterface
class RtlTcpSignalSource : public SignalSourceBase
{
public:
RtlTcpSignalSource(const ConfigurationInterface* configuration,
@ -53,19 +53,6 @@ public:
~RtlTcpSignalSource() = default;
inline std::string role() override
{
return role_;
}
/*!
* \brief Returns "RtlTcp_Signal_Source"
*/
inline std::string implementation() override
{
return "RtlTcp_Signal_Source";
}
inline size_t item_size() override
{
return item_size_;
@ -84,7 +71,6 @@ private:
gnss_shared_ptr<gr::block> valve_;
gr::blocks::file_sink::sptr file_sink_;
std::string role_;
std::string item_type_;
std::string dump_filename_;

View File

@ -0,0 +1,46 @@
/*!
* \file signal_source_base.cc
* \brief Base class for signal sources
* \author Jim Melton, 2020. jim.melton(at)sncorp.com
*
*
* -----------------------------------------------------------------------------
*
* GNSS-SDR is a Global Navigation Satellite System software-defined receiver.
* This file is part of GNSS-SDR.
*
* Copyright (C) 2010-2021 (see AUTHORS file for a list of contributors)
* SPDX-License-Identifier: GPL-3.0-or-later
*
* -----------------------------------------------------------------------------
*/
#include "signal_source_base.h"
#include "configuration_interface.h"
#include "gnss_sdr_string_literals.h"
#include <utility> // move
using namespace std::string_literals;
std::string SignalSourceBase::role()
{
return role_;
}
std::string SignalSourceBase::implementation()
{
return implementation_;
}
size_t SignalSourceBase::getRfChannels() const
{
return rfChannels_;
}
SignalSourceBase::SignalSourceBase(ConfigurationInterface const* configuration, std::string role, std::string impl)
: role_(std::move(role)), implementation_(std::move(impl))
{
// because clang-tidy insists on using std::move for the string arguments, and to avoid
// depending on the order of initialization, assign rfChannels_ in the body
rfChannels_ = configuration->property(role_ + ".RF_channels"s, uint64_t(1U));
}

View File

@ -0,0 +1,47 @@
/*!
* \file signal_source_base.h
* \brief Header file of the base class to signal_source GNSS blocks.
* \author Jim Melton, 2020. jim.melton(at)sncorp.com
*
*
* -----------------------------------------------------------------------------
*
* GNSS-SDR is a Global Navigation Satellite System software-defined receiver.
* This file is part of GNSS-SDR.
*
* Copyright (C) 2010-2021 (see AUTHORS file for a list of contributors)
* SPDX-License-Identifier: GPL-3.0-or-later
*
* -----------------------------------------------------------------------------
*/
#ifndef GNSS_SDR_SIGNAL_SOURCE_BASE_H
#define GNSS_SDR_SIGNAL_SOURCE_BASE_H
#include "signal_source_interface.h"
#include <cstddef>
#include <string>
class ConfigurationInterface;
class SignalSourceBase : public SignalSourceInterface
{
public:
std::string role() final;
std::string implementation() final;
size_t getRfChannels() const override;
protected:
//! Constructor
SignalSourceBase(ConfigurationInterface const* configuration, std::string role, std::string impl);
private:
std::string const role_;
std::string const implementation_;
size_t rfChannels_;
};
#endif

View File

@ -6,290 +6,74 @@
*
* -----------------------------------------------------------------------------
*
* Copyright (C) 2010-2020 (see AUTHORS file for a list of contributors)
*
* GNSS-SDR is a Global Navigation Satellite System software-defined receiver.
* This file is not part of GNSS-SDR.
* This file is part of GNSS-SDR.
*
* Copyright (C) 2010-2021 (see AUTHORS file for a list of contributors)
* SPDX-License-Identifier: GPL-3.0-or-later
*
* -----------------------------------------------------------------------------
*/
#include "spir_file_signal_source.h"
#include "configuration_interface.h"
#include "gnss_sdr_flags.h"
#include "gnss_sdr_valve.h"
#include "gnss_sdr_string_literals.h"
#include <glog/logging.h>
#include <exception>
#include <fstream>
#include <iomanip>
#include <iostream>
#include <utility>
using namespace std::string_literals;
SpirFileSignalSource::SpirFileSignalSource(const ConfigurationInterface* configuration,
const std::string& role, unsigned int in_streams, unsigned int out_streams,
Concurrent_Queue<pmt::pmt_t>* queue) : role_(role), in_streams_(in_streams), out_streams_(out_streams)
Concurrent_Queue<pmt::pmt_t>* queue)
: FileSourceBase(configuration, role, "Spir_File_Signal_Source"s, queue, "int"s)
{
const std::string default_filename("../data/my_capture.dat");
const std::string default_item_type("int");
const std::string default_dump_filename("../data/my_capture_dump.dat");
samples_ = configuration->property(role + ".samples", static_cast<uint64_t>(0));
sampling_frequency_ = configuration->property(role + ".sampling_frequency", static_cast<int64_t>(0));
filename_ = configuration->property(role + ".filename", default_filename);
// override value with commandline flag, if present
if (FLAGS_signal_source != "-")
{
filename_ = FLAGS_signal_source;
}
if (FLAGS_s != "-")
{
filename_ = FLAGS_s;
}
item_type_ = configuration->property(role + ".item_type", default_item_type);
repeat_ = configuration->property(role + ".repeat", false);
dump_ = configuration->property(role + ".dump", false);
dump_filename_ = configuration->property(role + ".dump_filename", default_dump_filename);
enable_throttle_control_ = configuration->property(role + ".enable_throttle_control", false);
if (item_type_ == "int")
{
item_size_ = sizeof(int);
}
else
{
LOG(WARNING) << item_type_ << " unrecognized item type. Using int.";
item_size_ = sizeof(int);
}
try
{
file_source_ = gr::blocks::file_source::make(item_size_, filename_.c_str(), repeat_);
unpack_intspir_ = make_unpack_intspir_1bit_samples();
}
catch (const std::exception& e)
{
std::cerr
<< "The receiver was configured to work with a file signal source\n"
<< "but the specified file is unreachable by GNSS-SDR.\n"
<< "Please modify your configuration file\n"
<< "and point SignalSource.filename to a valid raw data file. Then:\n"
<< "$ gnss-sdr --config_file=/path/to/my_GNSS_SDR_configuration.conf\n"
<< "Examples of configuration files available at:\n"
<< GNSSSDR_INSTALL_DIR "/share/gnss-sdr/conf/\n";
LOG(WARNING) << "file_signal_source: Unable to open the samples file "
<< filename_.c_str() << ", exiting the program.";
throw(e);
}
DLOG(INFO) << "file_source(" << file_source_->unique_id() << ")";
if (samples_ == 0) // read all file
{
/*!
* BUG workaround: The GNU Radio file source does not stop the receiver after reaching the End of File.
* A possible solution is to compute the file length in samples using file size, excluding the last 100 milliseconds, and enable always the
* valve block
*/
std::ifstream file(filename_.c_str(), std::ios::in | std::ios::binary | std::ios::ate);
std::ifstream::pos_type size;
if (file.is_open())
{
size = file.tellg();
LOG(INFO) << "Total samples in the file= " << floor(static_cast<double>(size) / static_cast<double>(item_size()));
}
else
{
std::cout << "file_signal_source: Unable to open the samples file " << filename_.c_str() << '\n';
LOG(ERROR) << "file_signal_source: Unable to open the samples file " << filename_.c_str();
}
std::streamsize ss = std::cout.precision();
std::cout << std::setprecision(16);
std::cout << "Processing file " << filename_ << ", which contains " << size << " [bytes]\n";
std::cout.precision(ss);
if (size > 0)
{
int sample_packet_factor = 1; // 1 int -> 1 complex sample (I&Q from 1 channel)
samples_ = floor(static_cast<double>(size) / static_cast<double>(item_size())) * sample_packet_factor;
samples_ = samples_ - ceil(0.002 * static_cast<double>(sampling_frequency_)); // process all the samples available in the file excluding the last 2 ms
}
}
CHECK(samples_ > 0) << "File does not contain enough samples to process.";
double signal_duration_s = static_cast<double>(samples_) * (1 / static_cast<double>(sampling_frequency_));
LOG(INFO) << "Total number samples to be processed= " << samples_ << " GNSS signal duration= " << signal_duration_s << " [s]";
std::cout << "GNSS signal recorded time to be processed: " << signal_duration_s << " [s]\n";
valve_ = gnss_sdr_make_valve(sizeof(float), samples_, queue);
DLOG(INFO) << "valve(" << valve_->unique_id() << ")";
if (dump_)
{
// sink_ = gr_make_file_sink(item_size_, dump_filename_.c_str());
sink_ = gr::blocks::file_sink::make(sizeof(float), dump_filename_.c_str());
DLOG(INFO) << "file_sink(" << sink_->unique_id() << ")";
}
if (enable_throttle_control_)
{
throttle_ = gr::blocks::throttle::make(sizeof(float), sampling_frequency_);
}
DLOG(INFO) << "File source filename " << filename_;
DLOG(INFO) << "Samples " << samples_;
DLOG(INFO) << "Sampling frequency " << sampling_frequency_;
DLOG(INFO) << "Item type " << item_type_;
DLOG(INFO) << "Item size " << item_size_;
DLOG(INFO) << "Repeat " << repeat_;
DLOG(INFO) << "Dump " << dump_;
DLOG(INFO) << "Dump filename " << dump_filename_;
if (in_streams_ > 0)
if (in_streams > 0)
{
LOG(ERROR) << "A signal source does not have an input stream";
}
if (out_streams_ > 1)
if (out_streams > 1)
{
LOG(ERROR) << "This implementation only supports one output stream";
}
}
void SpirFileSignalSource::connect(gr::top_block_sptr top_block)
std::tuple<size_t, bool> SpirFileSignalSource::itemTypeToSize()
{
if (samples_ > 0)
auto is_complex = false;
auto item_size = size_t(0);
if (item_type() == "int")
{
if (enable_throttle_control_ == true)
{
top_block->connect(file_source_, 0, unpack_intspir_, 0);
top_block->connect(unpack_intspir_, 0, throttle_, 0);
DLOG(INFO) << "connected file source to throttle";
top_block->connect(throttle_, 0, valve_, 0);
DLOG(INFO) << "connected throttle to valve";
if (dump_)
{
top_block->connect(valve_, 0, sink_, 0);
DLOG(INFO) << "connected valve to file sink";
}
}
else
{
top_block->connect(file_source_, 0, unpack_intspir_, 0);
top_block->connect(unpack_intspir_, 0, valve_, 0);
DLOG(INFO) << "connected file source to valve";
if (dump_)
{
top_block->connect(valve_, 0, sink_, 0);
DLOG(INFO) << "connected valve to file sink";
}
}
item_size = sizeof(int);
}
else
{
if (enable_throttle_control_ == true)
{
top_block->connect(file_source_, 0, unpack_intspir_, 0);
top_block->connect(unpack_intspir_, 0, throttle_, 0);
DLOG(INFO) << "connected file source to throttle";
if (dump_)
{
top_block->connect(throttle_, 0, sink_, 0);
DLOG(INFO) << "connected file source to sink";
}
}
else
{
if (dump_)
{
top_block->connect(file_source_, 0, unpack_intspir_, 0);
top_block->connect(unpack_intspir_, 0, sink_, 0);
DLOG(INFO) << "connected file source to sink";
}
}
LOG(WARNING) << item_type() << " unsupported item type. Using int.";
item_size = sizeof(int);
}
return std::make_tuple(item_size, is_complex);
}
// This class feeds the file data through a decoder to produce samples; for all intents this is the "source"
gnss_shared_ptr<gr::block> SpirFileSignalSource::source() const { return unpack_intspir_; }
void SpirFileSignalSource::disconnect(gr::top_block_sptr top_block)
void SpirFileSignalSource::create_file_source_hook()
{
if (samples_ > 0)
{
if (enable_throttle_control_ == true)
{
top_block->disconnect(file_source_, 0, unpack_intspir_, 0);
DLOG(INFO) << "disconnected file source to unpack_intspir_";
top_block->connect(unpack_intspir_, 0, throttle_, 0);
DLOG(INFO) << "disconnected unpack_intspir_ to throttle_";
top_block->disconnect(throttle_, 0, valve_, 0);
DLOG(INFO) << "disconnected throttle to valve";
if (dump_)
{
top_block->disconnect(valve_, 0, sink_, 0);
DLOG(INFO) << "disconnected valve to file sink";
}
}
else
{
top_block->disconnect(file_source_, 0, unpack_intspir_, 0);
DLOG(INFO) << "disconnected file source to unpack_intspir_";
top_block->disconnect(unpack_intspir_, 0, valve_, 0);
DLOG(INFO) << "disconnected unpack_intspir_ to valve";
if (dump_)
{
top_block->disconnect(valve_, 0, sink_, 0);
DLOG(INFO) << "disconnected valve to file sink";
}
}
}
else
{
if (enable_throttle_control_ == true)
{
top_block->disconnect(file_source_, 0, unpack_intspir_, 0);
DLOG(INFO) << "disconnected file source to unpack_intspir_";
top_block->disconnect(unpack_intspir_, 0, throttle_, 0);
DLOG(INFO) << "disconnected unpack_intspir_ to throttle";
if (dump_)
{
top_block->disconnect(unpack_intspir_, 0, sink_, 0);
DLOG(INFO) << "disconnected funpack_intspir_ to sink";
}
}
else
{
if (dump_)
{
top_block->disconnect(file_source_, 0, unpack_intspir_, 0);
DLOG(INFO) << "disconnected file source to unpack_intspir_";
top_block->disconnect(unpack_intspir_, 0, sink_, 0);
DLOG(INFO) << "disconnected unpack_intspir_ to sink";
}
}
}
// connect the file to the decoder
unpack_intspir_ = make_unpack_intspir_1bit_samples();
DLOG(INFO) << "unpack_intspir_1bit_samples(" << unpack_intspir_->unique_id() << ")";
}
gr::basic_block_sptr SpirFileSignalSource::get_left_block()
void SpirFileSignalSource::pre_connect_hook(gr::top_block_sptr top_block)
{
LOG(WARNING) << "Left block of a signal source should not be retrieved";
// return gr_block_sptr();
return gr::blocks::file_source::sptr();
top_block->connect(file_source(), 0, unpack_intspir_, 0);
DLOG(INFO) << "connected file_source to unpacker";
}
gr::basic_block_sptr SpirFileSignalSource::get_right_block()
void SpirFileSignalSource::post_disconnect_hook(gr::top_block_sptr top_block)
{
if (samples_ > 0)
{
return valve_;
}
if (enable_throttle_control_ == true)
{
return throttle_;
}
return unpack_intspir_;
top_block->disconnect(file_source(), 0, unpack_intspir_, 0);
DLOG(INFO) << "disconnected file_source from unpacker";
}

View File

@ -6,13 +6,10 @@
*
* -----------------------------------------------------------------------------
*
* Copyright (C) 2010-2020 (see AUTHORS file for a list of contributors)
*
* GNSS-SDR is a software defined Global Navigation
* Satellite Systems receiver
*
* This file is not part of GNSS-SDR.
* GNSS-SDR is a Global Navigation Satellite System software-defined receiver.
* This file is part of GNSS-SDR.
*
* Copyright (C) 2010-2021 (see AUTHORS file for a list of contributors)
* SPDX-License-Identifier: GPL-3.0-or-later
*
* -----------------------------------------------------------------------------
@ -21,16 +18,8 @@
#ifndef GNSS_SDR_SPIR_FILE_SIGNAL_SOURCE_H
#define GNSS_SDR_SPIR_FILE_SIGNAL_SOURCE_H
#include "concurrent_queue.h"
#include "gnss_block_interface.h"
#include "file_source_base.h"
#include "unpack_intspir_1bit_samples.h"
#include <gnuradio/blocks/file_sink.h>
#include <gnuradio/blocks/file_source.h>
#include <gnuradio/blocks/throttle.h>
#include <gnuradio/hier_block2.h>
#include <pmt/pmt.h>
#include <cstdint>
#include <string>
/** \addtogroup Signal_Source
@ -45,7 +34,7 @@ class ConfigurationInterface;
* \brief Class that reads signals samples from a file
* and adapts it to a SignalSourceInterface
*/
class SpirFileSignalSource : public GNSSBlockInterface
class SpirFileSignalSource : public FileSourceBase
{
public:
SpirFileSignalSource(const ConfigurationInterface* configuration, const std::string& role,
@ -54,77 +43,16 @@ public:
~SpirFileSignalSource() = default;
inline std::string role() override
{
return role_;
}
protected:
std::tuple<size_t, bool> itemTypeToSize() override;
gnss_shared_ptr<gr::block> source() const override;
void create_file_source_hook() override;
void pre_connect_hook(gr::top_block_sptr top_block) override;
void post_disconnect_hook(gr::top_block_sptr top_block) override;
/*!
* \brief Returns "Spir_File_Signal_Source".
*/
inline std::string implementation() override
{
return "Spir_File_Signal_Source";
}
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;
inline std::string filename() const
{
return filename_;
}
inline std::string item_type() const
{
return item_type_;
}
inline bool repeat() const
{
return repeat_;
}
inline int64_t sampling_frequency() const
{
return sampling_frequency_;
}
inline uint64_t samples() const
{
return samples_;
}
private:
gr::blocks::file_source::sptr file_source_;
unpack_intspir_1bit_samples_sptr unpack_intspir_;
gnss_shared_ptr<gr::block> valve_;
gr::blocks::file_sink::sptr sink_;
gr::blocks::throttle::sptr throttle_;
std::string filename_;
std::string item_type_;
std::string dump_filename_;
std::string role_;
uint64_t samples_;
int64_t sampling_frequency_;
size_t item_size_;
unsigned int in_streams_;
unsigned int out_streams_;
bool repeat_;
bool dump_;
// Throttle control
bool enable_throttle_control_;
};

View File

@ -18,6 +18,7 @@
#include "spir_gss6450_file_signal_source.h"
#include "configuration_interface.h"
#include "gnss_sdr_string_literals.h"
#include <glog/logging.h>
#include <exception>
#include <fstream>
@ -25,9 +26,11 @@
#include <iostream>
#include <utility>
using namespace std::string_literals;
SpirGSS6450FileSignalSource::SpirGSS6450FileSignalSource(const ConfigurationInterface* configuration,
const std::string& role, uint32_t in_streams, uint32_t out_streams, Concurrent_Queue<pmt::pmt_t>* queue) : role_(role), in_streams_(in_streams), out_streams_(out_streams)
const std::string& role, uint32_t in_streams, uint32_t out_streams, Concurrent_Queue<pmt::pmt_t>* queue)
: SignalSourceBase(configuration, role, "Spir_GSS6450_File_Signal_Source"s), in_streams_(in_streams), out_streams_(out_streams)
{
const std::string default_filename("../data/my_capture.dat");
const std::string default_dump_filename("../data/my_capture_dump.dat");

View File

@ -22,8 +22,8 @@
#define GNSS_SDR_SPIR_GSS6450_FILE_SIGNAL_SOURCE_H
#include "concurrent_queue.h"
#include "gnss_block_interface.h"
#include "gnss_sdr_valve.h"
#include "signal_source_base.h"
#include "unpack_spir_gss6450_samples.h"
#include <gnuradio/blocks/deinterleave.h>
#include <gnuradio/blocks/endian_swap.h>
@ -50,23 +50,12 @@ class ConfigurationInterface;
* \brief Class that reads signals samples from a file
* and adapts it to a SignalSourceInterface
*/
class SpirGSS6450FileSignalSource : public GNSSBlockInterface
class SpirGSS6450FileSignalSource : public SignalSourceBase
{
public:
SpirGSS6450FileSignalSource(const ConfigurationInterface* configuration, const std::string& role,
uint32_t in_streams, uint32_t out_streams, Concurrent_Queue<pmt::pmt_t>* queue);
~SpirGSS6450FileSignalSource() = default;
inline std::string role() override
{
return role_;
}
inline std::string implementation() override
{
return "Spir_GSS6450_File_Signal_Source";
}
inline size_t item_size() override
{
return item_size_;
@ -114,7 +103,6 @@ private:
std::vector<gr::blocks::throttle::sptr> throttle_vec_;
std::string filename_;
std::string dump_filename_;
std::string role_;
std::string item_type_;
uint64_t samples_;
int64_t sampling_frequency_;

View File

@ -9,296 +9,77 @@
* GNSS-SDR is a Global Navigation Satellite System software-defined receiver.
* This file is part of GNSS-SDR.
*
* Copyright (C) 2010-2020 (see AUTHORS file for a list of contributors)
* Copyright (C) 2010-2021 (see AUTHORS file for a list of contributors)
* SPDX-License-Identifier: GPL-3.0-or-later
*
* -----------------------------------------------------------------------------
*/
#include "two_bit_cpx_file_signal_source.h"
#include "configuration_interface.h"
#include "gnss_sdr_flags.h"
#include "gnss_sdr_valve.h"
#include "gnss_sdr_string_literals.h"
#include <glog/logging.h>
#include <exception>
#include <fstream>
#include <iomanip>
#include <iostream>
#include <utility>
using namespace std::string_literals;
TwoBitCpxFileSignalSource::TwoBitCpxFileSignalSource(
const ConfigurationInterface* configuration,
const std::string& role,
unsigned int in_streams,
unsigned int out_streams,
Concurrent_Queue<pmt::pmt_t>* queue) : role_(role),
in_streams_(in_streams),
out_streams_(out_streams)
unsigned int in_streams, unsigned int out_streams,
Concurrent_Queue<pmt::pmt_t>* queue)
: FileSourceBase(configuration, role, "Two_Bit_Cpx_File_Signal_Source"s, queue, "byte"s)
{
const std::string default_filename("../data/my_capture.dat");
const std::string default_item_type("byte");
const std::string default_dump_filename("../data/my_capture_dump.dat");
samples_ = configuration->property(role + ".samples", static_cast<uint64_t>(0));
sampling_frequency_ = configuration->property(role + ".sampling_frequency", static_cast<int64_t>(0));
filename_ = configuration->property(role + ".filename", default_filename);
// override value with commandline flag, if present
if (FLAGS_signal_source != "-")
{
filename_ = FLAGS_signal_source;
}
if (FLAGS_s != "-")
{
filename_ = FLAGS_s;
}
item_type_ = configuration->property(role + ".item_type", default_item_type);
repeat_ = configuration->property(role + ".repeat", false);
dump_ = configuration->property(role + ".dump", false);
dump_filename_ = configuration->property(role + ".dump_filename", default_dump_filename);
enable_throttle_control_ = configuration->property(role + ".enable_throttle_control", false);
if (item_type_ == "byte")
{
item_size_ = sizeof(char);
}
else
{
LOG(WARNING) << item_type_ << " unrecognized item type. Using byte.";
item_size_ = sizeof(char);
}
try
{
file_source_ = gr::blocks::file_source::make(item_size_, filename_.c_str(), repeat_);
unpack_byte_ = make_unpack_byte_2bit_cpx_samples();
inter_shorts_to_cpx_ = gr::blocks::interleaved_short_to_complex::make(false, true); // I/Q swap enabled
}
catch (const std::exception& e)
{
std::cerr
<< "The receiver was configured to work with a file signal source\n"
<< "but the specified file is unreachable by GNSS-SDR.\n"
<< "Please modify your configuration file\n"
<< "and point SignalSource.filename to a valid raw data file. Then:\n"
<< "$ gnss-sdr --config_file=/path/to/my_GNSS_SDR_configuration.conf\n"
<< "Examples of configuration files available at:\n"
<< GNSSSDR_INSTALL_DIR "/share/gnss-sdr/conf/\n";
LOG(WARNING) << "file_signal_source: Unable to open the samples file "
<< filename_.c_str() << ", exiting the program.";
throw(e);
}
DLOG(INFO) << "file_source(" << file_source_->unique_id() << ")";
if (samples_ == 0) // read all file
{
/*!
* BUG workaround: The GNU Radio file source does not stop the receiver after reaching the End of File.
* A possible solution is to compute the file length in samples using file size, excluding the last 2 milliseconds, and enable always the
* valve block
*/
std::ifstream file(filename_.c_str(), std::ios::in | std::ios::binary | std::ios::ate);
std::ifstream::pos_type size;
if (file.is_open())
{
size = file.tellg();
LOG(INFO) << "Total samples in the file= " << floor(static_cast<double>(size) / static_cast<double>(item_size()));
}
else
{
std::cout << "file_signal_source: Unable to open the samples file " << filename_.c_str() << '\n';
LOG(ERROR) << "file_signal_source: Unable to open the samples file " << filename_.c_str();
}
std::streamsize ss = std::cout.precision();
std::cout << std::setprecision(16);
std::cout << "Processing file " << filename_ << ", which contains " << size << " [bytes]\n";
std::cout.precision(ss);
if (size > 0)
{
int sample_packet_factor = 2; // 1 byte -> 2 samples
samples_ = floor(static_cast<double>(size) / static_cast<double>(item_size())) * sample_packet_factor;
samples_ = samples_ - ceil(0.002 * static_cast<double>(sampling_frequency_)); // process all the samples available in the file excluding the last 2 ms
}
}
CHECK(samples_ > 0) << "File does not contain enough samples to process.";
const double signal_duration_s = static_cast<double>(samples_) * (1 / static_cast<double>(sampling_frequency_));
LOG(INFO) << "Total number samples to be processed= " << samples_ << " GNSS signal duration= " << signal_duration_s << " [s]";
std::cout << "GNSS signal recorded time to be processed: " << signal_duration_s << " [s]\n";
valve_ = gnss_sdr_make_valve(sizeof(gr_complex), samples_, queue);
DLOG(INFO) << "valve(" << valve_->unique_id() << ")";
if (dump_)
{
// sink_ = gr_make_file_sink(item_size_, dump_filename_.c_str());
sink_ = gr::blocks::file_sink::make(sizeof(gr_complex), dump_filename_.c_str());
DLOG(INFO) << "file_sink(" << sink_->unique_id() << ")";
}
if (enable_throttle_control_)
{
throttle_ = gr::blocks::throttle::make(sizeof(gr_complex), sampling_frequency_);
}
DLOG(INFO) << "File source filename " << filename_;
DLOG(INFO) << "Samples " << samples_;
DLOG(INFO) << "Sampling frequency " << sampling_frequency_;
DLOG(INFO) << "Item type " << item_type_;
DLOG(INFO) << "Item size " << item_size_;
DLOG(INFO) << "Repeat " << repeat_;
DLOG(INFO) << "Dump " << dump_;
DLOG(INFO) << "Dump filename " << dump_filename_;
if (in_streams_ > 0)
if (in_streams > 0)
{
LOG(ERROR) << "A signal source does not have an input stream";
}
if (out_streams_ > 1)
if (out_streams > 1)
{
LOG(ERROR) << "This implementation only supports one output stream";
}
}
void TwoBitCpxFileSignalSource::connect(gr::top_block_sptr top_block)
std::tuple<size_t, bool> TwoBitCpxFileSignalSource::itemTypeToSize()
{
if (samples_ > 0)
auto is_complex = false;
auto item_size = size_t(sizeof(char)); // default
if (item_type() == "byte")
{
if (enable_throttle_control_ == true)
{
top_block->connect(file_source_, 0, unpack_byte_, 0);
top_block->connect(unpack_byte_, 0, inter_shorts_to_cpx_, 0);
top_block->connect(inter_shorts_to_cpx_, 0, throttle_, 0);
DLOG(INFO) << "connected file source to throttle";
top_block->connect(throttle_, 0, valve_, 0);
DLOG(INFO) << "connected throttle to valve";
if (dump_)
{
top_block->connect(valve_, 0, sink_, 0);
DLOG(INFO) << "connected valve to file sink";
}
}
else
{
top_block->connect(file_source_, 0, unpack_byte_, 0);
top_block->connect(unpack_byte_, 0, inter_shorts_to_cpx_, 0);
top_block->connect(inter_shorts_to_cpx_, 0, valve_, 0);
DLOG(INFO) << "connected file source to valve";
if (dump_)
{
top_block->connect(valve_, 0, sink_, 0);
DLOG(INFO) << "connected valve to file sink";
}
}
item_size = sizeof(char);
}
else
{
if (enable_throttle_control_ == true)
{
top_block->connect(file_source_, 0, unpack_byte_, 0);
top_block->connect(unpack_byte_, 0, inter_shorts_to_cpx_, 0);
top_block->connect(inter_shorts_to_cpx_, 0, throttle_, 0);
DLOG(INFO) << "connected file source to throttle";
if (dump_)
{
top_block->connect(throttle_, 0, sink_, 0);
DLOG(INFO) << "connected file source to sink";
}
}
else
{
if (dump_)
{
top_block->connect(file_source_, 0, unpack_byte_, 0);
top_block->connect(unpack_byte_, 0, inter_shorts_to_cpx_, 0);
top_block->connect(inter_shorts_to_cpx_, 0, sink_, 0);
DLOG(INFO) << "connected file source to sink";
}
}
LOG(WARNING) << item_type() << " unrecognized item type. Using byte.";
}
return std::make_tuple(item_size, is_complex);
}
// 1 byte -> 2 samples
double TwoBitCpxFileSignalSource::packetsPerSample() const { return 2.0; }
gnss_shared_ptr<gr::block> TwoBitCpxFileSignalSource::source() const { return inter_shorts_to_cpx_; }
void TwoBitCpxFileSignalSource::disconnect(gr::top_block_sptr top_block)
void TwoBitCpxFileSignalSource::create_file_source_hook()
{
if (samples_ > 0)
{
if (enable_throttle_control_ == true)
{
top_block->disconnect(file_source_, 0, unpack_byte_, 0);
DLOG(INFO) << "disconnected file source to unpack_byte_";
top_block->connect(unpack_byte_, 0, throttle_, 0);
DLOG(INFO) << "disconnected unpack_byte_ to throttle_";
top_block->disconnect(throttle_, 0, valve_, 0);
DLOG(INFO) << "disconnected throttle to valve";
if (dump_)
{
top_block->disconnect(valve_, 0, sink_, 0);
DLOG(INFO) << "disconnected valve to file sink";
}
}
else
{
top_block->disconnect(file_source_, 0, unpack_byte_, 0);
DLOG(INFO) << "disconnected file source to unpack_byte_";
top_block->disconnect(unpack_byte_, 0, valve_, 0);
DLOG(INFO) << "disconnected unpack_byte_ to valve";
if (dump_)
{
top_block->disconnect(valve_, 0, sink_, 0);
DLOG(INFO) << "disconnected valve to file sink";
}
}
}
else
{
if (enable_throttle_control_ == true)
{
top_block->disconnect(file_source_, 0, unpack_byte_, 0);
DLOG(INFO) << "disconnected file source to unpack_byte_";
top_block->disconnect(unpack_byte_, 0, throttle_, 0);
DLOG(INFO) << "disconnected unpack_byte_ to throttle";
if (dump_)
{
top_block->disconnect(unpack_byte_, 0, sink_, 0);
DLOG(INFO) << "disconnected funpack_byte_ to sink";
}
}
else
{
if (dump_)
{
top_block->disconnect(file_source_, 0, unpack_byte_, 0);
DLOG(INFO) << "disconnected file source to unpack_byte_";
top_block->disconnect(unpack_byte_, 0, sink_, 0);
DLOG(INFO) << "disconnected unpack_byte_ to sink";
}
}
}
unpack_byte_ = make_unpack_byte_2bit_cpx_samples();
DLOG(INFO) << "unpack_byte_2bit_cpx_samples(" << unpack_byte_->unique_id() << ")";
inter_shorts_to_cpx_ = gr::blocks::interleaved_short_to_complex::make(false, true); // I/Q swap enabled
DLOG(INFO) << "interleaved_short_to_complex(" << inter_shorts_to_cpx_->unique_id() << ")";
}
gr::basic_block_sptr TwoBitCpxFileSignalSource::get_left_block()
void TwoBitCpxFileSignalSource::pre_connect_hook(gr::top_block_sptr top_block)
{
LOG(WARNING) << "Left block of a signal source should not be retrieved";
// return gr_block_sptr();
return gr::blocks::file_source::sptr();
top_block->connect(file_source(), 0, unpack_byte_, 0);
top_block->connect(unpack_byte_, 0, inter_shorts_to_cpx_, 0);
DLOG(INFO) << "connected file_source to unpacker";
}
gr::basic_block_sptr TwoBitCpxFileSignalSource::get_right_block()
void TwoBitCpxFileSignalSource::pre_disconnect_hook(gr::top_block_sptr top_block)
{
if (samples_ > 0)
{
return valve_;
}
if (enable_throttle_control_ == true)
{
return throttle_;
}
return unpack_byte_;
top_block->disconnect(file_source(), 0, unpack_byte_, 0);
top_block->disconnect(unpack_byte_, 0, inter_shorts_to_cpx_, 0);
DLOG(INFO) << "disconnected file_source from unpacker";
}

View File

@ -11,7 +11,7 @@
* GNSS-SDR is a Global Navigation Satellite System software-defined receiver.
* This file is part of GNSS-SDR.
*
* Copyright (C) 2010-2020 (see AUTHORS file for a list of contributors)
* Copyright (C) 2010-2021 (see AUTHORS file for a list of contributors)
* SPDX-License-Identifier: GPL-3.0-or-later
*
* -----------------------------------------------------------------------------
@ -20,17 +20,9 @@
#ifndef GNSS_SDR_TWO_BIT_CPX_FILE_SIGNAL_SOURCE_H
#define GNSS_SDR_TWO_BIT_CPX_FILE_SIGNAL_SOURCE_H
#include "concurrent_queue.h"
#include "gnss_block_interface.h"
#include "file_source_base.h"
#include "unpack_byte_2bit_cpx_samples.h"
#include <gnuradio/blocks/file_sink.h>
#include <gnuradio/blocks/file_source.h>
#include <gnuradio/blocks/interleaved_short_to_complex.h>
#include <gnuradio/blocks/throttle.h>
#include <gnuradio/hier_block2.h>
#include <pmt/pmt.h>
#include <cstdint>
#include <string>
/** \addtogroup Signal_Source
* \{ */
@ -44,7 +36,7 @@ class ConfigurationInterface;
* \brief Class that reads signals samples from a file
* and adapts it to a SignalSourceInterface
*/
class TwoBitCpxFileSignalSource : public GNSSBlockInterface
class TwoBitCpxFileSignalSource : public FileSourceBase
{
public:
TwoBitCpxFileSignalSource(const ConfigurationInterface* configuration,
@ -54,74 +46,18 @@ public:
Concurrent_Queue<pmt::pmt_t>* queue);
~TwoBitCpxFileSignalSource() = default;
inline std::string role() override
{
return role_;
}
/*!
* \brief Returns "Two_Bit_Cpx_File_Signal_Source".
*/
inline std::string implementation() override
{
return "Two_Bit_Cpx_File_Signal_Source";
}
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;
inline std::string filename() const
{
return filename_;
}
inline std::string item_type() const
{
return item_type_;
}
inline bool repeat() const
{
return repeat_;
}
inline int64_t sampling_frequency() const
{
return sampling_frequency_;
}
inline uint64_t samples() const
{
return samples_;
}
protected:
std::tuple<size_t, bool> itemTypeToSize() override;
double packetsPerSample() const override;
gnss_shared_ptr<gr::block> source() const override;
void create_file_source_hook() override;
void pre_connect_hook(gr::top_block_sptr top_block) override;
void pre_disconnect_hook(gr::top_block_sptr top_block) override;
private:
gr::blocks::file_source::sptr file_source_;
gr::blocks::interleaved_short_to_complex::sptr inter_shorts_to_cpx_;
unpack_byte_2bit_cpx_samples_sptr unpack_byte_;
gnss_shared_ptr<gr::block> valve_;
gr::blocks::file_sink::sptr sink_;
gr::blocks::throttle::sptr throttle_;
std::string filename_;
std::string item_type_;
std::string dump_filename_;
std::string role_;
size_t item_size_;
uint64_t samples_;
int64_t sampling_frequency_;
unsigned int in_streams_;
unsigned int out_streams_;
bool repeat_;
bool dump_;
// Throttle control
bool enable_throttle_control_;
gr::blocks::interleaved_short_to_complex::sptr inter_shorts_to_cpx_;
};

View File

@ -10,7 +10,7 @@
* GNSS-SDR is a Global Navigation Satellite System software-defined receiver.
* This file is part of GNSS-SDR.
*
* Copyright (C) 2010-2020 (see AUTHORS file for a list of contributors)
* Copyright (C) 2010-2021 (see AUTHORS file for a list of contributors)
* SPDX-License-Identifier: GPL-3.0-or-later
*
* -----------------------------------------------------------------------------
@ -18,291 +18,122 @@
#include "two_bit_packed_file_signal_source.h"
#include "configuration_interface.h"
#include "gnss_sdr_flags.h"
#include "gnss_sdr_valve.h"
#include "gnss_sdr_string_literals.h"
#include <glog/logging.h>
#include <gnuradio/blocks/char_to_float.h>
#include <exception>
#include <fstream>
#include <iomanip>
#include <iostream>
#include <utility>
using namespace std::string_literals;
TwoBitPackedFileSignalSource::TwoBitPackedFileSignalSource(
const ConfigurationInterface* configuration,
const std::string& role,
unsigned int in_streams,
unsigned int out_streams,
Concurrent_Queue<pmt::pmt_t>* queue) : role_(role),
in_streams_(in_streams),
out_streams_(out_streams)
Concurrent_Queue<pmt::pmt_t>* queue)
: FileSourceBase(configuration, role, "Two_Bit_Packed_File_Signal_Source"s, queue, "byte"s), sample_type_(configuration->property(role + ".sample_type", "real"s)), // options: "real", "iq", "qi"
big_endian_items_(configuration->property(role + ".big_endian_items", true)),
big_endian_bytes_(configuration->property(role + ".big_endian_bytes", false)),
reverse_interleaving_(false)
{
const std::string default_filename("../data/my_capture.dat");
const std::string default_item_type("byte");
const std::string default_dump_filename("../data/my_capture_dump.dat");
const std::string default_sample_type("real");
const double default_seconds_to_skip = 0.0;
samples_ = configuration->property(role + ".samples", static_cast<uint64_t>(0));
sampling_frequency_ = configuration->property(role + ".sampling_frequency", static_cast<int64_t>(0));
filename_ = configuration->property(role + ".filename", default_filename);
// override value with commandline flag, if present
if (FLAGS_signal_source != "-")
{
filename_ = FLAGS_signal_source;
}
if (FLAGS_s != "-")
{
filename_ = FLAGS_s;
}
item_type_ = configuration->property(role + ".item_type", default_item_type);
big_endian_items_ = configuration->property(role + ".big_endian_items", true);
big_endian_bytes_ = configuration->property(role + ".big_endian_bytes", false);
sample_type_ = configuration->property(role + ".sample_type", default_sample_type); // options: "real", "iq", "qi"
repeat_ = configuration->property(role + ".repeat", false);
dump_ = configuration->property(role + ".dump", false);
dump_filename_ = configuration->property(role + ".dump_filename", default_dump_filename);
enable_throttle_control_ = configuration->property(role + ".enable_throttle_control", false);
const double seconds_to_skip = configuration->property(role + ".seconds_to_skip", default_seconds_to_skip);
int64_t bytes_to_skip = 0;
if (item_type_ == "byte")
{
item_size_ = sizeof(char);
}
else if (item_type_ == "short")
{
// If we have shorts stored in little endian format, might as
// well read them in as bytes.
if (big_endian_items_)
{
item_size_ = sizeof(int16_t);
}
else
{
item_size_ = sizeof(char);
}
}
else
{
LOG(WARNING) << item_type_ << " unrecognized item type. Using byte.";
item_size_ = sizeof(char);
}
reverse_interleaving_ = false;
is_complex_ = true;
if (sample_type_ == "real")
{
is_complex_ = false;
}
else if (sample_type_ == "iq")
{
is_complex_ = true;
}
else if (sample_type_ == "qi")
{
is_complex_ = true;
reverse_interleaving_ = true;
}
else
{
LOG(WARNING) << sample_type_ << " unrecognized sample type. Assuming: "
<< (is_complex_ ? (reverse_interleaving_ ? "qi" : "iq") : "real");
}
try
{
file_source_ = gr::blocks::file_source::make(item_size_, filename_.c_str(), repeat_);
if (seconds_to_skip > 0)
{
bytes_to_skip = static_cast<int64_t>(
seconds_to_skip * sampling_frequency_ / 4);
if (is_complex_)
{
bytes_to_skip <<= 1;
}
file_source_->seek(bytes_to_skip, SEEK_SET);
}
unpack_samples_ = make_unpack_2bit_samples(big_endian_bytes_,
item_size_, big_endian_items_, reverse_interleaving_);
if (is_complex_)
{
char_to_float_ =
gr::blocks::interleaved_char_to_complex::make(false);
}
else
{
char_to_float_ =
gr::blocks::char_to_float::make();
}
}
catch (const std::exception& e)
{
std::cerr
<< "The receiver was configured to work with a file signal source\n"
<< "but the specified file is unreachable by GNSS-SDR.\n"
<< "Please modify your configuration file\n"
<< "and point SignalSource.filename to a valid raw data file. Then:\n"
<< "$ gnss-sdr --config_file=/path/to/my_GNSS_SDR_configuration.conf\n"
<< "Examples of configuration files available at:\n"
<< GNSSSDR_INSTALL_DIR "/share/gnss-sdr/conf/\n";
LOG(WARNING) << "file_signal_source: Unable to open the samples file "
<< filename_.c_str() << ", exiting the program.";
throw(e);
}
DLOG(INFO) << "file_source(" << file_source_->unique_id() << ")";
const size_t output_item_size = (is_complex_ ? sizeof(gr_complex) : sizeof(float));
if (samples_ == 0) // read all file
{
/*!
* BUG workaround: The GNU Radio file source does not stop the receiver after reaching the End of File.
* A possible solution is to compute the file length in samples using file size, excluding the last 2 milliseconds, and enable always the
* valve block
*/
std::ifstream file(filename_.c_str(), std::ios::in | std::ios::binary | std::ios::ate);
std::ifstream::pos_type size;
if (file.is_open())
{
size = file.tellg();
samples_ = floor(static_cast<double>(size) * (is_complex_ ? 2.0 : 4.0));
LOG(INFO) << "Total samples in the file= " << samples_; // 4 samples per byte
samples_ -= bytes_to_skip;
// Also skip the last two milliseconds:
samples_ -= ceil(0.002 * sampling_frequency_ / (is_complex_ ? 2.0 : 4.0));
}
else
{
std::cout << "file_signal_source: Unable to open the samples file " << filename_.c_str() << '\n';
LOG(ERROR) << "file_signal_source: Unable to open the samples file " << filename_.c_str();
}
std::streamsize ss = std::cout.precision();
std::cout << std::setprecision(16);
std::cout << "Processing file " << filename_ << ", which contains " << size << " [bytes]\n";
std::cout.precision(ss);
}
CHECK(samples_ > 0) << "File does not contain enough samples to process.";
double signal_duration_s;
signal_duration_s = static_cast<double>(samples_) * (1 / static_cast<double>(sampling_frequency_));
LOG(INFO) << "Total number samples to be processed= " << samples_ << " GNSS signal duration= " << signal_duration_s << " [s]";
std::cout << "GNSS signal recorded time to be processed: " << signal_duration_s << " [s]\n";
valve_ = gnss_sdr_make_valve(output_item_size, samples_, queue);
DLOG(INFO) << "valve(" << valve_->unique_id() << ")";
if (dump_)
{
// sink_ = gr_make_file_sink(item_size_, dump_filename_.c_str());
sink_ = gr::blocks::file_sink::make(output_item_size, dump_filename_.c_str());
DLOG(INFO) << "file_sink(" << sink_->unique_id() << ")";
}
if (enable_throttle_control_)
{
throttle_ = gr::blocks::throttle::make(output_item_size, sampling_frequency_);
}
DLOG(INFO) << "File source filename " << filename_;
DLOG(INFO) << "Samples " << samples_;
DLOG(INFO) << "Sampling frequency " << sampling_frequency_;
DLOG(INFO) << "Item type " << item_type_;
DLOG(INFO) << "Item size " << item_size_;
DLOG(INFO) << "Repeat " << repeat_;
DLOG(INFO) << "Dump " << dump_;
DLOG(INFO) << "Dump filename " << dump_filename_;
if (in_streams_ > 0)
if (in_streams > 0)
{
LOG(ERROR) << "A signal source does not have an input stream";
}
if (out_streams_ > 1)
if (out_streams > 1)
{
LOG(ERROR) << "This implementation only supports one output stream";
}
}
void TwoBitPackedFileSignalSource::connect(gr::top_block_sptr top_block)
std::tuple<size_t, bool> TwoBitPackedFileSignalSource::itemTypeToSize()
{
gr::basic_block_sptr left_block = file_source_;
gr::basic_block_sptr right_block = unpack_samples_;
auto is_complex_t = false;
auto item_size = size_t(sizeof(char)); // default
top_block->connect(file_source_, 0, unpack_samples_, 0);
left_block = right_block;
if (item_type() == "byte")
{
item_size = sizeof(char);
}
else if (item_type() == "short")
{
// If we have shorts stored in little endian format, might as
// well read them in as bytes.
// TODO: this seems to make assumptions about the endianness of this machine
if (big_endian_items_)
{
item_size = sizeof(int16_t);
}
else
{
// how can this be right? the number of samples is computed based on this value
item_size = sizeof(char);
}
}
else
{
LOG(WARNING) << item_type() << " unrecognized item type. Using byte.";
}
// the complex-ness of the input is inferred from the output type
if (sample_type_ == "real")
{
is_complex_t = false;
}
else if (sample_type_ == "iq")
{
is_complex_t = true;
}
else if (sample_type_ == "qi")
{
is_complex_t = true;
reverse_interleaving_ = true;
}
else
{
LOG(WARNING) << sample_type_ << " unrecognized sample type. Assuming: "
<< (is_complex_t ? (reverse_interleaving_ ? "qi" : "iq") : "real");
}
return std::make_tuple(item_size, is_complex_t);
}
// Each sample is 2 bits; if the item_type() is char, then the size is 8/2 = 4 packets per sample
// If the item_type() is short, then the size is 16/2 = 8 packets per sample
double TwoBitPackedFileSignalSource::packetsPerSample() const { return item_size() / 2.0; }
gnss_shared_ptr<gr::block> TwoBitPackedFileSignalSource::source() const { return char_to_float_; }
void TwoBitPackedFileSignalSource::create_file_source_hook()
{
unpack_samples_ = make_unpack_2bit_samples(big_endian_bytes_, item_size(),
big_endian_items_, reverse_interleaving_);
DLOG(INFO) << "unpack_byte_2bit_samples(" << unpack_samples_->unique_id() << ")";
if (is_complex())
{
char_to_float_ = gr::blocks::interleaved_char_to_complex::make(false);
DLOG(INFO) << "interleaved_char_to_complex(" << char_to_float_->unique_id() << ")";
}
else
{
char_to_float_ = gr::blocks::char_to_float::make();
DLOG(INFO) << "char_to_float(" << char_to_float_->unique_id() << ")";
}
}
void TwoBitPackedFileSignalSource::pre_connect_hook(gr::top_block_sptr top_block)
{
top_block->connect(file_source(), 0, unpack_samples_, 0);
DLOG(INFO) << "connected file source to unpack samples";
right_block = char_to_float_;
top_block->connect(left_block, 0, right_block, 0);
left_block = right_block;
top_block->connect(unpack_samples_, 0, char_to_float_, 0);
DLOG(INFO) << "connected unpack samples to char to float";
if (enable_throttle_control_)
{
right_block = throttle_;
top_block->connect(left_block, 0, right_block, 0);
left_block = right_block;
DLOG(INFO) << " connected to throttle";
}
top_block->connect(left_block, 0, valve_, 0);
DLOG(INFO) << "connected to valve";
if (dump_)
{
top_block->connect(valve_, 0, sink_, 0);
DLOG(INFO) << "connected valve to file sink";
}
}
void TwoBitPackedFileSignalSource::disconnect(gr::top_block_sptr top_block)
void TwoBitPackedFileSignalSource::pre_disconnect_hook(gr::top_block_sptr top_block)
{
gr::basic_block_sptr left_block = file_source_;
gr::basic_block_sptr right_block = unpack_samples_;
top_block->disconnect(file_source_, 0, unpack_samples_, 0);
left_block = right_block;
top_block->disconnect(file_source(), 0, unpack_samples_, 0);
DLOG(INFO) << "disconnected file source to unpack samples";
right_block = char_to_float_;
top_block->disconnect(left_block, 0, right_block, 0);
left_block = right_block;
top_block->disconnect(unpack_samples_, 0, char_to_float_, 0);
DLOG(INFO) << "disconnected unpack samples to char to float";
if (enable_throttle_control_)
{
right_block = throttle_;
top_block->disconnect(left_block, 0, right_block, 0);
left_block = right_block;
DLOG(INFO) << " disconnected to throttle";
}
top_block->disconnect(left_block, 0, valve_, 0);
DLOG(INFO) << "disconnected to valve";
if (dump_)
{
top_block->disconnect(valve_, 0, sink_, 0);
DLOG(INFO) << "disconnected valve to file sink";
}
}
gr::basic_block_sptr TwoBitPackedFileSignalSource::get_left_block()
{
LOG(WARNING) << "Left block of a signal source should not be retrieved";
// return gr_block_sptr();
return gr::blocks::file_source::sptr();
}
gr::basic_block_sptr TwoBitPackedFileSignalSource::get_right_block()
{
return valve_;
}

View File

@ -21,17 +21,9 @@
#ifndef GNSS_SDR_TWO_BIT_PACKED_FILE_SIGNAL_SOURCE_H
#define GNSS_SDR_TWO_BIT_PACKED_FILE_SIGNAL_SOURCE_H
#include "concurrent_queue.h"
#include "gnss_block_interface.h"
#include "file_source_base.h"
#include "unpack_2bit_samples.h"
#include <gnuradio/blocks/file_sink.h>
#include <gnuradio/blocks/file_source.h>
#include <gnuradio/blocks/interleaved_char_to_complex.h>
#include <gnuradio/blocks/throttle.h>
#include <gnuradio/hier_block2.h>
#include <pmt/pmt.h>
#include <cstdint>
#include <string>
/** \addtogroup Signal_Source
@ -46,7 +38,7 @@ class ConfigurationInterface;
* \brief Class that reads signals samples from a file
* and adapts it to a SignalSourceInterface
*/
class TwoBitPackedFileSignalSource : public GNSSBlockInterface
class TwoBitPackedFileSignalSource : public FileSourceBase
{
public:
TwoBitPackedFileSignalSource(const ConfigurationInterface* configuration, const std::string& role,
@ -54,54 +46,8 @@ public:
Concurrent_Queue<pmt::pmt_t>* queue);
~TwoBitPackedFileSignalSource() = default;
inline std::string role() override
{
return role_;
}
/*!
* \brief Returns "Two_Bit_Packed_File_Signal_Source".
*/
inline std::string implementation() override
{
return "Two_Bit_Packed_File_Signal_Source";
}
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;
inline std::string filename() const
{
return filename_;
}
inline std::string item_type() const
{
return item_type_;
}
inline bool repeat() const
{
return repeat_;
}
inline int64_t sampling_frequency() const
{
return sampling_frequency_;
}
inline uint64_t samples() const
{
return samples_;
}
private:
inline bool big_endian_items() const
{
return big_endian_items_;
@ -112,41 +58,27 @@ public:
return big_endian_bytes_;
}
inline bool is_complex() const
{
return is_complex_;
}
inline bool reverse_interleaving() const
{
return reverse_interleaving_;
}
protected:
std::tuple<size_t, bool> itemTypeToSize() override;
double packetsPerSample() const override;
gnss_shared_ptr<gr::block> source() const override;
void create_file_source_hook() override;
void pre_connect_hook(gr::top_block_sptr top_block) override;
void pre_disconnect_hook(gr::top_block_sptr top_block) override;
private:
gr::blocks::file_source::sptr file_source_;
unpack_2bit_samples_sptr unpack_samples_;
gr::basic_block_sptr char_to_float_;
gnss_shared_ptr<gr::block> valve_;
gr::blocks::file_sink::sptr sink_;
gr::blocks::throttle::sptr throttle_;
std::string filename_;
std::string item_type_;
std::string dump_filename_;
std::string role_;
std::string sample_type_;
uint64_t samples_;
int64_t sampling_frequency_;
size_t item_size_;
unsigned int in_streams_;
unsigned int out_streams_;
bool big_endian_items_;
bool big_endian_bytes_;
bool is_complex_;
bool reverse_interleaving_;
bool repeat_;
bool dump_;
// Throttle control
bool enable_throttle_control_;
unpack_2bit_samples_sptr unpack_samples_;
gnss_shared_ptr<gr::block> char_to_float_;
};

View File

@ -17,6 +17,7 @@
#include "uhd_signal_source.h"
#include "GPS_L1_CA.h"
#include "configuration_interface.h"
#include "gnss_sdr_string_literals.h"
#include "gnss_sdr_valve.h"
#include <glog/logging.h>
#include <uhd/exception.hpp>
@ -25,10 +26,13 @@
#include <iostream>
#include <utility>
using namespace std::string_literals;
UhdSignalSource::UhdSignalSource(const ConfigurationInterface* configuration,
const std::string& role, unsigned int in_stream, unsigned int out_stream,
Concurrent_Queue<pmt::pmt_t>* queue) : role_(role), in_stream_(in_stream), out_stream_(out_stream)
Concurrent_Queue<pmt::pmt_t>* queue)
: SignalSourceBase(configuration, role, "UHD_Signal_Source"s), in_stream_(in_stream), out_stream_(out_stream)
{
// DUMP PARAMETERS
const std::string empty;

View File

@ -18,7 +18,7 @@
#define GNSS_SDR_UHD_SIGNAL_SOURCE_H
#include "concurrent_queue.h"
#include "gnss_block_interface.h"
#include "signal_source_base.h"
#include <gnuradio/blocks/file_sink.h>
#include <gnuradio/hier_block2.h>
#include <gnuradio/uhd/usrp_source.h>
@ -38,7 +38,7 @@ class ConfigurationInterface;
/*!
* \brief This class reads samples from a UHD device (see http://code.ettus.com/redmine/ettus/projects/uhd/wiki)
*/
class UhdSignalSource : public GNSSBlockInterface
class UhdSignalSource : public SignalSourceBase
{
public:
UhdSignalSource(const ConfigurationInterface* configuration,
@ -47,19 +47,6 @@ public:
~UhdSignalSource() = default;
inline std::string role() override
{
return role_;
}
/*!
* \brief Returns "UHD_Signal_Source"
*/
inline std::string implementation() override
{
return "UHD_Signal_Source";
}
inline size_t item_size() override
{
return item_size_;
@ -89,7 +76,6 @@ private:
std::string item_type_;
std::string subdevice_;
std::string clock_source_;
std::string role_;
double sample_rate_;
size_t item_size_;

View File

@ -17,6 +17,8 @@ if(ENABLE_FPGA OR ENABLE_AD9361)
set(OPT_SIGNAL_SOURCE_LIB_HEADERS ${OPT_SIGNAL_SOURCE_LIB_HEADERS} fpga_switch.h)
set(OPT_SIGNAL_SOURCE_LIB_SOURCES ${OPT_SIGNAL_SOURCE_LIB_SOURCES} fpga_dynamic_bit_selection.cc)
set(OPT_SIGNAL_SOURCE_LIB_HEADERS ${OPT_SIGNAL_SOURCE_LIB_HEADERS} fpga_dynamic_bit_selection.h)
set(OPT_SIGNAL_SOURCE_LIB_SOURCES ${OPT_SIGNAL_SOURCE_LIB_SOURCES} fpga_buffer_monitor.cc)
set(OPT_SIGNAL_SOURCE_LIB_HEADERS ${OPT_SIGNAL_SOURCE_LIB_HEADERS} fpga_buffer_monitor.h)
endif()
set(SIGNAL_SOURCE_LIB_SOURCES
@ -90,6 +92,13 @@ if(ENABLE_FMCOMMS2 OR ENABLE_AD9361)
endif()
endif()
if(ENABLE_FPGA OR ENABLE_AD9361)
target_link_libraries(signal_source_libs
PUBLIC
algorithms_libs
)
endif()
if(ENABLE_CLANG_TIDY)
if(CLANG_TIDY_EXE)
set_target_properties(signal_source_libs

View File

@ -0,0 +1,259 @@
/*!
* \file fpga_buffer_monitor.cc
* \brief Check receiver buffer overflow and monitor the status of the receiver
* buffers.
* \authors
* <ul>
* <li> Marc Majoral, 2021. mmajoral(at)cttc.es
* </ul>
*
* Class that checks the receiver buffer overflow flags and monitors the status
* of the receiver buffers.
*
*
* -----------------------------------------------------------------------------
*
* GNSS-SDR is a Global Navigation Satellite System software-defined receiver.
* This file is part of GNSS-SDR.
*
* Copyright (C) 2010-2021 (see AUTHORS file for a list of contributors)
* SPDX-License-Identifier: GPL-3.0-or-later
*
* -----------------------------------------------------------------------------
*/
#include "fpga_buffer_monitor.h"
#include "command_event.h"
#include "gnss_sdr_create_directory.h"
#include "gnss_sdr_filesystem.h"
#include <glog/logging.h>
#include <ctime> // for time, localtime
#include <fcntl.h> // for open, O_RDWR, O_SYNC
#include <fstream> // for string, ofstream
#include <iostream> // for cout
#include <sys/mman.h> // for mmap
#include <utility> // for move
Fpga_buffer_monitor::Fpga_buffer_monitor(const std::string &device_name, uint32_t num_freq_bands, bool dump, std::string dump_filename)
{
d_num_freq_bands = num_freq_bands;
d_dump = dump;
d_dump_filename = std::move(dump_filename);
// open device descriptor
if ((d_device_descriptor = open(device_name.c_str(), O_RDWR | O_SYNC)) == -1)
{
LOG(WARNING) << "Cannot open deviceio" << device_name;
}
// device memory map
d_map_base = reinterpret_cast<volatile unsigned *>(mmap(nullptr, FPGA_PAGE_SIZE,
PROT_READ | PROT_WRITE, MAP_SHARED, d_device_descriptor, 0));
if (d_map_base == reinterpret_cast<void *>(-1))
{
LOG(WARNING) << "Cannot map the FPGA buffer monitor module";
std::cout << "Could not map the FPGA buffer monitor \n";
}
// sanity check: check test register
if (buffer_monitor_test_register() < 0)
{
LOG(WARNING) << "FPGA buffer monitor test register sanity check failed";
std::cout << "FPGA buffer monitor test register sanity check failed\n";
}
else
{
LOG(INFO) << "FPGA buffer monitor test register sanity check success !";
}
DLOG(INFO) << "FPGA buffer monitor class created";
// initialize maximum buffer occupancy in case buffer monitoring is enabled
d_max_buff_occ_freq_band_0 = 0;
d_max_buff_occ_freq_band_1 = 0;
if (d_dump)
{
std::string dump_path;
// Get path
if (d_dump_filename.find_last_of('/') != std::string::npos)
{
const std::string dump_filename_ = d_dump_filename.substr(d_dump_filename.find_last_of('/') + 1);
dump_path = d_dump_filename.substr(0, d_dump_filename.find_last_of('/'));
d_dump_filename = dump_filename_;
}
else
{
dump_path = std::string(".");
}
if (d_dump_filename.empty())
{
d_dump_filename = "FPGA_buffer_monitor_dump";
}
// remove extension if any
if (d_dump_filename.substr(1).find_last_of('.') != std::string::npos)
{
d_dump_filename = d_dump_filename.substr(0, d_dump_filename.find_last_of('.'));
}
d_dump_filename = dump_path + fs::path::preferred_separator + d_dump_filename;
// create directory
if (!gnss_sdr_create_directory(dump_path))
{
std::cerr << "GNSS-SDR cannot create dump file for the Buffer Monitor block. Wrong permissions?\n";
d_dump = false;
}
std::string dump_filename_ = d_dump_filename;
dump_filename_.append(".dat");
if (!d_dump_file.is_open())
{
try
{
d_dump_file.exceptions(std::ifstream::failbit | std::ifstream::badbit);
d_dump_file.open(dump_filename_.c_str(), std::ios::out | std::ios::binary);
LOG(INFO) << "FPGA buffer monitor dump enabled. Log file: " << dump_filename_.c_str();
}
catch (const std::ifstream::failure &e)
{
LOG(WARNING) << "Exception opening FPGA buffer monitor dump file " << e.what();
}
}
}
}
Fpga_buffer_monitor::~Fpga_buffer_monitor()
{
close_device();
if (d_dump)
{
if (d_dump_file.is_open())
{
try
{
d_dump_file.close();
}
catch (const std::exception &ex)
{
LOG(WARNING) << "Exception in FPGA buffer monitor destructor: " << ex.what();
}
}
}
}
void Fpga_buffer_monitor::check_buffer_overflow_and_monitor_buffer_status()
{
// check buffer overflow flags
uint32_t buffer_overflow_status = d_map_base[overflow_flags_reg_addr];
if ((buffer_overflow_status & overflow_freq_band_0_bit_pos) != 0)
{
if (d_num_freq_bands > 1)
{
LOG(ERROR) << "FPGA Buffer overflow in frequency band 0";
}
else
{
LOG(ERROR) << "FPGA Buffer overflow";
}
}
if (d_num_freq_bands > 1)
{
if ((buffer_overflow_status & overflow_freq_band_1_bit_pos) != 0)
{
LOG(ERROR) << "FPGA Buffer overflow in frequency band 1";
}
}
// buffer monitor
if (d_dump == 1)
{
uint32_t current_buff_occ_freq_band_0 = d_map_base[current_buff_occ_freq_band_0_reg_addr] * num_sapmples_per_buffer_element;
uint32_t temp_max_buff_occ_freq_band_0 = d_map_base[max_buff_occ_freq_band_0_reg_addr] * num_sapmples_per_buffer_element;
if (temp_max_buff_occ_freq_band_0 > d_max_buff_occ_freq_band_0)
{
d_max_buff_occ_freq_band_0 = temp_max_buff_occ_freq_band_0;
}
time_t rawtime;
struct tm *timeinfo;
char buff_time_ch[80];
time(&rawtime);
timeinfo = localtime(&rawtime);
strftime(buff_time_ch, sizeof(buff_time_ch), "%d-%m-%Y %H:%M:%S", timeinfo);
std::string buffer_time(buff_time_ch);
d_dump_file << buffer_time << " ";
std::string buffer_txt;
// current buffer occupancy frequency band 0 (number of samples)
buffer_txt = std::to_string(current_buff_occ_freq_band_0);
d_dump_file << buffer_txt << " ";
// temporary maximum buffer occupancy frequency band 0 (number of samples)
buffer_txt = std::to_string(temp_max_buff_occ_freq_band_0);
d_dump_file << buffer_txt << " ";
// maximum buffer occupancy frequency band 0 (number of samples)
buffer_txt = std::to_string(d_max_buff_occ_freq_band_0);
d_dump_file << buffer_txt;
if (d_num_freq_bands > 1)
{
d_dump_file << " ";
uint32_t current_buff_occ_freq_band_1 = d_map_base[current_buff_occ_freq_band_1_reg_addr] * num_sapmples_per_buffer_element;
uint32_t temp_max_buff_occ_freq_band_1 = d_map_base[max_buff_occ_freq_band_1_reg_addr] * num_sapmples_per_buffer_element;
if (temp_max_buff_occ_freq_band_1 > d_max_buff_occ_freq_band_1)
{
d_max_buff_occ_freq_band_1 = temp_max_buff_occ_freq_band_1;
}
// current buffer occupancy frequency band 1 (number of samples)
buffer_txt = std::to_string(current_buff_occ_freq_band_1);
d_dump_file << buffer_txt << " ";
// temporary maximum buffer occupancy frequency band 1 (number of samples)
buffer_txt = std::to_string(temp_max_buff_occ_freq_band_1);
d_dump_file << buffer_txt << " ";
// maximum buffer occupancy frequency band 1 (number of samples)
buffer_txt = std::to_string(d_max_buff_occ_freq_band_1);
d_dump_file << buffer_txt << std::endl;
}
else
{
d_dump_file << std::endl;
}
}
}
int32_t Fpga_buffer_monitor::buffer_monitor_test_register()
{
// write value to test register
d_map_base[test_reg_addr] = test_register_writeval;
// read value from test register
uint32_t readval = d_map_base[test_reg_addr];
if (test_register_writeval != readval)
{
return -1;
}
return 0;
}
void Fpga_buffer_monitor::close_device()
{
auto *aux = const_cast<unsigned *>(d_map_base);
if (munmap(static_cast<void *>(aux), FPGA_PAGE_SIZE) == -1)
{
std::cout << "Failed to unmap memory uio\n";
}
close(d_device_descriptor);
}

View File

@ -0,0 +1,101 @@
/*!
* \file fpga_buffer_monitor.h
* \brief Check receiver buffer overflow and monitor the status of the receiver
* buffers.
* \authors
* <ul>
* <li> Marc Majoral, 2021. mmajoral(at)cttc.es
* </ul>
*
* Class that checks the receiver buffer overflow flags and monitors the status
* of the receiver buffers.
*
*
* -----------------------------------------------------------------------------
*
* GNSS-SDR is a Global Navigation Satellite System software-defined receiver.
* This file is part of GNSS-SDR.
*
* Copyright (C) 2010-2021 (see AUTHORS file for a list of contributors)
* SPDX-License-Identifier: GPL-3.0-or-later
*
* -----------------------------------------------------------------------------
*/
#ifndef GNSS_SDR_FPGA_BUFFER_MONITOR_H
#define GNSS_SDR_FPGA_BUFFER_MONITOR_H
#include "concurrent_queue.h"
#include <pmt/pmt.h> // pmt
#include <cstdint> // for int32_t
#include <fstream> // for string, ofstream
/** \addtogroup Signal_Source
* \{ */
/** \addtogroup Signal_Source_libs
* \{ */
/*!
* \brief Class that checks the receiver buffer overflow flags and monitors the
* status of the receiver buffers.
*/
class Fpga_buffer_monitor
{
public:
/*!
* \brief Constructor
*/
explicit Fpga_buffer_monitor(const std::string& device_name,
uint32_t num_freq_bands,
bool dump,
std::string dump_filename);
/*!
* \brief Destructor
*/
~Fpga_buffer_monitor();
/*!
* \brief This function checks buffer overflow and monitors the FPGA buffer status
*/
void check_buffer_overflow_and_monitor_buffer_status();
private:
static const size_t FPGA_PAGE_SIZE = 0x10000;
static const uint32_t test_register_writeval = 0x55AA;
static const uint32_t num_sapmples_per_buffer_element = 2;
// write addresses
static const uint32_t reset_overflow_flags_and_max_buff_size_reg_addr = 0;
// read-write addresses
static const uint32_t test_reg_addr = 7;
// read addresses
static const uint32_t current_buff_occ_freq_band_0_reg_addr = 0;
static const uint32_t current_buff_occ_freq_band_1_reg_addr = 1;
static const uint32_t max_buff_occ_freq_band_0_reg_addr = 2;
static const uint32_t max_buff_occ_freq_band_1_reg_addr = 3;
static const uint32_t overflow_flags_reg_addr = 4;
// FPGA-related constants
static const uint32_t overflow_freq_band_0_bit_pos = 1;
static const uint32_t overflow_freq_band_1_bit_pos = 2;
int32_t buffer_monitor_test_register();
void close_device();
volatile unsigned* d_map_base; // driver memory map corresponding to the FPGA buffer monitor
int d_device_descriptor; // driver descriptor corresponding to the FPGA buffer monitor
uint32_t d_num_freq_bands;
uint32_t d_max_buff_occ_freq_band_0;
uint32_t d_max_buff_occ_freq_band_1;
bool d_dump;
std::string d_dump_filename;
std::ofstream d_dump_file;
};
/** \} */
/** \} */
#endif // GNSS_SDR_FPGA_BUFFER_MONITOR_H

View File

@ -381,7 +381,7 @@ void galileo_telemetry_decoder_gs::decode_INAV_word(float *page_part_symbols, in
std::cout << TEXT_BLUE << "New Galileo E5b I/NAV message received in channel " << d_channel << ": UTC model parameters from satellite " << d_satellite << TEXT_RESET << '\n';
}
this->message_port_pub(pmt::mp("telemetry"), pmt::make_any(tmp_obj));
d_delta_t = tmp_obj->A_0G_10 + tmp_obj->A_1G_10 * (static_cast<double>(d_TOW_at_current_symbol_ms) / 1000.0 - tmp_obj->t_0G_10 + 604800 * (std::fmod(static_cast<float>(d_inav_nav.get_Galileo_week() - tmp_obj->WN_0G_10), 64.0)));
d_delta_t = tmp_obj->A_0G + tmp_obj->A_1G * (static_cast<double>(d_TOW_at_current_symbol_ms) / 1000.0 - tmp_obj->t_0G + 604800 * (std::fmod(static_cast<float>(d_inav_nav.get_Galileo_week() - tmp_obj->WN_0G), 64.0)));
DLOG(INFO) << "delta_t=" << d_delta_t << "[s]";
}
if (d_inav_nav.have_new_almanac() == true)

View File

@ -411,7 +411,7 @@ int glonass_l1_ca_telemetry_decoder_gs::general_work(int noutput_items __attribu
// if(d_nav.flag_GGTO_1 == true and d_nav.flag_GGTO_2 == true and d_nav.flag_GGTO_3 == true and d_nav.flag_GGTO_4 == true) // all GGTO parameters arrived
// {
// delta_t = d_nav.A_0G_10 + d_nav.A_1G_10 * (d_TOW_at_current_symbol - d_nav.t_0G_10 + 604800.0 * (fmod((d_nav.WN_0 - d_nav.WN_0G_10), 64)));
// delta_t = d_nav.A_0G + d_nav.A_1G * (d_TOW_at_current_symbol - d_nav.t_0G + 604800.0 * (fmod((d_nav.WN_0 - d_nav.WN_0G), 64)));
// }
if (d_flag_frame_sync == true and d_nav.is_flag_TOW_set() == true)

View File

@ -410,7 +410,7 @@ int glonass_l2_ca_telemetry_decoder_gs::general_work(int noutput_items __attribu
// if(d_nav.flag_GGTO_1 == true and d_nav.flag_GGTO_2 == true and d_nav.flag_GGTO_3 == true and d_nav.flag_GGTO_4 == true) // all GGTO parameters arrived
// {
// delta_t = d_nav.A_0G_10 + d_nav.A_1G_10 * (d_TOW_at_current_symbol - d_nav.t_0G_10 + 604800.0 * (fmod((d_nav.WN_0 - d_nav.WN_0G_10), 64)));
// delta_t = d_nav.A_0G + d_nav.A_1G * (d_TOW_at_current_symbol - d_nav.t_0G + 604800.0 * (fmod((d_nav.WN_0 - d_nav.WN_0G), 64)));
// }
if (d_flag_frame_sync == true and d_nav.is_flag_TOW_set() == true)

View File

@ -62,13 +62,35 @@ GalileoE1DllPllVemlTrackingFpga::GalileoE1DllPllVemlTrackingFpga(
std::memcpy(trk_params_fpga.signal, sig_.data(), 3);
// UIO device file
device_name = configuration->property(role + ".devicename", default_device_name);
device_name = configuration->property(role + ".devicename", default_device_name_Galileo_E1);
// compute the number of tracking channels that have already been instantiated. The order in which
// GNSS-SDR instantiates the tracking channels i L1, L2, L5, E1, E5a
num_prev_assigned_ch = configuration->property("Channels_1C.count", 0) +
configuration->property("Channels_2S.count", 0) +
configuration->property("Channels_L5.count", 0);
uint32_t num_prev_assigned_ch_1C = 0;
std::string device_io_name;
if (configuration->property("Tracking_1C.devicename", default_device_name_GPS_L1) == default_device_name_GPS_L1)
{
for (uint32_t k = 0; k < configuration->property("Channels_1C.count", 0U); k++)
{
if (find_uio_dev_file_name(device_io_name, default_device_name_GPS_L1, k + 1) == 0)
{
num_prev_assigned_ch_1C = num_prev_assigned_ch_1C + 1;
}
}
}
else
{
if (configuration->property("Tracking_1C.devicename", std::string("")) != device_name)
{
num_prev_assigned_ch_1C = configuration->property("Channels_1C.count", 0);
}
}
uint32_t num_prev_assigned_ch_2S = configuration->property("Channels_2S.count", 0);
uint32_t num_prev_assigned_ch_L5 = configuration->property("Channels_L5.count", 0);
num_prev_assigned_ch = num_prev_assigned_ch_1C + num_prev_assigned_ch_2S + num_prev_assigned_ch_L5;
// ################# PRE-COMPUTE ALL THE CODES #################
uint32_t code_samples_per_chip = 2;

View File

@ -123,7 +123,8 @@ public:
void stop_tracking() override;
private:
const std::string default_device_name = "multicorrelator_resampler_5_1_AXI"; // UIO device name
const std::string default_device_name_Galileo_E1 = "multicorrelator_resampler_5_1_AXI"; // UIO device name
const std::string default_device_name_GPS_L1 = "multicorrelator_resampler_S00_AXI"; // UIO device name
// the following flags are FPGA-specific and they are using arrange the values of the local code in the way the FPGA
// expects. This arrangement is done in the initialisation to avoid consuming unnecessary clock cycles during tracking.

View File

@ -59,7 +59,7 @@ GalileoE5aDllPllTrackingFpga::GalileoE5aDllPllTrackingFpga(
d_data_codes = nullptr;
// UIO device file
device_name = configuration->property(role + ".devicename", default_device_name);
device_name = configuration->property(role + ".devicename", default_device_name_Galileo_E5a);
// compute the number of tracking channels that have already been instantiated. The order in which
// GNSS-SDR instantiates the tracking channels i L1, L2, L5, E1, E5a
@ -67,9 +67,15 @@ GalileoE5aDllPllTrackingFpga::GalileoE5aDllPllTrackingFpga(
// Therefore for the proper assignment of the FPGA tracking device file numbers to the E5a tracking channels,
// the number of channels that have already been assigned to L5 must not be substracted to this channel number,
// so they are not counted here.
num_prev_assigned_ch = configuration->property("Channels_1C.count", 0) +
configuration->property("Channels_2S.count", 0) +
configuration->property("Channels_1B.count", 0);
uint32_t num_prev_assigned_ch_1C = configuration->property("Channels_1C.count", 0);
uint32_t num_prev_assigned_ch_2S = 0;
if (configuration->property("Tracking_2S.devicename", std::string("")) != device_name)
{
num_prev_assigned_ch_2S = configuration->property("Channels_2S.count", 0);
}
uint32_t num_prev_assigned_ch_1B = configuration->property("Channels_1B.count", 0);
num_prev_assigned_ch = num_prev_assigned_ch_1C + num_prev_assigned_ch_2S + num_prev_assigned_ch_1B;
// ################# PRE-COMPUTE ALL THE CODES #################
uint32_t code_samples_per_chip = 1;

View File

@ -116,7 +116,7 @@ public:
void stop_tracking() override;
private:
const std::string default_device_name = "multicorrelator_resampler_3_1_AXI"; // UIO device name
const std::string default_device_name_Galileo_E5a = "multicorrelator_resampler_3_1_AXI"; // UIO device name
// the following flags are FPGA-specific and they are using arrange the values of the local code in the way the FPGA
// expects. This arrangement is done in the initialisation to avoid consuming unnecessary clock cycles during tracking.

View File

@ -67,7 +67,7 @@ GpsL1CaDllPllTrackingFpga::GpsL1CaDllPllTrackingFpga(
std::memcpy(trk_params_fpga.signal, sig_.data(), 3);
// UIO device file
device_name = configuration->property(role + ".devicename", default_device_name);
device_name = configuration->property(role + ".devicename", default_device_name_GPS_L1);
// compute the number of tracking channels that have already been instantiated. The order in which
// GNSS-SDR instantiates the tracking channels i L1, l2, L5, E1, E5a
@ -153,11 +153,31 @@ void GpsL1CaDllPllTrackingFpga::set_channel(unsigned int channel)
// UIO device file
std::string device_io_name;
// find the uio device file corresponding to the tracking multicorrelator
if (find_uio_dev_file_name(device_io_name, device_name, channel - num_prev_assigned_ch) < 0)
{
std::cout << "Cannot find the FPGA uio device file corresponding to device name " << device_name << std::endl;
throw std::exception();
bool alt_device_found = false; // alternative compatible HW accelerator device not found by default
// If the HW accelerator is the default one in the L1 band then look for an alternative hardware accelerator
if (device_name == default_device_name_GPS_L1)
{
if (find_uio_dev_file_name(device_io_name, default_device_name_Galileo_E1, channel - num_prev_assigned_ch) < 0)
{
std::cout << "Cannot find the FPGA uio device file corresponding to device names " << device_name << " or " << default_device_name_Galileo_E1 << std::endl;
throw std::exception();
}
else
{
alt_device_found = true; // alternative compatible HW accelerator device has been found
}
}
if (!alt_device_found)
{
std::cout << "Cannot find the FPGA uio device file corresponding to device name " << device_name << std::endl;
throw std::exception();
}
}
tracking_fpga_sc->set_channel(channel, device_io_name);

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