diff --git a/src/algorithms/PVT/gnuradio_blocks/rtklib_pvt_cc.cc b/src/algorithms/PVT/gnuradio_blocks/rtklib_pvt_cc.cc index 6bbf91c2d..9a5335c8a 100644 --- a/src/algorithms/PVT/gnuradio_blocks/rtklib_pvt_cc.cc +++ b/src/algorithms/PVT/gnuradio_blocks/rtklib_pvt_cc.cc @@ -364,8 +364,7 @@ rtklib_pvt_cc::rtklib_pvt_cc(uint32_t nchannels, d_rinexobs_rate_ms = rinexobs_rate_ms; d_rinexnav_rate_ms = rinexnav_rate_ms; - d_dump_filename.append("_raw.dat"); - dump_ls_pvt_filename.append("_ls_pvt.dat"); + dump_ls_pvt_filename.append("_pvt.dat"); d_ls_pvt = std::make_shared(static_cast(nchannels), dump_ls_pvt_filename, d_dump, rtk); d_ls_pvt->set_averaging_depth(1); @@ -374,23 +373,6 @@ rtklib_pvt_cc::rtklib_pvt_cc(uint32_t nchannels, d_last_status_print_seg = 0; - // ############# ENABLE DATA FILE LOG ################# - if (d_dump == true) - { - if (d_dump_file.is_open() == false) - { - try - { - d_dump_file.exceptions(std::ifstream::failbit | std::ifstream::badbit); - d_dump_file.open(d_dump_filename.c_str(), std::ios::out | std::ios::binary); - LOG(INFO) << "PVT dump enabled Log file: " << d_dump_filename.c_str(); - } - catch (const std::ifstream::failure& e) - { - LOG(WARNING) << "Exception opening PVT dump file " << e.what(); - } - } - } // Create Sys V message queue first_fix = true; @@ -500,18 +482,6 @@ rtklib_pvt_cc::~rtklib_pvt_cc() { LOG(WARNING) << "Failed to save GLONASS GNAV Ephemeris, map is empty"; } - - if (d_dump_file.is_open() == true) - { - try - { - d_dump_file.close(); - } - catch (const std::exception& ex) - { - LOG(WARNING) << "Exception in destructor closing the dump file " << ex.what(); - } - } } @@ -2102,7 +2072,7 @@ int rtklib_pvt_cc::work(int noutput_items, gr_vector_const_void_star& input_item << std::fixed << std::setprecision(3) << " [deg], Height = " << d_ls_pvt->get_height() << " [m]" << TEXT_RESET << std::endl; std::cout << std::setprecision(ss); - LOG(INFO) << "RX clock offset: " << d_ls_pvt->get_time_offset_s() << "[s]"; + DLOG(INFO) << "RX clock offset: " << d_ls_pvt->get_time_offset_s() << "[s]"; // boost::posix_time::ptime p_time; // gtime_t rtklib_utc_time = gpst2time(adjgpsweek(d_ls_pvt->gps_ephemeris_map.cbegin()->second.i_GPS_week), d_rx_time); @@ -2110,36 +2080,15 @@ int rtklib_pvt_cc::work(int noutput_items, gr_vector_const_void_star& input_item // p_time += boost::posix_time::microseconds(round(rtklib_utc_time.sec * 1e6)); // std::cout << TEXT_MAGENTA << "Observable RX time (GPST) " << boost::posix_time::to_simple_string(p_time) << TEXT_RESET << std::endl; - LOG(INFO) << "Position at " << boost::posix_time::to_simple_string(d_ls_pvt->get_position_UTC_time()) - << " UTC using " << d_ls_pvt->get_num_valid_observations() << " observations is Lat = " << d_ls_pvt->get_latitude() << " [deg], Long = " << d_ls_pvt->get_longitude() - << " [deg], Height = " << d_ls_pvt->get_height() << " [m]"; + DLOG(INFO) << "Position at " << boost::posix_time::to_simple_string(d_ls_pvt->get_position_UTC_time()) + << " UTC using " << d_ls_pvt->get_num_valid_observations() << " observations is Lat = " << d_ls_pvt->get_latitude() << " [deg], Long = " << d_ls_pvt->get_longitude() + << " [deg], Height = " << d_ls_pvt->get_height() << " [m]"; /* std::cout << "Dilution of Precision at " << boost::posix_time::to_simple_string(d_ls_pvt->get_position_UTC_time()) << " UTC using "<< d_ls_pvt->get_num_valid_observations() <<" observations is HDOP = " << d_ls_pvt->get_hdop() << " VDOP = " << d_ls_pvt->get_vdop() << " GDOP = " << d_ls_pvt->get_gdop() << std::endl; */ } - - // MULTIPLEXED FILE RECORDING - Record results to file - if (d_dump == true) - { - try - { - double tmp_double; - for (uint32_t i = 0; i < d_nchannels; i++) - { - tmp_double = in[i][epoch].Pseudorange_m; - d_dump_file.write(reinterpret_cast(&tmp_double), sizeof(double)); - tmp_double = 0; - d_dump_file.write(reinterpret_cast(&tmp_double), sizeof(double)); - d_dump_file.write(reinterpret_cast(&d_rx_time), sizeof(double)); - } - } - catch (const std::ifstream::failure& e) - { - LOG(WARNING) << "Exception writing observables dump file " << e.what(); - } - } } } diff --git a/src/algorithms/PVT/gnuradio_blocks/rtklib_pvt_cc.h b/src/algorithms/PVT/gnuradio_blocks/rtklib_pvt_cc.h index 97e581f86..36d09fab4 100644 --- a/src/algorithms/PVT/gnuradio_blocks/rtklib_pvt_cc.h +++ b/src/algorithms/PVT/gnuradio_blocks/rtklib_pvt_cc.h @@ -122,7 +122,6 @@ private: uint32_t d_nchannels; std::string d_dump_filename; - std::ofstream d_dump_file; int32_t d_output_rate_ms; int32_t d_display_rate_ms; diff --git a/src/algorithms/PVT/libs/rtklib_solver.cc b/src/algorithms/PVT/libs/rtklib_solver.cc index 472ffc9d4..1f87b8797 100644 --- a/src/algorithms/PVT/libs/rtklib_solver.cc +++ b/src/algorithms/PVT/libs/rtklib_solver.cc @@ -86,7 +86,7 @@ rtklib_solver::rtklib_solver(int nchannels, std::string dump_filename, bool flag } catch (const std::ifstream::failure& e) { - LOG(WARNING) << "Exception opening PVT lib dump file " << e.what(); + LOG(WARNING) << "Exception opening RTKLIB dump file " << e.what(); } } } @@ -103,7 +103,7 @@ rtklib_solver::~rtklib_solver() } catch (const std::exception& ex) { - LOG(WARNING) << "Exception in destructor closing the dump file " << ex.what(); + LOG(WARNING) << "Exception in destructor closing the RTKLIB dump file " << ex.what(); } } } @@ -556,34 +556,55 @@ bool rtklib_solver::get_PVT(const std::map& gnss_observables_ try { double tmp_double; + uint32_t tmp_uint32; + // TOW + tmp_uint32 = gnss_observables_map.begin()->second.TOW_at_current_symbol_ms; + d_dump_file.write(reinterpret_cast(&tmp_uint32), sizeof(uint32_t)); + // WEEK + tmp_uint32 = adjgpsweek(nav_data.eph[0].week); + d_dump_file.write(reinterpret_cast(&tmp_uint32), sizeof(uint32_t)); // PVT GPS time tmp_double = gnss_observables_map.begin()->second.RX_time; d_dump_file.write(reinterpret_cast(&tmp_double), sizeof(double)); - // ECEF User Position East [m] - tmp_double = rx_position_and_time(0); - d_dump_file.write(reinterpret_cast(&tmp_double), sizeof(double)); - // ECEF User Position North [m] - tmp_double = rx_position_and_time(1); - d_dump_file.write(reinterpret_cast(&tmp_double), sizeof(double)); - // ECEF User Position Up [m] - tmp_double = rx_position_and_time(2); - d_dump_file.write(reinterpret_cast(&tmp_double), sizeof(double)); // User clock offset [s] tmp_double = rx_position_and_time(3); d_dump_file.write(reinterpret_cast(&tmp_double), sizeof(double)); + + // ECEF POS X,Y,X [m] + ECEF VEL X,Y,X [m/s] (6 x double) + d_dump_file.write(reinterpret_cast(&pvt_sol.rr[0]), sizeof(pvt_sol.rr)); + + // position variance/covariance (m^2) {c_xx,c_yy,c_zz,c_xy,c_yz,c_zx} (6 x double) + d_dump_file.write(reinterpret_cast(&pvt_sol.qr[0]), sizeof(pvt_sol.qr)); + // GEO user position Latitude [deg] - tmp_double = this->get_latitude(); + tmp_double = get_latitude(); d_dump_file.write(reinterpret_cast(&tmp_double), sizeof(double)); // GEO user position Longitude [deg] - tmp_double = this->get_longitude(); + tmp_double = get_longitude(); d_dump_file.write(reinterpret_cast(&tmp_double), sizeof(double)); // GEO user position Height [m] - tmp_double = this->get_height(); + tmp_double = get_height(); d_dump_file.write(reinterpret_cast(&tmp_double), sizeof(double)); + + // NUMBER OF VALID SATS + d_dump_file.write(reinterpret_cast(&pvt_sol.ns), sizeof(uint8_t)); + // RTKLIB solution status + d_dump_file.write(reinterpret_cast(&pvt_sol.stat), sizeof(uint8_t)); + // RTKLIB solution type (0:xyz-ecef,1:enu-baseline) + d_dump_file.write(reinterpret_cast(&pvt_sol.type), sizeof(uint8_t)); + //AR ratio factor for validation + tmp_double = pvt_sol.ratio; + d_dump_file.write(reinterpret_cast(&pvt_sol.ratio), sizeof(float)); + //AR ratio threshold for validation + tmp_double = pvt_sol.thres; + d_dump_file.write(reinterpret_cast(&pvt_sol.thres), sizeof(float)); + + //GDOP//PDOP//HDOP//VDOP + d_dump_file.write(reinterpret_cast(&dop_[0]), sizeof(dop_)); } catch (const std::ifstream::failure& e) { - LOG(WARNING) << "Exception writing PVT LS dump file " << e.what(); + LOG(WARNING) << "Exception writing RTKLIB dump file " << e.what(); } } } diff --git a/src/tests/CMakeLists.txt b/src/tests/CMakeLists.txt index 32f6b24bf..8ed59e572 100644 --- a/src/tests/CMakeLists.txt +++ b/src/tests/CMakeLists.txt @@ -18,6 +18,7 @@ add_subdirectory(unit-tests/signal-processing-blocks/libs) +add_subdirectory(system-tests/libs) ################################################################################ # Google Test - https://github.com/google/googletest @@ -342,6 +343,7 @@ set(LIST_INCLUDE_DIRS ${CMAKE_SOURCE_DIR}/src/algorithms/acquisition/gnuradio_blocks ${CMAKE_SOURCE_DIR}/src/algorithms/PVT/libs ${CMAKE_SOURCE_DIR}/src/tests/unit-tests/signal-processing-blocks/libs + ${CMAKE_SOURCE_DIR}/src/tests/system-tests/libs ${CMAKE_SOURCE_DIR}/src/tests/common-files ${GLOG_INCLUDE_DIRS} ${GFlags_INCLUDE_DIRS} @@ -489,7 +491,8 @@ if(ENABLE_SYSTEM_TESTING) ${GTEST_LIBRARIES} ${GNURADIO_RUNTIME_LIBRARIES} ${GNURADIO_BLOCKS_LIBRARIES} ${GNURADIO_FILTER_LIBRARIES} ${GNURADIO_ANALOG_LIBRARIES} ${VOLK_GNSSSDR_LIBRARIES} - gnss_sp_libs gnss_rx gnss_system_parameters ) + gnss_sp_libs gnss_rx gnss_system_parameters + system_testing_lib) add_system_test(position_test) diff --git a/src/tests/common-files/signal_generator_flags.h b/src/tests/common-files/signal_generator_flags.h index 399c1ce26..b5e737adc 100644 --- a/src/tests/common-files/signal_generator_flags.h +++ b/src/tests/common-files/signal_generator_flags.h @@ -38,7 +38,7 @@ DEFINE_bool(disable_generator, false, "Disable the signal generator (a external DEFINE_string(generator_binary, std::string(SW_GENERATOR_BIN), "Path of software-defined signal generator binary"); DEFINE_string(rinex_nav_file, std::string(DEFAULT_RINEX_NAV), "Input RINEX navigation file"); DEFINE_int32(duration, 100, "Duration of the experiment [in seconds, max = 300]"); -DEFINE_string(static_position, "30.286502,120.032669,100", "Static receiver position [log,lat,height]"); +DEFINE_string(static_position, "30.286502,120.032669,100", "Static receiver position [latitude,longitude,height]"); DEFINE_string(dynamic_position, "", "Observer positions file, in .csv or .nmea format"); DEFINE_string(filename_rinex_obs, "sim.16o", "Filename of output RINEX navigation file"); DEFINE_string(filename_raw_data, "signal_out.bin", "Filename of output raw data file"); diff --git a/src/tests/system-tests/libs/CMakeLists.txt b/src/tests/system-tests/libs/CMakeLists.txt new file mode 100644 index 000000000..71d863733 --- /dev/null +++ b/src/tests/system-tests/libs/CMakeLists.txt @@ -0,0 +1,40 @@ +# Copyright (C) 2012-2018 (see AUTHORS file for a list of contributors) +# +# This file is part of GNSS-SDR. +# +# GNSS-SDR is free software: you can redistribute it and/or modify +# it under the terms of the GNU General Public License as published by +# the Free Software Foundation, either version 3 of the License, or +# (at your option) any later version. +# +# GNSS-SDR is distributed in the hope that it will be useful, +# but WITHOUT ANY WARRANTY; without even the implied warranty of +# MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +# GNU General Public License for more details. +# +# You should have received a copy of the GNU General Public License +# along with GNSS-SDR. If not, see . +# + + +set(SYSTEM_TESTING_LIB_SOURCES + spirent_motion_csv_dump_reader.cc + rtklib_solver_dump_reader.cc +) + +include_directories( + ${CMAKE_CURRENT_SOURCE_DIR} + ${GLOG_INCLUDE_DIRS} + ${GFlags_INCLUDE_DIRS} + ${MATIO_INCLUDE_DIRS} +) + + +file(GLOB SYSTEM_TESTING_LIB_HEADERS "*.h") +list(SORT SYSTEM_TESTING_LIB_HEADERS) +add_library(system_testing_lib ${SYSTEM_TESTING_LIB_SOURCES} ${SYSTEM_TESTING_LIB_HEADERS}) +source_group(Headers FILES ${SYSTEM_TESTING_LIB_HEADERS}) + +if(NOT MATIO_FOUND) + add_dependencies(system_testing_lib matio-${GNSSSDR_MATIO_LOCAL_VERSION}) +endif(NOT MATIO_FOUND) \ No newline at end of file diff --git a/src/tests/system-tests/libs/position_test_flags.h b/src/tests/system-tests/libs/position_test_flags.h new file mode 100644 index 000000000..e911fb892 --- /dev/null +++ b/src/tests/system-tests/libs/position_test_flags.h @@ -0,0 +1,46 @@ +/*! + * \file signal_generator_flags.h + * \brief Helper file for unit testing + * \author Javier Arribas, 2018. jarribas(at)cttc.es + * + * ------------------------------------------------------------------------- + * + * Copyright (C) 2010-2018 (see AUTHORS file for a list of contributors) + * + * GNSS-SDR is a software defined Global Navigation + * Satellite Systems receiver + * + * This file is part of GNSS-SDR. + * + * GNSS-SDR is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * GNSS-SDR is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with GNSS-SDR. If not, see . + * + * ------------------------------------------------------------------------- + */ + +#ifndef GNSS_SDR_POSITION_TEST_FLAGS_H_ +#define GNSS_SDR_POSITION_TEST_FLAGS_H_ + +#include +#include + +DEFINE_string(config_file_ptest, std::string(""), "File containing the configuration parameters for the position test."); +DEFINE_bool(plot_position_test, false, "Plots results of with gnuplot"); +DEFINE_bool(static_scenario, true, "Compute figures of merit for static user position (DRMS, CEP, etc..)"); +DEFINE_bool(use_pvt_solver_dump, false, "Use PVT solver binary dump or fall back to KML PVT file (contains only position information)"); +DEFINE_bool(use_ref_motion_file, false, "Enable or disable the use of a reference file containing the true receiver position, velocity and acceleration."); +DEFINE_int32(ref_motion_file_type, 1, "Type of reference motion file: 1- Spirent CSV motion file"); +DEFINE_string(ref_motion_filename, std::string("motion.csv"), "Path and filename for the reference motion file"); +DEFINE_string(pvt_solver_dump_filename, std::string("PVT_pvt.dat"), "Path and filename for the PVT solver binary dump file"); + +#endif diff --git a/src/tests/system-tests/libs/rtklib_solver_dump_reader.cc b/src/tests/system-tests/libs/rtklib_solver_dump_reader.cc new file mode 100644 index 000000000..2c2fc87f0 --- /dev/null +++ b/src/tests/system-tests/libs/rtklib_solver_dump_reader.cc @@ -0,0 +1,155 @@ +/*! + * \file rtklib_solver_dump_reader.cc + * \brief Helper file for unit testing + * \author Javier Arribas, 2017. jarribas(at)cttc.es + * + * ------------------------------------------------------------------------- + * + * Copyright (C) 2010-2018 (see AUTHORS file for a list of contributors) + * + * GNSS-SDR is a software defined Global Navigation + * Satellite Systems receiver + * + * This file is part of GNSS-SDR. + * + * GNSS-SDR is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * GNSS-SDR is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with GNSS-SDR. If not, see . + * + * ------------------------------------------------------------------------- + */ + +#include "rtklib_solver_dump_reader.h" + +#include + +bool rtklib_solver_dump_reader::read_binary_obs() +{ + try + { + d_dump_file.read(reinterpret_cast(&TOW_at_current_symbol_ms), sizeof(TOW_at_current_symbol_ms)); + // std::cout << "TOW_at_current_symbol_ms: " << TOW_at_current_symbol_ms << std::endl; + d_dump_file.read(reinterpret_cast(&week), sizeof(week)); + // std::cout << "week: " << week << std::endl; + d_dump_file.read(reinterpret_cast(&RX_time), sizeof(RX_time)); + // std::cout << "RX_time: " << RX_time << std::endl; + d_dump_file.read(reinterpret_cast(&clk_offset_s), sizeof(clk_offset_s)); + // std::cout << "clk_offset_s: " << clk_offset_s << std::endl; + d_dump_file.read(reinterpret_cast(&rr[0]), sizeof(rr)); + // for (int n = 0; n < 6; n++) + // { + // std::cout << "rr: " << rr[n] << std::endl; + // } + d_dump_file.read(reinterpret_cast(&qr[0]), sizeof(qr)); + // for (int n = 0; n < 6; n++) + // { + // std::cout << "qr" << qr[n] << std::endl; + // } + d_dump_file.read(reinterpret_cast(&latitude), sizeof(latitude)); + std::cout << "latitude: " << latitude << std::endl; + d_dump_file.read(reinterpret_cast(&longitude), sizeof(longitude)); + std::cout << "longitude: " << longitude << std::endl; + d_dump_file.read(reinterpret_cast(&height), sizeof(height)); + std::cout << "height: " << height << std::endl; + d_dump_file.read(reinterpret_cast(&ns), sizeof(ns)); + // std::cout << "ns: " << (int)ns << std::endl; + d_dump_file.read(reinterpret_cast(&status), sizeof(status)); + // std::cout << "status: " << (int)status << std::endl; + d_dump_file.read(reinterpret_cast(&type), sizeof(type)); + // std::cout << "type: " << (int)type << std::endl; + d_dump_file.read(reinterpret_cast(&AR_ratio), sizeof(AR_ratio)); + // std::cout << "AR_ratio: " << AR_ratio << std::endl; + d_dump_file.read(reinterpret_cast(&AR_thres), sizeof(AR_thres)); + // std::cout << "AR_thres: " << AR_thres << std::endl; + d_dump_file.read(reinterpret_cast(&dop[0]), sizeof(dop)); + + // for (int n = 0; n < 4; n++) + // { + // std::cout << "dop" << dop[n] << std::endl; + // } + // getchar(); + } + catch (const std::ifstream::failure &e) + { + return false; + } + return true; +} + + +bool rtklib_solver_dump_reader::restart() +{ + if (d_dump_file.is_open()) + { + d_dump_file.clear(); + d_dump_file.seekg(0, std::ios::beg); + return true; + } + else + { + return false; + } +} + + +int64_t rtklib_solver_dump_reader::num_epochs() +{ + // std::ifstream::pos_type size; + // int number_of_double_vars = 1; + // int number_of_float_vars = 17; + // int epoch_size_bytes = sizeof(uint64_t) + sizeof(double) * number_of_double_vars + + // sizeof(float) * number_of_float_vars + sizeof(unsigned int); + // std::ifstream tmpfile(d_dump_filename.c_str(), std::ios::binary | std::ios::ate); + // if (tmpfile.is_open()) + // { + // size = tmpfile.tellg(); + // int64_t nepoch = size / epoch_size_bytes; + // return nepoch; + // } + // else + // { + return 0; + // } +} + + +bool rtklib_solver_dump_reader::open_obs_file(std::string out_file) +{ + if (d_dump_file.is_open() == false) + { + try + { + d_dump_filename = out_file; + d_dump_file.exceptions(std::ifstream::failbit | std::ifstream::badbit); + d_dump_file.open(d_dump_filename.c_str(), std::ios::in | std::ios::binary); + return true; + } + catch (const std::ifstream::failure &e) + { + std::cout << "Problem opening rtklib_solver dump Log file: " << d_dump_filename.c_str() << std::endl; + return false; + } + } + else + { + return false; + } +} + + +rtklib_solver_dump_reader::~rtklib_solver_dump_reader() +{ + if (d_dump_file.is_open() == true) + { + d_dump_file.close(); + } +} diff --git a/src/tests/system-tests/libs/rtklib_solver_dump_reader.h b/src/tests/system-tests/libs/rtklib_solver_dump_reader.h new file mode 100644 index 000000000..e89659b37 --- /dev/null +++ b/src/tests/system-tests/libs/rtklib_solver_dump_reader.h @@ -0,0 +1,88 @@ +/*! + * \file rtklib_solver_dump_reader.h + * \brief Helper file for unit testing + * \author Javier Arribas, 2017. jarribas(at)cttc.es + * + * ------------------------------------------------------------------------- + * + * Copyright (C) 2010-2018 (see AUTHORS file for a list of contributors) + * + * GNSS-SDR is a software defined Global Navigation + * Satellite Systems receiver + * + * This file is part of GNSS-SDR. + * + * GNSS-SDR is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * GNSS-SDR is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with GNSS-SDR. If not, see . + * + * ------------------------------------------------------------------------- + */ + +#ifndef GNSS_SDR_RTKLIB_SOLVER_DUMP_READER_H +#define GNSS_SDR_RTKLIB_SOLVER_DUMP_READER_H + +#include +#include +#include +#include + +class rtklib_solver_dump_reader +{ +public: + ~rtklib_solver_dump_reader(); + bool read_binary_obs(); + bool restart(); + int64_t num_epochs(); + bool open_obs_file(std::string out_file); + + //rtklib_solver dump variables + // TOW + uint32_t TOW_at_current_symbol_ms; + // WEEK + uint32_t week; + // PVT GPS time + double RX_time; + // User clock offset [s] + double clk_offset_s; + // ECEF POS X,Y,X [m] + ECEF VEL X,Y,X [m/s] (6 x double) + double rr[6]; + // position variance/covariance (m^2) {c_xx,c_yy,c_zz,c_xy,c_yz,c_zx} (6 x double) + float qr[6]; + + // GEO user position Latitude [deg] + double latitude; + // GEO user position Longitude [deg] + double longitude; + // GEO user position Height [m] + double height; + + // NUMBER OF VALID SATS + uint8_t ns; + // RTKLIB solution status + uint8_t status; + // RTKLIB solution type (0:xyz-ecef,1:enu-baseline) + uint8_t type; + //AR ratio factor for validation + float AR_ratio; + //AR ratio threshold for validation + float AR_thres; + + //GDOP//PDOP//HDOP//VDOP + double dop[4]; + +private: + std::string d_dump_filename; + std::ifstream d_dump_file; +}; + +#endif //GNSS_SDR_RTKLIB_SOLVER_DUMP_READER_H diff --git a/src/tests/system-tests/libs/spirent_motion_csv_dump_reader.cc b/src/tests/system-tests/libs/spirent_motion_csv_dump_reader.cc new file mode 100644 index 000000000..f4b3d741c --- /dev/null +++ b/src/tests/system-tests/libs/spirent_motion_csv_dump_reader.cc @@ -0,0 +1,202 @@ +/*! + * \file spirent_motion_csv_dump_reader.cc + * \brief Helper file for unit testing + * \author Javier Arribas, 2017. jarribas(at)cttc.es + * + * ------------------------------------------------------------------------- + * + * Copyright (C) 2010-2018 (see AUTHORS file for a list of contributors) + * + * GNSS-SDR is a software defined Global Navigation + * Satellite Systems receiver + * + * This file is part of GNSS-SDR. + * + * GNSS-SDR is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * GNSS-SDR is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with GNSS-SDR. If not, see . + * + * ------------------------------------------------------------------------- + */ + +#include "spirent_motion_csv_dump_reader.h" +#include + +bool spirent_motion_csv_dump_reader::read_csv_obs() +{ + try + { + std::vector vec; + std::string line; + if (getline(d_dump_file, line)) + { + boost::tokenizer> tk( + line, boost::escaped_list_separator('\\', ',', '\"')); + for (boost::tokenizer>::iterator i( + tk.begin()); + i != tk.end(); ++i) + { + try + { + vec.push_back(std::stod(*i)); + } + catch (const std::exception &ex) + { + vec.push_back(0.0); + } + } + } + } + catch (const std::ifstream::failure &e) + { + return false; + } + return true; +} + +bool spirent_motion_csv_dump_reader::parse_vector(std::vector &vec) +{ + try + { + int n = 0; + TOW_ms = vec.at(n++); + Pos_X = vec.at(n++); + Pos_Y = vec.at(n++); + Pos_Z = vec.at(n++); + Vel_X = vec.at(n++); + Vel_Y = vec.at(n++); + Vel_Z = vec.at(n++); + Acc_X = vec.at(n++); + Acc_Y = vec.at(n++); + Acc_Z = vec.at(n++); + Jerk_X = vec.at(n++); + Jerk_Y = vec.at(n++); + Jerk_Z = vec.at(n++); + Lat = vec.at(n++); + Long = vec.at(n++); + Height = vec.at(n++); + Heading = vec.at(n++); + Elevation = vec.at(n++); + Bank = vec.at(n++); + Ang_vel_X = vec.at(n++); + Ang_vel_Y = vec.at(n++); + Ang_vel_Z = vec.at(n++); + Ang_acc_X = vec.at(n++); + Ang_acc_Y = vec.at(n++); + Ang_acc_Z = vec.at(n++); + Ant1_Pos_X = vec.at(n++); + Ant1_Pos_Y = vec.at(n++); + Ant1_Pos_Z = vec.at(n++); + Ant1_Vel_X = vec.at(n++); + Ant1_Vel_Y = vec.at(n++); + Ant1_Vel_Z = vec.at(n++); + Ant1_Acc_X = vec.at(n++); + Ant1_Acc_Y = vec.at(n++); + Ant1_Acc_Z = vec.at(n++); + Ant1_Lat = vec.at(n++); + Ant1_Long = vec.at(n++); + Ant1_Height = vec.at(n++); + Ant1_DOP = vec.at(n++); + return true; + } + catch (const std::exception &ex) + { + return false; + } +} +bool spirent_motion_csv_dump_reader::restart() +{ + if (d_dump_file.is_open()) + { + d_dump_file.clear(); + d_dump_file.seekg(0, std::ios::beg); + std::string line; + for (int n = 0; n < header_lines; n++) + { + getline(d_dump_file, line); + } + return true; + } + else + { + return false; + } +} + + +int64_t spirent_motion_csv_dump_reader::num_epochs() +{ + int64_t nepoch = 0; + std::string line; + std::ifstream tmpfile(d_dump_filename.c_str(), std::ios::binary | std::ios::ate); + if (tmpfile.is_open()) + { + while (std::getline(tmpfile, line)) + ++nepoch; + return nepoch - header_lines; + } + else + { + return 0; + } +} + + +bool spirent_motion_csv_dump_reader::open_obs_file(std::string out_file) +{ + if (d_dump_file.is_open() == false) + { + try + { + d_dump_filename = out_file; + d_dump_file.exceptions(std::ifstream::failbit | std::ifstream::badbit); + d_dump_file.open(d_dump_filename.c_str()); + std::string line; + for (int n = 0; n < header_lines; n++) + { + getline(d_dump_file, line); + } + return true; + } + catch (const std::ifstream::failure &e) + { + std::cout << "Problem opening Spirent CSV dump Log file: " << d_dump_filename.c_str() << std::endl; + return false; + } + } + else + { + return false; + } +} + +void spirent_motion_csv_dump_reader::close_obs_file() +{ + if (d_dump_file.is_open() == false) + { + d_dump_file.close(); + } +} + +spirent_motion_csv_dump_reader::spirent_motion_csv_dump_reader() +{ + header_lines = 2; +} + + +spirent_motion_csv_dump_reader::~spirent_motion_csv_dump_reader() +{ + if (d_dump_file.is_open() == true) + { + d_dump_file.close(); + } +} diff --git a/src/tests/system-tests/libs/spirent_motion_csv_dump_reader.h b/src/tests/system-tests/libs/spirent_motion_csv_dump_reader.h new file mode 100644 index 000000000..c7fe736cf --- /dev/null +++ b/src/tests/system-tests/libs/spirent_motion_csv_dump_reader.h @@ -0,0 +1,98 @@ +/*! + * \file spirent_motion_csv_dump_reader.h + * \brief Helper file for unit testing + * \author Javier Arribas, 2018. jarribas(at)cttc.es + * + * ------------------------------------------------------------------------- + * + * Copyright (C) 2010-2018 (see AUTHORS file for a list of contributors) + * + * GNSS-SDR is a software defined Global Navigation + * Satellite Systems receiver + * + * This file is part of GNSS-SDR. + * + * GNSS-SDR is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * GNSS-SDR is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with GNSS-SDR. If not, see . + * + * ------------------------------------------------------------------------- + */ + +#ifndef GNSS_SDR_spirent_motion_csv_dump_READER_H +#define GNSS_SDR_spirent_motion_csv_dump_READER_H + +#include +#include +#include +#include +#include + +class spirent_motion_csv_dump_reader +{ +public: + spirent_motion_csv_dump_reader(); + ~spirent_motion_csv_dump_reader(); + bool read_csv_obs(); + bool restart(); + int64_t num_epochs(); + bool open_obs_file(std::string out_file); + void close_obs_file(); + + int header_lines; + //dump variables + double TOW_ms; + double Pos_X; + double Pos_Y; + double Pos_Z; + double Vel_X; + double Vel_Y; + double Vel_Z; + double Acc_X; + double Acc_Y; + double Acc_Z; + double Jerk_X; + double Jerk_Y; + double Jerk_Z; + double Lat; + double Long; + double Height; + double Heading; + double Elevation; + double Bank; + double Ang_vel_X; + double Ang_vel_Y; + double Ang_vel_Z; + double Ang_acc_X; + double Ang_acc_Y; + double Ang_acc_Z; + double Ant1_Pos_X; + double Ant1_Pos_Y; + double Ant1_Pos_Z; + double Ant1_Vel_X; + double Ant1_Vel_Y; + double Ant1_Vel_Z; + double Ant1_Acc_X; + double Ant1_Acc_Y; + double Ant1_Acc_Z; + double Ant1_Lat; + double Ant1_Long; + double Ant1_Height; + double Ant1_DOP; + +private: + std::string d_dump_filename; + std::ifstream d_dump_file; + bool parse_vector(std::vector &vec); +}; + +#endif //GNSS_SDR_spirent_motion_csv_dump_READER_H diff --git a/src/tests/system-tests/position_test.cc b/src/tests/system-tests/position_test.cc index 63bc18016..21e8bfd81 100644 --- a/src/tests/system-tests/position_test.cc +++ b/src/tests/system-tests/position_test.cc @@ -1,7 +1,10 @@ /*! * \file position_test.cc * \brief This class implements a test for the validation of computed position. - * \author Carles Fernandez-Prades, 2016. cfernandez(at)cttc.es + * \authors
    + *
  • Carles Fernandez-Prades, 2016. cfernandez(at)cttc.es + *
  • Javier Arribas, 2018. jarribas(at)cttc.es + *
* * * ------------------------------------------------------------------------- @@ -29,6 +32,9 @@ * ------------------------------------------------------------------------- */ +#include "position_test_flags.h" +#include "rtklib_solver_dump_reader.h" +#include "spirent_motion_csv_dump_reader.h" #include "concurrent_map.h" #include "concurrent_queue.h" #include "control_thread.h" @@ -39,6 +45,7 @@ #include "test_flags.h" #include "signal_generator_flags.h" #include +#include #include #include #include @@ -48,10 +55,6 @@ #include #include - -DEFINE_string(config_file_ptest, std::string(""), "File containing the configuration parameters for the position test."); -DEFINE_bool(plot_position_test, false, "Plots results of FFTLengthTest with gnuplot"); - // For GPS NAVIGATION (L1) concurrent_queue global_gps_acq_assist_queue; concurrent_map global_gps_acq_assist_map; @@ -144,9 +147,9 @@ void StaticPositionSystemTest::geodetic2Enu(double latitude, double longitude, d geodetic2Ecef(ref_lat * d2r, ref_long * d2r, ref_h, &ref_x, &ref_y, &ref_z); - double aux_x = x - ref_x; - double aux_y = y - ref_y; - double aux_z = z - ref_z; + double aux_x = x; // - ref_x; + double aux_y = y; // - ref_y; + double aux_z = z; // - ref_z; // ECEF to NED matrix double phiP = atan2(ref_z, sqrt(std::pow(ref_x, 2.0) + std::pow(ref_y, 2.0))); @@ -386,7 +389,7 @@ int StaticPositionSystemTest::configure_receiver() config->set_property("PVT.flag_rtcm_server", "false"); config->set_property("PVT.flag_rtcm_tty_port", "false"); config->set_property("PVT.rtcm_dump_devname", "/dev/pts/1"); - config->set_property("PVT.dump", "false"); + config->set_property("PVT.dump", "true"); config->set_property("PVT.rinex_version", std::to_string(2)); config->set_property("PVT.iono_model", "OFF"); config->set_property("PVT.trop_model", "OFF"); @@ -455,123 +458,166 @@ int StaticPositionSystemTest::run_receiver() void StaticPositionSystemTest::check_results() { - std::fstream myfile(StaticPositionSystemTest::generated_kml_file, std::ios_base::in); - ASSERT_TRUE(myfile.is_open()) << "No valid kml file could be opened"; - std::string line; - std::vector pos_e; std::vector pos_n; std::vector pos_u; - // Skip header - std::getline(myfile, line); - bool is_header = true; - while (is_header) + std::istringstream iss2(FLAGS_static_position); + std::string str_aux; + std::getline(iss2, str_aux, ','); + double ref_lat = std::stod(str_aux); + std::getline(iss2, str_aux, ','); + double ref_long = std::stod(str_aux); + std::getline(iss2, str_aux, '\n'); + double ref_h = std::stod(str_aux); + double ref_e, ref_n, ref_u; + geodetic2Enu(ref_lat, ref_long, ref_h, + &ref_e, &ref_n, &ref_u); + + if (!FLAGS_use_pvt_solver_dump) { + //fall back to read receiver KML output (position only) + std::fstream myfile(StaticPositionSystemTest::generated_kml_file, std::ios_base::in); + ASSERT_TRUE(myfile.is_open()) << "No valid kml file could be opened"; + std::string line; + // Skip header std::getline(myfile, line); - ASSERT_FALSE(myfile.eof()) << "No valid kml file found."; - std::size_t found = line.find(""); - if (found != std::string::npos) is_header = false; - } - bool is_data = true; - - //read data - while (is_data) - { - if (!std::getline(myfile, line)) + bool is_header = true; + while (is_header) { - is_data = false; - break; + std::getline(myfile, line); + ASSERT_FALSE(myfile.eof()) << "No valid kml file found."; + std::size_t found = line.find(""); + if (found != std::string::npos) is_header = false; } - std::size_t found = line.find(""); - if (found != std::string::npos) - is_data = false; - else - { - std::string str2; - std::istringstream iss(line); - double value; - double lat = 0.0; - double longitude = 0.0; - double h = 0.0; - for (int i = 0; i < 3; i++) - { - std::getline(iss, str2, ','); - value = std::stod(str2); - if (i == 0) lat = value; - if (i == 1) longitude = value; - if (i == 2) h = value; - } + bool is_data = true; + //read data + while (is_data) + { + if (!std::getline(myfile, line)) + { + is_data = false; + break; + } + std::size_t found = line.find(""); + if (found != std::string::npos) + is_data = false; + else + { + std::string str2; + std::istringstream iss(line); + double value; + double lat = 0.0; + double longitude = 0.0; + double h = 0.0; + for (int i = 0; i < 3; i++) + { + std::getline(iss, str2, ','); + value = std::stod(str2); + if (i == 0) longitude = value; + if (i == 1) lat = value; + if (i == 2) h = value; + } + + double north, east, up; + geodetic2Enu(lat, longitude, h, &east, &north, &up); + // std::cout << "lat = " << lat << ", longitude = " << longitude << " h = " << h << std::endl; + // std::cout << "E = " << east << ", N = " << north << " U = " << up << std::endl; + pos_e.push_back(east); + pos_n.push_back(north); + pos_u.push_back(up); + // getchar(); + } + } + myfile.close(); + ASSERT_FALSE(pos_e.size() == 0) << "KML file is empty"; + } + else + { + //use complete binary dump from pvt solver + rtklib_solver_dump_reader pvt_reader; + pvt_reader.open_obs_file(FLAGS_pvt_solver_dump_filename); + while (pvt_reader.read_binary_obs()) + { double north, east, up; - geodetic2Enu(lat, longitude, h, &east, &north, &up); - //std::cout << "E = " << east << ", N = " << north << " U = " << up << std::endl; + geodetic2Enu(pvt_reader.latitude, pvt_reader.longitude, pvt_reader.height, &east, &north, &up); + // std::cout << "lat = " << pvt_reader.latitude << ", longitude = " << pvt_reader.longitude << " h = " << pvt_reader.height << std::endl; + // std::cout << "E = " << east << ", N = " << north << " U = " << up << std::endl; pos_e.push_back(east); pos_n.push_back(north); pos_u.push_back(up); + // getchar(); } } - myfile.close(); - ASSERT_FALSE(pos_e.size() == 0) << "KML file is empty"; - double sigma_E_2_precision = std::pow(compute_stdev_precision(pos_e), 2.0); - double sigma_N_2_precision = std::pow(compute_stdev_precision(pos_n), 2.0); - double sigma_U_2_precision = std::pow(compute_stdev_precision(pos_u), 2.0); + // compute results - double sigma_E_2_accuracy = std::pow(compute_stdev_accuracy(pos_e, 0.0), 2.0); - double sigma_N_2_accuracy = std::pow(compute_stdev_accuracy(pos_n, 0.0), 2.0); - double sigma_U_2_accuracy = std::pow(compute_stdev_accuracy(pos_u, 0.0), 2.0); - - double sum__e = std::accumulate(pos_e.begin(), pos_e.end(), 0.0); - double mean__e = sum__e / pos_e.size(); - double sum__n = std::accumulate(pos_n.begin(), pos_n.end(), 0.0); - double mean__n = sum__n / pos_n.size(); - double sum__u = std::accumulate(pos_u.begin(), pos_u.end(), 0.0); - double mean__u = sum__u / pos_u.size(); - - std::stringstream stm; - std::ofstream position_test_file; - - if (FLAGS_config_file_ptest.empty()) + if (FLAGS_static_scenario) { - stm << "---- ACCURACY ----" << std::endl; - stm << "2DRMS = " << 2 * sqrt(sigma_E_2_accuracy + sigma_N_2_accuracy) << " [m]" << std::endl; - stm << "DRMS = " << sqrt(sigma_E_2_accuracy + sigma_N_2_accuracy) << " [m]" << std::endl; - stm << "CEP = " << 0.62 * compute_stdev_accuracy(pos_n, 0.0) + 0.56 * compute_stdev_accuracy(pos_e, 0.0) << " [m]" << std::endl; - stm << "99% SAS = " << 1.122 * (sigma_E_2_accuracy + sigma_N_2_accuracy + sigma_U_2_accuracy) << " [m]" << std::endl; - stm << "90% SAS = " << 0.833 * (sigma_E_2_accuracy + sigma_N_2_accuracy + sigma_U_2_accuracy) << " [m]" << std::endl; - stm << "MRSE = " << sqrt(sigma_E_2_accuracy + sigma_N_2_accuracy + sigma_U_2_accuracy) << " [m]" << std::endl; - stm << "SEP = " << 0.51 * (sigma_E_2_accuracy + sigma_N_2_accuracy + sigma_U_2_accuracy) << " [m]" << std::endl; - stm << "Bias 2D = " << sqrt(std::pow(mean__e, 2.0) + std::pow(mean__n, 2.0)) << " [m]" << std::endl; - stm << "Bias 3D = " << sqrt(std::pow(mean__e, 2.0) + std::pow(mean__n, 2.0) + std::pow(mean__u, 2.0)) << " [m]" << std::endl; - stm << std::endl; + double sigma_E_2_precision = std::pow(compute_stdev_precision(pos_e), 2.0); + double sigma_N_2_precision = std::pow(compute_stdev_precision(pos_n), 2.0); + double sigma_U_2_precision = std::pow(compute_stdev_precision(pos_u), 2.0); + + double sigma_E_2_accuracy = std::pow(compute_stdev_accuracy(pos_e, ref_e), 2.0); + double sigma_N_2_accuracy = std::pow(compute_stdev_accuracy(pos_n, ref_n), 2.0); + double sigma_U_2_accuracy = std::pow(compute_stdev_accuracy(pos_u, ref_u), 2.0); + + double sum__e = std::accumulate(pos_e.begin(), pos_e.end(), 0.0); + double mean__e = sum__e / pos_e.size(); + double sum__n = std::accumulate(pos_n.begin(), pos_n.end(), 0.0); + double mean__n = sum__n / pos_n.size(); + double sum__u = std::accumulate(pos_u.begin(), pos_u.end(), 0.0); + double mean__u = sum__u / pos_u.size(); + + std::stringstream stm; + std::ofstream position_test_file; + + if (FLAGS_config_file_ptest.empty()) + { + stm << "---- ACCURACY ----" << std::endl; + stm << "2DRMS = " << 2 * sqrt(sigma_E_2_accuracy + sigma_N_2_accuracy) << " [m]" << std::endl; + stm << "DRMS = " << sqrt(sigma_E_2_accuracy + sigma_N_2_accuracy) << " [m]" << std::endl; + stm << "CEP = " << 0.62 * compute_stdev_accuracy(pos_n, 0.0) + 0.56 * compute_stdev_accuracy(pos_e, 0.0) << " [m]" << std::endl; + stm << "99% SAS = " << 1.122 * (sigma_E_2_accuracy + sigma_N_2_accuracy + sigma_U_2_accuracy) << " [m]" << std::endl; + stm << "90% SAS = " << 0.833 * (sigma_E_2_accuracy + sigma_N_2_accuracy + sigma_U_2_accuracy) << " [m]" << std::endl; + stm << "MRSE = " << sqrt(sigma_E_2_accuracy + sigma_N_2_accuracy + sigma_U_2_accuracy) << " [m]" << std::endl; + stm << "SEP = " << 0.51 * (sigma_E_2_accuracy + sigma_N_2_accuracy + sigma_U_2_accuracy) << " [m]" << std::endl; + stm << "Bias 2D = " << sqrt(std::pow(mean__e, 2.0) + std::pow(mean__n, 2.0)) << " [m]" << std::endl; + stm << "Bias 3D = " << sqrt(std::pow(mean__e, 2.0) + std::pow(mean__n, 2.0) + std::pow(mean__u, 2.0)) << " [m]" << std::endl; + stm << std::endl; + } + + stm << "---- PRECISION ----" << std::endl; + stm << "2DRMS = " << 2 * sqrt(sigma_E_2_precision + sigma_N_2_precision) << " [m]" << std::endl; + stm << "DRMS = " << sqrt(sigma_E_2_precision + sigma_N_2_precision) << " [m]" << std::endl; + stm << "CEP = " << 0.62 * compute_stdev_precision(pos_n) + 0.56 * compute_stdev_precision(pos_e) << " [m]" << std::endl; + stm << "99% SAS = " << 1.122 * (sigma_E_2_precision + sigma_N_2_precision + sigma_U_2_precision) << " [m]" << std::endl; + stm << "90% SAS = " << 0.833 * (sigma_E_2_precision + sigma_N_2_precision + sigma_U_2_precision) << " [m]" << std::endl; + stm << "MRSE = " << sqrt(sigma_E_2_precision + sigma_N_2_precision + sigma_U_2_precision) << " [m]" << std::endl; + stm << "SEP = " << 0.51 * (sigma_E_2_precision + sigma_N_2_precision + sigma_U_2_precision) << " [m]" << std::endl; + + std::cout << stm.rdbuf(); + std::string output_filename = "position_test_output_" + StaticPositionSystemTest::generated_kml_file.erase(StaticPositionSystemTest::generated_kml_file.length() - 3, 3) + "txt"; + position_test_file.open(output_filename.c_str()); + if (position_test_file.is_open()) + { + position_test_file << stm.str(); + position_test_file.close(); + } + + // Sanity Check + double precision_SEP = 0.51 * (sigma_E_2_precision + sigma_N_2_precision + sigma_U_2_precision); + ASSERT_LT(precision_SEP, 20.0); + + if (FLAGS_plot_position_test == true) + { + print_results(pos_e, pos_n, pos_u); + } } - - stm << "---- PRECISION ----" << std::endl; - stm << "2DRMS = " << 2 * sqrt(sigma_E_2_precision + sigma_N_2_precision) << " [m]" << std::endl; - stm << "DRMS = " << sqrt(sigma_E_2_precision + sigma_N_2_precision) << " [m]" << std::endl; - stm << "CEP = " << 0.62 * compute_stdev_precision(pos_n) + 0.56 * compute_stdev_precision(pos_e) << " [m]" << std::endl; - stm << "99% SAS = " << 1.122 * (sigma_E_2_precision + sigma_N_2_precision + sigma_U_2_precision) << " [m]" << std::endl; - stm << "90% SAS = " << 0.833 * (sigma_E_2_precision + sigma_N_2_precision + sigma_U_2_precision) << " [m]" << std::endl; - stm << "MRSE = " << sqrt(sigma_E_2_precision + sigma_N_2_precision + sigma_U_2_precision) << " [m]" << std::endl; - stm << "SEP = " << 0.51 * (sigma_E_2_precision + sigma_N_2_precision + sigma_U_2_precision) << " [m]" << std::endl; - - std::cout << stm.rdbuf(); - std::string output_filename = "position_test_output_" + StaticPositionSystemTest::generated_kml_file.erase(StaticPositionSystemTest::generated_kml_file.length() - 3, 3) + "txt"; - position_test_file.open(output_filename.c_str()); - if (position_test_file.is_open()) + else { - position_test_file << stm.str(); - position_test_file.close(); - } - - // Sanity Check - double precision_SEP = 0.51 * (sigma_E_2_precision + sigma_N_2_precision + sigma_U_2_precision); - ASSERT_LT(precision_SEP, 20.0); - - if (FLAGS_plot_position_test == true) - { - print_results(pos_e, pos_n, pos_u); + //dynamic position } } @@ -698,7 +744,7 @@ TEST_F(StaticPositionSystemTest, Position_system_test) configure_receiver(); // Run the receiver - EXPECT_EQ(run_receiver(), 0) << "Problem executing the software-defined signal generator"; + EXPECT_EQ(run_receiver(), 0) << "Problem executing GNSS-SDR"; // Check results check_results();