1
0
mirror of https://github.com/gnss-sdr/gnss-sdr synced 2025-11-13 05:37:20 +00:00

Added J.Arribas contributions: PVT with basic least squares and rinex 2.1 output is now enabled, tracking channels now estimate the CN0 and performs a basic carrier lock detector and returns to acquisition if the tracking loss the lock.

git-svn-id: https://svn.code.sf.net/p/gnss-sdr/code/trunk@75 64b25241-fba3-4117-9849-534c7e92360d
This commit is contained in:
Javier Arribas
2011-10-28 15:01:46 +00:00
parent 0069bef236
commit 1040e6865d
25 changed files with 961 additions and 373 deletions

View File

@@ -45,13 +45,6 @@
#include <glog/log_severity.h>
#include <glog/logging.h>
/* The extern keyword declares a variable or function and specifies
* that it has external linkage (its name is visible from files other
* than the one in which it's defined). When modifying a variable,
* extern specifies that the variable has static duration (it is allocated
* when the program begins and deallocated when the program ends).
* The variable is defined in main.cc
*/
extern concurrent_queue<gps_navigation_message> global_gps_nav_msg_queue;
using google::LogMessage;

View File

@@ -52,18 +52,34 @@ gps_l1_ca_observables_cc::gps_l1_ca_observables_cc(unsigned int nchannels, gr_ms
d_dump = dump;
d_nchannels = nchannels;
d_rinex_printer.set_headers("GNSS-SDR"); //TODO: read filename from config
d_ls_pvt=new gps_l1_ca_ls_pvt(nchannels);
d_ephemeris_clock_s=0.0;
if (d_dump==true)
{
std::stringstream d_dump_filename_str;//create a stringstream to form the dump filename
d_dump_filename_str<<"./data/obs.dat"; //TODO: get filename and path from config in the adapter
d_dump_filename=d_dump_filename_str.str();
d_dump_file.open(d_dump_filename.c_str(), std::ios::out | std::ios::binary);
}
}
gps_l1_ca_observables_cc::~gps_l1_ca_observables_cc() {
delete d_ls_pvt;
}
bool pairCompare( pair<int,gnss_synchro> a, pair<int,gnss_synchro> b)
bool pairCompare_min( pair<int,gnss_synchro> a, pair<int,gnss_synchro> b)
{
return a.second.last_preamble_index < b.second.last_preamble_index;
return (a.second.preamble_delay_ms+a.second.prn_delay_ms) < (b.second.preamble_delay_ms+b.second.prn_delay_ms);
}
bool pairCompare_max( pair<int,gnss_synchro> a, pair<int,gnss_synchro> b)
{
return (a.second.preamble_delay_ms+a.second.prn_delay_ms) > (b.second.preamble_delay_ms+b.second.prn_delay_ms);
}
int gps_l1_ca_observables_cc::general_work (int noutput_items, gr_vector_int &ninput_items,
gr_vector_const_void_star &input_items, gr_vector_void_star &output_items) {
@@ -71,7 +87,7 @@ int gps_l1_ca_observables_cc::general_work (int noutput_items, gr_vector_int &ni
// CONSTANTS TODO: place in a file
const float code_length_s=0.001; //1 ms
const float C_m_ms= GPS_C_m_s/1000; // The speed of light, [m/ms]
const float C_m_ms= GPS_C_m_s/1000.0; // The speed of light, [m/ms]
const float nav_sol_period_ms=1000;
//--- Find number of samples per spreading code ----------------------------
@@ -84,46 +100,60 @@ int gps_l1_ca_observables_cc::general_work (int noutput_items, gr_vector_int &ni
map<int,float> pseudoranges;
map<int,float>::iterator pseudoranges_iter;
map<int,float> pseudoranges_dump;
float min_preamble_delay_ms;
float max_preamble_delay_ms;
bool flag_valid_pseudoranges=false;
unsigned long int min_preamble_index;
float prn_delay_ms;
float pseudoranges_timestamp_ms;
float traveltime_ms;
float pseudorange_m;
int pseudoranges_reference_sat_ID=0;
for (unsigned int i=0; i<d_nchannels ; i++)
{
if (in[i][0].valid_word) //if this channel have valid word
{
gps_words.insert(pair<int,gnss_synchro>(in[i][0].satellite_PRN,in[i][0])); //record the word structure in a map for pseudoranges
gps_words.insert(pair<int,gnss_synchro>(in[i][0].channel_ID,in[i][0])); //record the word structure in a map for pseudoranges
}
}
if(gps_words.size()>0)
{
// find the minimum index (nearest satellite, will be the reference)
gps_words_iter=min_element(gps_words.begin(),gps_words.end(),pairCompare);
min_preamble_index=gps_words_iter->second.last_preamble_index;
//compute the pseudoranges
for(gps_words_iter = gps_words.begin(); gps_words_iter != gps_words.end(); gps_words_iter++)
{
prn_delay_ms=gps_words_iter->second.prn_delay/(float)samples_per_code;
traveltime_ms=(float)(1000*(gps_words_iter->second.last_preamble_index-min_preamble_index))/(float)samples_per_code+GPS_STARTOFFSET_ms+prn_delay_ms;
//cout<<"traveltime ms"<<gps_words_iter->first<<" ="<<traveltime_ms<<endl;
pseudorange_m=traveltime_ms*C_m_ms;
pseudoranges.insert(pair<int,float>(gps_words_iter->first,pseudorange_m)); //record the preamble index in a map
}
// find the minimum index (nearest satellite, will be the reference)
gps_words_iter=min_element(gps_words.begin(),gps_words.end(),pairCompare_min);
min_preamble_delay_ms=gps_words_iter->second.preamble_delay_ms+gps_words_iter->second.prn_delay_ms; //[ms]
pseudoranges_timestamp_ms=min_preamble_delay_ms; //save the shortest pseudorange timestamp to compute the RINEX timestamp
pseudoranges_reference_sat_ID=gps_words_iter->second.satellite_PRN;
gps_words_iter=max_element(gps_words.begin(),gps_words.end(),pairCompare_max);
max_preamble_delay_ms=gps_words_iter->second.preamble_delay_ms; //[ms]
if ((max_preamble_delay_ms-min_preamble_delay_ms)<70) flag_valid_pseudoranges=true;
//compute the pseudoranges
for(gps_words_iter = gps_words.begin(); gps_words_iter != gps_words.end(); gps_words_iter++)
{
std::cout<<"prn_delay="<<gps_words_iter->second.prn_delay_ms<<std::endl;
traveltime_ms=gps_words_iter->second.preamble_delay_ms+gps_words_iter->second.prn_delay_ms-min_preamble_delay_ms+GPS_STARTOFFSET_ms; //[ms]
pseudorange_m=traveltime_ms*C_m_ms; // [m]
pseudoranges.insert(pair<int,float>(gps_words_iter->second.satellite_PRN,pseudorange_m)); //record the preamble index in a map
if (d_dump==true)
{
pseudoranges_dump.insert(pair<int,float>(gps_words_iter->second.channel_ID,pseudorange_m));
}
}
// write the pseudoranges to RINEX OBS file
// 1- need a valid clock
if (d_last_nav_msg.d_satellite_PRN>0)
if (flag_valid_pseudoranges==true and d_last_nav_msg.d_satellite_PRN>0)
{
std::cout<<"d_inter_frame_sec_counter="<<d_inter_frame_sec_counter<<std::endl;
d_rinex_printer.LogRinex2Obs(d_last_nav_msg,d_inter_frame_sec_counter,pseudoranges);
//d_rinex_printer.LogRinex2Obs(d_last_nav_msg,d_ephemeris_clock_s+((double)pseudoranges_timestamp_ms-d_ephemeris_timestamp_ms)/1000.0,pseudoranges);
// compute on the fly PVT solution
d_ls_pvt->get_PVT(pseudoranges,d_ephemeris_clock_s+((double)pseudoranges_timestamp_ms-d_ephemeris_timestamp_ms)/1000.0);
}
d_inter_frame_sec_counter+=((float)NAVIGATION_OUTPUT_RATE_MS)/1000.0; //TODO: synchronize the gps time of the ephemeris with the obs
}
//debug
@@ -134,29 +164,36 @@ int gps_l1_ca_observables_cc::general_work (int noutput_items, gr_vector_int &ni
{
cout<<"Pseudoranges =("<<pseudoranges_iter->first<<","<<pseudoranges_iter->second<<")"<<endl;
}
gps_navigation_message nav_msg;
if (d_nav_queue->try_pop(nav_msg)==true)
{
cout<<"New ephemeris record has arrived!"<<endl;
cout<<"d_channel_ID="<<nav_msg.d_channel_ID<<endl;
cout<<"d_satellite_PRN="<<nav_msg.d_satellite_PRN<<endl;
cout<<"d_satpos_X="<<nav_msg.d_satpos_X<<endl;
cout<<"d_satpos_Y="<<nav_msg.d_satpos_Y<<endl;
cout<<"d_satpos_Z="<<nav_msg.d_satpos_Z<<endl;
cout<<"d_master_clock="<<nav_msg.d_master_clock<<endl;
cout<<"d_satClkCorr="<<nav_msg.d_satClkCorr<<endl;
cout<<"d_dtr="<<nav_msg.d_dtr<<endl;
// write ephemeris to RINES NAV file
// TODO: check operation ok
cout<<"New ephemeris record has arrived from SAT ID "<<nav_msg.d_satellite_PRN<<endl;
d_last_nav_msg=nav_msg;
d_inter_frame_sec_counter=0; //reset the interframe seconds counter
d_rinex_printer.LogRinex2Nav(nav_msg);
d_ls_pvt->d_ephemeris[nav_msg.d_channel_ID]=nav_msg;
// **** update pseudoranges clock ****
if (nav_msg.d_satellite_PRN==pseudoranges_reference_sat_ID)
{
d_ephemeris_clock_s=d_last_nav_msg.d_TOW;
d_ephemeris_timestamp_ms=d_last_nav_msg.d_subframe1_timestamp_ms;
}
// **** write ephemeris to RINES NAV file
//d_rinex_printer.LogRinex2Nav(nav_msg);
}
if (d_dump==true)
{
float tmp_float=0.0;
for (int i=0;i<d_nchannels;i++)
{
pseudoranges_iter=pseudoranges_dump.find(i);
if (pseudoranges_iter!=pseudoranges_dump.end())
{
d_dump_file.write((char*)&pseudoranges_iter->second, sizeof(float));
}else{
d_dump_file.write((char*)&tmp_float, sizeof(float));
}
}
}
consume_each(1); //one by one
return 0;
}

View File

@@ -24,6 +24,7 @@
#include "gps_navigation_message.h"
#include "rinex_2_1_printer.h"
#include "gps_l1_ca_ls_pvt.h"
#include "GPS_L1_CA.h"
@@ -56,10 +57,14 @@ private:
rinex_printer d_rinex_printer; // RINEX printer class
double d_inter_frame_sec_counter; // counter for seconds between GPS frames
gps_navigation_message d_last_nav_msg; //last navigation message
double d_ephemeris_clock_s;
double d_ephemeris_timestamp_ms;
gps_l1_ca_ls_pvt *d_ls_pvt;
public:
~gps_l1_ca_observables_cc ();

View File

@@ -0,0 +1,316 @@
/**
* Copyright notice
*/
/**
* Author: Javier Arribas, 2011. jarribas(at)cttc.es
*/
#include <itpp/itbase.h>
#include <itpp/stat/misc_stat.h>
#include <itpp/base/matfunc.h>
using namespace itpp;
#include "gps_l1_ca_ls_pvt.h"
gps_l1_ca_ls_pvt::gps_l1_ca_ls_pvt(int nchannels)
{
// init empty ephemerids for all the available GNSS channels
d_nchannels=nchannels;
d_ephemeris=new gps_navigation_message[nchannels];
}
gps_l1_ca_ls_pvt::~gps_l1_ca_ls_pvt()
{
delete d_ephemeris;
}
vec gps_l1_ca_ls_pvt::e_r_corr(double traveltime, vec X_sat) {
/*
%E_R_CORR Returns rotated satellite ECEF coordinates due to Earth
%rotation during signal travel time
%
%X_sat_rot = e_r_corr(traveltime, X_sat);
%
% Inputs:
% travelTime - signal travel time
% X_sat - satellite's ECEF coordinates
%
% Outputs:
% X_sat_rot - rotated satellite's coordinates (ECEF)
*/
double Omegae_dot = 7.292115147e-5; // rad/sec
//--- Find rotation angle --------------------------------------------------
double omegatau;
omegatau = Omegae_dot * traveltime;
//--- Make a rotation matrix -----------------------------------------------
mat R3=zeros(3,3);
R3(0, 0)= cos(omegatau);
R3(0, 1)= sin(omegatau);
R3(0, 2)= 0.0;
R3(1, 0)=-sin(omegatau);
R3(1, 1)= cos(omegatau);
R3(1, 2)=0.0;
R3(2, 0)= 0.0;
R3(2, 1)= 0.0;
R3(2, 2)= 1;
//--- Do the rotation ------------------------------------------------------
vec X_sat_rot;
X_sat_rot = R3 * X_sat;
return X_sat_rot;
}
vec gps_l1_ca_ls_pvt::leastSquarePos(mat satpos, vec obs, mat w) {
//Function calculates the Least Square Solution.
//pos= leastSquarePos(satpos, obs, w);
// Inputs:
// satpos - Satellites positions (in ECEF system: [X; Y; Z;]
// obs - Observations - the pseudorange measurements to each
// satellite
// w - weigths vector
// Outputs:
// pos - receiver position and receiver clock error
// (in ECEF system: [X, Y, Z, dt])
//////////////////////////////////////////////////////////////////////////
// el - Satellites elevation angles (degrees)
// az - Satellites azimuth angles (degrees)
// dop - Dilutions Of Precision ([GDOP PDOP HDOP VDOP TDOP])
//=== Initialization =======================================================
int nmbOfIterations = 10; // TODO: include in config
//double dtr = GPS_PI / 180.0;
int nmbOfSatellites;
nmbOfSatellites = satpos.cols();
vec pos = "0.0 0.0 0.0 0.0";
mat A;
mat omc;
mat az;
mat el;
A=zeros(nmbOfSatellites,4);
omc=zeros(nmbOfSatellites,1);
az=zeros(1,nmbOfSatellites);
el=zeros(1,nmbOfSatellites);
for (int i = 0; i < nmbOfSatellites; i++) {
for (int j = 0; j < 4; j++) {
A.set(i, j, 0.0);
}
omc(i, 0)=0.0;
az(0, i)=0.0;
}
el = az;
mat X = satpos;
vec Rot_X;
double rho2;
double traveltime;
double trop;
mat mat_tmp;
vec x;
//=== Iteratively find receiver position ===================================
for (int iter = 0; iter < nmbOfIterations; iter++) {
for (int i = 0; i < nmbOfSatellites; i++) {
if (iter == 0) {
//--- Initialize variables at the first iteration --------------
Rot_X=X.get_col(i);
trop = 0.0;
} else {
//--- Update equations -----------------------------------------
rho2 = (X(0, i) - pos(0))*(X(0, i) - pos(0)) + (X(1, i) - pos(1))*(X(1, i) - pos(1))+ (X(2,i) - pos(2))*(X(2,i) - pos(2));
traveltime = sqrt(rho2) / GPS_C_m_s;
//--- Correct satellite position (do to earth rotation) --------
Rot_X = e_r_corr(traveltime, X.get_col(i));
//--- Find the elevation angel of the satellite ----------------
//[az(i), el(i), dist] = topocent(pos(1:3, :), Rot_X - pos(1:3, :));
}
//--- Apply the corrections ----------------------------------------
omc(i) = (obs(i) - norm(Rot_X - pos.left(3)) - pos(4) - trop);
//--- Construct the A matrix ---------------------------------------
A.set(i, 0, (-(Rot_X(0) - pos(0))) / obs(i));
A.set(i, 1, (-(Rot_X(1) - pos(1))) / obs(i));
A.set(i, 2, (-(Rot_X(2) - pos(2))) / obs(i));
A.set(i, 3, 1.0);
}
// These lines allow the code to exit gracefully in case of any errors
//if (rank(A) != 4) {
// pos.clear();
// return pos;
//}
//--- Find position update ---------------------------------------------
x = ls_solve_od(w*A,w*omc);
//--- Apply position update --------------------------------------------
pos = pos + x;
}
return pos;
}
void gps_l1_ca_ls_pvt::get_PVT(std::map<int,float> pseudoranges,double GPS_current_time)
{
std::map<int,float>::iterator pseudoranges_iter;
mat satpos;
mat W=eye(d_nchannels); //channels weights matrix
vec obs=zeros(d_nchannels); // pseudoranges observation vector
satpos=zeros(3,d_nchannels); //satellite positions matrix
int valid_obs=0; //valid observations counter
for (int i=0; i<d_nchannels; i++)
{
if (d_ephemeris[i].satellite_validation()==true)
{
pseudoranges_iter=pseudoranges.find(d_ephemeris[i].d_satellite_PRN);
if (pseudoranges_iter!=pseudoranges.end())
{
W(i,i)=1; // TODO: Place here the satellite CN0 (power level, or weight factor)
// compute the GPS master clock
d_ephemeris[i].master_clock(GPS_current_time);
// compute the satellite current ECEF position
d_ephemeris[i].satpos();
// compute the clock error including relativistic effects
d_ephemeris[i].relativistic_clock_correction(GPS_current_time);
satpos(0,i)=d_ephemeris[i].d_satpos_X;
satpos(1,i)=d_ephemeris[i].d_satpos_Y;
satpos(2,i)=d_ephemeris[i].d_satpos_Z;
obs(i)=pseudoranges_iter->second+d_ephemeris[i].d_satClkCorr*GPS_C_m_s;
valid_obs++;
}else{
// no valid pseudorange for the current channel
W(i,i)=0; // channel de-activated
obs(i)=1; // to avoid algorithm problems (divide by zero)
}
}else{
// no valid ephemeris for the current channel
W(i,i)=0; // channel de-activated
obs(i)=1; // to avoid algorithm problems (divide by zero)
}
}
std::cout<<"PVT: valid observations="<<valid_obs<<std::endl;
if (valid_obs>=4)
{
vec mypos;
mypos=leastSquarePos(satpos,obs,W);
std::cout << "Position ("<<GPS_current_time<<") ECEF = " << mypos << std::endl;
cart2geo(mypos(0), mypos(1), mypos(2), 4);
std::cout << "Position ("<<GPS_current_time<<") Lat = " << d_latitude_d << " Long ="<< d_longitude_d <<" Height="<<d_height_m<< std::endl;
}
}
void gps_l1_ca_ls_pvt::cart2geo(double X, double Y, double Z, int elipsoid_selection)
{
//function [phi, lambda, h] = cart2geo(X, Y, Z, i)
//CART2GEO Conversion of Cartesian coordinates (X,Y,Z) to geographical
//coordinates (phi, lambda, h) on a selected reference ellipsoid.
//
//[phi, lambda, h] = cart2geo(X, Y, Z, i);
//
// Choices i of Reference Ellipsoid for Geographical Coordinates
// 0. International Ellipsoid 1924
// 1. International Ellipsoid 1967
// 2. World Geodetic System 1972
// 3. Geodetic Reference System 1980
// 4. World Geodetic System 1984
double a[5] = {6378388, 6378160, 6378135, 6378137, 6378137};
double f[5] = {1/297, 1/298.247, 1/298.26, 1/298.257222101, 1/298.257223563};
double lambda;
lambda = atan2(Y,X);
double ex2;
ex2 = (2-f[elipsoid_selection])*f[elipsoid_selection]/((1-f[elipsoid_selection])*(1-f[elipsoid_selection]));
double c;
c = a[elipsoid_selection]*sqrt(1+ex2);
double phi;
phi = atan(Z/((sqrt(X*X+Y*Y)*(1-(2-f[elipsoid_selection]))*f[elipsoid_selection])));
double h = 0.1;
double oldh = 0;
double N;
int iterations = 0;
do{
oldh = h;
N = c/sqrt(1+ex2*(cos(phi)*cos(phi)));
phi = atan(Z/((sqrt(X*X+Y*Y)*(1-(2-f[elipsoid_selection])*f[elipsoid_selection]*N/(N+h)))));
h = sqrt(X*X+Y*Y)/cos(phi)-N;
iterations = iterations + 1;
if (iterations > 100)
{
std::cout<<"Failed to approximate h with desired precision. h-oldh= "<<h-oldh<<std::endl;
break;
}
}while (abs(h-oldh) > 1.0e-12);
d_latitude_d = phi*180.0/GPS_PI;
d_longitude_d = lambda*180/pi;
d_height_m = h;
}
//void gps_l1_ca_ls_pvt::topocent(traveltime, X_sat)
//{
/*
%function [Az, El, D] = topocent(X, dx)
%TOPOCENT Transformation of vector dx into topocentric coordinate
% system with origin at X.
% Both parameters are 3 by 1 vectors.
%
%[Az, El, D] = topocent(X, dx);
%
% Inputs:
% X - vector origin corrdinates (in ECEF system [X; Y; Z;])
% dx - vector ([dX; dY; dZ;]).
%
% Outputs:
% D - vector length. Units like units of the input
% Az - azimuth from north positive clockwise, degrees
% El - elevation angle, degrees
dtr = pi/180;
[phi, lambda, h] = togeod(6378137, 298.257223563, X(1), X(2), X(3));
cl = cos(lambda * dtr);
sl = sin(lambda * dtr);
cb = cos(phi * dtr);
sb = sin(phi * dtr);
F = [-sl -sb*cl cb*cl;
cl -sb*sl cb*sl;
0 cb sb];
local_vector = F' * dx;
E = local_vector(1);
N = local_vector(2);
U = local_vector(3);
hor_dis = sqrt(E^2 + N^2);
if hor_dis < 1.e-20
Az = 0;
El = 90;
else
Az = atan2(E, N)/dtr;
El = atan2(U, hor_dis)/dtr;
end
if Az < 0
Az = Az + 360;
end
D = sqrt(dx(1)^2 + dx(2)^2 + dx(3)^2);
%%%%%%%%% end topocent.m %%%%%%%%%
*/
//}

View File

@@ -0,0 +1,57 @@
/**
* Copyright notice
*/
/**
* Author: Javier Arribas, 2011. jarribas(at)cttc.es
* Luis Esteve, 2011. luis(at)epsilon-formacion.com
*/
#ifndef GPS_L1_CA_LS_PVT_H_
#define GPS_L1_CA_LS_PVT_H_
#include <string>
#include <iostream>
#include <sstream>
#include <stdlib.h>
#include <stdio.h>
#include <sys/time.h>
#include <time.h>
#include <math.h>
#include <map>
#include <algorithm>
#include "gps_navigation_message.h"
#include "GPS_L1_CA.h"
#include <itpp/itbase.h>
#include <itpp/stat/misc_stat.h>
#include <itpp/base/matfunc.h>
using namespace itpp;
class gps_l1_ca_ls_pvt
{
private:
vec leastSquarePos(mat satpos, vec obs, mat w);
vec e_r_corr(double traveltime, vec X_sat);
//void cart2geo();
//void topocent();
public:
int d_nchannels;
gps_navigation_message* d_ephemeris;
double d_pseudoranges_time_ms;
double d_latitude_d;
double d_longitude_d;
double d_height_m;
double d_x_m;
double d_y_m;
double d_z_m;
gps_l1_ca_ls_pvt(int nchannels);
~gps_l1_ca_ls_pvt();
void get_PVT(std::map<int,float> pseudoranges,double GPS_current_time);
void cart2geo(double X, double Y, double Z, int elipsoid_selection);
};
#endif

View File

@@ -1,3 +1,4 @@
project : build-dir ../../../../build ;
obj rinex_2_1_printer : rinex_2_1_printer.cc ;
obj rinex_2_1_printer : rinex_2_1_printer.cc ;
obj gps_l1_ca_ls_pvt : gps_l1_ca_ls_pvt.cc ;

View File

@@ -192,7 +192,7 @@ void rinex_printer::Rinex2ObsHeader()
}
void rinex_printer::LogRinex2Obs(gps_navigation_message nav_msg,double interframe_seconds, std::map<int,float> pseudoranges)
void rinex_printer::LogRinex2Obs(gps_navigation_message nav_msg,double pseudoranges_clock, std::map<int,float> pseudoranges)
{
int ss;
char sat_vis[36];
@@ -224,7 +224,7 @@ void rinex_printer::LogRinex2Obs(gps_navigation_message nav_msg,double interfram
double decimalday,daydecimalhour,decimalhour,decimalmin,decimalsec;
double day,hour,minutes,seconds,enterseconds,a;
double gpstime;
gpstime=nav_msg.d_master_clock;
gpstime=pseudoranges_clock; //[s]
//calculate date of gps time:
//Days & weeks between 00h 1 Jan 1970 and 00h 6 Jan 1980
//520 weeks and 12 days.
@@ -233,7 +233,7 @@ void rinex_printer::LogRinex2Obs(gps_navigation_message nav_msg,double interfram
tmPtr = gmtime(&temps);
strftime( cad1, 20, " %y %m %d", tmPtr );
strftime( cad2, 20, " %Y %m %d", tmPtr );
decimalday=((gpstime+interframe_seconds)/(24*3600));//Dies dins de la semana
decimalday=(gpstime/(24*3600));//Dies dins de la semana
daydecimalhour=modf(decimalday,&day);//day=#dies sencers, daydecimalhour=porcio de dia
daydecimalhour=daydecimalhour*24;//porcio de dia en hores
decimalhour=modf(daydecimalhour,&hour);//hour=hora del dia; decimalhour=porcio d'hora