Miscellaneous improvements

Improve modularity of CMake design
Improve building speed in multicore processors
Files command_event.* moved to core/libs
Remove Armadillo from public core_receiver interface
Uniformize name format for classes
Apply some fixes by clang-tidy
Improve documentation
This commit is contained in:
Carles Fernandez 2019-07-21 12:55:59 +02:00
parent 82c4643ffb
commit 37fdfca5ec
No known key found for this signature in database
GPG Key ID: 4C583C52B0C3877D
23 changed files with 176 additions and 125 deletions

View File

@ -157,7 +157,7 @@ public:
/*! /*!
* \brief Generates the Mixed GPS L1,L5 + BDS B1I, B3I Navigation Data header * \brief Generates the Mixed GPS L1,L5 + BDS B1I, B3I Navigation Data header
*/ */
void rinex_nav_header(std::fstream& out, const Gps_Iono& gps_lnav_iono, const Gps_Utc_Model& gps_lnav_utc_model, const Gps_Ephemeris& eph, const Beidou_Dnav_Iono& bds_dnav_iono, const Beidou_Dnav_Utc_Model& bds_dnav_utc_model); void rinex_nav_header(std::fstream& out, const Gps_Iono& gps_iono, const Gps_Utc_Model& gps_utc_model, const Gps_Ephemeris& eph, const Beidou_Dnav_Iono& bds_dnav_iono, const Beidou_Dnav_Utc_Model& bds_dnav_utc_model);
/*! /*!
* \brief Generates the Mixed GPS L2C + BDS B1I, B3I Navigation Data header * \brief Generates the Mixed GPS L2C + BDS B1I, B3I Navigation Data header

View File

@ -31,7 +31,6 @@ target_link_libraries(channel_adapters
Gnuradio::runtime Gnuradio::runtime
channel_libs channel_libs
core_system_parameters core_system_parameters
core_receiver
PRIVATE PRIVATE
Gflags::gflags Gflags::gflags
Glog::glog Glog::glog
@ -41,6 +40,7 @@ target_link_libraries(channel_adapters
target_include_directories(channel_adapters target_include_directories(channel_adapters
PUBLIC PUBLIC
${CMAKE_SOURCE_DIR}/src/core/interfaces ${CMAKE_SOURCE_DIR}/src/core/interfaces
${CMAKE_SOURCE_DIR}/src/core/receiver
) )
if(ENABLE_CLANG_TIDY) if(ENABLE_CLANG_TIDY)

View File

@ -35,16 +35,21 @@ add_library(channel_libs ${CHANNEL_FSM_SOURCES} ${CHANNEL_FSM_HEADERS})
target_link_libraries(channel_libs target_link_libraries(channel_libs
PUBLIC PUBLIC
core_libs
core_system_parameters core_system_parameters
Gnuradio::runtime Gnuradio::runtime
Gnuradio::pmt Gnuradio::pmt
PRIVATE PRIVATE
core_libs
Boost::boost Boost::boost
Gflags::gflags Gflags::gflags
Glog::glog Glog::glog
) )
target_include_directories(channel_libs
PUBLIC
${CMAKE_SOURCE_DIR}/src/core/receiver
)
if(ENABLE_CLANG_TIDY) if(ENABLE_CLANG_TIDY)
if(CLANG_TIDY_EXE) if(CLANG_TIDY_EXE)
set_target_properties(channel_libs set_target_properties(channel_libs

View File

@ -109,7 +109,7 @@ Pass_Through::Pass_Through(ConfigurationInterface* configuration, const std::str
} }
kludge_copy_ = gr::blocks::copy::make(item_size_); kludge_copy_ = gr::blocks::copy::make(item_size_);
unsigned long int max_source_buffer_samples = configuration->property("GNSS-SDR.max_source_buffer_samples", 0); uint64_t max_source_buffer_samples = configuration->property("GNSS-SDR.max_source_buffer_samples", 0ULL);
if (max_source_buffer_samples > 0) if (max_source_buffer_samples > 0)
{ {
kludge_copy_->set_max_output_buffer(max_source_buffer_samples); kludge_copy_->set_max_output_buffer(max_source_buffer_samples);

View File

@ -34,12 +34,12 @@ target_link_libraries(signal_generator_adapters
Gflags::gflags Gflags::gflags
Glog::glog Glog::glog
algorithms_libs algorithms_libs
core_receiver
) )
target_include_directories(signal_generator_adapters target_include_directories(signal_generator_adapters
PUBLIC PUBLIC
${CMAKE_SOURCE_DIR}/src/core/interfaces ${CMAKE_SOURCE_DIR}/src/core/interfaces
${CMAKE_SOURCE_DIR}/src/core/receiver
) )
if(ENABLE_CLANG_TIDY) if(ENABLE_CLANG_TIDY)

View File

@ -148,7 +148,7 @@ private:
std::vector<std::vector<gr_complex>> sampled_code_data_; std::vector<std::vector<gr_complex>> sampled_code_data_;
std::vector<std::vector<gr_complex>> sampled_code_pilot_; std::vector<std::vector<gr_complex>> sampled_code_pilot_;
std::vector<gr_complex> complex_phase_; std::vector<gr_complex> complex_phase_;
unsigned int work_counter_; unsigned int work_counter_{};
std::random_device r; std::random_device r;
std::default_random_engine e1; std::default_random_engine e1;
std::default_random_engine e2; std::default_random_engine e2;

View File

@ -60,15 +60,20 @@ add_library(signal_source_gr_blocks
target_link_libraries(signal_source_gr_blocks target_link_libraries(signal_source_gr_blocks
PUBLIC PUBLIC
signal_source_libs
Boost::thread Boost::thread
Gnuradio::runtime Gnuradio::runtime
signal_source_libs
PRIVATE PRIVATE
core_receiver core_libs
Gflags::gflags Gflags::gflags
Glog::glog Glog::glog
) )
target_include_directories(signal_source_gr_blocks
PUBLIC
${CMAKE_SOURCE_DIR}/src/core/receiver
)
if(ENABLE_RAW_UDP AND PCAP_FOUND) if(ENABLE_RAW_UDP AND PCAP_FOUND)
target_link_libraries(signal_source_gr_blocks target_link_libraries(signal_source_gr_blocks
PUBLIC PUBLIC

View File

@ -71,10 +71,15 @@ target_link_libraries(signal_source_libs
PUBLIC PUBLIC
Boost::boost Boost::boost
Gnuradio::runtime Gnuradio::runtime
core_receiver
PRIVATE PRIVATE
Gflags::gflags Gflags::gflags
Glog::glog Glog::glog
core_libs
)
target_include_directories(signal_source_libs
PUBLIC
${CMAKE_SOURCE_DIR}/src/core/receiver
) )
if(ENABLE_PLUTOSDR OR ENABLE_FMCOMMS2) if(ENABLE_PLUTOSDR OR ENABLE_FMCOMMS2)

View File

@ -26,6 +26,7 @@ set(CORE_LIBS_SOURCES
gnss_sdr_sample_counter.cc gnss_sdr_sample_counter.cc
channel_status_msg_receiver.cc channel_status_msg_receiver.cc
channel_event.cc channel_event.cc
command_event.cc
) )
set(CORE_LIBS_HEADERS set(CORE_LIBS_HEADERS
@ -36,6 +37,7 @@ set(CORE_LIBS_HEADERS
gnss_sdr_sample_counter.h gnss_sdr_sample_counter.h
channel_status_msg_receiver.h channel_status_msg_receiver.h
channel_event.h channel_event.h
command_event.h
) )
if(ENABLE_FPGA) if(ENABLE_FPGA)

View File

@ -32,10 +32,10 @@
channel_event_sptr channel_event_make(int channel_id, int event_type) channel_event_sptr channel_event_make(int channel_id, int event_type)
{ {
return channel_event_sptr(new channel_event(channel_id, event_type)); return channel_event_sptr(new Channel_Event(channel_id, event_type));
} }
channel_event::channel_event(int channel_id_, int event_type_) Channel_Event::Channel_Event(int channel_id_, int event_type_)
{ {
channel_id = channel_id_; channel_id = channel_id_;
event_type = event_type_; event_type = event_type_;

View File

@ -33,21 +33,21 @@
#include <memory> #include <memory>
class channel_event; class Channel_Event;
using channel_event_sptr = std::shared_ptr<channel_event>; using channel_event_sptr = std::shared_ptr<Channel_Event>;
channel_event_sptr channel_event_make(int channel_id, int event_type); channel_event_sptr channel_event_make(int channel_id, int event_type);
class channel_event class Channel_Event
{ {
public: public:
int channel_id; int channel_id;
int event_type; int event_type;
private: private:
friend channel_event_sptr channel_event_make(int channel_id, int event_type); friend channel_event_sptr channel_event_make(int channel_id, int event_type);
channel_event(int channel_id_, int event_type_); Channel_Event(int channel_id_, int event_type_);
}; };
#endif #endif

View File

@ -1,11 +1,11 @@
/*! /*!
* \file channel_status_msg_receiver.cc * \file channel_status_msg_receiver.cc
* \brief GNU Radio block that receives asynchronous channel messages from acquisition and tracking blocks * \brief GNU Radio block that receives asynchronous channel messages from acquisition and tracking blocks
* \author Javier Arribas, 2016. jarribas(at)cttc.es * \author Javier Arribas, 2019. jarribas(at)cttc.es
* *
* ------------------------------------------------------------------------- * -------------------------------------------------------------------------
* *
* Copyright (C) 2010-2018 (see AUTHORS file for a list of contributors) * Copyright (C) 2010-2019 (see AUTHORS file for a list of contributors)
* *
* GNSS-SDR is a software defined Global Navigation * GNSS-SDR is a software defined Global Navigation
* Satellite Systems receiver * Satellite Systems receiver
@ -75,12 +75,12 @@ void channel_status_msg_receiver::msg_handler_events(const pmt::pmt_t& msg)
d_channel_status_map.erase(gnss_synchro_obj->Channel_ID); d_channel_status_map.erase(gnss_synchro_obj->Channel_ID);
} }
// std::cout << "-------- \n\n"; // std::cout << "-------- " << std::endl << std::endl;
// for (std::map<int, std::shared_ptr<Gnss_Synchro>>::iterator it = d_channel_status_map.begin(); it != d_channel_status_map.end(); ++it) // for (std::map<int, std::shared_ptr<Gnss_Synchro>>::iterator it = d_channel_status_map.begin(); it != d_channel_status_map.end(); ++it)
// { // {
// std::cout << " Channel: " << it->first << " => Doppler: " << it->second->Carrier_Doppler_hz << "[Hz] \n"; // std::cout << " Channel: " << it->first << " => Doppler: " << it->second->Carrier_Doppler_hz << "[Hz] " << std::endl;
// } // }
// std::cout << "-------- \n\n"; // std::cout << "-------- " << std::endl << std::endl;
} }
else if (pmt::any_ref(msg).type() == typeid(std::shared_ptr<Monitor_Pvt>)) else if (pmt::any_ref(msg).type() == typeid(std::shared_ptr<Monitor_Pvt>))
{ {
@ -88,10 +88,10 @@ void channel_status_msg_receiver::msg_handler_events(const pmt::pmt_t& msg)
std::shared_ptr<Monitor_Pvt> monitor_pvt_obj; std::shared_ptr<Monitor_Pvt> monitor_pvt_obj;
monitor_pvt_obj = boost::any_cast<std::shared_ptr<Monitor_Pvt>>(pmt::any_ref(msg)); monitor_pvt_obj = boost::any_cast<std::shared_ptr<Monitor_Pvt>>(pmt::any_ref(msg));
d_pvt_status = *monitor_pvt_obj.get(); d_pvt_status = *monitor_pvt_obj.get();
//
// std::cout << "-------- \n\n"; // std::cout << "-------- " << std::endl << std::endl;
// std::cout << "PVT TOW: " << d_pvt_status->TOW_at_current_symbol_ms << std::endl; // std::cout << "PVT TOW: " << d_pvt_status->TOW_at_current_symbol_ms << std::endl;
// std::cout << "-------- \n\n"; // std::cout << "-------- " << std::endl << std::endl;
} }
else else
{ {
@ -104,11 +104,14 @@ void channel_status_msg_receiver::msg_handler_events(const pmt::pmt_t& msg)
} }
} }
std::map<int, std::shared_ptr<Gnss_Synchro>> channel_status_msg_receiver::get_current_status_map() std::map<int, std::shared_ptr<Gnss_Synchro>> channel_status_msg_receiver::get_current_status_map()
{ {
gr::thread::scoped_lock lock(d_setlock); // require mutex with msg_handler_events function called by the scheduler gr::thread::scoped_lock lock(d_setlock); // require mutex with msg_handler_events function called by the scheduler
return d_channel_status_map; return d_channel_status_map;
} }
Monitor_Pvt channel_status_msg_receiver::get_current_status_pvt() Monitor_Pvt channel_status_msg_receiver::get_current_status_pvt()
{ {
gr::thread::scoped_lock lock(d_setlock); // require mutex with msg_handler_events function called by the scheduler gr::thread::scoped_lock lock(d_setlock); // require mutex with msg_handler_events function called by the scheduler

View File

@ -1,11 +1,11 @@
/*! /*!
* \file channel_msg_receiver_cc.h * \file channel_msg_receiver_cc.h
* \brief GNU Radio block that receives asynchronous channel messages from acquisition and tracking blocks * \brief GNU Radio block that receives asynchronous channel messages from acquisition and tracking blocks
* \author Javier Arribas, 2016. jarribas(at)cttc.es * \author Javier Arribas, 2019. jarribas(at)cttc.es
* *
* ------------------------------------------------------------------------- * -------------------------------------------------------------------------
* *
* Copyright (C) 2010-2018 (see AUTHORS file for a list of contributors) * Copyright (C) 2010-2019 (see AUTHORS file for a list of contributors)
* *
* GNSS-SDR is a software defined Global Navigation * GNSS-SDR is a software defined Global Navigation
* Satellite Systems receiver * Satellite Systems receiver
@ -50,10 +50,12 @@ class channel_status_msg_receiver : public gr::block
{ {
public: public:
~channel_status_msg_receiver(); //!< Default destructor ~channel_status_msg_receiver(); //!< Default destructor
/*! /*!
* \brief return the current status map of all channels with valid telemetry * \brief return the current status map of all channels with valid telemetry
*/ */
std::map<int, std::shared_ptr<Gnss_Synchro>> get_current_status_map(); std::map<int, std::shared_ptr<Gnss_Synchro>> get_current_status_map();
/*! /*!
* \brief return the current receiver PVT * \brief return the current receiver PVT
*/ */
@ -63,7 +65,6 @@ private:
friend channel_status_msg_receiver_sptr channel_status_msg_receiver_make(); friend channel_status_msg_receiver_sptr channel_status_msg_receiver_make();
channel_status_msg_receiver(); channel_status_msg_receiver();
std::map<int, std::shared_ptr<Gnss_Synchro>> d_channel_status_map; std::map<int, std::shared_ptr<Gnss_Synchro>> d_channel_status_map;
Monitor_Pvt d_pvt_status{}; Monitor_Pvt d_pvt_status{};
void msg_handler_events(const pmt::pmt_t& msg); void msg_handler_events(const pmt::pmt_t& msg);
}; };

View File

@ -32,10 +32,10 @@
command_event_sptr command_event_make(int command_id, int event_type) command_event_sptr command_event_make(int command_id, int event_type)
{ {
return command_event_sptr(new command_event(command_id, event_type)); return command_event_sptr(new Command_Event(command_id, event_type));
} }
command_event::command_event(int command_id_, int event_type_) Command_Event::Command_Event(int command_id_, int event_type_)
{ {
command_id = command_id_; command_id = command_id_;
event_type = event_type_; event_type = event_type_;

View File

@ -28,18 +28,18 @@
* ------------------------------------------------------------------------- * -------------------------------------------------------------------------
*/ */
#ifndef GNSS_SDR_command_EVENT_H #ifndef GNSS_SDR_COMMAND_EVENT_H
#define GNSS_SDR_command_EVENT_H #define GNSS_SDR_COMMAND_EVENT_H
#include <memory> #include <memory>
class command_event; class Command_Event;
using command_event_sptr = std::shared_ptr<command_event>; using command_event_sptr = std::shared_ptr<Command_Event>;
command_event_sptr command_event_make(int command_id, int event_type); command_event_sptr command_event_make(int command_id, int event_type);
class command_event class Command_Event
{ {
public: public:
int command_id; int command_id;
@ -47,7 +47,7 @@ public:
private: private:
friend command_event_sptr command_event_make(int command_id, int event_type); friend command_event_sptr command_event_make(int command_id, int event_type);
command_event(int command_id_, int event_type_); Command_Event(int command_id_, int event_type_);
}; };
#endif #endif

View File

@ -24,7 +24,6 @@ set(GNSS_RECEIVER_SOURCES
gnss_flowgraph.cc gnss_flowgraph.cc
in_memory_configuration.cc in_memory_configuration.cc
tcp_cmd_interface.cc tcp_cmd_interface.cc
command_event.cc
) )
set(GNSS_RECEIVER_HEADERS set(GNSS_RECEIVER_HEADERS
@ -36,7 +35,6 @@ set(GNSS_RECEIVER_HEADERS
tcp_cmd_interface.h tcp_cmd_interface.h
concurrent_map.h concurrent_map.h
concurrent_queue.h concurrent_queue.h
command_event.h
) )
list(SORT GNSS_RECEIVER_HEADERS) list(SORT GNSS_RECEIVER_HEADERS)
@ -135,17 +133,11 @@ endif()
target_link_libraries(core_receiver target_link_libraries(core_receiver
PUBLIC PUBLIC
Armadillo::armadillo
Boost::boost
Boost::thread
Gnuradio::runtime
channel_libs
core_libs core_libs
core_monitor core_monitor
Boost::thread
Gnuradio::runtime
PRIVATE PRIVATE
Boost::chrono
Gflags::gflags
Glog::glog
signal_source_adapters signal_source_adapters
data_type_adapters data_type_adapters
input_filter_adapters input_filter_adapters
@ -157,6 +149,11 @@ target_link_libraries(core_receiver
telemetry_decoder_adapters telemetry_decoder_adapters
obs_adapters obs_adapters
pvt_adapters pvt_adapters
Boost::boost
Boost::chrono
Gflags::gflags
Glog::glog
Armadillo::armadillo
) )
# Fix for Boost Asio < 1.70 # Fix for Boost Asio < 1.70

View File

@ -31,8 +31,8 @@
#ifndef GNSS_SDR_CONCURRENT_MAP_H #ifndef GNSS_SDR_CONCURRENT_MAP_H
#define GNSS_SDR_CONCURRENT_MAP_H #define GNSS_SDR_CONCURRENT_MAP_H
#include <boost/thread/mutex.hpp>
#include <map> #include <map>
#include <mutex>
#include <utility> #include <utility>
@ -49,7 +49,7 @@ class Concurrent_Map
public: public:
void write(int key, Data const& data) void write(int key, Data const& data)
{ {
boost::mutex::scoped_lock lock(the_mutex); std::unique_lock<std::mutex> lock(the_mutex);
Data_iterator data_iter; Data_iterator data_iter;
data_iter = the_map.find(key); data_iter = the_map.find(key);
if (data_iter != the_map.end()) if (data_iter != the_map.end())
@ -65,7 +65,7 @@ public:
std::map<int, Data> get_map_copy() std::map<int, Data> get_map_copy()
{ {
boost::mutex::scoped_lock lock(the_mutex); std::unique_lock<std::mutex> lock(the_mutex);
std::map<int, Data> map_aux = the_map; std::map<int, Data> map_aux = the_map;
lock.unlock(); lock.unlock();
return map_aux; return map_aux;
@ -73,7 +73,7 @@ public:
size_t size() size_t size()
{ {
boost::mutex::scoped_lock lock(the_mutex); std::unique_lock<std::mutex> lock(the_mutex);
size_t size_ = the_map.size(); size_t size_ = the_map.size();
lock.unlock(); lock.unlock();
return size_; return size_;
@ -81,7 +81,7 @@ public:
bool read(int key, Data& p_data) bool read(int key, Data& p_data)
{ {
boost::mutex::scoped_lock lock(the_mutex); std::unique_lock<std::mutex> lock(the_mutex);
Data_iterator data_iter; Data_iterator data_iter;
data_iter = the_map.find(key); data_iter = the_map.find(key);
if (data_iter != the_map.end()) if (data_iter != the_map.end())
@ -96,7 +96,7 @@ public:
private: private:
std::map<int, Data> the_map; std::map<int, Data> the_map;
boost::mutex the_mutex; mutable std::mutex the_mutex;
}; };
#endif #endif

View File

@ -60,6 +60,8 @@
#include "rtklib_conversions.h" // for alm_to_rtklib #include "rtklib_conversions.h" // for alm_to_rtklib
#include "rtklib_ephemeris.h" // for alm2pos, eph2pos #include "rtklib_ephemeris.h" // for alm2pos, eph2pos
#include "rtklib_rtkcmn.h" // for utc2gpst #include "rtklib_rtkcmn.h" // for utc2gpst
#include <armadillo> // for interaction with geofunctions
#include <boost/chrono.hpp> // for steady_clock
#include <boost/lexical_cast.hpp> // for bad_lexical_cast #include <boost/lexical_cast.hpp> // for bad_lexical_cast
#include <glog/logging.h> // for LOG #include <glog/logging.h> // for LOG
#include <pmt/pmt.h> // for make_any #include <pmt/pmt.h> // for make_any
@ -67,7 +69,6 @@
#include <array> // for array #include <array> // for array
#include <chrono> // for milliseconds #include <chrono> // for milliseconds
#include <cmath> // for floor, fmod, log #include <cmath> // for floor, fmod, log
#include <ctime> // for gmtime, strftime
#include <exception> // for exception #include <exception> // for exception
#include <iostream> // for operator<<, endl #include <iostream> // for operator<<, endl
#include <limits> // for numeric_limits #include <limits> // for numeric_limits
@ -225,6 +226,7 @@ void ControlThread::telecommand_listener()
} }
} }
void ControlThread::event_dispatcher(bool &valid_event, pmt::pmt_t &msg) void ControlThread::event_dispatcher(bool &valid_event, pmt::pmt_t &msg)
{ {
if (valid_event) if (valid_event)
@ -270,6 +272,7 @@ void ControlThread::event_dispatcher(bool &valid_event, pmt::pmt_t &msg)
} }
} }
/* /*
* Runs the control thread that manages the receiver control plane * Runs the control thread that manages the receiver control plane
* *
@ -813,9 +816,9 @@ void ControlThread::assist_GNSS()
if ((agnss_ref_location_.valid == true) and ((enable_gps_supl_assistance == true) or (enable_agnss_xml == true))) if ((agnss_ref_location_.valid == true) and ((enable_gps_supl_assistance == true) or (enable_agnss_xml == true)))
{ {
// Get the list of visible satellites // Get the list of visible satellites
arma::vec ref_LLH = arma::zeros(3, 1); std::array<float, 3> ref_LLH{};
ref_LLH(0) = agnss_ref_location_.lat; ref_LLH[0] = agnss_ref_location_.lat;
ref_LLH(1) = agnss_ref_location_.lon; ref_LLH[1] = agnss_ref_location_.lon;
time_t ref_rx_utc_time = 0; time_t ref_rx_utc_time = 0;
if (agnss_ref_time_.valid == true) if (agnss_ref_time_.valid == true)
{ {
@ -885,10 +888,10 @@ void ControlThread::apply_action(unsigned int what)
} }
std::vector<std::pair<int, Gnss_Satellite>> ControlThread::get_visible_sats(time_t rx_utc_time, const arma::vec &LLH) std::vector<std::pair<int, Gnss_Satellite>> ControlThread::get_visible_sats(time_t rx_utc_time, const std::array<float, 3> &LLH)
{ {
// 1. Compute rx ECEF position from LLH WGS84 // 1. Compute rx ECEF position from LLH WGS84
arma::vec LLH_rad = arma::vec{degtorad(LLH(0)), degtorad(LLH(1)), LLH(2)}; arma::vec LLH_rad = arma::vec{degtorad(LLH[0]), degtorad(LLH[1]), LLH[2]};
arma::mat C_tmp = arma::zeros(3, 3); arma::mat C_tmp = arma::zeros(3, 3);
arma::vec r_eb_e = arma::zeros(3, 1); arma::vec r_eb_e = arma::zeros(3, 1);
arma::vec v_eb_e = arma::zeros(3, 1); arma::vec v_eb_e = arma::zeros(3, 1);
@ -912,7 +915,7 @@ std::vector<std::pair<int, Gnss_Satellite>> ControlThread::get_visible_sats(time
strftime(buf, sizeof(buf), "%d/%m/%Y %H:%M:%S ", &tstruct); strftime(buf, sizeof(buf), "%d/%m/%Y %H:%M:%S ", &tstruct);
std::string str_time = std::string(buf); std::string str_time = std::string(buf);
std::cout << "Get visible satellites at " << str_time std::cout << "Get visible satellites at " << str_time
<< "UTC, assuming RX position " << LLH(0) << " [deg], " << LLH(1) << " [deg], " << LLH(2) << " [m]" << std::endl; << "UTC, assuming RX position " << LLH[0] << " [deg], " << LLH[1] << " [deg], " << LLH[2] << " [m]" << std::endl;
std::map<int, Gps_Ephemeris> gps_eph_map = pvt_ptr->get_gps_ephemeris(); std::map<int, Gps_Ephemeris> gps_eph_map = pvt_ptr->get_gps_ephemeris();
for (auto &it : gps_eph_map) for (auto &it : gps_eph_map)

View File

@ -9,7 +9,7 @@
* *
* ------------------------------------------------------------------------- * -------------------------------------------------------------------------
* *
* Copyright (C) 2010-2018 (see AUTHORS file for a list of contributors) * Copyright (C) 2010-2019 (see AUTHORS file for a list of contributors)
* *
* GNSS-SDR is a software defined Global Navigation * GNSS-SDR is a software defined Global Navigation
* Satellite Systems receiver * Satellite Systems receiver
@ -35,15 +35,15 @@
#ifndef GNSS_SDR_CONTROL_THREAD_H_ #ifndef GNSS_SDR_CONTROL_THREAD_H_
#define GNSS_SDR_CONTROL_THREAD_H_ #define GNSS_SDR_CONTROL_THREAD_H_
#include "agnss_ref_location.h" // for Agnss_Ref_Location #include "agnss_ref_location.h" // for Agnss_Ref_Location
#include "agnss_ref_time.h" // for Agnss_Ref_Time #include "agnss_ref_time.h" // for Agnss_Ref_Time
#include "concurrent_queue.h" #include "concurrent_queue.h" // for Concurrent_Queue
#include "gnss_sdr_supl_client.h" // for Gnss_Sdr_Supl_Client #include "gnss_sdr_supl_client.h" // for Gnss_Sdr_Supl_Client
#include "tcp_cmd_interface.h" // for TcpCmdInterface #include "tcp_cmd_interface.h" // for TcpCmdInterface
#include <armadillo> // for arma::vec
#include <boost/thread.hpp> // for boost::thread #include <boost/thread.hpp> // for boost::thread
#include <pmt/pmt.h> #include <pmt/pmt.h>
#include <ctime> // for time_t #include <array> // for array
#include <ctime> // for time_t (gmtime, strftime in implementation)
#include <memory> // for shared_ptr #include <memory> // for shared_ptr
#include <string> // for string #include <string> // for string
#include <thread> // for std::thread #include <thread> // for std::thread
@ -75,7 +75,9 @@ public:
*/ */
ControlThread(std::shared_ptr<ConfigurationInterface> configuration); ControlThread(std::shared_ptr<ConfigurationInterface> configuration);
//! \brief Destructor /*!
* \brief Destructor
*/
~ControlThread(); ~ControlThread();
/*! \brief Runs the control thread /*! \brief Runs the control thread
@ -99,12 +101,12 @@ public:
*/ */
void set_control_queue(const std::shared_ptr<Concurrent_Queue<pmt::pmt_t>> control_queue); // NOLINT(performance-unnecessary-value-param) void set_control_queue(const std::shared_ptr<Concurrent_Queue<pmt::pmt_t>> control_queue); // NOLINT(performance-unnecessary-value-param)
unsigned int processed_control_messages() unsigned int processed_control_messages() const
{ {
return processed_control_messages_; return processed_control_messages_;
} }
unsigned int applied_actions() unsigned int applied_actions() const
{ {
return applied_actions_; return applied_actions_;
} }
@ -120,15 +122,18 @@ public:
} }
private: private:
//Telecommand TCP interface // Telecommand TCP interface
TcpCmdInterface cmd_interface_; TcpCmdInterface cmd_interface_;
void telecommand_listener(); void telecommand_listener();
/* /*
* New receiver event dispatcher * New receiver event dispatcher
*/ */
void event_dispatcher(bool &valid_event, pmt::pmt_t &msg); void event_dispatcher(bool &valid_event, pmt::pmt_t &msg);
std::thread cmd_interface_thread_; std::thread cmd_interface_thread_;
//SUPL assistance classes
// SUPL assistance classes
Gnss_Sdr_Supl_Client supl_client_acquisition_; Gnss_Sdr_Supl_Client supl_client_acquisition_;
Gnss_Sdr_Supl_Client supl_client_ephemeris_; Gnss_Sdr_Supl_Client supl_client_ephemeris_;
int supl_mcc; // Current network MCC (Mobile country code), 3 digits. int supl_mcc; // Current network MCC (Mobile country code), 3 digits.
@ -141,9 +146,6 @@ private:
// Read {ephemeris, iono, utc, ref loc, ref time} assistance from a local XML file previously recorded // Read {ephemeris, iono, utc, ref loc, ref time} assistance from a local XML file previously recorded
bool read_assistance_from_XML(); bool read_assistance_from_XML();
// Save {ephemeris, iono, utc, ref loc, ref time} assistance to a local XML file
//bool save_assistance_to_XML();
/* /*
* Blocking function that reads the GPS assistance queue * Blocking function that reads the GPS assistance queue
*/ */
@ -153,7 +155,7 @@ private:
* Compute elevations for the specified time and position for all the available satellites in ephemeris and almanac queues * Compute elevations for the specified time and position for all the available satellites in ephemeris and almanac queues
* returns a vector filled with the available satellites ordered from high elevation to low elevation angle. * returns a vector filled with the available satellites ordered from high elevation to low elevation angle.
*/ */
std::vector<std::pair<int, Gnss_Satellite>> get_visible_sats(time_t rx_utc_time, const arma::vec &LLH); std::vector<std::pair<int, Gnss_Satellite>> get_visible_sats(time_t rx_utc_time, const std::array<float, 3> &LLH);
/* /*
* Read initial GNSS assistance from SUPL server or local XML files * Read initial GNSS assistance from SUPL server or local XML files

View File

@ -64,7 +64,6 @@
#include <set> // for set #include <set> // for set
#include <stdexcept> // for invalid_argument #include <stdexcept> // for invalid_argument
#include <thread> // for thread #include <thread> // for thread
#include <utility> // for move
#ifdef GR_GREATER_38 #ifdef GR_GREATER_38
#include <gnuradio/filter/fir_filter_blk.h> #include <gnuradio/filter/fir_filter_blk.h>
#else #else
@ -1295,7 +1294,10 @@ void GNSSFlowgraph::apply_action(unsigned int who, unsigned int what)
push_back_signal(gs); push_back_signal(gs);
} }
channels_state_[who] = 0; channels_state_[who] = 0;
if (acq_channels_count_ > 0) acq_channels_count_--; if (acq_channels_count_ > 0)
{
acq_channels_count_--;
}
// call the acquisition manager to assign new satellite and start next acquisition (if required) // call the acquisition manager to assign new satellite and start next acquisition (if required)
acquisition_manager(who); acquisition_manager(who);
break; break;
@ -1305,7 +1307,10 @@ void GNSSFlowgraph::apply_action(unsigned int who, unsigned int what)
remove_signal(channels_[who]->get_signal()); remove_signal(channels_[who]->get_signal());
channels_state_[who] = 2; channels_state_[who] = 2;
if (acq_channels_count_ > 0) acq_channels_count_--; if (acq_channels_count_ > 0)
{
acq_channels_count_--;
}
// call the acquisition manager to assign new satellite and start next acquisition (if required) // call the acquisition manager to assign new satellite and start next acquisition (if required)
acquisition_manager(who); acquisition_manager(who);
break; break;
@ -1900,18 +1905,18 @@ Gnss_Signal GNSSFlowgraph::search_next_signal(const std::string& searched_signal
std::map<int, std::shared_ptr<Gnss_Synchro>> current_channels_status = channels_status_->get_current_status_map(); std::map<int, std::shared_ptr<Gnss_Synchro>> current_channels_status = channels_status_->get_current_status_map();
// 2. search the currently tracked GPS L1 satellites and assist the GPS L2 acquisition if the satellite is not tracked on L2 // 2. search the currently tracked GPS L1 satellites and assist the GPS L2 acquisition if the satellite is not tracked on L2
bool found_signal = false; bool found_signal = false;
for (std::map<int, std::shared_ptr<Gnss_Synchro>>::iterator it = current_channels_status.begin(); it != current_channels_status.end(); ++it) for (auto& current_status : current_channels_status)
{ {
if (std::string(it->second->Signal) == "1C") if (std::string(current_status.second->Signal) == "1C")
{ {
std::list<Gnss_Signal>::iterator it2; std::list<Gnss_Signal>::iterator it2;
it2 = std::find_if(std::begin(available_GPS_2S_signals_), std::end(available_GPS_2S_signals_), it2 = std::find_if(std::begin(available_GPS_2S_signals_), std::end(available_GPS_2S_signals_),
[&](Gnss_Signal const& sig) { return sig.get_satellite().get_PRN() == it->second->PRN; }); [&](Gnss_Signal const& sig) { return sig.get_satellite().get_PRN() == current_status.second->PRN; });
if (it2 != available_GPS_2S_signals_.end()) if (it2 != available_GPS_2S_signals_.end())
{ {
estimated_doppler = it->second->Carrier_Doppler_hz; estimated_doppler = current_status.second->Carrier_Doppler_hz;
RX_time = it->second->RX_time; RX_time = current_status.second->RX_time;
// std::cout << " Channel: " << it->first << " => Doppler: " << estimated_doppler << "[Hz] \n"; // std::cout << " Channel: " << it->first << " => Doppler: " << estimated_doppler << "[Hz] \n";
// 3. return the GPS L2 satellite and remove it from list // 3. return the GPS L2 satellite and remove it from list
result = *it2; result = *it2;
@ -1953,18 +1958,18 @@ Gnss_Signal GNSSFlowgraph::search_next_signal(const std::string& searched_signal
// 1. Get the current channel status map // 1. Get the current channel status map
std::map<int, std::shared_ptr<Gnss_Synchro>> current_channels_status = channels_status_->get_current_status_map(); std::map<int, std::shared_ptr<Gnss_Synchro>> current_channels_status = channels_status_->get_current_status_map();
// 2. search the currently tracked GPS L1 satellites and assist the GPS L5 acquisition if the satellite is not tracked on L5 // 2. search the currently tracked GPS L1 satellites and assist the GPS L5 acquisition if the satellite is not tracked on L5
for (std::map<int, std::shared_ptr<Gnss_Synchro>>::iterator it = current_channels_status.begin(); it != current_channels_status.end(); ++it) for (auto& current_status : current_channels_status)
{ {
if (std::string(it->second->Signal) == "1C") if (std::string(current_status.second->Signal) == "1C")
{ {
std::list<Gnss_Signal>::iterator it2; std::list<Gnss_Signal>::iterator it2;
it2 = std::find_if(std::begin(available_GPS_L5_signals_), std::end(available_GPS_L5_signals_), it2 = std::find_if(std::begin(available_GPS_L5_signals_), std::end(available_GPS_L5_signals_),
[&](Gnss_Signal const& sig) { return sig.get_satellite().get_PRN() == it->second->PRN; }); [&](Gnss_Signal const& sig) { return sig.get_satellite().get_PRN() == current_status.second->PRN; });
if (it2 != available_GPS_L5_signals_.end()) if (it2 != available_GPS_L5_signals_.end())
{ {
estimated_doppler = it->second->Carrier_Doppler_hz; estimated_doppler = current_status.second->Carrier_Doppler_hz;
RX_time = it->second->RX_time; RX_time = current_status.second->RX_time;
// std::cout << " Channel: " << it->first << " => Doppler: " << estimated_doppler << "[Hz] \n"; // std::cout << " Channel: " << it->first << " => Doppler: " << estimated_doppler << "[Hz] \n";
// 3. return the GPS L5 satellite and remove it from list // 3. return the GPS L5 satellite and remove it from list
result = *it2; result = *it2;
@ -2007,18 +2012,18 @@ Gnss_Signal GNSSFlowgraph::search_next_signal(const std::string& searched_signal
// 1. Get the current channel status map // 1. Get the current channel status map
std::map<int, std::shared_ptr<Gnss_Synchro>> current_channels_status = channels_status_->get_current_status_map(); std::map<int, std::shared_ptr<Gnss_Synchro>> current_channels_status = channels_status_->get_current_status_map();
// 2. search the currently tracked Galileo E1 satellites and assist the Galileo E5 acquisition if the satellite is not tracked on E5 // 2. search the currently tracked Galileo E1 satellites and assist the Galileo E5 acquisition if the satellite is not tracked on E5
for (std::map<int, std::shared_ptr<Gnss_Synchro>>::iterator it = current_channels_status.begin(); it != current_channels_status.end(); ++it) for (auto& current_status : current_channels_status)
{ {
if (std::string(it->second->Signal) == "1B") if (std::string(current_status.second->Signal) == "1B")
{ {
std::list<Gnss_Signal>::iterator it2; std::list<Gnss_Signal>::iterator it2;
it2 = std::find_if(std::begin(available_GAL_5X_signals_), std::end(available_GAL_5X_signals_), it2 = std::find_if(std::begin(available_GAL_5X_signals_), std::end(available_GAL_5X_signals_),
[&](Gnss_Signal const& sig) { return sig.get_satellite().get_PRN() == it->second->PRN; }); [&](Gnss_Signal const& sig) { return sig.get_satellite().get_PRN() == current_status.second->PRN; });
if (it2 != available_GAL_5X_signals_.end()) if (it2 != available_GAL_5X_signals_.end())
{ {
estimated_doppler = it->second->Carrier_Doppler_hz; estimated_doppler = current_status.second->Carrier_Doppler_hz;
RX_time = it->second->RX_time; RX_time = current_status.second->RX_time;
// std::cout << " Channel: " << it->first << " => Doppler: " << estimated_doppler << "[Hz] \n"; // std::cout << " Channel: " << it->first << " => Doppler: " << estimated_doppler << "[Hz] \n";
// 3. return the Gal 5X satellite and remove it from list // 3. return the Gal 5X satellite and remove it from list
result = *it2; result = *it2;

View File

@ -11,7 +11,7 @@
* *
* ------------------------------------------------------------------------- * -------------------------------------------------------------------------
* *
* Copyright (C) 2010-2018 (see AUTHORS file for a list of contributors) * Copyright (C) 2010-2019 (see AUTHORS file for a list of contributors)
* *
* GNSS-SDR is a software defined Global Navigation * GNSS-SDR is a software defined Global Navigation
* Satellite Systems receiver * Satellite Systems receiver
@ -42,7 +42,7 @@
#include "gnss_sdr_sample_counter.h" #include "gnss_sdr_sample_counter.h"
#include "gnss_signal.h" #include "gnss_signal.h"
#include "pvt_interface.h" #include "pvt_interface.h"
#include <gnuradio/blocks/null_sink.h> //for null_sink #include <gnuradio/blocks/null_sink.h> // for null_sink
#include <gnuradio/runtime_types.h> // for basic_block_sptr, top_block_sptr #include <gnuradio/runtime_types.h> // for basic_block_sptr, top_block_sptr
#include <pmt/pmt.h> // for pmt_t #include <pmt/pmt.h> // for pmt_t
#include <list> // for list #include <list> // for list
@ -79,10 +79,14 @@ public:
*/ */
~GNSSFlowgraph(); ~GNSSFlowgraph();
//! \brief Start the flow graph /*!
* \brief Start the flow graph
*/
void start(); void start();
//! \brief Stop the flow graph /*!
* \brief Stop the flow graph
*/
void stop(); void stop();
/*! /*!
@ -92,16 +96,27 @@ public:
*/ */
void connect(); void connect();
/*!
* \brief Disconnect the blocks in the flow graph
*/
void disconnect(); void disconnect();
/*!
* \brief Wait for a flowgraph to complete.
*
* Flowgraphs complete when either
* (1) all blocks indicate that they are done, or
* (2) after stop() has been called to request shutdown.
*/
void wait(); void wait();
#ifdef ENABLE_FPGA
void start_acquisition_helper();
void perform_hw_reset();
#endif
/*!
* \brief Manage satellite acquisition
*
* \param[in] who Channel ID
*/
void acquisition_manager(unsigned int who); void acquisition_manager(unsigned int who);
/*! /*!
* \brief Applies an action to the flow graph * \brief Applies an action to the flow graph
* *
@ -110,10 +125,9 @@ public:
*/ */
void apply_action(unsigned int who, unsigned int what); void apply_action(unsigned int who, unsigned int what);
/*!
void push_back_signal(const Gnss_Signal& gs); * \brief Set flow graph configuratiob
void remove_signal(const Gnss_Signal& gs); */
void set_configuration(std::shared_ptr<ConfigurationInterface> configuration); void set_configuration(std::shared_ptr<ConfigurationInterface> configuration);
bool connected() const bool connected() const
@ -127,7 +141,7 @@ public:
} }
/*! /*!
* \brief Sends a GNURadio asynchronous message from telemetry to PVT * \brief Sends a GNU Radio asynchronous message from telemetry to PVT
* *
* It is used to assist the receiver with external ephemeris data * It is used to assist the receiver with external ephemeris data
*/ */
@ -146,6 +160,12 @@ public:
*/ */
void priorize_satellites(const std::vector<std::pair<int, Gnss_Satellite>>& visible_satellites); void priorize_satellites(const std::vector<std::pair<int, Gnss_Satellite>>& visible_satellites);
#ifdef ENABLE_FPGA
void start_acquisition_helper();
void perform_hw_reset();
#endif
private: private:
void init(); // Populates the SV PRN list available for acquisition and tracking void init(); // Populates the SV PRN list available for acquisition and tracking
void set_signals_list(); void set_signals_list();
@ -157,6 +177,10 @@ private:
bool& assistance_available, bool& assistance_available,
float& estimated_doppler, float& estimated_doppler,
double& RX_time); double& RX_time);
void push_back_signal(const Gnss_Signal& gs);
void remove_signal(const Gnss_Signal& gs);
bool connected_; bool connected_;
bool running_; bool running_;
int sources_count_; int sources_count_;
@ -209,7 +233,7 @@ private:
std::map<std::string, StringValue> mapStringValues_; std::map<std::string, StringValue> mapStringValues_;
std::vector<unsigned int> channels_state_; std::vector<unsigned int> channels_state_;
channel_status_msg_receiver_sptr channels_status_; //class that receives and stores the current status of the receiver channels channel_status_msg_receiver_sptr channels_status_; // class that receives and stores the current status of the receiver channels
std::mutex signal_list_mutex; std::mutex signal_list_mutex;
bool enable_monitor_; bool enable_monitor_;
@ -217,4 +241,4 @@ private:
std::vector<std::string> split_string(const std::string& s, char delim); std::vector<std::string> split_string(const std::string& s, char delim);
}; };
#endif /*GNSS_SDR_GNSS_FLOWGRAPH_H_*/ #endif /* GNSS_SDR_GNSS_FLOWGRAPH_H_ */

View File

@ -33,7 +33,6 @@
#include "command_event.h" #include "command_event.h"
#include "pvt_interface.h" #include "pvt_interface.h"
#include <boost/asio.hpp> #include <boost/asio.hpp>
#include <array>
#include <cmath> // for isnan #include <cmath> // for isnan
#include <exception> // for exception #include <exception> // for exception
#include <iomanip> // for setprecision #include <iomanip> // for setprecision
@ -51,9 +50,9 @@ TcpCmdInterface::TcpCmdInterface()
register_functions(); register_functions();
keep_running_ = true; keep_running_ = true;
control_queue_ = nullptr; control_queue_ = nullptr;
rx_latitude_ = 0; rx_latitude_ = 0.0;
rx_longitude_ = 0; rx_longitude_ = 0.0;
rx_altitude_ = 0; rx_altitude_ = 0.0;
receiver_utc_time_ = 0; receiver_utc_time_ = 0;
} }
@ -85,9 +84,9 @@ time_t TcpCmdInterface::get_utc_time()
} }
arma::vec TcpCmdInterface::get_LLH() std::array<float, 3> TcpCmdInterface::get_LLH() const
{ {
return arma::vec{rx_latitude_, rx_longitude_, rx_altitude_}; return std::array<float, 3>{rx_latitude_, rx_longitude_, rx_altitude_};
} }
@ -192,9 +191,9 @@ std::string TcpCmdInterface::hotstart(const std::vector<std::string> &commandLin
receiver_utc_time_ = timegm(&tm); receiver_utc_time_ = timegm(&tm);
// Read latitude, longitude, and height // Read latitude, longitude, and height
rx_latitude_ = std::stod(commandLine.at(3).c_str()); rx_latitude_ = std::stof(commandLine.at(3).c_str());
rx_longitude_ = std::stod(commandLine.at(4).c_str()); rx_longitude_ = std::stof(commandLine.at(4).c_str());
rx_altitude_ = std::stod(commandLine.at(5).c_str()); rx_altitude_ = std::stof(commandLine.at(5).c_str());
if (std::isnan(rx_latitude_) || std::isnan(rx_longitude_) || std::isnan(rx_altitude_)) if (std::isnan(rx_latitude_) || std::isnan(rx_longitude_) || std::isnan(rx_altitude_))
{ {

View File

@ -33,8 +33,8 @@
#include "concurrent_queue.h" #include "concurrent_queue.h"
#include <armadillo>
#include <pmt/pmt.h> #include <pmt/pmt.h>
#include <array>
#include <cstdint> #include <cstdint>
#include <ctime> #include <ctime>
#include <functional> #include <functional>
@ -61,7 +61,7 @@ public:
/*! /*!
* \brief gets the Latitude, Longitude and Altitude vector from the last TC command issued * \brief gets the Latitude, Longitude and Altitude vector from the last TC command issued
*/ */
arma::vec get_LLH(); std::array<float, 3> get_LLH() const;
void set_pvt(std::shared_ptr<PvtInterface> PVT_sptr); void set_pvt(std::shared_ptr<PvtInterface> PVT_sptr);
@ -83,9 +83,9 @@ private:
time_t receiver_utc_time_; time_t receiver_utc_time_;
double rx_latitude_; float rx_latitude_;
double rx_longitude_; float rx_longitude_;
double rx_altitude_; float rx_altitude_;
std::shared_ptr<PvtInterface> PVT_sptr_; std::shared_ptr<PvtInterface> PVT_sptr_;
}; };