mirror of
https://github.com/gnss-sdr/gnss-sdr
synced 2024-12-14 04:00:34 +00:00
Merge branch 'next' of github.com:gnss-sdr/gnss-sdr into pps_lime
This commit is contained in:
commit
0c49a44946
@ -334,7 +334,7 @@ set(GNSSSDR_GNSS_SIM_LOCAL_VERSION "master")
|
||||
set(GNSSSDR_GPSTK_LOCAL_VERSION "8.0.0")
|
||||
set(GNSSSDR_MATIO_LOCAL_VERSION "1.5.21")
|
||||
set(GNSSSDR_PUGIXML_LOCAL_VERSION "1.11.4")
|
||||
set(GNSSSDR_PROTOCOLBUFFERS_LOCAL_VERSION "3.18.0")
|
||||
set(GNSSSDR_PROTOCOLBUFFERS_LOCAL_VERSION "3.19.0")
|
||||
set(GNSSSDR_BENCHMARK_LOCAL_VERSION "1.5.6")
|
||||
set(GNSSSDR_MATHJAX_EXTERNAL_VERSION "2.7.7")
|
||||
|
||||
@ -565,11 +565,24 @@ endif()
|
||||
|
||||
|
||||
|
||||
################################################################################
|
||||
# VOLK - Vector-Optimized Library of Kernels
|
||||
################################################################################
|
||||
find_package(VOLK)
|
||||
if(NOT VOLK_FOUND)
|
||||
message(FATAL_ERROR "*** VOLK is required to build gnss-sdr")
|
||||
endif()
|
||||
set_package_properties(VOLK PROPERTIES
|
||||
PURPOSE "Provides an abstraction of optimized math routines targeting several SIMD processors."
|
||||
TYPE REQUIRED
|
||||
)
|
||||
|
||||
|
||||
|
||||
################################################################################
|
||||
# GNU Radio - https://www.gnuradio.org
|
||||
################################################################################
|
||||
set(GR_REQUIRED_COMPONENTS RUNTIME PMT BLOCKS FFT FILTER ANALOG)
|
||||
|
||||
find_package(UHD)
|
||||
set_package_properties(UHD PROPERTIES
|
||||
PURPOSE "Used for communication with front-ends of the USRP family."
|
||||
@ -976,20 +989,6 @@ endif()
|
||||
|
||||
|
||||
|
||||
################################################################################
|
||||
# VOLK - Vector-Optimized Library of Kernels
|
||||
################################################################################
|
||||
find_package(VOLK)
|
||||
if(NOT VOLK_FOUND)
|
||||
message(FATAL_ERROR "*** VOLK is required to build gnss-sdr")
|
||||
endif()
|
||||
set_package_properties(VOLK PROPERTIES
|
||||
PURPOSE "Provides an abstraction of optimized math routines targeting several SIMD processors."
|
||||
TYPE REQUIRED
|
||||
)
|
||||
|
||||
|
||||
|
||||
################################################################################
|
||||
# volk_gnsssdr module - GNSS-SDR's own VOLK library
|
||||
################################################################################
|
||||
|
@ -369,6 +369,11 @@ if(GNURADIO_VERSION VERSION_GREATER 3.8.99)
|
||||
INTERFACE_LINK_LIBRARIES "${GNURADIO_LIBRARY}"
|
||||
)
|
||||
endif()
|
||||
|
||||
# check templatized API
|
||||
if(NOT EXISTS "${GNURADIO_IIO_INCLUDE_DIRS}/gnuradio/iio/pluto_source.h")
|
||||
set(GR_IIO_TEMPLATIZED_API TRUE)
|
||||
endif()
|
||||
endif()
|
||||
endif()
|
||||
|
||||
|
@ -150,7 +150,7 @@ Rtklib_Pvt::Rtklib_Pvt(const ConfigurationInterface* configuration,
|
||||
pvt_output_parameters.gpx_rate_ms = bc::lcm(configuration->property(role + ".gpx_rate_ms", pvt_output_parameters.gpx_rate_ms), pvt_output_parameters.output_rate_ms);
|
||||
pvt_output_parameters.geojson_rate_ms = bc::lcm(configuration->property(role + ".geojson_rate_ms", pvt_output_parameters.geojson_rate_ms), pvt_output_parameters.output_rate_ms);
|
||||
pvt_output_parameters.nmea_rate_ms = bc::lcm(configuration->property(role + ".nmea_rate_ms", pvt_output_parameters.nmea_rate_ms), pvt_output_parameters.output_rate_ms);
|
||||
pvt_output_parameters.an_rate_ms = bc::lcm(configuration->property(role + ".an_rate_ms", pvt_output_parameters.an_rate_ms), pvt_output_parameters.output_rate_ms);
|
||||
pvt_output_parameters.an_rate_ms = configuration->property(role + ".an_rate_ms", pvt_output_parameters.an_rate_ms);
|
||||
|
||||
// Infer the type of receiver
|
||||
/*
|
||||
|
@ -135,6 +135,7 @@ rtklib_pvt_gs::rtklib_pvt_gs(uint32_t nchannels,
|
||||
d_galileo_has_data_sptr_type_hash_code(typeid(std::shared_ptr<Galileo_HAS_data>).hash_code()),
|
||||
d_rinex_version(conf_.rinex_version),
|
||||
d_rx_time(0.0),
|
||||
d_local_counter_ms(0ULL),
|
||||
d_rinexobs_rate_ms(conf_.rinexobs_rate_ms),
|
||||
d_kml_rate_ms(conf_.kml_rate_ms),
|
||||
d_gpx_rate_ms(conf_.gpx_rate_ms),
|
||||
@ -1952,6 +1953,7 @@ int rtklib_pvt_gs::work(int noutput_items, gr_vector_const_void_star& input_item
|
||||
bool flag_write_RTCM_1045_output = false;
|
||||
bool flag_write_RTCM_MSM_output = false;
|
||||
bool flag_write_RINEX_obs_output = false;
|
||||
d_local_counter_ms += static_cast<uint64_t>(d_observable_interval_ms);
|
||||
|
||||
d_gnss_observables_map.clear();
|
||||
const auto** in = reinterpret_cast<const Gnss_Synchro**>(&input_items[0]); // Get the input buffer pointer
|
||||
@ -2342,13 +2344,6 @@ int rtklib_pvt_gs::work(int noutput_items, gr_vector_const_void_star& input_item
|
||||
flag_write_RTCM_1045_output,
|
||||
d_enable_rx_clock_correction);
|
||||
}
|
||||
if (d_an_printer_enabled)
|
||||
{
|
||||
if (current_RX_time_ms % d_an_rate_ms == 0)
|
||||
{
|
||||
d_an_printer->print_packet(d_user_pvt_solver.get(), d_gnss_observables_map);
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
@ -2424,6 +2419,13 @@ int rtklib_pvt_gs::work(int noutput_items, gr_vector_const_void_star& input_item
|
||||
}
|
||||
}
|
||||
}
|
||||
if (d_an_printer_enabled)
|
||||
{
|
||||
if (d_local_counter_ms % static_cast<uint64_t>(d_an_rate_ms) == 0)
|
||||
{
|
||||
d_an_printer->print_packet(d_user_pvt_solver.get(), d_gnss_observables_map);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
return noutput_items;
|
||||
|
@ -242,6 +242,7 @@ private:
|
||||
|
||||
double d_rinex_version;
|
||||
double d_rx_time;
|
||||
uint64_t d_local_counter_ms;
|
||||
|
||||
key_t d_sysv_msg_key;
|
||||
int d_sysv_msqid;
|
||||
|
@ -30,8 +30,10 @@
|
||||
#include <unistd.h> // for write(), read(), close()
|
||||
|
||||
|
||||
An_Packet_Printer::An_Packet_Printer(const std::string& an_dump_devname) : d_an_devname(an_dump_devname),
|
||||
d_an_dev_descriptor(init_serial(d_an_devname))
|
||||
An_Packet_Printer::An_Packet_Printer(const std::string& an_dump_devname)
|
||||
: d_start(std::chrono::system_clock::now()),
|
||||
d_an_devname(an_dump_devname),
|
||||
d_an_dev_descriptor(init_serial(d_an_devname))
|
||||
{
|
||||
if (d_an_dev_descriptor != -1)
|
||||
{
|
||||
@ -91,11 +93,12 @@ void An_Packet_Printer::close_serial() const
|
||||
*/
|
||||
void An_Packet_Printer::update_sdr_gnss_packet(sdr_gnss_packet_t* _packet, const Rtklib_Solver* const pvt, const std::map<int, Gnss_Synchro>& gnss_observables_map) const
|
||||
{
|
||||
std::chrono::time_point<std::chrono::system_clock> this_epoch;
|
||||
std::map<int, Gnss_Synchro>::const_iterator gnss_observables_iter;
|
||||
uint8_t num_gps_sats = 0;
|
||||
uint8_t num_gal_sats = 0;
|
||||
uint32_t microseconds = 0;
|
||||
int index = 0;
|
||||
bool fix_3d = pvt->is_valid_position();
|
||||
const int max_reported_sats = *(&_packet->sats + 1) - _packet->sats;
|
||||
|
||||
for (gnss_observables_iter = gnss_observables_map.cbegin();
|
||||
@ -128,7 +131,6 @@ void An_Packet_Printer::update_sdr_gnss_packet(sdr_gnss_packet_t* _packet, const
|
||||
}
|
||||
|
||||
_packet->sats[index].doppler = doppler;
|
||||
microseconds = static_cast<uint32_t>(static_cast<double>(gnss_observables_iter->second.Tracking_sample_counter) / static_cast<double>(gnss_observables_iter->second.fs)) * 1e6;
|
||||
index++;
|
||||
}
|
||||
break;
|
||||
@ -154,7 +156,6 @@ void An_Packet_Printer::update_sdr_gnss_packet(sdr_gnss_packet_t* _packet, const
|
||||
}
|
||||
|
||||
_packet->sats[index].doppler = doppler;
|
||||
microseconds = static_cast<uint32_t>(static_cast<double>(gnss_observables_iter->second.Tracking_sample_counter) / static_cast<double>(gnss_observables_iter->second.fs)) * 1e6;
|
||||
index++;
|
||||
}
|
||||
break;
|
||||
@ -164,10 +165,12 @@ void An_Packet_Printer::update_sdr_gnss_packet(sdr_gnss_packet_t* _packet, const
|
||||
}
|
||||
}
|
||||
|
||||
this_epoch = std::chrono::system_clock::now();
|
||||
std::chrono::duration<double> elapsed_seconds = this_epoch - d_start;
|
||||
_packet->nsvfix = static_cast<uint8_t>(pvt->get_num_valid_observations());
|
||||
_packet->gps_satellites = num_gps_sats;
|
||||
_packet->galileo_satellites = num_gal_sats;
|
||||
_packet->microseconds = microseconds;
|
||||
_packet->microseconds = static_cast<uint32_t>(elapsed_seconds.count() * 1.0e6);
|
||||
_packet->latitude = static_cast<double>(pvt->get_latitude()) * (M_PI / 180.0);
|
||||
_packet->longitude = static_cast<double>(pvt->get_longitude()) * (M_PI / 180.0);
|
||||
_packet->height = static_cast<double>(pvt->get_height());
|
||||
@ -176,8 +179,10 @@ void An_Packet_Printer::update_sdr_gnss_packet(sdr_gnss_packet_t* _packet, const
|
||||
_packet->velocity[2] = static_cast<float>(-pvt->get_rx_vel()[2]);
|
||||
|
||||
uint16_t status = 0;
|
||||
// Set 3D fix (bit 0 and 1) / Set Doppler velocity valid (bit 2) / Set Time valid (bit 3)
|
||||
status = status & 0b00001111;
|
||||
if (fix_3d)
|
||||
{
|
||||
status = 15; // Set 3D fix (bit 0 and 1) / Set Doppler velocity valid (bit 2) / Set Time valid (bit 3)
|
||||
}
|
||||
_packet->status = status;
|
||||
}
|
||||
|
||||
@ -190,8 +195,6 @@ void An_Packet_Printer::update_sdr_gnss_packet(sdr_gnss_packet_t* _packet, const
|
||||
*/
|
||||
void An_Packet_Printer::encode_sdr_gnss_packet(sdr_gnss_packet_t* sdr_gnss_packet, an_packet_t* _packet) const
|
||||
{
|
||||
_packet->id = SDR_GNSS_PACKET_ID;
|
||||
_packet->length = SDR_GNSS_PACKET_LENGTH;
|
||||
uint8_t offset = 0;
|
||||
LSB_bytes_to_array(reinterpret_cast<uint8_t*>(&sdr_gnss_packet->nsvfix), offset, _packet->data, sizeof(sdr_gnss_packet->nsvfix));
|
||||
offset += sizeof(sdr_gnss_packet->nsvfix);
|
||||
@ -236,10 +239,9 @@ void An_Packet_Printer::encode_sdr_gnss_packet(sdr_gnss_packet_t* sdr_gnss_packe
|
||||
void An_Packet_Printer::an_packet_encode(an_packet_t* an_packet) const
|
||||
{
|
||||
uint16_t crc;
|
||||
an_packet->header[1] = an_packet->id;
|
||||
an_packet->header[2] = an_packet->length;
|
||||
crc = calculate_crc16(an_packet->data, an_packet->length);
|
||||
memcpy(&an_packet->header[3], &crc, sizeof(uint16_t));
|
||||
an_packet->header[1] = SDR_GNSS_PACKET_ID;
|
||||
crc = calculate_crc16(an_packet->data, SDR_GNSS_PACKET_LENGTH);
|
||||
memcpy(&an_packet->header[2], &crc, sizeof(uint16_t));
|
||||
an_packet->header[0] = calculate_header_lrc(&an_packet->header[1]);
|
||||
}
|
||||
|
||||
@ -249,7 +251,7 @@ void An_Packet_Printer::an_packet_encode(an_packet_t* an_packet) const
|
||||
*/
|
||||
uint8_t An_Packet_Printer::calculate_header_lrc(const uint8_t* data) const
|
||||
{
|
||||
return ((data[0] + data[1] + data[2] + data[3]) ^ 0xFF) + 1;
|
||||
return ((data[0] + data[1] + data[2]) ^ 0xFF) + 1;
|
||||
}
|
||||
|
||||
|
||||
|
@ -23,6 +23,7 @@
|
||||
|
||||
#include "gnss_synchro.h"
|
||||
#include <array>
|
||||
#include <chrono>
|
||||
#include <cstddef>
|
||||
#include <cstdint>
|
||||
#include <map>
|
||||
@ -60,10 +61,8 @@ struct sdr_gnss_packet_t
|
||||
|
||||
struct an_packet_t
|
||||
{
|
||||
uint8_t id;
|
||||
uint8_t length;
|
||||
uint8_t header[5]; // AN_PACKET_HEADER_SIZE
|
||||
uint8_t data[126]; // AN_MAXIMUM_PACKET_SIZE
|
||||
uint8_t header[4];
|
||||
uint8_t data[73]; // SDR_GNSS_PACKET_LENGTH
|
||||
};
|
||||
|
||||
|
||||
@ -121,6 +120,7 @@ private:
|
||||
void encode_sdr_gnss_packet(sdr_gnss_packet_t* sdr_gnss_packet, an_packet_t* _packet) const;
|
||||
void LSB_bytes_to_array(void* _in, int offset, uint8_t* _out, uint8_t var_size) const;
|
||||
|
||||
std::chrono::time_point<std::chrono::system_clock> d_start;
|
||||
std::string d_an_devname;
|
||||
int d_an_dev_descriptor; // serial device descriptor (i.e. COM port)
|
||||
};
|
||||
|
@ -40,6 +40,7 @@ HybridObservables::HybridObservables(const ConfigurationInterface* configuration
|
||||
conf.nchannels_out = out_streams_;
|
||||
conf.observable_interval_ms = configuration->property("GNSS-SDR.observable_interval_ms", conf.observable_interval_ms);
|
||||
conf.enable_carrier_smoothing = configuration->property(role + ".enable_carrier_smoothing", conf.enable_carrier_smoothing);
|
||||
conf.always_output_gs = configuration->property("PVT.an_output_enabled", conf.always_output_gs) || configuration->property(role + ".always_output_gs", conf.always_output_gs);
|
||||
|
||||
if (FLAGS_carrier_smoothing_factor == DEFAULT_CARRIER_SMOOTHING_FACTOR)
|
||||
{
|
||||
|
@ -61,6 +61,7 @@ hybrid_observables_gs::hybrid_observables_gs(const Obs_Conf &conf_)
|
||||
d_nchannels_in(conf_.nchannels_in),
|
||||
d_nchannels_out(conf_.nchannels_out),
|
||||
d_T_rx_TOW_set(false),
|
||||
d_always_output_gs(conf_.always_output_gs),
|
||||
d_dump(conf_.dump),
|
||||
d_dump_mat(conf_.dump_mat && d_dump)
|
||||
{
|
||||
@ -904,5 +905,14 @@ int hybrid_observables_gs::general_work(int noutput_items __attribute__((unused)
|
||||
return 1;
|
||||
}
|
||||
}
|
||||
if (d_always_output_gs)
|
||||
{
|
||||
Gnss_Synchro empty_gs{};
|
||||
for (uint32_t n = 0; n < d_nchannels_out; n++)
|
||||
{
|
||||
out[n][0] = empty_gs;
|
||||
}
|
||||
return 1;
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
|
@ -127,6 +127,7 @@ private:
|
||||
uint32_t d_nchannels_out;
|
||||
|
||||
bool d_T_rx_TOW_set; // rx time follow GPST
|
||||
bool d_always_output_gs;
|
||||
bool d_dump;
|
||||
bool d_dump_mat;
|
||||
};
|
||||
|
@ -38,6 +38,7 @@ public:
|
||||
uint32_t nchannels_out{0U};
|
||||
uint32_t observable_interval_ms{20U};
|
||||
bool enable_carrier_smoothing{false};
|
||||
bool always_output_gs{false};
|
||||
bool dump{false};
|
||||
bool dump_mat{false};
|
||||
};
|
||||
|
@ -262,6 +262,11 @@ if(ENABLE_PLUTOSDR OR ENABLE_FMCOMMS2)
|
||||
Gnuradio::analog
|
||||
)
|
||||
endif()
|
||||
if(GR_IIO_TEMPLATIZED_API)
|
||||
target_compile_definitions(signal_source_adapters
|
||||
PUBLIC -DGR_IIO_TEMPLATIZED_API=1
|
||||
)
|
||||
endif()
|
||||
endif()
|
||||
|
||||
if(GRLIMESDR_PPS)
|
||||
|
@ -185,7 +185,11 @@ Fmcomms2SignalSource::Fmcomms2SignalSource(const ConfigurationInterface *configu
|
||||
{
|
||||
#if GNURADIO_API_IIO
|
||||
std::vector<bool> enable_channels{rx1_en_, rx2_en_};
|
||||
#if GR_IIO_TEMPLATIZED_API
|
||||
fmcomms2_source_f32c_ = gr::iio::fmcomms2_source<gr_complex>::make(uri_, enable_channels, buffer_size_);
|
||||
#else
|
||||
fmcomms2_source_f32c_ = gr::iio::fmcomms2_source::make(uri_, enable_channels, buffer_size_);
|
||||
#endif
|
||||
fmcomms2_source_f32c_->set_frequency(freq_);
|
||||
fmcomms2_source_f32c_->set_samplerate(sample_rate_);
|
||||
if (rx1_en_)
|
||||
@ -261,7 +265,11 @@ Fmcomms2SignalSource::Fmcomms2SignalSource(const ConfigurationInterface *configu
|
||||
{
|
||||
#if GNURADIO_API_IIO
|
||||
std::vector<bool> enable_channels{rx1_en_, rx2_en_};
|
||||
#if GR_IIO_TEMPLATIZED_API
|
||||
fmcomms2_source_f32c_ = gr::iio::fmcomms2_source<gr_complex>::make(uri_, enable_channels, buffer_size_);
|
||||
#else
|
||||
fmcomms2_source_f32c_ = gr::iio::fmcomms2_source::make(uri_, enable_channels, buffer_size_);
|
||||
#endif
|
||||
fmcomms2_source_f32c_->set_frequency(freq_);
|
||||
fmcomms2_source_f32c_->set_samplerate(sample_rate_);
|
||||
fmcomms2_source_f32c_->set_gain_mode(0, gain_mode_rx1_);
|
||||
|
@ -62,7 +62,11 @@ public:
|
||||
|
||||
private:
|
||||
#if GNURADIO_API_IIO
|
||||
#if GR_IIO_TEMPLATIZED_API
|
||||
gr::iio::fmcomms2_source<gr_complex>::sptr fmcomms2_source_f32c_;
|
||||
#else
|
||||
gr::iio::fmcomms2_source::sptr fmcomms2_source_f32c_;
|
||||
#endif
|
||||
#else
|
||||
gr::iio::fmcomms2_source_f32c::sptr fmcomms2_source_f32c_;
|
||||
#endif
|
||||
|
@ -126,11 +126,17 @@ PlutosdrSignalSource::PlutosdrSignalSource(const ConfigurationInterface* configu
|
||||
std::cout << "item type: " << item_type_ << '\n';
|
||||
|
||||
#if GNURADIO_API_IIO
|
||||
#if GR_IIO_TEMPLATIZED_API
|
||||
plutosdr_source_ = gr::iio::fmcomms2_source<gr_complex>::make(uri_, {true}, buffer_size_);
|
||||
plutosdr_source_->set_gain_mode(0, gain_mode_);
|
||||
plutosdr_source_->set_gain(0, rf_gain_);
|
||||
#else
|
||||
plutosdr_source_ = gr::iio::pluto_source::make(uri_, buffer_size_);
|
||||
plutosdr_source_->set_frequency(freq_);
|
||||
plutosdr_source_->set_samplerate(sample_rate_);
|
||||
plutosdr_source_->set_gain_mode(gain_mode_);
|
||||
plutosdr_source_->set_gain(rf_gain_);
|
||||
#endif
|
||||
plutosdr_source_->set_frequency(freq_);
|
||||
plutosdr_source_->set_samplerate(sample_rate_);
|
||||
plutosdr_source_->set_quadrature(quadrature_);
|
||||
plutosdr_source_->set_rfdc(rf_dc_);
|
||||
plutosdr_source_->set_bbdc(bb_dc_);
|
||||
|
@ -22,7 +22,11 @@
|
||||
#include "signal_source_base.h"
|
||||
#include <gnuradio/blocks/file_sink.h>
|
||||
#if GRIIO_INCLUDE_HAS_GNURADIO
|
||||
#if GR_IIO_TEMPLATIZED_API
|
||||
#include <gnuradio/iio/fmcomms2_source.h>
|
||||
#else
|
||||
#include <gnuradio/iio/pluto_source.h>
|
||||
#endif
|
||||
#else
|
||||
#include <iio/pluto_source.h>
|
||||
#endif
|
||||
@ -62,7 +66,11 @@ public:
|
||||
gr::basic_block_sptr get_right_block() override;
|
||||
|
||||
private:
|
||||
#if GR_IIO_TEMPLATIZED_API
|
||||
gr::iio::fmcomms2_source<gr_complex>::sptr plutosdr_source_;
|
||||
#else
|
||||
gr::iio::pluto_source::sptr plutosdr_source_;
|
||||
#endif
|
||||
|
||||
gnss_shared_ptr<gr::block> valve_;
|
||||
gr::blocks::file_sink::sptr file_sink_;
|
||||
|
Loading…
Reference in New Issue
Block a user