Skip to content

Commit

Permalink
Add new command-line arguments to rnx2rtkp to enable post-processing of
Browse files Browse the repository at this point in the history
wide-lane corrections from Skylark:
1. -w argument enables widelane integer ambiguity resolution
2. -z argument to output SPP position if no RTK solution
3. -rb argument to specify reference position to use for base station.
   New posopt (POSOPT_RINEX_DYN==6) to read base station position from
   RINEX header and subsequent site occupation events
  • Loading branch information
dgburr committed Feb 18, 2022
1 parent 3243afe commit 0123f7d
Show file tree
Hide file tree
Showing 5 changed files with 59 additions and 21 deletions.
49 changes: 33 additions & 16 deletions app/consapp/rnx2rtkp/rnx2rtkp.c
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,7 @@ static const char *help[]={
"",
" usage: rnx2rtkp [option]... file file [...]",
"",
" Read RINEX OBS/NAV/GNAV/HNAV/CLK, SP3, SBAS message log files and ccompute ",
" Read RINEX OBS/NAV/GNAV/HNAV/CLK, SP3, SBAS message log files and compute ",
" receiver (rover) positions and output position solutions.",
" The first RINEX OBS file shall contain receiver (rover) observations. For the",
" relative mode, the second RINEX OBS file shall contain reference",
Expand Down Expand Up @@ -57,16 +57,22 @@ static const char *help[]={
" -c forward/backward combined solutions [off]",
" -i instantaneous integer ambiguity resolution [off]",
" -h fix and hold for integer ambiguity resolution [off]",
" -w widelane integer ambiguity resolution [off]",
" -e output x/y/z-ecef position [latitude/longitude/height]",
" -a output e/n/u-baseline [latitude/longitude/height]",
" -n output NMEA-0183 GGA sentence [off]",
" -g output latitude/longitude in the form of ddd mm ss.ss' [ddd.ddd]",
" -t output time in the form of yyyy/mm/dd hh:mm:ss.ss [sssss.ss]",
" -u output time in utc [gpst]",
" -z output single point position when unable to compute",
" DGPS/float/fix/PPP position",
" -d col number of decimals in time [3]",
" -s sep field separator [' ']",
" -r x y z reference (base) receiver ecef pos (m) [average of single pos]",
" rover receiver ecef pos (m) for fixed or ppp-fixed mode",
" -rb mode reference (base) receiver position mode (1:average of single pos,",
" 2:read from file,3:read from RINEX header,6:read from RINEX header",
" and subsequent site occupancy events) [1]",
" -l lat lon hgt reference (base) receiver latitude/longitude/height (deg/m)",
" rover latitude/longitude/height for fixed or ppp-fixed mode",
" -y level output soltion status (0:off,1:states,2:residuals) [0]",
Expand Down Expand Up @@ -99,16 +105,18 @@ int main(int argc, char **argv)
gtime_t ts={0},te={0};
double tint=0.0,es[]={2000,1,1,0,0,0},ee[]={2000,12,31,23,59,59},pos[3];
int i,j,n,ret;
char *infile[MAXFILE],*outfile="",*p;

prcopt.mode =PMODE_KINEMA;
char *infile[MAXFILE] = {[0 ... (MAXFILE-1)] = ""};
char *outfile = "";
char *p = NULL;

prcopt.mode = PMODE_KINEMA;
prcopt.navsys=0;
prcopt.refpos=1;
prcopt.glomodear=1;
solopt.timef=0;
sprintf(solopt.prog ,"%s ver.%s %s",PROGNAME,VER_RTKLIB,PATCH_LEVEL);
sprintf(filopt.trace,"%s.trace",PROGNAME);

/* load options from configuration file */
for (i=1;i<argc;i++) {
if (!strcmp(argv[i],"-k")&&i+1<argc) {
Expand Down Expand Up @@ -136,12 +144,12 @@ int main(int argc, char **argv)
else if (!strcmp(argv[i],"-sys")&&i+1<argc) {
for (p=argv[++i];*p;p++) {
switch (*p) {
case 'G': prcopt.navsys|=SYS_GPS;
case 'R': prcopt.navsys|=SYS_GLO;
case 'E': prcopt.navsys|=SYS_GAL;
case 'J': prcopt.navsys|=SYS_QZS;
case 'C': prcopt.navsys|=SYS_CMP;
case 'I': prcopt.navsys|=SYS_IRN;
case 'G': prcopt.navsys|=SYS_GPS; break;
case 'R': prcopt.navsys|=SYS_GLO; break;
case 'E': prcopt.navsys|=SYS_GAL; break;
case 'J': prcopt.navsys|=SYS_QZS; break;
case 'C': prcopt.navsys|=SYS_CMP; break;
case 'I': prcopt.navsys|=SYS_IRN; break;
}
if (!(p=strchr(p,','))) break;
}
Expand All @@ -152,21 +160,27 @@ int main(int argc, char **argv)
else if (!strcmp(argv[i],"-d")&&i+1<argc) solopt.timeu=atoi(argv[++i]);
else if (!strcmp(argv[i],"-b")) prcopt.soltype=1;
else if (!strcmp(argv[i],"-c")) prcopt.soltype=2;
else if (!strcmp(argv[i],"-i")) prcopt.modear=2;
else if (!strcmp(argv[i],"-h")) prcopt.modear=3;
else if (!strcmp(argv[i],"-i")) prcopt.modear=ARMODE_INST;
else if (!strcmp(argv[i],"-h")) {
if (prcopt.modear!=ARMODE_WL) prcopt.modear=ARMODE_FIXHOLD;
prcopt.wlmodear=1;
}
else if (!strcmp(argv[i],"-t")) solopt.timef=1;
else if (!strcmp(argv[i],"-u")) solopt.times=TIMES_UTC;
else if (!strcmp(argv[i],"-z")) prcopt.outsingle=1;
else if (!strcmp(argv[i],"-e")) solopt.posf=SOLF_XYZ;
else if (!strcmp(argv[i],"-a")) solopt.posf=SOLF_ENU;
else if (!strcmp(argv[i],"-n")) solopt.posf=SOLF_NMEA;
else if (!strcmp(argv[i],"-g")) solopt.degf=1;
else if (!strcmp(argv[i],"-w")) prcopt.modear=ARMODE_WL;
else if (!strcmp(argv[i],"-r")&&i+3<argc) {
prcopt.refpos=prcopt.rovpos=0;
prcopt.refpos=prcopt.rovpos=POSOPT_POS;
for (j=0;j<3;j++) prcopt.rb[j]=atof(argv[++i]);
matcpy(prcopt.ru,prcopt.rb,3,1);
}
else if (!strcmp(argv[i],"-rb")&&i+1<argc) prcopt.refpos=atoi(argv[++i]);
else if (!strcmp(argv[i],"-l")&&i+3<argc) {
prcopt.refpos=prcopt.rovpos=0;
prcopt.refpos=prcopt.rovpos=POSOPT_POS;
for (j=0;j<3;j++) pos[j]=atof(argv[++i]);
for (j=0;j<2;j++) pos[j]*=D2R;
pos2ecef(pos,prcopt.rb);
Expand All @@ -180,12 +194,15 @@ int main(int argc, char **argv)
if (!prcopt.navsys) {
prcopt.navsys=SYS_GPS|SYS_GLO;
}
if (prcopt.modear==ARMODE_WL&&(prcopt.navsys&SYS_CMP)) {
prcopt.bdsmodear=0;
}
if (n<=0) {
showmsg("error : no input file");
return -2;
}
ret=postpos(ts,te,tint,0.0,&prcopt,&solopt,&filopt,infile,n,outfile,"","");

if (!ret) fprintf(stderr,"%40s\r","");
return ret;
}
2 changes: 1 addition & 1 deletion src/options.c
Original file line number Diff line number Diff line change
Expand Up @@ -59,7 +59,7 @@ static char snrmask_[NFREQ][1024];
#define STAOPT "0:all,1:single"
#define STSOPT "0:off,1:state,2:residual"
#define ARMOPT "0:off,1:continuous,2:instantaneous,3:fix-and-hold,4:WLNL,5:TCAR,6:wide-lane"
#define POSOPT "0:llh,1:xyz,2:single,3:posfile,4:rinexhead,5:rtcm,6:raw"
#define POSOPT "0:llh,1:xyz,2:single,3:posfile,4:rinexhead,5:rtcm,6:raw,7:rinexdynamic"
#define TIDEOPT "0:off,1:on,2:otl"
#define PHWOPT "0:off,1:on,2:precise"

Expand Down
13 changes: 10 additions & 3 deletions src/rinex.c
Original file line number Diff line number Diff line change
Expand Up @@ -647,7 +647,7 @@ static int readrnxh(FILE *fp, double *ver, char *type, int *sys, int *tsys,

trace(3,"readrnxh:\n");

*ver=2.10; *type=' '; *sys=SYS_GPS;
*ver=2.10; *type=' '; *sys=SYS_GPS; *tsys=TSYS_GPS;

while (fgets(buff,MAXRNXLEN,fp)) {

Expand Down Expand Up @@ -1015,7 +1015,14 @@ static int readrnxobsb(FILE *fp, const char *opt, double ver, int *tsys,
data[n].sat=(uint8_t)sats[i-1];

/* decode RINEX observation data */
if (decode_obsdata(fp,buff,ver,mask,index,data+n)) n++;
if (decode_obsdata(fp,buff,ver,mask,index,data+n)) {
if (sta) {
data[n].refpos[0]=sta->pos[0];
data[n].refpos[1]=sta->pos[1];
data[n].refpos[2]=sta->pos[2];
}
n++;
}
}
else if (*flag==3||*flag==4) { /* new site or header info follows */

Expand All @@ -1035,7 +1042,7 @@ static int readrnxobs(FILE *fp, gtime_t ts, gtime_t te, double tint,
uint8_t slips[MAXSAT][NFREQ+NEXOBS]={{0}};
int i,n,flag=0,stat=0;

trace(4,"readrnxobs: rcv=%d ver=%.2f tsys=%d\n",rcv,ver,tsys);
trace(4,"readrnxobs: rcv=%d ver=%.2f tsys=%d\n",rcv,ver,*tsys);

if (!obs||rcv>MAXRCV) return 0;

Expand Down
9 changes: 8 additions & 1 deletion src/rtklib.h
Original file line number Diff line number Diff line change
Expand Up @@ -425,7 +425,9 @@ extern "C" {
#define POSOPT_SINGLE 1 /* pos option: average of single pos */
#define POSOPT_FILE 2 /* pos option: read from pos file */
#define POSOPT_RINEX 3 /* pos option: rinex header pos */
#define POSOPT_RTCM 4 /* pos option: rtcm/raw station pos */
#define POSOPT_RTCM 4 /* pos option: rtcm station pos */
#define POSOPT_RAW 5 /* pos option: raw station pos */
#define POSOPT_RINEX_DYN 6 /* pos option: rinex site occupation pos */

#define STR_NONE 0 /* stream type: none */
#define STR_SERIAL 1 /* stream type: serial */
Expand Down Expand Up @@ -543,6 +545,8 @@ typedef struct { /* observation data record */
double L[NFREQ+NEXOBS]; /* observation data carrier-phase (cycle) */
double P[NFREQ+NEXOBS]; /* observation data pseudorange (m) */
float D[NFREQ+NEXOBS]; /* observation data doppler frequency (Hz) */
/* only used if refpos == POSOPT_RINEX_DYN */
double refpos[3]; /* station coordinates associated with this observation */
} obsd_t;

typedef struct { /* observation data */
Expand Down Expand Up @@ -1170,6 +1174,9 @@ typedef struct { /* receiver raw data control type */
char opt[256]; /* receiver dependent options */
int format; /* receiver stream format */
void *rcv_data; /* receiver dependent data */

/* only used for STRFMT_SBP and STRFMT_SBPJSON */
int staid; /* station id */
} raw_t;

typedef struct { /* stream type */
Expand Down
7 changes: 7 additions & 0 deletions src/rtkpos.c
Original file line number Diff line number Diff line change
Expand Up @@ -1994,6 +1994,13 @@ extern int rtkpos(rtk_t *rtk, const obsd_t *obs, int n, const nav_t *nav)
/* count rover/base station observations */
for (nu=0;nu <n&&obs[nu ].rcv==1;nu++) ;
for (nr=0;nu+nr<n&&obs[nu+nr].rcv==2;nr++) ;

if (opt->refpos==POSOPT_RINEX_DYN&&opt->mode!=PMODE_SINGLE&&
opt->mode!=PMODE_MOVEB) {
if (nr > 0) {
for (i=0;i<6;i++) rtk->rb[i]=i<3?obs[nu].refpos[i]:0.0;
}
}

time=rtk->sol.time; /* previous epoch */

Expand Down

0 comments on commit 0123f7d

Please sign in to comment.