1
0
mirror of https://github.com/gnss-sdr/gnss-sdr synced 2024-07-15 16:14:43 +00:00

Merge branch 'next' of https://github.com/gnss-sdr/gnss-sdr into next

This commit is contained in:
Carles Fernandez 2019-07-04 08:07:04 +02:00
commit 09e9967589
No known key found for this signature in database
GPG Key ID: 4C583C52B0C3877D
20 changed files with 117 additions and 73 deletions

View File

@ -101,6 +101,9 @@ find_package_handle_standard_args(GROSMOSDR DEFAULT_MSG GROSMOSDR_LIBRARIES GROS
if(GROSMOSDR_PKG_VERSION)
set(GROSMOSDR_VERSION ${GROSMOSDR_PKG_VERSION})
set(KK "v1.2.3")
string(REGEX REPLACE "^v" "" KK_AUX KK)
message(STATUS "++++++++++++++++++++${KK_AUX}")
endif()
set_package_properties(GROSMOSDR PROPERTIES

View File

@ -50,6 +50,7 @@ public:
GOOGLE_PROTOBUF_VERIFY_VERSION;
monitor_.New();
}
~Serdes_Monitor_Pvt()
{
// google::protobuf::ShutdownProtobufLibrary();
@ -94,7 +95,6 @@ public:
return data;
}
inline Monitor_Pvt readProtobuffer(const gnss_sdr::MonitorPvt& mon) //!< Deserialization
{
Monitor_Pvt monitor;

View File

@ -81,7 +81,6 @@ Fpga_Acquisition::Fpga_Acquisition(std::string device_name,
int64_t fs_in,
uint32_t sampled_ms __attribute__((unused)),
uint32_t select_queue,
//lv_16sc_t *all_fft_codes,
uint32_t *all_fft_codes,
uint32_t excludelimit)
{
@ -209,6 +208,7 @@ void Fpga_Acquisition::set_block_exp(uint32_t total_block_exp)
d_map_base[11] = total_block_exp;
}
void Fpga_Acquisition::set_doppler_sweep(uint32_t num_sweeps, uint32_t doppler_step, int32_t doppler_min)
{
float phase_step_rad_real;
@ -233,7 +233,6 @@ void Fpga_Acquisition::set_doppler_sweep(uint32_t num_sweeps, uint32_t doppler_s
void Fpga_Acquisition::configure_acquisition()
{
//Fpga_Acquisition::open_device();
d_map_base[0] = d_select_queue;
d_map_base[1] = d_vector_length;
d_map_base[2] = d_nsamples;
@ -318,6 +317,7 @@ void Fpga_Acquisition::read_fpga_total_scale_factor(uint32_t *total_scale_factor
*fw_scale_factor = 0;
}
void Fpga_Acquisition::read_result_valid(uint32_t *result_valid)
{
uint32_t readval = 0;

View File

@ -36,7 +36,6 @@
#ifndef GNSS_SDR_FPGA_ACQUISITION_H_
#define GNSS_SDR_FPGA_ACQUISITION_H_
#include <volk/volk_complex.h> // for lv_16sc_t
#include <cstdint>
#include <string>
@ -46,7 +45,8 @@
class Fpga_Acquisition
{
public:
Fpga_Acquisition(std::string device_name,
Fpga_Acquisition(
std::string device_name,
uint32_t nsamples,
uint32_t doppler_max,
uint32_t nsamples_total,
@ -57,13 +57,24 @@ public:
uint32_t excludelimit);
~Fpga_Acquisition();
bool set_local_code(uint32_t PRN);
void set_doppler_sweep(uint32_t num_sweeps, uint32_t doppler_step, int32_t doppler_min);
void run_acquisition(void);
void read_acquisition_results(uint32_t *max_index, float *firstpeak, float *secondpeak, uint64_t *initial_sample, float *power_sum, uint32_t *doppler_index, uint32_t *total_blk_exp);
void read_acquisition_results(
uint32_t *max_index,
float *firstpeak,
float *secondpeak,
uint64_t *initial_sample,
float *power_sum,
uint32_t *doppler_index,
uint32_t *total_blk_exp);
void block_samples();
void unblock_samples();
/*!
@ -100,9 +111,10 @@ public:
void configure_acquisition(void);
void close_device();
void open_device();
void close_device();
private:
int64_t d_fs_in;
// data related to the hardware module and the driver

View File

@ -87,6 +87,7 @@ bool ChannelFsm::Event_start_acquisition_fpga()
return true;
}
bool ChannelFsm::Event_start_acquisition()
{
std::lock_guard<std::mutex> lk(mx);
@ -170,11 +171,14 @@ void ChannelFsm::set_tracking(std::shared_ptr<TrackingInterface> tracking)
trk_ = std::move(tracking);
}
void ChannelFsm::set_telemetry(std::shared_ptr<TelemetryDecoderInterface> telemetry)
{
std::lock_guard<std::mutex> lk(mx);
nav_ = std::move(telemetry);
}
void ChannelFsm::set_queue(gr::msg_queue::sptr queue)
{
std::lock_guard<std::mutex> lk(mx);
@ -194,6 +198,7 @@ void ChannelFsm::stop_acquisition()
acq_->stop_acquisition();
}
void ChannelFsm::stop_tracking()
{
trk_->stop_tracking();

View File

@ -51,11 +51,11 @@ public:
~channel_msg_receiver_cc(); //!< Default destructor
private:
friend channel_msg_receiver_cc_sptr channel_msg_receiver_make_cc(std::shared_ptr<ChannelFsm> channel_fsm, bool repeat);
channel_msg_receiver_cc(std::shared_ptr<ChannelFsm> channel_fsm, bool repeat);
std::shared_ptr<ChannelFsm> d_channel_fsm;
bool d_repeat; // todo: change FSM to include repeat value
friend channel_msg_receiver_cc_sptr channel_msg_receiver_make_cc(std::shared_ptr<ChannelFsm> channel_fsm, bool repeat);
void msg_handler_events(pmt::pmt_t msg);
channel_msg_receiver_cc(std::shared_ptr<ChannelFsm> channel_fsm, bool repeat);
};
#endif

View File

@ -49,7 +49,7 @@ BeamformerFilter::BeamformerFilter(
if (item_type_ == "gr_complex")
{
item_size_ = sizeof(gr_complex);
beamformer_ = make_beamformer();
beamformer_ = make_beamformer_sptr();
DLOG(INFO) << "Item size " << item_size_;
DLOG(INFO) << "resampler(" << beamformer_->unique_id() << ")";
}

View File

@ -36,7 +36,7 @@
#define GNSS_SDR_BEAMFORMER_CHANNELS 8
beamformer_sptr make_beamformer()
beamformer_sptr make_beamformer_sptr()
{
return beamformer_sptr(new beamformer());
}

View File

@ -36,7 +36,7 @@
class beamformer;
using beamformer_sptr = boost::shared_ptr<beamformer>;
beamformer_sptr make_beamformer();
beamformer_sptr make_beamformer_sptr();
/*!
* \brief This class implements a real-time software-defined spatial filter using the CTTC GNSS experimental antenna array input and a set of dynamically reloadable weights
@ -44,13 +44,13 @@ beamformer_sptr make_beamformer();
class beamformer : public gr::sync_block
{
public:
beamformer();
~beamformer();
int work(int noutput_items, gr_vector_const_void_star &input_items,
gr_vector_void_star &output_items);
private:
friend beamformer_sptr make_beamformer_sptr();
beamformer();
gr_complex *weight_vector;
};

View File

@ -41,8 +41,12 @@ class Notch;
using notch_sptr = boost::shared_ptr<Notch>;
notch_sptr make_notch_filter(float pfa, float p_c_factor,
int32_t length_, int32_t n_segments_est, int32_t n_segments_reset);
notch_sptr make_notch_filter(
float pfa,
float p_c_factor,
int32_t length_,
int32_t n_segments_est,
int32_t n_segments_reset);
/*!
* \brief This class implements a real-time software-defined multi state notch filter
@ -50,8 +54,6 @@ notch_sptr make_notch_filter(float pfa, float p_c_factor,
class Notch : public gr::block
{
public:
Notch(float pfa, float p_c_factor, int32_t length_, int32_t n_segments_est, int32_t n_segments_reset);
~Notch();
void forecast(int noutput_items, gr_vector_int &ninput_items_required);
@ -61,6 +63,8 @@ public:
gr_vector_void_star &output_items);
private:
friend notch_sptr make_notch_filter(float pfa, float p_c_factor, int32_t length_, int32_t n_segments_est, int32_t n_segments_reset);
Notch(float pfa, float p_c_factor, int32_t length_, int32_t n_segments_est, int32_t n_segments_reset);
float pfa;
float noise_pow_est;
float thres_;

View File

@ -41,7 +41,13 @@ class NotchLite;
using notch_lite_sptr = boost::shared_ptr<NotchLite>;
notch_lite_sptr make_notch_filter_lite(float p_c_factor, float pfa, int32_t length_, int32_t n_segments_est, int32_t n_segments_reset, int32_t n_segments_coeff);
notch_lite_sptr make_notch_filter_lite(
float p_c_factor,
float pfa,
int32_t length_,
int32_t n_segments_est,
int32_t n_segments_reset,
int32_t n_segments_coeff);
/*!
* \brief This class implements a real-time software-defined multi state notch filter light version
@ -49,8 +55,6 @@ notch_lite_sptr make_notch_filter_lite(float p_c_factor, float pfa, int32_t leng
class NotchLite : public gr::block
{
public:
NotchLite(float p_c_factor, float pfa, int32_t length_, int32_t n_segments_est, int32_t n_segments_reset, int32_t n_segments_coeff);
~NotchLite();
void forecast(int noutput_items, gr_vector_int &ninput_items_required);
@ -60,6 +64,8 @@ public:
gr_vector_void_star &output_items);
private:
friend notch_lite_sptr make_notch_filter_lite(float p_c_factor, float pfa, int32_t length_, int32_t n_segments_est, int32_t n_segments_reset, int32_t n_segments_coeff);
NotchLite(float p_c_factor, float pfa, int32_t length_, int32_t n_segments_est, int32_t n_segments_reset, int32_t n_segments_coeff);
int32_t length_;
int32_t n_segments;
int32_t n_segments_est;

View File

@ -39,14 +39,15 @@ class pulse_blanking_cc;
using pulse_blanking_cc_sptr = boost::shared_ptr<pulse_blanking_cc>;
pulse_blanking_cc_sptr make_pulse_blanking_cc(float pfa, int32_t length_, int32_t n_segments_est, int32_t n_segments_reset);
pulse_blanking_cc_sptr make_pulse_blanking_cc(
float pfa,
int32_t length_,
int32_t n_segments_est,
int32_t n_segments_reset);
class pulse_blanking_cc : public gr::block
{
public:
pulse_blanking_cc(float pfa, int32_t length_, int32_t n_segments_est, int32_t n_segments_reset);
~pulse_blanking_cc();
void forecast(int noutput_items, gr_vector_int &ninput_items_required);
@ -55,6 +56,8 @@ public:
gr_vector_const_void_star &input_items, gr_vector_void_star &output_items);
private:
friend pulse_blanking_cc_sptr make_pulse_blanking_cc(float pfa, int32_t length_, int32_t n_segments_est, int32_t n_segments_reset);
pulse_blanking_cc(float pfa, int32_t length_, int32_t n_segments_est, int32_t n_segments_reset);
int32_t length_;
int32_t n_segments;
int32_t n_segments_est;

View File

@ -34,7 +34,7 @@
#ifndef GNSS_SDR_HYBRID_OBSERVABLES_GS_H
#define GNSS_SDR_HYBRID_OBSERVABLES_GS_H
#include <boost/circular_buffer.hpp> // for boost::curcular_buffer
#include <boost/circular_buffer.hpp> // for boost::circular_buffer
#include <boost/shared_ptr.hpp> // for boost::shared_ptr
#include <gnuradio/block.h> // for block
#include <gnuradio/types.h> // for gr_vector_int
@ -50,8 +50,12 @@ class Gnss_circular_deque;
using hybrid_observables_gs_sptr = boost::shared_ptr<hybrid_observables_gs>;
hybrid_observables_gs_sptr
hybrid_observables_gs_make(unsigned int nchannels_in, unsigned int nchannels_out, bool dump, bool dump_mat, std::string dump_filename);
hybrid_observables_gs_sptr hybrid_observables_gs_make(
unsigned int nchannels_in,
unsigned int nchannels_out,
bool dump,
bool dump_mat,
std::string dump_filename);
/*!
* \brief This class implements a block that computes observables
@ -60,38 +64,44 @@ class hybrid_observables_gs : public gr::block
{
public:
~hybrid_observables_gs();
void forecast(int noutput_items, gr_vector_int& ninput_items_required);
int general_work(int noutput_items, gr_vector_int& ninput_items,
gr_vector_const_void_star& input_items, gr_vector_void_star& output_items);
void forecast(int noutput_items, gr_vector_int& ninput_items_required);
private:
friend hybrid_observables_gs_sptr
hybrid_observables_gs_make(uint32_t nchannels_in, uint32_t nchannels_out, bool dump, bool dump_mat, std::string dump_filename);
hybrid_observables_gs(uint32_t nchannels_in, uint32_t nchannels_out, bool dump, bool dump_mat, std::string dump_filename);
void msg_handler_pvt_to_observables(const pmt::pmt_t& msg);
bool interpolate_data(Gnss_Synchro& out, const uint32_t& ch, const double& ti);
bool interp_trk_obs(Gnss_Synchro& interpolated_obs, const uint32_t& ch, const uint64_t& rx_clock);
double compute_T_rx_s(const Gnss_Synchro& a);
void compute_pranges(std::vector<Gnss_Synchro>& data);
void update_TOW(const std::vector<Gnss_Synchro>& data);
int32_t save_matfile();
friend hybrid_observables_gs_sptr hybrid_observables_gs_make(
uint32_t nchannels_in,
uint32_t nchannels_out,
bool dump,
bool dump_mat,
std::string dump_filename);
//time history
boost::circular_buffer<uint64_t> d_Rx_clock_buffer;
//Tracking observable history
Gnss_circular_deque<Gnss_Synchro>* d_gnss_synchro_history;
//rx time follow GPST
bool T_rx_TOW_set;
hybrid_observables_gs(
uint32_t nchannels_in,
uint32_t nchannels_out,
bool dump,
bool dump_mat,
std::string dump_filename);
bool T_rx_TOW_set; // rx time follow GPST
bool d_dump;
bool d_dump_mat;
uint32_t T_rx_TOW_ms;
uint32_t T_rx_remnant_to_20ms;
uint32_t T_rx_step_ms;
double T_rx_offset_ms;
bool d_dump;
bool d_dump_mat;
uint32_t d_nchannels_in;
uint32_t d_nchannels_out;
double T_rx_offset_ms;
std::string d_dump_filename;
std::ofstream d_dump_file;
boost::circular_buffer<uint64_t> d_Rx_clock_buffer; // time history
Gnss_circular_deque<Gnss_Synchro>* d_gnss_synchro_history; // Tracking observable history
void msg_handler_pvt_to_observables(const pmt::pmt_t& msg);
double compute_T_rx_s(const Gnss_Synchro& a);
bool interp_trk_obs(Gnss_Synchro& interpolated_obs, const uint32_t& ch, const uint64_t& rx_clock);
void update_TOW(const std::vector<Gnss_Synchro>& data);
void compute_pranges(std::vector<Gnss_Synchro>& data);
int32_t save_matfile();
};
#endif

View File

@ -55,14 +55,14 @@ Gnss_Sdr_Valve::Gnss_Sdr_Valve(size_t sizeof_stream_item,
}
boost::shared_ptr<gr::block> gnss_sdr_make_valve(size_t sizeof_stream_item, uint64_t nitems, gr::msg_queue::sptr queue, bool stop_flowgraph)
boost::shared_ptr<Gnss_Sdr_Valve> gnss_sdr_make_valve(size_t sizeof_stream_item, uint64_t nitems, gr::msg_queue::sptr queue, bool stop_flowgraph)
{
boost::shared_ptr<Gnss_Sdr_Valve> valve_(new Gnss_Sdr_Valve(sizeof_stream_item, nitems, std::move(queue), stop_flowgraph));
return valve_;
}
boost::shared_ptr<gr::block> gnss_sdr_make_valve(size_t sizeof_stream_item, uint64_t nitems, gr::msg_queue::sptr queue)
boost::shared_ptr<Gnss_Sdr_Valve> gnss_sdr_make_valve(size_t sizeof_stream_item, uint64_t nitems, gr::msg_queue::sptr queue)
{
boost::shared_ptr<Gnss_Sdr_Valve> valve_(new Gnss_Sdr_Valve(sizeof_stream_item, nitems, std::move(queue), true));
return valve_;

View File

@ -41,12 +41,14 @@
#include <cstddef> // for size_t
#include <cstdint>
boost::shared_ptr<gr::block> gnss_sdr_make_valve(
class Gnss_Sdr_Valve;
boost::shared_ptr<Gnss_Sdr_Valve> gnss_sdr_make_valve(
size_t sizeof_stream_item,
uint64_t nitems,
gr::msg_queue::sptr queue);
boost::shared_ptr<gr::block> gnss_sdr_make_valve(
boost::shared_ptr<Gnss_Sdr_Valve> gnss_sdr_make_valve(
size_t sizeof_stream_item,
uint64_t nitems,
gr::msg_queue::sptr queue,
@ -66,12 +68,12 @@ public:
gr_vector_void_star &output_items);
private:
friend boost::shared_ptr<gr::block> gnss_sdr_make_valve(
friend boost::shared_ptr<Gnss_Sdr_Valve> gnss_sdr_make_valve(
size_t sizeof_stream_item,
uint64_t nitems,
gr::msg_queue::sptr queue);
friend boost::shared_ptr<gr::block> gnss_sdr_make_valve(
friend boost::shared_ptr<Gnss_Sdr_Valve> gnss_sdr_make_valve(
size_t sizeof_stream_item,
uint64_t nitems,
gr::msg_queue::sptr queue,

View File

@ -174,7 +174,7 @@ int Gnss_Sdr_Supl_Client::get_assistance(int i_mcc, int i_mns, int i_lac, int i_
// PERFORM SUPL COMMUNICATION
std::vector<char> cstr(server_name.length() + 1);
for (int i = 0; i != server_name.length(); ++i)
for (unsigned int i = 0; i != server_name.length(); ++i)
{
cstr[i] = static_cast<char>(server_name[i]);
}

View File

@ -34,7 +34,7 @@
#include "gnss_synchro.h"
#include "gnss_synchro.pb.h" // file created by Protocol Buffers at compile time
#include <cstring> // for memcpy
#include <array>
#include <vector>
@ -52,6 +52,7 @@ public:
GOOGLE_PROTOBUF_VERIFY_VERSION;
observables.New();
}
~Serdes_Gnss_Synchro()
{
google::protobuf::ShutdownProtobufLibrary();
@ -60,21 +61,17 @@ public:
inline std::string createProtobuffer(const std::vector<Gnss_Synchro>& vgs) //!< Serialization into a string
{
observables.Clear();
std::string data;
for (auto gs : vgs)
{
gnss_sdr::GnssSynchro* obs = observables.add_observable();
char c[2];
c[0] = gs.System;
c[1] = '\0';
const std::string sys(c);
char c = gs.System;
const std::string sys(1, c);
char cc[3];
std::array<char, 2> cc;
cc[0] = gs.Signal[0];
cc[1] = gs.Signal[1];
cc[2] = '\0';
const std::string sig(cc);
const std::string sig(cc.cbegin(), cc.cend());
obs->set_system(sys);
obs->set_signal(sig);
@ -109,20 +106,19 @@ public:
return data;
}
inline std::vector<Gnss_Synchro> readProtobuffer(const gnss_sdr::Observables& obs) //!< Deserialization
inline std::vector<Gnss_Synchro> readProtobuffer(const gnss_sdr::Observables& obs) const //!< Deserialization
{
std::vector<Gnss_Synchro> vgs;
vgs.reserve(obs.observable_size());
for (int i = 0; i < obs.observable_size(); ++i)
{
const gnss_sdr::GnssSynchro& gs_read = obs.observable(i);
Gnss_Synchro gs = Gnss_Synchro();
const std::string& sys = gs_read.system();
gs.System = *sys.c_str();
const std::string& sig = gs_read.signal();
std::memcpy(static_cast<void*>(gs.Signal), sig.c_str(), 3);
gs.System = gs_read.system()[0];
gs.Signal[0] = gs_read.signal()[0];
gs.Signal[1] = gs_read.signal()[1];
gs.Signal[2] = '\0';
gs.PRN = gs_read.prn();
gs.Channel_ID = gs_read.channel_id();
@ -153,6 +149,7 @@ public:
}
return vgs;
}
private:
gnss_sdr::Observables observables;
};

View File

@ -95,12 +95,15 @@ TEST(Protobuf, Works)
Gnss_Synchro gs_read = vgs_read[0];
uint32_t prn_read = gs_read.PRN;
uint32_t prn_read2 = vgs_read[1].PRN;
std::string system_read(1, gs_read.System);
std::string signal_read(gs_read.Signal);
// or without the need of gnss_synchro:
int obs_size = obs.observable_size();
uint32_t prn_read3 = obs.observable(0).prn();
EXPECT_EQ(prn_true, prn_read);
EXPECT_EQ(sig, signal_read);
EXPECT_EQ(sys, system_read);
EXPECT_EQ(prn_true2, prn_read2);
EXPECT_EQ(prn_true, prn_read3);
EXPECT_EQ(2, obs_size);

View File

@ -96,7 +96,7 @@ TEST(GpuMulticorrelatorTest, MeasureExecutionTime)
//--- Perform initializations ------------------------------
//local code resampler on GPU
// generate local reference (1 sample per chip)
gps_l1_ca_code_gen_complex(d_ca_code, 1, 0);
gps_l1_ca_code_gen_complex(gsl::span<gr_complex>(d_ca_code, static_cast<int>(GPS_L1_CA_CODE_LENGTH_CHIPS)), 1, 0);
// generate inut signal
for (int n = 0; n < 2 * d_vector_length; n++)
{

View File

@ -796,9 +796,8 @@ TEST_F(TrackingPullInTest, ValidationOfResults)
// create the msg queue for valve
queue = gr::msg_queue::make(0);
boost::shared_ptr<Gnss_Sdr_Valve> reseteable_valve;
long long int acq_to_trk_delay_samples = ceil(static_cast<double>(FLAGS_fs_gen_sps) * FLAGS_acq_to_trk_delay_s);
boost::shared_ptr<Gnss_Sdr_Valve> resetable_valve_(new Gnss_Sdr_Valve(sizeof(gr_complex), acq_to_trk_delay_samples, queue, false));
auto resetable_valve_ = gnss_sdr_make_valve(sizeof(gr_complex), acq_to_trk_delay_samples, queue, false);
std::shared_ptr<ControlMessageFactory> control_message_factory_;
std::shared_ptr<std::vector<std::shared_ptr<ControlMessage>>> control_messages_;