├── .gitattributes ├── .gitignore ├── LICENSE.txt ├── app └── consapp │ ├── rnx2rtkp │ ├── gcc │ │ └── makefile │ ├── gcc_mkl │ │ └── makefile │ └── rnx2rtkp.c │ └── rtkrcv │ ├── gcc │ └── makefile │ ├── gcc_mkl │ └── makefile │ ├── rtkrcv.c │ ├── vt.c │ └── vt.h ├── bin ├── rnx2rtkp.conf └── rtkrcv.conf ├── data └── MALIB_OSS_data.tar.gz ├── doc ├── doc │ ├── manual.docx │ ├── relnote_2.4.1.htm │ ├── relnotes_2.2.1.txt │ ├── relnotes_2.2.2.txt │ ├── relnotes_2.3.0.txt │ └── relnotes_2.4.0.doc ├── manual_2.4.2.pdf ├── manual_MALIB1.0.0.pdf └── relnote_2.4.2.htm ├── lib └── mkl │ ├── readme.txt │ └── redist.txt ├── readme.md ├── src ├── ephemeris.c ├── geoid.c ├── ionex.c ├── lambda.c ├── mdccssr.c ├── options.c ├── pntpos.c ├── postpos.c ├── ppp.c ├── ppp_ar.c ├── ppp_corr.c ├── preceph.c ├── rcv │ ├── binex.c │ ├── crescent.c │ ├── javad.c │ ├── novatel.c │ ├── nvs.c │ ├── rt17.c │ ├── septentrio.c │ ├── skytraq.c │ ├── ss2.c │ └── ublox.c ├── rcvraw.c ├── rinex.c ├── rtcm.c ├── rtcm2.c ├── rtcm3.c ├── rtcm3e.c ├── rtkcmn.c ├── rtklib.h ├── rtkpos.c ├── rtksvr.c ├── sbas.c ├── solution.c ├── stream.c └── tides.c ├── test ├── data │ ├── rcvraw │ │ ├── GMSD7_20121014.rtcm3 │ │ ├── cres_20080526.bin │ │ ├── gw10_20110121.sbas │ │ ├── javad_20110115.jps │ │ ├── oem3_20090410.gps │ │ ├── oemv_200911218.gps │ │ ├── ss2_20080517.log │ │ ├── testglo.rtcm2 │ │ ├── testglo.rtcm3 │ │ └── ubx_20080526.ubx │ ├── rinex │ │ ├── 07590920.05n │ │ ├── 07590920.05o │ │ ├── 30400920.05n │ │ ├── 30400920.05o │ │ ├── brdc0910.09g │ │ ├── brdc1820.10n │ │ └── brdc1830.10n │ ├── sp3 │ │ ├── esa15253.clk │ │ ├── esa15253.sp3 │ │ ├── igl15253.sp3 │ │ ├── igrg3380.10i │ │ ├── igrg3390.10i │ │ ├── igs15904.clk │ │ ├── igs15904.sp3 │ │ └── igs15905.sp3 │ └── tle │ │ ├── RFC_854_telnet.txt │ │ ├── TLE_GNSS_20121101.txt │ │ ├── brdc3050.12g │ │ ├── brdc3050.12n │ │ ├── brdc3050.12q │ │ ├── igs17127.erp │ │ ├── prn_name.txt │ │ ├── tle_nav.txt │ │ └── tle_sgp4.txt └── utest │ ├── figtest1.jpg │ ├── figtest2.jpg │ ├── figtest3.jpg │ ├── makefile │ ├── plotigp.m │ ├── t_atmos.c │ ├── t_coord.c │ ├── t_corrperf.c │ ├── t_filter.c │ ├── t_geoid.c │ ├── t_gloeph.c │ ├── t_ionex.c │ ├── t_lambda.c │ ├── t_matrix.c │ ├── t_misc.c │ ├── t_ppp.c │ ├── t_preceph.c │ ├── t_rinex.c │ ├── t_time.c │ ├── t_tle.c │ ├── testgloeph.m │ ├── testionex.m │ ├── testionex3.m │ ├── testionex4.m │ ├── testionppp.m │ ├── testpeph1.m │ ├── testpeph2.m │ └── utest_eph.m └── util ├── data ├── COD.EPH_U ├── COD16510.EPH_R ├── COD16511.EPH_R ├── COD16512.EPH_R ├── COD16513.EPH_R ├── COD16514.EPH_R ├── COD16515.EPH_R ├── COD16516.EPH_R ├── igl16295.sp3 ├── igr16295.sp3 ├── igr_igs.diff ├── igs16295.sp3 ├── igs16296.sp3 ├── igu16295_00.sp3 ├── igu16295_00_p.sp3 ├── igu16295_06.sp3 ├── igu16295_12.sp3 ├── igu16295_18.sp3 ├── igu16295_18_p.sp3 └── igu_igs.diff ├── gencrc ├── crc16.c ├── crc24.c ├── gencrc.c ├── genmsk.c ├── genxor.c └── makefile ├── geniono ├── estiono.c ├── gengrid.c ├── geniono.c ├── genstec.c ├── geonet.csv ├── makefile ├── plotgrid.m ├── plotiono.m ├── plotstec.m └── rcvdcb.c ├── geoid ├── WW15MGH.zip └── gengeoid.m ├── lncnt └── lncnt.sh ├── logfile └── margelog.c ├── rnx2rtcm ├── makefile └── rnx2rtcm.c ├── simobs ├── gcc │ └── makefile ├── sim │ ├── brdc0910.09g │ ├── brdc0910.09l │ └── brdc0910.09n └── simobs.c ├── testeph ├── diffeph.c ├── dumpssr.c └── makefile └── testlex ├── 20130428_lex.jaxa ├── 20130429_lex.jaxa ├── convlex.c ├── dumplex.c ├── dumpssr.c ├── makefile ├── outlexion.c ├── plotlexeph.m ├── plotlexion.m └── plotlexure.m /.gitattributes: -------------------------------------------------------------------------------- 1 | # Auto detect text files and perform LF normalization 2 | * text=auto 3 | 4 | # Custom for Visual Studio 5 | *.cs diff=csharp 6 | *.sln merge=union 7 | *.csproj merge=union 8 | *.vbproj merge=union 9 | *.fsproj merge=union 10 | *.dbproj merge=union 11 | 12 | # Standard to msysgit 13 | *.doc diff=astextplain 14 | *.DOC diff=astextplain 15 | *.docx diff=astextplain 16 | *.DOCX diff=astextplain 17 | *.dot diff=astextplain 18 | *.DOT diff=astextplain 19 | *.pdf diff=astextplain 20 | *.PDF diff=astextplain 21 | *.rtf diff=astextplain 22 | *.RTF diff=astextplain 23 | -------------------------------------------------------------------------------- /.gitignore: -------------------------------------------------------------------------------- 1 | *.o 2 | *.d 3 | *.obs 4 | *.ini 5 | *.local 6 | Release 7 | Release_Build 8 | Debug 9 | Debug_Build 10 | __history 11 | __astcache 12 | -------------------------------------------------------------------------------- /LICENSE.txt: -------------------------------------------------------------------------------- 1 | 2 | The MALIB software package is distributed under the following BSD 2-clause 3 | license. Users are permitted to develop, produce or sell their own non- 4 | commercial or commercial products utilizing, linking or including MALIB as long 5 | as they comply with the license. 6 | 7 | -------------------------------------------------------------------------------- 8 | 9 | Copyright (c) 2007-2023, T. Takasu, All rights reserved. 10 | Copyright (c) 2023-2024, Japan Aerospace Exploration Agency. All Rights Reserved. 11 | Copyright (C) 2023-2024, TOSHIBA ELECTRONIC TECHNOLOGIES CORPORATION. All Rights Reserved. 12 | 13 | Redistribution and use in source and binary forms, with or without modification, 14 | are permitted provided that the following conditions are met: 15 | 16 | Redistributions of source code must retain the above copyright notice, this list 17 | of conditions and the following disclaimer. Redistributions in binary form must 18 | reproduce the above copyright notice, this list of conditions and the following 19 | disclaimer in the documentation and/or other materials provided with the 20 | distribution. 21 | 22 | The software package includes some companion executive binaries or shared 23 | libraries necessary to execute APs on Windows. These licenses succeed to the 24 | original ones of these software. 25 | 26 | THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND 27 | ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED 28 | WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE 29 | DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE 30 | FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL 31 | DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR 32 | SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 33 | CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, 34 | OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE 35 | OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 36 | 37 | -------------------------------------------------------------------------------- 38 | 39 | Notes: 40 | Previous versions of RTKLIB until ver. 2.4.1 had been distributed under GPLv3 41 | license. 42 | 43 | -------------------------------------------------------------------------------- /app/consapp/rnx2rtkp/gcc/makefile: -------------------------------------------------------------------------------- 1 | # makefile for rnx2rtkp 2 | 3 | BINDIR = ../../../../bin 4 | SRC = ../../../../src 5 | LIBDIR = ../../../../lib 6 | 7 | OPTS = -DTRACE -DENAGLO -DENAQZS -DENAGAL -DENACMP -DENAIRN -DNFREQ=5 -DNEXOBS=5 8 | LIBS = 9 | 10 | # with Intel MKL 11 | #MKLDIR = $(LIBDIR)/mkl/intel64 12 | #OPTS += -DMKL 13 | #LIBS += -L$(MKLDIR) -lmkl_intel_lp64 -lmkl_core -lmkl_gnu_thread -lpthread -lgomp 14 | 15 | CFLAGS = -Wall -O0 -ansi -pedantic -Wno-unused-but-set-variable -I$(SRC) $(OPTS) -g -O 16 | LDLIBS = $(LIBS) -lm -lrt 17 | 18 | all : rnx2rtkp 19 | rnx2rtkp : rnx2rtkp.o rtkcmn.o rinex.o rtkpos.o postpos.o solution.o 20 | rnx2rtkp : lambda.o geoid.o sbas.o preceph.o pntpos.o ephemeris.o options.o 21 | rnx2rtkp : ppp.o ppp_ar.o ppp_corr.o rtcm.o rtcm2.o rtcm3.o rtcm3e.o ionex.o tides.o mdccssr.o 22 | 23 | rnx2rtkp.o : ../rnx2rtkp.c 24 | $(CC) -c $(CFLAGS) ../rnx2rtkp.c 25 | rtkcmn.o : $(SRC)/rtkcmn.c 26 | $(CC) -c $(CFLAGS) $(SRC)/rtkcmn.c 27 | rinex.o : $(SRC)/rinex.c 28 | $(CC) -c $(CFLAGS) $(SRC)/rinex.c 29 | rtkpos.o : $(SRC)/rtkpos.c 30 | $(CC) -c $(CFLAGS) $(SRC)/rtkpos.c 31 | postpos.o : $(SRC)/postpos.c 32 | $(CC) -c $(CFLAGS) $(SRC)/postpos.c 33 | solution.o : $(SRC)/solution.c 34 | $(CC) -c $(CFLAGS) $(SRC)/solution.c 35 | lambda.o : $(SRC)/lambda.c 36 | $(CC) -c $(CFLAGS) $(SRC)/lambda.c 37 | geoid.o : $(SRC)/geoid.c 38 | $(CC) -c $(CFLAGS) $(SRC)/geoid.c 39 | sbas.o : $(SRC)/sbas.c 40 | $(CC) -c $(CFLAGS) $(SRC)/sbas.c 41 | preceph.o : $(SRC)/preceph.c 42 | $(CC) -c $(CFLAGS) $(SRC)/preceph.c 43 | pntpos.o : $(SRC)/pntpos.c 44 | $(CC) -c $(CFLAGS) $(SRC)/pntpos.c 45 | ephemeris.o: $(SRC)/ephemeris.c 46 | $(CC) -c $(CFLAGS) $(SRC)/ephemeris.c 47 | options.o : $(SRC)/options.c 48 | $(CC) -c $(CFLAGS) $(SRC)/options.c 49 | ppp.o : $(SRC)/ppp.c 50 | $(CC) -c $(CFLAGS) $(SRC)/ppp.c 51 | ppp_ar.o : $(SRC)/ppp_ar.c 52 | $(CC) -c $(CFLAGS) $(SRC)/ppp_ar.c 53 | ppp_corr.o : $(SRC)/ppp_corr.c 54 | $(CC) -c $(CFLAGS) $(SRC)/ppp_corr.c 55 | rtcm.o : $(SRC)/rtcm.c 56 | $(CC) -c $(CFLAGS) $(SRC)/rtcm.c 57 | rtcm2.o : $(SRC)/rtcm2.c 58 | $(CC) -c $(CFLAGS) $(SRC)/rtcm2.c 59 | rtcm3.o : $(SRC)/rtcm3.c 60 | $(CC) -c $(CFLAGS) $(SRC)/rtcm3.c 61 | rtcm3e.o : $(SRC)/rtcm3e.c 62 | $(CC) -c $(CFLAGS) $(SRC)/rtcm3e.c 63 | ionex.o : $(SRC)/ionex.c 64 | $(CC) -c $(CFLAGS) $(SRC)/ionex.c 65 | tides.o : $(SRC)/tides.c 66 | $(CC) -c $(CFLAGS) $(SRC)/tides.c 67 | mdccssr.o : $(SRC)/mdccssr.c 68 | $(CC) -c $(CFLAGS) $(SRC)/mdccssr.c 69 | 70 | rnx2rtkp.o : $(SRC)/rtklib.h 71 | rtkcmn.o : $(SRC)/rtklib.h 72 | rinex.o : $(SRC)/rtklib.h 73 | rtkpos.o : $(SRC)/rtklib.h 74 | postpos.o : $(SRC)/rtklib.h 75 | solution.o : $(SRC)/rtklib.h 76 | lambda.o : $(SRC)/rtklib.h 77 | geoid.o : $(SRC)/rtklib.h 78 | sbas.o : $(SRC)/rtklib.h 79 | preceph.o : $(SRC)/rtklib.h 80 | pntpos.o : $(SRC)/rtklib.h 81 | ephemeris.o: $(SRC)/rtklib.h 82 | options.o : $(SRC)/rtklib.h 83 | ppp.o : $(SRC)/rtklib.h 84 | ppp_ar.o : $(SRC)/rtklib.h 85 | ppp_corr.o : $(SRC)/rtklib.h 86 | rtcm.o : $(SRC)/rtklib.h 87 | rtcm2.o : $(SRC)/rtklib.h 88 | rtcm3.o : $(SRC)/rtklib.h 89 | rtcm3e.o : $(SRC)/rtklib.h 90 | ionex.o : $(SRC)/rtklib.h 91 | tides.o : $(SRC)/rtklib.h 92 | mdccssr.o : $(SRC)/rtklib.h 93 | 94 | clean : 95 | rm -f rnx2rtkp rnx2rtkp.exe *.o *.pos *.trace 96 | 97 | install : 98 | cp rnx2rtkp $(BINDIR) 99 | 100 | -------------------------------------------------------------------------------- /app/consapp/rnx2rtkp/gcc_mkl/makefile: -------------------------------------------------------------------------------- 1 | # makefile for rnx2rtkp 2 | 3 | BINDIR = ../../../../bin 4 | SRC = ../../../../src 5 | LIBDIR = ../../../../lib 6 | 7 | OPTS = -DTRACE -DENAGLO -DENAQZS -DENAGAL -DENACMP -DENAIRN -DNFREQ=5 -DNEXOBS=5 8 | LIBS = 9 | 10 | # with Intel MKL 11 | MKLDIR = $(LIBDIR)/mkl/intel64 12 | OPTS += -DMKL 13 | LIBS += -L$(MKLDIR) -lmkl_intel_lp64 -lmkl_core -lmkl_gnu_thread -lpthread -lgomp 14 | 15 | CFLAGS = -Wall -O0 -ansi -pedantic -Wno-unused-but-set-variable -I$(SRC) $(OPTS) -g -O 16 | LDLIBS = $(LIBS) -lm -lrt 17 | 18 | all : rnx2rtkp 19 | rnx2rtkp : rnx2rtkp.o rtkcmn.o rinex.o rtkpos.o postpos.o solution.o 20 | rnx2rtkp : lambda.o geoid.o sbas.o preceph.o pntpos.o ephemeris.o options.o 21 | rnx2rtkp : ppp.o ppp_ar.o ppp_corr.o rtcm.o rtcm2.o rtcm3.o rtcm3e.o ionex.o tides.o mdccssr.o 22 | 23 | rnx2rtkp.o : ../rnx2rtkp.c 24 | $(CC) -c $(CFLAGS) ../rnx2rtkp.c 25 | rtkcmn.o : $(SRC)/rtkcmn.c 26 | $(CC) -c $(CFLAGS) $(SRC)/rtkcmn.c 27 | rinex.o : $(SRC)/rinex.c 28 | $(CC) -c $(CFLAGS) $(SRC)/rinex.c 29 | rtkpos.o : $(SRC)/rtkpos.c 30 | $(CC) -c $(CFLAGS) $(SRC)/rtkpos.c 31 | postpos.o : $(SRC)/postpos.c 32 | $(CC) -c $(CFLAGS) $(SRC)/postpos.c 33 | solution.o : $(SRC)/solution.c 34 | $(CC) -c $(CFLAGS) $(SRC)/solution.c 35 | lambda.o : $(SRC)/lambda.c 36 | $(CC) -c $(CFLAGS) $(SRC)/lambda.c 37 | geoid.o : $(SRC)/geoid.c 38 | $(CC) -c $(CFLAGS) $(SRC)/geoid.c 39 | sbas.o : $(SRC)/sbas.c 40 | $(CC) -c $(CFLAGS) $(SRC)/sbas.c 41 | preceph.o : $(SRC)/preceph.c 42 | $(CC) -c $(CFLAGS) $(SRC)/preceph.c 43 | pntpos.o : $(SRC)/pntpos.c 44 | $(CC) -c $(CFLAGS) $(SRC)/pntpos.c 45 | ephemeris.o: $(SRC)/ephemeris.c 46 | $(CC) -c $(CFLAGS) $(SRC)/ephemeris.c 47 | options.o : $(SRC)/options.c 48 | $(CC) -c $(CFLAGS) $(SRC)/options.c 49 | ppp.o : $(SRC)/ppp.c 50 | $(CC) -c $(CFLAGS) $(SRC)/ppp.c 51 | ppp_ar.o : $(SRC)/ppp_ar.c 52 | $(CC) -c $(CFLAGS) $(SRC)/ppp_ar.c 53 | ppp_corr.o : $(SRC)/ppp_corr.c 54 | $(CC) -c $(CFLAGS) $(SRC)/ppp_corr.c 55 | rtcm.o : $(SRC)/rtcm.c 56 | $(CC) -c $(CFLAGS) $(SRC)/rtcm.c 57 | rtcm2.o : $(SRC)/rtcm2.c 58 | $(CC) -c $(CFLAGS) $(SRC)/rtcm2.c 59 | rtcm3.o : $(SRC)/rtcm3.c 60 | $(CC) -c $(CFLAGS) $(SRC)/rtcm3.c 61 | rtcm3e.o : $(SRC)/rtcm3e.c 62 | $(CC) -c $(CFLAGS) $(SRC)/rtcm3e.c 63 | ionex.o : $(SRC)/ionex.c 64 | $(CC) -c $(CFLAGS) $(SRC)/ionex.c 65 | tides.o : $(SRC)/tides.c 66 | $(CC) -c $(CFLAGS) $(SRC)/tides.c 67 | mdccssr.o : $(SRC)/mdccssr.c 68 | $(CC) -c $(CFLAGS) $(SRC)/mdccssr.c 69 | 70 | rnx2rtkp.o : $(SRC)/rtklib.h 71 | rtkcmn.o : $(SRC)/rtklib.h 72 | rinex.o : $(SRC)/rtklib.h 73 | rtkpos.o : $(SRC)/rtklib.h 74 | postpos.o : $(SRC)/rtklib.h 75 | solution.o : $(SRC)/rtklib.h 76 | lambda.o : $(SRC)/rtklib.h 77 | geoid.o : $(SRC)/rtklib.h 78 | sbas.o : $(SRC)/rtklib.h 79 | preceph.o : $(SRC)/rtklib.h 80 | pntpos.o : $(SRC)/rtklib.h 81 | ephemeris.o: $(SRC)/rtklib.h 82 | options.o : $(SRC)/rtklib.h 83 | ppp.o : $(SRC)/rtklib.h 84 | ppp_ar.o : $(SRC)/rtklib.h 85 | ppp_corr.o : $(SRC)/rtklib.h 86 | rtcm.o : $(SRC)/rtklib.h 87 | rtcm2.o : $(SRC)/rtklib.h 88 | rtcm3.o : $(SRC)/rtklib.h 89 | rtcm3e.o : $(SRC)/rtklib.h 90 | ionex.o : $(SRC)/rtklib.h 91 | tides.o : $(SRC)/rtklib.h 92 | mdccssr.o : $(SRC)/rtklib.h 93 | 94 | clean : 95 | rm -f rnx2rtkp rnx2rtkp.exe *.o *.pos *.trace 96 | 97 | install : 98 | cp rnx2rtkp $(BINDIR) 99 | 100 | -------------------------------------------------------------------------------- /app/consapp/rtkrcv/gcc/makefile: -------------------------------------------------------------------------------- 1 | # makefile for rtkrcv 2 | 3 | BINDIR = ../../../../bin 4 | SRC = ../../../../src 5 | LIBDIR = ../../../../lib 6 | 7 | OPTS= -DENAGLO -DENAQZS -DENACMP -DENAGAL -DENAIRN -DNFREQ=5 -DSVR_REUSEADDR -DNEXOBS=5 -DTRACE 8 | LIBS = 9 | 10 | # with Intel MKL 11 | #MKLDIR = $(LIBDIR)/mkl/intel64 12 | #OPTS += -DMKL 13 | #LIBS += -L$(MKLDIR) -lmkl_intel_lp64 -lmkl_core -lmkl_gnu_thread -lpthread -lgomp 14 | 15 | CFLAGS = -Wall -O3 -ansi -pedantic -Wno-unused-but-set-variable -I$(SRC) -I.. $(OPTS) -g 16 | LDLIBS = $(LIBS) -lm -lrt -lpthread 17 | 18 | all : rtkrcv 19 | rtkrcv : rtkrcv.o vt.o rtkcmn.o rtksvr.o rtkpos.o geoid.o solution.o lambda.o 20 | rtkrcv : sbas.o stream.o rcvraw.o rtcm.o preceph.o options.o pntpos.o ppp.o ppp_ar.o ppp_corr.o 21 | rtkrcv : novatel.o ublox.o ss2.o crescent.o skytraq.o javad.o nvs.o binex.o 22 | rtkrcv : rt17.o ephemeris.o rinex.o ionex.o rtcm2.o rtcm3.o rtcm3e.o 23 | rtkrcv : tides.o septentrio.o mdccssr.o 24 | 25 | rtkrcv.o : ../rtkrcv.c 26 | $(CC) -c $(CFLAGS) ../rtkrcv.c 27 | vt.o : ../vt.c 28 | $(CC) -c $(CFLAGS) ../vt.c 29 | rtkcmn.o : $(SRC)/rtkcmn.c 30 | $(CC) -c $(CFLAGS) $(SRC)/rtkcmn.c 31 | rtksvr.o : $(SRC)/rtksvr.c 32 | $(CC) -c $(CFLAGS) $(SRC)/rtksvr.c 33 | rtkpos.o : $(SRC)/rtkpos.c 34 | $(CC) -c $(CFLAGS) $(SRC)/rtkpos.c 35 | geoid.o : $(SRC)/geoid.c 36 | $(CC) -c $(CFLAGS) $(SRC)/geoid.c 37 | solution.o : $(SRC)/solution.c 38 | $(CC) -c $(CFLAGS) $(SRC)/solution.c 39 | lambda.o : $(SRC)/lambda.c 40 | $(CC) -c $(CFLAGS) $(SRC)/lambda.c 41 | sbas.o : $(SRC)/sbas.c 42 | $(CC) -c $(CFLAGS) $(SRC)/sbas.c 43 | stream.o : $(SRC)/stream.c 44 | $(CC) -c $(CFLAGS) $(SRC)/stream.c 45 | rcvraw.o : $(SRC)/rcvraw.c 46 | $(CC) -c $(CFLAGS) $(SRC)/rcvraw.c 47 | rtcm.o : $(SRC)/rtcm.c 48 | $(CC) -c $(CFLAGS) $(SRC)/rtcm.c 49 | rtcm2.o : $(SRC)/rtcm2.c 50 | $(CC) -c $(CFLAGS) $(SRC)/rtcm2.c 51 | rtcm3.o : $(SRC)/rtcm3.c 52 | $(CC) -c $(CFLAGS) $(SRC)/rtcm3.c 53 | rtcm3e.o : $(SRC)/rtcm3e.c 54 | $(CC) -c $(CFLAGS) $(SRC)/rtcm3e.c 55 | preceph.o : $(SRC)/preceph.c 56 | $(CC) -c $(CFLAGS) $(SRC)/preceph.c 57 | options.o : $(SRC)/options.c 58 | $(CC) -c $(CFLAGS) $(SRC)/options.c 59 | pntpos.o : $(SRC)/pntpos.c 60 | $(CC) -c $(CFLAGS) $(SRC)/pntpos.c 61 | ppp.o : $(SRC)/ppp.c 62 | $(CC) -c $(CFLAGS) $(SRC)/ppp.c 63 | ppp_ar.o : $(SRC)/ppp_ar.c 64 | $(CC) -c $(CFLAGS) $(SRC)/ppp_ar.c 65 | ppp_corr.o : $(SRC)/ppp_corr.c 66 | $(CC) -c $(CFLAGS) $(SRC)/ppp_corr.c 67 | novatel.o : $(SRC)/rcv/novatel.c 68 | $(CC) -c $(CFLAGS) $(SRC)/rcv/novatel.c 69 | ublox.o : $(SRC)/rcv/ublox.c 70 | $(CC) -c $(CFLAGS) $(SRC)/rcv/ublox.c 71 | ss2.o : $(SRC)/rcv/ss2.c 72 | $(CC) -c $(CFLAGS) $(SRC)/rcv/ss2.c 73 | crescent.o : $(SRC)/rcv/crescent.c 74 | $(CC) -c $(CFLAGS) $(SRC)/rcv/crescent.c 75 | skytraq.o : $(SRC)/rcv/skytraq.c 76 | $(CC) -c $(CFLAGS) $(SRC)/rcv/skytraq.c 77 | javad.o : $(SRC)/rcv/javad.c 78 | $(CC) -c $(CFLAGS) $(SRC)/rcv/javad.c 79 | nvs.o : $(SRC)/rcv/nvs.c 80 | $(CC) -c $(CFLAGS) $(SRC)/rcv/nvs.c 81 | binex.o : $(SRC)/rcv/binex.c 82 | $(CC) -c $(CFLAGS) $(SRC)/rcv/binex.c 83 | rt17.o : $(SRC)/rcv/rt17.c 84 | $(CC) -c $(CFLAGS) $(SRC)/rcv/rt17.c 85 | ephemeris.o: $(SRC)/ephemeris.c 86 | $(CC) -c $(CFLAGS) $(SRC)/ephemeris.c 87 | rinex.o : $(SRC)/rinex.c 88 | $(CC) -c $(CFLAGS) $(SRC)/rinex.c 89 | ionex.o : $(SRC)/ionex.c 90 | $(CC) -c $(CFLAGS) $(SRC)/ionex.c 91 | tides.o : $(SRC)/tides.c 92 | $(CC) -c $(CFLAGS) $(SRC)/tides.c 93 | septentrio.o: $(SRC)/rcv/septentrio.c 94 | $(CC) -c $(CFLAGS) $(SRC)/rcv/septentrio.c 95 | mdccssr.o : $(SRC)/mdccssr.c 96 | $(CC) -c $(CFLAGS) $(SRC)/mdccssr.c 97 | 98 | rtkrcv.o : $(SRC)/rtklib.h ../vt.h 99 | rtkcmn.o : $(SRC)/rtklib.h 100 | rtksvr.o : $(SRC)/rtklib.h 101 | rtkpos.o : $(SRC)/rtklib.h 102 | geoid.o : $(SRC)/rtklib.h 103 | solution.o : $(SRC)/rtklib.h 104 | lambda.o : $(SRC)/rtklib.h 105 | sbas.o : $(SRC)/rtklib.h 106 | rcvraw.o : $(SRC)/rtklib.h 107 | rtcm.o : $(SRC)/rtklib.h 108 | rtcm2.o : $(SRC)/rtklib.h 109 | rtcm3.o : $(SRC)/rtklib.h 110 | rtcm3e.o : $(SRC)/rtklib.h 111 | preceph.o : $(SRC)/rtklib.h 112 | options.o : $(SRC)/rtklib.h 113 | pntpos.o : $(SRC)/rtklib.h 114 | ppp.o : $(SRC)/rtklib.h 115 | ppp_ar.o : $(SRC)/rtklib.h 116 | ppp_corr.o : $(SRC)/rtklib.h 117 | novatel.o : $(SRC)/rtklib.h 118 | ublox.o : $(SRC)/rtklib.h 119 | ss2.o : $(SRC)/rtklib.h 120 | crescent.o : $(SRC)/rtklib.h 121 | skytraq.o : $(SRC)/rtklib.h 122 | javad.o : $(SRC)/rtklib.h 123 | nvs.o : $(SRC)/rtklib.h 124 | binex.o : $(SRC)/rtklib.h 125 | rt17.o : $(SRC)/rtklib.h 126 | septentrio.o: $(SRC)/rtklib.h 127 | ephemeris.o: $(SRC)/rtklib.h 128 | rinex.o : $(SRC)/rtklib.h 129 | ionex.o : $(SRC)/rtklib.h 130 | tides.o : $(SRC)/rtklib.h 131 | mdccssr.o : $(SRC)/rtklib.h 132 | 133 | install: 134 | cp rtkrcv $(BINDIR) 135 | 136 | clean: 137 | rm -f rtkrcv rtkrcv.exe rtkrcv.nav *.o *.out *.trace 138 | 139 | -------------------------------------------------------------------------------- /app/consapp/rtkrcv/gcc_mkl/makefile: -------------------------------------------------------------------------------- 1 | # makefile for rtkrcv 2 | 3 | BINDIR = ../../../../bin 4 | SRC = ../../../../src 5 | LIBDIR = ../../../../lib 6 | 7 | OPTS= -DENAGLO -DENAQZS -DENACMP -DENAGAL -DENAIRN -DNFREQ=5 -DSVR_REUSEADDR -DNEXOBS=5 -DTRACE 8 | LIBS = 9 | 10 | # with Intel MKL 11 | MKLDIR = $(LIBDIR)/mkl/intel64 12 | OPTS += -DMKL 13 | LIBS += -L$(MKLDIR) -lmkl_intel_lp64 -lmkl_core -lmkl_gnu_thread -lpthread -lgomp 14 | 15 | CFLAGS = -Wall -O3 -ansi -pedantic -Wno-unused-but-set-variable -I$(SRC) -I.. $(OPTS) -g 16 | LDLIBS = $(LIBS) -lm -lrt -lpthread 17 | 18 | all : rtkrcv 19 | rtkrcv : rtkrcv.o vt.o rtkcmn.o rtksvr.o rtkpos.o geoid.o solution.o lambda.o 20 | rtkrcv : sbas.o stream.o rcvraw.o rtcm.o preceph.o options.o pntpos.o ppp.o ppp_ar.o ppp_corr.o 21 | rtkrcv : novatel.o ublox.o ss2.o crescent.o skytraq.o javad.o nvs.o binex.o 22 | rtkrcv : rt17.o ephemeris.o rinex.o ionex.o rtcm2.o rtcm3.o rtcm3e.o 23 | rtkrcv : tides.o septentrio.o mdccssr.o 24 | 25 | rtkrcv.o : ../rtkrcv.c 26 | $(CC) -c $(CFLAGS) ../rtkrcv.c 27 | vt.o : ../vt.c 28 | $(CC) -c $(CFLAGS) ../vt.c 29 | rtkcmn.o : $(SRC)/rtkcmn.c 30 | $(CC) -c $(CFLAGS) $(SRC)/rtkcmn.c 31 | rtksvr.o : $(SRC)/rtksvr.c 32 | $(CC) -c $(CFLAGS) $(SRC)/rtksvr.c 33 | rtkpos.o : $(SRC)/rtkpos.c 34 | $(CC) -c $(CFLAGS) $(SRC)/rtkpos.c 35 | geoid.o : $(SRC)/geoid.c 36 | $(CC) -c $(CFLAGS) $(SRC)/geoid.c 37 | solution.o : $(SRC)/solution.c 38 | $(CC) -c $(CFLAGS) $(SRC)/solution.c 39 | lambda.o : $(SRC)/lambda.c 40 | $(CC) -c $(CFLAGS) $(SRC)/lambda.c 41 | sbas.o : $(SRC)/sbas.c 42 | $(CC) -c $(CFLAGS) $(SRC)/sbas.c 43 | stream.o : $(SRC)/stream.c 44 | $(CC) -c $(CFLAGS) $(SRC)/stream.c 45 | rcvraw.o : $(SRC)/rcvraw.c 46 | $(CC) -c $(CFLAGS) $(SRC)/rcvraw.c 47 | rtcm.o : $(SRC)/rtcm.c 48 | $(CC) -c $(CFLAGS) $(SRC)/rtcm.c 49 | rtcm2.o : $(SRC)/rtcm2.c 50 | $(CC) -c $(CFLAGS) $(SRC)/rtcm2.c 51 | rtcm3.o : $(SRC)/rtcm3.c 52 | $(CC) -c $(CFLAGS) $(SRC)/rtcm3.c 53 | rtcm3e.o : $(SRC)/rtcm3e.c 54 | $(CC) -c $(CFLAGS) $(SRC)/rtcm3e.c 55 | preceph.o : $(SRC)/preceph.c 56 | $(CC) -c $(CFLAGS) $(SRC)/preceph.c 57 | options.o : $(SRC)/options.c 58 | $(CC) -c $(CFLAGS) $(SRC)/options.c 59 | pntpos.o : $(SRC)/pntpos.c 60 | $(CC) -c $(CFLAGS) $(SRC)/pntpos.c 61 | ppp.o : $(SRC)/ppp.c 62 | $(CC) -c $(CFLAGS) $(SRC)/ppp.c 63 | ppp_ar.o : $(SRC)/ppp_ar.c 64 | $(CC) -c $(CFLAGS) $(SRC)/ppp_ar.c 65 | ppp_corr.o : $(SRC)/ppp_corr.c 66 | $(CC) -c $(CFLAGS) $(SRC)/ppp_corr.c 67 | novatel.o : $(SRC)/rcv/novatel.c 68 | $(CC) -c $(CFLAGS) $(SRC)/rcv/novatel.c 69 | ublox.o : $(SRC)/rcv/ublox.c 70 | $(CC) -c $(CFLAGS) $(SRC)/rcv/ublox.c 71 | ss2.o : $(SRC)/rcv/ss2.c 72 | $(CC) -c $(CFLAGS) $(SRC)/rcv/ss2.c 73 | crescent.o : $(SRC)/rcv/crescent.c 74 | $(CC) -c $(CFLAGS) $(SRC)/rcv/crescent.c 75 | skytraq.o : $(SRC)/rcv/skytraq.c 76 | $(CC) -c $(CFLAGS) $(SRC)/rcv/skytraq.c 77 | javad.o : $(SRC)/rcv/javad.c 78 | $(CC) -c $(CFLAGS) $(SRC)/rcv/javad.c 79 | nvs.o : $(SRC)/rcv/nvs.c 80 | $(CC) -c $(CFLAGS) $(SRC)/rcv/nvs.c 81 | binex.o : $(SRC)/rcv/binex.c 82 | $(CC) -c $(CFLAGS) $(SRC)/rcv/binex.c 83 | rt17.o : $(SRC)/rcv/rt17.c 84 | $(CC) -c $(CFLAGS) $(SRC)/rcv/rt17.c 85 | ephemeris.o: $(SRC)/ephemeris.c 86 | $(CC) -c $(CFLAGS) $(SRC)/ephemeris.c 87 | rinex.o : $(SRC)/rinex.c 88 | $(CC) -c $(CFLAGS) $(SRC)/rinex.c 89 | ionex.o : $(SRC)/ionex.c 90 | $(CC) -c $(CFLAGS) $(SRC)/ionex.c 91 | tides.o : $(SRC)/tides.c 92 | $(CC) -c $(CFLAGS) $(SRC)/tides.c 93 | septentrio.o: $(SRC)/rcv/septentrio.c 94 | $(CC) -c $(CFLAGS) $(SRC)/rcv/septentrio.c 95 | mdccssr.o : $(SRC)/mdccssr.c 96 | $(CC) -c $(CFLAGS) $(SRC)/mdccssr.c 97 | 98 | rtkrcv.o : $(SRC)/rtklib.h ../vt.h 99 | rtkcmn.o : $(SRC)/rtklib.h 100 | rtksvr.o : $(SRC)/rtklib.h 101 | rtkpos.o : $(SRC)/rtklib.h 102 | geoid.o : $(SRC)/rtklib.h 103 | solution.o : $(SRC)/rtklib.h 104 | lambda.o : $(SRC)/rtklib.h 105 | sbas.o : $(SRC)/rtklib.h 106 | rcvraw.o : $(SRC)/rtklib.h 107 | rtcm.o : $(SRC)/rtklib.h 108 | rtcm2.o : $(SRC)/rtklib.h 109 | rtcm3.o : $(SRC)/rtklib.h 110 | rtcm3e.o : $(SRC)/rtklib.h 111 | preceph.o : $(SRC)/rtklib.h 112 | options.o : $(SRC)/rtklib.h 113 | pntpos.o : $(SRC)/rtklib.h 114 | ppp.o : $(SRC)/rtklib.h 115 | ppp_ar.o : $(SRC)/rtklib.h 116 | ppp_corr.o : $(SRC)/rtklib.h 117 | novatel.o : $(SRC)/rtklib.h 118 | ublox.o : $(SRC)/rtklib.h 119 | ss2.o : $(SRC)/rtklib.h 120 | crescent.o : $(SRC)/rtklib.h 121 | skytraq.o : $(SRC)/rtklib.h 122 | javad.o : $(SRC)/rtklib.h 123 | nvs.o : $(SRC)/rtklib.h 124 | binex.o : $(SRC)/rtklib.h 125 | rt17.o : $(SRC)/rtklib.h 126 | septentrio.o: $(SRC)/rtklib.h 127 | ephemeris.o: $(SRC)/rtklib.h 128 | rinex.o : $(SRC)/rtklib.h 129 | ionex.o : $(SRC)/rtklib.h 130 | tides.o : $(SRC)/rtklib.h 131 | mdccssr.o : $(SRC)/rtklib.h 132 | 133 | install: 134 | cp rtkrcv $(BINDIR) 135 | 136 | clean: 137 | rm -f rtkrcv rtkrcv.exe rtkrcv.nav *.o *.out *.trace 138 | 139 | -------------------------------------------------------------------------------- /app/consapp/rtkrcv/vt.h: -------------------------------------------------------------------------------- 1 | /*------------------------------------------------------------------------------ 2 | * vt.h : header file for virtual console 3 | * 4 | * Copyright (C) 2015 by T.TAKASU, All rights reserved. 5 | * 6 | * version : $Revision:$ $Date:$ 7 | * history : 2015/01/11 1.0 separated from rtkrcv.c 8 | *-----------------------------------------------------------------------------*/ 9 | #ifndef VT_H 10 | #define VT_H 11 | #include 12 | #include "rtklib.h" 13 | 14 | #define MAXBUFF 4096 /* size of line buffer */ 15 | #define MAXHIST 256 /* size of history buffer */ 16 | 17 | /* type definitions ----------------------------------------------------------*/ 18 | typedef struct vt_tag { /* virtual console type */ 19 | int state; /* state(0:close,1:open) */ 20 | int type; /* type (0:dev,1:telnet) */ 21 | int in,out; /* input/output file descriptor */ 22 | int n,nesc; /* number of line buffer/escape */ 23 | int cur; /* cursor position */ 24 | int cur_h; /* current history */ 25 | int brk; /* break status */ 26 | int blind; /* blind inpu mode */ 27 | struct termios tio; /* original terminal attribute */ 28 | char buff[MAXBUFF]; /* line buffer */ 29 | char esc[8]; /* escape buffer */ 30 | char *hist[MAXHIST]; /* history buffer */ 31 | FILE *logfp; /* log file pointer */ 32 | } vt_t; 33 | 34 | /* function prototypes -------------------------------------------------------*/ 35 | extern vt_t *vt_open(int sock, const char *dev); 36 | extern void vt_close(vt_t *vt); 37 | extern int vt_getc(vt_t *vt, char *c); 38 | extern int vt_gets(vt_t *vt, char *buff, int n); 39 | extern int vt_putc(vt_t *vt, char c); 40 | extern int vt_puts(vt_t *vt, const char *buff); 41 | extern int vt_printf(vt_t *vt, const char *format, ...); 42 | extern int vt_chkbrk(vt_t *vt); 43 | extern int vt_openlog(vt_t *vt, const char *file); 44 | extern void vt_closelog(vt_t *vt); 45 | 46 | #endif /* VT_H */ 47 | -------------------------------------------------------------------------------- /bin/rnx2rtkp.conf: -------------------------------------------------------------------------------- 1 | # 2 | # rnx2rtkp.conf: rnx2rtkp options for post processning ppp 3 | # 4 | 5 | pos1-posmode =ppp-kine # (0:single,1:dgps,2:kinematic,3:static,4:movingbase,5:fixed,6:ppp-kine,7:ppp-static,8:ppp-fixed) 6 | pos1-frequency =l1+2 # (1:l1,2:l1+2,3:l1+2+3,4:l1+2+3+4,5:l1+2+3+4+5) 7 | pos1-soltype =forward # (0:forward,1:backward,2:combined) 8 | pos1-elmask =10 # (deg) 9 | pos1-snrmask_r =off # (0:off,1:on) 10 | pos1-snrmask_b =off # (0:off,1:on) 11 | pos1-snrmask_L1 =0,0,0,0,0,0,0,0,0 12 | pos1-snrmask_L2 =0,0,0,0,0,0,0,0,0 13 | pos1-snrmask_L5 =0,0,0,0,0,0,0,0,0 14 | pos1-dynamics =off # (0:off,1:on) 15 | pos1-tidecorr =on # (0:off,1:on,2:otl) 16 | pos1-ionoopt =est-stec # (0:off,1:brdc,2:sbas,3:dual-freq,4:est-stec,5:ionex-tec,6:qzs-brdc) 17 | pos1-tropopt =est-ztd # (0:off,1:saas,2:sbas,3:est-ztd,4:est-ztdgrad) 18 | pos1-sateph =brdc+ssrapc # (0:brdc,1:precise,2:brdc+sbas,3:brdc+ssrapc,4:brdc+ssrcom) 19 | pos1-posopt1 =on # (0:off,1:on) 20 | pos1-posopt2 =on # (0:off,1:on) 21 | pos1-posopt3 =on # (0:off,1:on,2:precise) 22 | pos1-posopt4 =on # (0:off,1:on) 23 | pos1-posopt5 =off # (0:off,1:on) 24 | pos1-posopt6 =off # (0:off,1:on) 25 | pos1-exclsats = # (prn ...) 26 | pos1-navsys =29 # (1:gps+2:sbas+4:glo+8:gal+16:qzs+32:bds+64:navic) 27 | pos2-armode =continuous # (0:off,1:continuous,2:instantaneous,3:fix-and-hold) 28 | pos2-gloarmode =off # (0:off,1:on) 29 | pos2-bdsarmode =off # (0:off,1:on) 30 | pos2-arsys =1 # (1:gps+8:gal+16:qzs) 31 | pos2-arthres =3.0 32 | pos2-arthres1 =0.9999 33 | pos2-arthres2 =0.25 34 | pos2-arthres3 =0.1 35 | pos2-arthres4 =0.05 36 | pos2-arlockcnt =0 37 | pos2-arelmask =15 # (deg) 38 | pos2-arminfix =10 39 | pos2-armaxiter =99 40 | pos2-elmaskhold =0 # (deg) 41 | pos2-aroutcnt =5 42 | pos2-maxage =30 # (s) 43 | pos2-syncsol =off # (0:off,1:on) 44 | pos2-slipthres =0.15 # (m) 45 | pos2-rejionno =100 # (m) 46 | pos2-rejgdop =30 47 | pos2-niter =1 48 | pos2-baselen =0 # (m) 49 | pos2-basesig =0 # (m) 50 | pos2-siggpsIIR-M =0 # (0:L1C/A-L2P,1:L1C/A-L2C) 51 | pos2-siggpsIIF =0 # (0:L1C/A-L2P,1:L1C/A-L2C,2:L1C/A-L5) 52 | pos2-siggpsIIIA =0 # (0:L1C/A-L2P,1:L1C/A-L2C,2:L1C/A-L5) 53 | pos2-sigqzs1_2 =1 # (0:L1C-L5,1:L1C/A-L2C) 54 | pos2-siggal1_2 =0 # (0:E1C-E5a,1:E1C-E5b) 55 | pos2-ign_chierr =off # (0:off,1:on) 56 | out-solformat =llh # (0:llh,1:xyz,2:enu,3:nmea) 57 | out-outhead =on # (0:off,1:on) 58 | out-outopt =on # (0:off,1:on) 59 | out-outvel =off # (0:off,1:on) 60 | out-timesys =gpst # (0:gpst,1:utc,2:jst) 61 | out-timeform =hms # (0:tow,1:hms) 62 | out-timendec =3 63 | out-degform =deg # (0:deg,1:dms) 64 | out-fieldsep = 65 | out-outsingle =off # (0:off,1:on) 66 | out-maxsolstd =0 # (m) 67 | out-height =ellipsoidal # (0:ellipsoidal,1:geodetic) 68 | out-geoid =internal # (0:internal,1:egm96,2:egm08_2.5,3:egm08_1,4:gsi2000) 69 | out-solstatic =all # (0:all,1:single) 70 | out-nmeaintv1 =0 # (s) 71 | out-nmeaintv2 =0 # (s) 72 | out-outstat =off # (0:off,1:state,2:residual) 73 | stats-eratio1 =300 74 | stats-eratio2 =300 75 | stats-errphase =0.003 # (m) 76 | stats-errphaseel =0.003 # (m) 77 | stats-errphasebl =0 # (m/10km) 78 | stats-errdoppler =1 # (Hz) 79 | stats-stdbias =30 # (m) 80 | stats-stdiono =0.03 # (m) 81 | stats-stdtrop =0.3 # (m) 82 | stats-prnaccelh =1 # (m/s^2) 83 | stats-prnaccelv =0.1 # (m/s^2) 84 | stats-prnbias =0.00001 # (m) 85 | stats-prniono =0.01 # (m) 86 | stats-prntrop =0.00003 # (m) 87 | stats-prnpos =0 # (m) 88 | stats-clkstab =5e-12 # (s/s) 89 | ant1-postype =llh # (0:llh,1:xyz,2:single,3:posfile,4:rinexhead,5:rtcm,6:raw) 90 | ant1-pos1 =90 # (deg|m) 91 | ant1-pos2 =0 # (deg|m) 92 | ant1-pos3 =-6335367.6285 # (m|m) 93 | ant1-anttype =* 94 | ant1-antdele =0 # (m) 95 | ant1-antdeln =0 # (m) 96 | ant1-antdelu =0 # (m) 97 | ant2-postype =llh # (0:llh,1:xyz,2:single,3:posfile,4:rinexhead,5:rtcm,6:raw) 98 | ant2-pos1 =90 # (deg|m) 99 | ant2-pos2 =0 # (deg|m) 100 | ant2-pos3 =-6335367.6285 # (m|m) 101 | ant2-anttype = 102 | ant2-antdele =0 # (m) 103 | ant2-antdeln =0 # (m) 104 | ant2-antdelu =0 # (m) 105 | ant2-maxaveep =0 106 | ant2-initrst =off # (0:off,1:on) 107 | misc-timeinterp =off # (0:off,1:on) 108 | misc-sbasatsel =0 # (0:all) 109 | misc-rnxopt1 = 110 | misc-rnxopt2 = 111 | misc-pppopt = 112 | misc-rtcmopt = 113 | file-satantfile =./data/igs14_20230719_KMD_add.atx 114 | file-rcvantfile =./data/igs14_20230719_KMD_add.atx 115 | file-staposfile = 116 | file-geoidfile = 117 | file-ionofile = 118 | file-dcbfile = 119 | file-eopfile = 120 | file-blqfile = 121 | file-tempdir = 122 | file-geexefile = 123 | file-solstatfile = 124 | file-tracefile = 125 | -------------------------------------------------------------------------------- /bin/rtkrcv.conf: -------------------------------------------------------------------------------- 1 | # 2 | # rtkrcv.conf: rtkrcv options for real-time ppp 3 | # 4 | 5 | pos1-posmode =ppp-kine # (0:single,1:dgps,2:kinematic,3:static,4:movingbase,5:fixed,6:ppp-kine,7:ppp-static,8:ppp-fixed) 6 | pos1-frequency =l1+2 # (1:l1,2:l1+2,3:l1+2+3,4:l1+2+3+4,5:l1+2+3+4+5) 7 | pos1-soltype =forward # (0:forward,1:backward,2:combined) 8 | pos1-elmask =10 # (deg) 9 | pos1-snrmask_r =off # (0:off,1:on) 10 | pos1-snrmask_b =off # (0:off,1:on) 11 | pos1-snrmask_L1 =0,0,0,0,0,0,0,0,0 12 | pos1-snrmask_L2 =0,0,0,0,0,0,0,0,0 13 | pos1-snrmask_L5 =0,0,0,0,0,0,0,0,0 14 | pos1-dynamics =off # (0:off,1:on) 15 | pos1-tidecorr =on # (0:off,1:on,2:otl) 16 | pos1-ionoopt =est-stec # (0:off,1:brdc,2:sbas,3:dual-freq,4:est-stec,5:ionex-tec,6:qzs-brdc) 17 | pos1-tropopt =est-ztd # (0:off,1:saas,2:sbas,3:est-ztd,4:est-ztdgrad) 18 | pos1-sateph =brdc+ssrapc # (0:brdc,1:precise,2:brdc+sbas,3:brdc+ssrapc,4:brdc+ssrcom) 19 | pos1-posopt1 =on # (0:off,1:on) 20 | pos1-posopt2 =on # (0:off,1:on) 21 | pos1-posopt3 =on # (0:off,1:on,2:precise) 22 | pos1-posopt4 =on # (0:off,1:on) 23 | pos1-posopt5 =off # (0:off,1:on) 24 | pos1-posopt6 =off # (0:off,1:on) 25 | pos1-exclsats = # (prn ...) 26 | pos1-navsys =29 # (1:gps+2:sbas+4:glo+8:gal+16:qzs+32:bds+64:navic) 27 | pos2-armode =continuous # (0:off,1:continuous,2:instantaneous,3:fix-and-hold) 28 | pos2-gloarmode =off # (0:off,1:on) 29 | pos2-bdsarmode =off # (0:off,1:on) 30 | pos2-arsys =1 # (1:gps+8:gal+16:qzs) 31 | pos2-arthres =3.0 32 | pos2-arthres1 =0.9999 33 | pos2-arthres2 =0.25 34 | pos2-arthres3 =0.1 35 | pos2-arthres4 =0.05 36 | pos2-arlockcnt =0 37 | pos2-arelmask =15 # (deg) 38 | pos2-arminfix =10 39 | pos2-armaxiter =99 40 | pos2-elmaskhold =0 # (deg) 41 | pos2-aroutcnt =5 42 | pos2-maxage =30 # (s) 43 | pos2-syncsol =off # (0:off,1:on) 44 | pos2-slipthres =0.15 # (m) 45 | pos2-rejionno =100 # (m) 46 | pos2-rejgdop =30 47 | pos2-niter =1 48 | pos2-baselen =0 # (m) 49 | pos2-basesig =0 # (m) 50 | pos2-siggpsIIR-M =0 # (0:L1C/A-L2P,1:L1C/A-L2C) 51 | pos2-siggpsIIF =0 # (0:L1C/A-L2P,1:L1C/A-L2C,2:L1C/A-L5) 52 | pos2-siggpsIIIA =0 # (0:L1C/A-L2P,1:L1C/A-L2C,2:L1C/A-L5) 53 | pos2-sigqzs1_2 =1 # (0:L1C-L5,1:L1C/A-L2C) 54 | pos2-siggal =1 # (0:E1C-E5a,1:E1C-E5b) 55 | pos2-ign_chierr =off # (0:off,1:on) 56 | out-solformat =llh # (0:llh,1:xyz,2:enu,3:nmea) 57 | out-outhead =on # (0:off,1:on) 58 | out-outopt =on # (0:off,1:on) 59 | out-outvel =off # (0:off,1:on) 60 | out-timesys =gpst # (0:gpst,1:utc,2:jst) 61 | out-timeform =hms # (0:tow,1:hms) 62 | out-timendec =3 63 | out-degform =deg # (0:deg,1:dms) 64 | out-fieldsep = 65 | out-outsingle =off # (0:off,1:on) 66 | out-maxsolstd =0 # (m) 67 | out-height =ellipsoidal # (0:ellipsoidal,1:geodetic) 68 | out-geoid =internal # (0:internal,1:egm96,2:egm08_2.5,3:egm08_1,4:gsi2000) 69 | out-solstatic =all # (0:all,1:single) 70 | out-nmeaintv1 =0 # (s) 71 | out-nmeaintv2 =0 # (s) 72 | out-outstat =off # (0:off,1:state,2:residual) 73 | stats-eratio1 =300 74 | stats-eratio2 =300 75 | stats-errphase =0.003 # (m) 76 | stats-errphaseel =0.003 # (m) 77 | stats-errphasebl =0 # (m/10km) 78 | stats-errdoppler =1 # (Hz) 79 | stats-stdbias =30 # (m) 80 | stats-stdiono =0.03 # (m) 81 | stats-stdtrop =0.3 # (m) 82 | stats-prnaccelh =1 # (m/s^2) 83 | stats-prnaccelv =0.1 # (m/s^2) 84 | stats-prnbias =0.00001 # (m) 85 | stats-prniono =0.01 # (m) 86 | stats-prntrop =0.00003 # (m) 87 | stats-prnpos =0 # (m) 88 | stats-clkstab =5e-12 # (s/s) 89 | ant1-postype =llh # (0:llh,1:xyz,2:single,3:posfile,4:rinexhead,5:rtcm,6:raw) 90 | ant1-pos1 =90 # (deg|m) 91 | ant1-pos2 =0 # (deg|m) 92 | ant1-pos3 =-6335367.6285 # (m|m) 93 | ant1-anttype = 94 | ant1-antdele =0 # (m) 95 | ant1-antdeln =0 # (m) 96 | ant1-antdelu =0 # (m) 97 | ant2-postype =llh # (0:llh,1:xyz,2:single,3:posfile,4:rinexhead,5:rtcm,6:raw) 98 | ant2-pos1 =90 # (deg|m) 99 | ant2-pos2 =0 # (deg|m) 100 | ant2-pos3 =-6335367.6285 # (m|m) 101 | ant2-anttype = 102 | ant2-antdele =0 # (m) 103 | ant2-antdeln =0 # (m) 104 | ant2-antdelu =0 # (m) 105 | ant2-maxaveep =0 106 | ant2-initrst =off # (0:off,1:on) 107 | misc-timeinterp =off # (0:off,1:on) 108 | misc-sbasatsel =0 # (0:all) 109 | misc-rnxopt1 = 110 | misc-rnxopt2 = 111 | misc-pppopt = 112 | misc-rtcmopt = 113 | file-satantfile =./data/igs14_20230719_KMD_add.atx 114 | file-rcvantfile =./data/igs14_20230719_KMD_add.atx 115 | file-staposfile = 116 | file-geoidfile = 117 | file-ionofile = 118 | file-dcbfile = 119 | file-eopfile = 120 | file-blqfile = 121 | file-tempdir = 122 | file-geexefile = 123 | file-solstatfile = 124 | file-tracefile = 125 | 126 | console-passwd = 127 | console-timetype =gpst # (0:gpst,1:utc,2:jst,3:tow) 128 | console-soltype =deg # (0:dms,1:deg,2:xyz,3:enu,4:pyl) 129 | console-solflag =off # (0:off,1:std+2:age/ratio/ns) 130 | inpstr1-type =file # (0:off,1:serial,2:file,3:tcpsvr,4:tcpcli,6:ntripcli,7:ftp,8:http,10:udpsvr,11:udpcli) 131 | inpstr2-type =off # (0:off,1:serial,2:file,3:tcpsvr,4:tcpcli,6:ntripcli,7:ftp,8:http,10:udpsvr,11:udpcli) 132 | inpstr3-type =file # (0:off,1:serial,2:file,3:tcpsvr,4:tcpcli,6:ntripcli,7:ftp,8:http,10:udpsvr,11:udpcli) 133 | inpstr1-path =./data/MALIB_OSS_data_obsnav_240822-1100.sbf::T::x10 134 | inpstr2-path = 135 | inpstr3-path =./data/MALIB_OSS_data_l6e_240822-1100.sbf::T::x10 136 | inpstr1-format =sbf # (0:rtcm2,1:rtcm3,2:oem4,3:oem3,4:ubx,5:ss2,6:hemis,7:skytraq,8:javad,9:nvs,10:binex,11:rt17,12:sbf,14:sp3,21:l6e) 137 | inpstr2-format = # (0:rtcm2,1:rtcm3,2:oem4,3:oem3,4:ubx,5:ss2,6:hemis,7:skytraq,8:javad,9:nvs,10:binex,11:rt17,12:sbf,14:sp3,21:l6e) 138 | inpstr3-format =sbf # (0:rtcm2,1:rtcm3,2:oem4,3:oem3,4:ubx,5:ss2,6:hemis,7:skytraq,8:javad,9:nvs,10:binex,11:rt17,12:sbf,14:sp3,21:l6e) 139 | inpstr2-nmeareq =off # (0:off,1:latlon,2:single) 140 | inpstr2-nmealat =0 # (deg) 141 | inpstr2-nmealon =0 # (deg) 142 | outstr1-type =file # (0:off,1:serial,2:file,3:tcpsvr,4:tcpcli,5:ntripsvr,9:ntripcas,10:udpsvr,11:udpcli) 143 | outstr2-type =off # (0:off,1:serial,2:file,3:tcpsvr,4:tcpcli,5:ntripsvr,9:ntripcas,10:udpsvr,11:udpcli) 144 | outstr1-path =./data/out/rtkrcv_test.pos 145 | outstr2-path = 146 | outstr1-format =llh # (0:llh,1:xyz,2:enu,3:nmea,4:stat) 147 | outstr2-format =llh # (0:llh,1:xyz,2:enu,3:nmea,4:stat) 148 | logstr1-type =off # (0:off,1:serial,2:file,3:tcpsvr,4:tcpcli,5:ntripsvr,9:ntripcas,10:udpsvr,11:udpcli) 149 | logstr2-type =off # (0:off,1:serial,2:file,3:tcpsvr,4:tcpcli,5:ntripsvr,9:ntripcas,10:udpsvr,11:udpcli) 150 | logstr3-type =off # (0:off,1:serial,2:file,3:tcpsvr,4:tcpcli,5:ntripsvr,9:ntripcas,10:udpsvr,11:udpcli) 151 | logstr1-path = 152 | logstr2-path = 153 | logstr3-path = 154 | misc-svrcycle =10 # (ms) 155 | misc-timeout =10000 # (ms) 156 | misc-reconnect =10000 # (ms) 157 | misc-nmeacycle =5000 # (ms) 158 | misc-buffsize =32768 # (bytes) 159 | misc-navmsgsel =all # (0:all,1:rover,2:base,3:corr) 160 | misc-proxyaddr = 161 | misc-fswapmargin =30 # (s) 162 | -------------------------------------------------------------------------------- /data/MALIB_OSS_data.tar.gz: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JAXA-SNU/MALIB/3b217d34d8429e04ea095c68e78678d3f9fcecfc/data/MALIB_OSS_data.tar.gz -------------------------------------------------------------------------------- /doc/doc/manual.docx: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JAXA-SNU/MALIB/3b217d34d8429e04ea095c68e78678d3f9fcecfc/doc/doc/manual.docx -------------------------------------------------------------------------------- /doc/doc/relnotes_2.2.1.txt: -------------------------------------------------------------------------------- 1 | RTKLIB: ver.2.2.1 Release Notes 2 | 2009/5/17 3 | -------------------------------------------------------------------------------- 4 | 5 | Supported Receivers and Data Messages 6 | 7 | 8 | (1) RTCM 2.3 (http://www.rtcm.org/) 9 | 10 | Type 1, 3, 9, 14, 16, 17, 18, 19, 22 11 | 12 | (2) RTCM 3.0/3.1 (http://www.rtcm.org/) 13 | 14 | Type 1002, 1004, 1005, 1006, 1019 15 | 16 | (3) NovAtel OEM4/V (http://www.novatel.com/) 17 | 18 | RANGEB, RANGECMPB, RAWEPHEMB, IONUTCB, RAWWAASFRAMEB, 19 | 20 | (4) NovAtel OEM3 (Millennium) (http://www.novatel.com/) 21 | 22 | RGEB, REPB, IONB, UTCB, FRMB 23 | 24 | (5) u-blox LEA-4T (AEK-4T) (http://u-blox.com/) 25 | 26 | RXMRAW, RXMSFRB 27 | 28 | (6) NovAtel Superstar II (http://www.novatel.com/) 29 | 30 | ID#20, ID#21, ID#22, ID#23, ID#67 31 | 32 | (7) Hemisphere Crescent (http://www.hemispheregps.com/) 33 | 34 | bin 80, bin 94, bin 95, bin 96 35 | 36 | -------------------------------------------------------------------------------- 37 | 38 | Changes: ver.2.2.0 -> ver.2.2.1 39 | 40 | 41 | (1) The following RTCM 2.3 and RTCM 3.0/3.1 messages are supported. 42 | 43 | (a) RTCM 2.3: Type 1, 3, 9, 14, 16, 17, 18, 19, 22 44 | (b) RTCM 3.0/3.1: Type 1002, 1004, 1005, 1006, 1019 45 | 46 | (2) The following receiver raw data messages are supported. 47 | 48 | (a) NovAtel OEM3 (Milennium): RGEB, REPB, FRMB, IONB, UTCB 49 | (b) NovAtel OEM4/5: RANGEB 50 | 51 | (3) The following APIs are added, deleted or modified. 52 | 53 | (a) Added: 54 | satno(), satsys(), satid2no(), satno2id(), traceb(), geph2pos(), convrnx(), 55 | getbitu(), getbits(), crc32(), crc24q(), decode_word(), decode_frame(), 56 | init_raw(), free_raw(), input_raw(), input_rawf(), input_oem4(), input_oem3(), 57 | input_ubx(), input_ss2(), input_cres(), input_oem4f(), input_oem3f(), 58 | input_ubxf(), input_ss2f(), input_cresf(), init_rtcm(), free_rtcm(), 59 | input_rtcm2(), input_rtcm3(), input_rctm2f(), input_rtcm3f(), outnmea_rmc(), 60 | outnmea_gga(), outnmea_gsa(), outnmea_gsv() 61 | 62 | (b) Deleted: 63 | readrnxf(), decodefrm(), decodenav(), addobs(), addnav(), addsbs(), 64 | addionutc(), convlog(), readlog(), readlogs(), decodelog(), rtksvrgetsol(), 65 | SAT(), PRN(), decodenov(), convnov(), readnov(), decodeubx(), convubx(), 66 | readubx(), decodess2(), convss2(), readss2(), decodecres(), convcres(), 67 | readcres() 68 | 69 | (c) Modified: 70 | outrnxobsh(), outrnxobsb(), outrnxnavh(), outrnxnavb(), outsols(), outsol(), 71 | sbsreadmsg(), sbsreadmsgt(), sbsdecodemsg(), sbspntpos(), strsvrstart(), 72 | rtksvrstart() 73 | 74 | (4) The following library source codes are added or deleted. 75 | 76 | (a) Added: 77 | convrnx.c, rcvraw.c, rtcm.c 78 | 79 | (b) Deleted: 80 | rcvlog.c, rcv/novatel.h, rcv/ublox.h, rcv/ss2.h, rcv/crescent.h 81 | 82 | (5) RTKNAVI 83 | 84 | (a) "RTK Map" window is added. "Gnd Track" plots in the main window are 85 | deleted. 86 | (b) "Rover : Base/NRTK SNR" plot in the main window is added. 87 | (c) "Streams" dialog is separated into "Input Streams", "Output Streams" 88 | and "Log Streams" dialogs. 89 | (d) "RTCM 2", "RTCM 3" and "NovAtel OEM3" are supported as the input 90 | stream format. 91 | (e) Transmission of NMEA GPGGA to base-station or NRTK (Network RTK) is 92 | supported. 93 | (f) Time tagging is supported for the input, output and log file streams. 94 | (g) Separated multiple "RTK Monitor" windows are supported. 95 | (h) Some "RTK Monitor" windows are added: Covariance, RTCM, RTCM DGPS, 96 | Input Rover, Input Base/NRTK, Solution 1/2 and Error/Warning. 97 | (i) Hide Button is added to minimize the main window as the task-tray-icon. 98 | (j) "Excluded Satellites" is activated in "Options - Setting1" dialog. 99 | (k) "RTCM Station Position" is added as "Base/NRTK Station position" in 100 | "Options - Position" dialog. 101 | (l) "Timeout/Rec-connect Interval" is added in "Options - Misc" dialog. 102 | (m) "NMEA Transmission Cycle" is added in "Options - Misc" dialog. 103 | 104 | (6) RTKPOST/RTKPOST_MKL 105 | 106 | (a) Time "Unit" options is suppored in the main window. 107 | (b) Keyword replacement in input and output file paths is supported for 108 | batch processing. 109 | (c) "Excluded Satellites" is activated in "Options - Setting1" dialog. 110 | (d) "RINEX Header Position" is added as "Base/NRTK Station postion" in 111 | "Options - Position" dialog. 112 | (e) "Rover List" and "Base Station List" are added in "Options - Misc" 113 | dialog. 114 | (f) The file mkl_def.dll is added in /bin to execute RTKPOST with MKL for 115 | non-mkl environment. 116 | 117 | (7) RTKCONV 118 | 119 | (a) "RTCM 2", "RTCM 3" and "NovAtel OEM3" are supported as the input log 120 | file format. 121 | (b) "Navigation Systems", "Observation Types", "Frequencies", "Output Debug 122 | Trace" options are added in "Options" dialog. 123 | 124 | (8) RTKPLOT 125 | 126 | (a) "Animation Start/Stop" Menus and "Animation" Button are added in the 127 | main window. 128 | (b) "View - Toolbar" and "View - Statusbar" menus are added in the main 129 | window. 130 | (c) "Parity Unknown", "Hide Low Satellite", "Graph Label", "Grid Label", 131 | "Compass", "Scale" and "Anim. Interval" options are added in "Options" 132 | dialog. 133 | 134 | (9) STRSVR 135 | 136 | (a) "Stream Monitor" window is added. 137 | (b) Hide Button is added to minimize the main window as the task-tray-icon. 138 | (c) "NMEA Request Cycle" and "Lat/Lon/Height" options are added in "Options" 139 | dialog. 140 | 141 | (10) CONVBIN 142 | 143 | (a) Command line options -f, -od, -os are added. 144 | (b) Log format type "rtcm2", "rtcm3", and "oem3" are added for -r command 145 | line option. 146 | 147 | -------------------------------------------------------------------------------- 148 | -------------------------------------------------------------------------------- /doc/doc/relnotes_2.2.2.txt: -------------------------------------------------------------------------------- 1 | RTKLIB: ver.2.2.2 Release Notes 2 | 2009/9/5 3 | -------------------------------------------------------------------------------- 4 | 5 | Supported Receivers and Data Messages 6 | 7 | 8 | (1) RTCM 2.3 (http://www.rtcm.org/) 9 | 10 | Type 1, 3, 9, 14, 16, 17, 18, 19, 22 11 | 12 | (2) RTCM 3.0/3.1 (http://www.rtcm.org/) 13 | 14 | Type 1002, 1004, 1005, 1006, 1019 15 | 16 | (3) NovAtel OEM4/V (http://www.novatel.com/) 17 | 18 | RANGEB, RANGECMPB, RAWEPHEMB, IONUTCB, RAWWAASFRAMEB, 19 | 20 | (4) NovAtel OEM3 (Millennium) (http://www.novatel.com/) 21 | 22 | RGEB, RGED, REPB, IONB, UTCB, FRMB 23 | 24 | (5) u-blox LEA-4T (AEK-4T)/LEA-5T (EVK-5T) (http://u-blox.com/) 25 | 26 | RXMRAW, RXMSFRB 27 | 28 | (6) NovAtel Superstar II (http://www.novatel.com/) 29 | 30 | ID#20, ID#21, ID#22, ID#23, ID#67 31 | 32 | (7) Hemisphere Crescent (http://www.hemispheregps.com/) 33 | 34 | bin 80, bin 94, bin 95, bin 96 35 | 36 | -------------------------------------------------------------------------------- 37 | 38 | Changes: ver.2.2.1 -> ver.2.2.2 39 | 40 | 41 | (1) The following patchs are incorpolated. 42 | 43 | (a) rtklib_2.2.1_p1.zip 44 | (b) rtklib_2.2.1_p2.zip 45 | (c) rtklib_2.2.1_p3.zip 46 | (d) rtklib_2.2.1_p4.zip 47 | (e) rtklib_2.2.1_p5.zip 48 | 49 | (2) The following problems are fixed. 50 | 51 | (a) No.2 Unable positioning when SBAS ranging enabled. 52 | (b) No.8 No geoid correction outside of the neighborhood of Japan 53 | (c) No.13 Flipped or vibrated plots of single point solutions in "RTK Map" window 54 | (d) No.14 Sats/DOP plot for 20Hz or higher sampling rate data 55 | (e) No.17 Invalid solutions with Moving-Base and Combined modes 56 | (f) No.20 Decimal point format error to set the positioning options 57 | (g) No.24 No proper default values for the time format and the base station position 58 | 59 | (3) No API changed. 60 | 61 | (4) No additional source code. 62 | 63 | (5) RTKNAVI 64 | 65 | No functional change. 66 | 67 | (6) RTKPOST/RTKPOST_MKL 68 | 69 | No functional change. 70 | 71 | (7) RTKCONV 72 | 73 | No functional change. 74 | 75 | (8) RTKPLOT 76 | 77 | No functional change. 78 | 79 | (9) STRSVR 80 | 81 | No functional change. 82 | 83 | (10) CONVBIN 84 | 85 | No functional change. 86 | 87 | (11) RNX2RTKP 88 | 89 | (a) command line options -p 4, -l, -z are added. 90 | 91 | -------------------------------------------------------------------------------- 92 | -------------------------------------------------------------------------------- /doc/doc/relnotes_2.3.0.txt: -------------------------------------------------------------------------------- 1 | RTKLIB: ver.2.3.0 Release Notes 2 | 2009/12/17 3 | -------------------------------------------------------------------------------- 4 | 5 | Supported Receivers and Data Messages 6 | 7 | 8 | (1) RTCM 2.3 (http://www.rtcm.org/) 9 | 10 | Type 1, 3, 9, 14, 16, 17, 18, 19, 22 11 | 12 | (2) RTCM 3.0/3.1 (http://www.rtcm.org/) 13 | 14 | Type 1002, 1004, 1005, 1006, 1010, 1012, 1019, 1020 15 | 16 | (3) NovAtel OEM4/V (http://www.novatel.com/) 17 | 18 | RANGEB, RANGECMPB, RAWEPHEMB, IONUTCB, RAWWAASFRAMEB, GLOEPHEMERISB 19 | 20 | (4) NovAtel OEM3 (Millennium) (http://www.novatel.com/) 21 | 22 | RGEB, RGED, REPB, IONB, UTCB, FRMB 23 | 24 | (5) u-blox LEA-4T (AEK-4T)/LEA-5T (EVK-5T) (http://u-blox.com/) 25 | 26 | RXMRAW, RXMSFRB 27 | 28 | (6) NovAtel Superstar II (http://www.novatel.com/) 29 | 30 | ID#20, ID#21, ID#22, ID#23, ID#67 31 | 32 | (7) Hemisphere Crescent (http://www.hemispheregps.com/) 33 | 34 | bin 80, bin 94, bin 95, bin 96 35 | 36 | (8) SkyTraq S1315F (http://www.hemispheregps.com/) 37 | 38 | msg 0xDD, 0xE0, 0xDC 39 | 40 | -------------------------------------------------------------------------------- 41 | 42 | Changes: ver.2.2.2 -> ver.2.3.0 43 | 44 | (1) The following patches for ver.2.2.2 are included. 45 | (a) rtklib_2.2.2_p1 46 | (b) rtklib_2.2.2_p2 47 | (c) rtklib_2.2.2_p3 48 | 49 | (2) The following problems are fixed. 50 | (a) No.25 Improper row height of string-grid with non-standard DPI font scale 51 | (b) No.26 Improper antenna correction when Antenna Type is blank 52 | (c) No.30 Inverted Polarity of Doppler Frequency in NovAtel OEM3 REGD 53 | 54 | (3) The following APIs are added, deleted or changed. 55 | (a) added 56 | readnav(), savenav(), tracegnav(), tracepeph(), satwavelen(), opengeoid(), 57 | closegeoid(), outrnxgnavh(), outrnxgnavb(), input_stq(), input_stqf(), 58 | gen_ubx(), gen_stq(), rtkopenstat(), rtkclosestat(), readsolstat(), 59 | strsendnmea(), strsendcmd() 60 | 61 | (b) deleted 62 | none 63 | 64 | (c) changed 65 | pntpos(), convrnx() 66 | 67 | (4) The following source codes are added. 68 | rcv/skytraq.c 69 | 70 | (5) RTKNAVI 71 | (a) GLONASS and GPS/GLONASS combined RTK are supported 72 | (b) "Baseline" display mode is added 73 | (c) Multiple TCP client connection is supported for TCP server of Output/Log stream 74 | (d) Keyword replacement is supported for File of Output/Log stream 75 | (e) Vertical solution plot is added to RTK Map 76 | (f) "GLONASS Nav" is adde to RTK Monitor 77 | (g) "Fix and Hold" mode for ambiguity resolution is supported 78 | (h) Receiver Dyamics is supported 79 | (i) "Fixed" selection as "Positioning Mode" is added in "Options"-"Setting1" dialog 80 | (j) "Receiver Dynamics" option is added in "Options"-"Setting1" dialog 81 | (k) "Navi Sys" option is added in "Options"-"Setting1" dialog 82 | (l) "Fix and Hold" selection as "Integer Ambiguity Resolution" is added in "Options"-"Setting2" dialog 83 | (m) "GLONASS Ambiguity Resolution" option is added in "Options"-"Setting2" dialog 84 | (o) "Baseline Length Constraint" options are added in "Options"-"Setting2" dialog 85 | (p) "# of Decimals" option is added in "Options"-"Output" dialog 86 | (q) "Geoid Model" options are added in "Options"-"Output" dialog 87 | (r) "Output Solution Status" option is added in "Options"-"Output" dialog 88 | (s) "Meas Errors of Doppler Frequency" option is added in "Options"-"Statistics" dialog 89 | (t) "Process Noise of Receiver Accel Horiz/Vertical" option is added in "Options"-"Statistics" dialog 90 | (u) "Rover Position" can be set in "Options"-"Postions" dialog if "Fixed" is selected as "Positioning Mode" 91 | (v) "Geoid Data File" option is added in "Options"-"Files" 92 | (w) SkyTraq S1315F receiver is supported. 93 | (x) Hemisphere Eclipse receiver is supported. 94 | (y) Binary commands for ublox and SkyTraq are supported for startup/shutdown commands. 95 | (z) RTCM 3.1 type 1010, 1012, 1020 messages are supported. 96 | (aa) NovAtel OEMV GLOEPHEMERISB message is supported. 97 | (ab) GLONASS measurement data in NovAtel OEMV RANGEB and RANGECMPB are supported. 98 | 99 | (6) RTKRCV 100 | (a) A console version real-time positining AP is added for Linux or other environments. 101 | 102 | (7) RTKPOST/RTKPOST_MKL 103 | (a) GLONASS and GPS/GLONASS combined positioning are supported 104 | (b) "Fix and Hold" mode for ambiguity resolution is supported 105 | (c) Receiver Dyamics is supported 106 | (d) A Field for GLONASS navigation data is added 107 | (e) Buttons to view solution status and debug trace are added 108 | (f) "Fixed" selection as "Positioning Mode" is added in "Options"-"Setting1" dialog 109 | (g) "Receiver Dynamics" option is added in "Options"-"Setting1" dialog 110 | (h) "Navi Sys" option is added in "Options"-"Setting1" dialog 111 | (i) "Fix and Hold" selection as "Integer Ambiguity Resolution" is added in "Options"-"Setting2" dialog 112 | (j) "GLONASS Ambiguity Resolution" option is added in "Options"-"Setting2" dialog 113 | (k) "Baseline Length Constraint" options are added in "Options"-"Setting2" dialog 114 | (l) "# of Decimals" option is added in "Options"-"Output" dialog 115 | (m) "Geoid Model" options are added in "Options"-"Output" dialog 116 | (n) "Output Solution Status" option is added in "Options"-"Output" dialog 117 | (o) "Meas Errors of Doppler Frequency" option is added in "Options"-"Statistics" dialog 118 | (p) "Process Noise of Receiver Accel Horiz/Vertical" option is added in "Options"-"Statistics" dialog 119 | (q) "Rover Position" can be set in "Options"-"Postions" dialog if "Fixed" is selected as "Positioning Mode" 120 | (r) "Geoid Data File" option is added in "Options"-"Files" 121 | (s) '#' can be used for comment in "Rover List" or "Base Station List" in Options-"Misc" dialog 122 | (t) Wild-cards in file path of precise ephemeris (SP3) are supported. 123 | 124 | (8) RTKCONV 125 | (a) "RINEX GNAV file" field is added as an output file path 126 | (b) "Crescent" selection as "Format" option is chaned to "Hemisphere" 127 | (c) "Receiver Options" field is added in "Options" dialog instead of "Flip Sign (ublox)" option 128 | (d) SkyTraq S1315F receiver is supported. 129 | (e) Hemisphere Eclipse receiver is supported. 130 | (f) RTCM 3.1 type 1010, 1012, 1020 messages are supported. 131 | (g) NovAtel OEMV GLOEPHEMERISB message is supported. 132 | (h) GLONASS measurement data in NovAtel OEMV RANGEB and RANGECMPB are supported. 133 | 134 | (9) RTKPLOT 135 | (a) GLONASS observation data plot is supported 136 | (b) NSat/Age/Ratio plot mode is added for solution plot 137 | (c) L1/L2 residuals plot mode is added for solution plot 138 | (d) "Maximum DOP", "Navigation System" and "Excluded Sats" options are added to "Options" dialog. 139 | 140 | (10) STRSVR 141 | (a) Multiple TCP client connection is supported for TCP server of Output stream 142 | (b) Binary commands for ublox and SkyTraq are supported for startup/shutdown commands. 143 | 144 | (11) CONVBIN 145 | (a) command line options -r stq, -g, are added. 146 | (b) command line option -r cres is changed to -r hemis 147 | (c) GLONASS data and RINEX GNAV file are supported. 148 | 149 | (12) RNX2RTKP 150 | (a) GLONASS is supported. 151 | (b) Command line options -p 4, -h, -a, -l, -x are added. 152 | 153 | (13) STR2STR 154 | (a) A console version stream server AP is supported for Linux or other environments. 155 | 156 | 157 | 158 | -------------------------------------------------------------------------------- 159 | -------------------------------------------------------------------------------- /doc/doc/relnotes_2.4.0.doc: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JAXA-SNU/MALIB/3b217d34d8429e04ea095c68e78678d3f9fcecfc/doc/doc/relnotes_2.4.0.doc -------------------------------------------------------------------------------- /doc/manual_2.4.2.pdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JAXA-SNU/MALIB/3b217d34d8429e04ea095c68e78678d3f9fcecfc/doc/manual_2.4.2.pdf -------------------------------------------------------------------------------- /doc/manual_MALIB1.0.0.pdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JAXA-SNU/MALIB/3b217d34d8429e04ea095c68e78678d3f9fcecfc/doc/manual_MALIB1.0.0.pdf -------------------------------------------------------------------------------- /lib/mkl/readme.txt: -------------------------------------------------------------------------------- 1 | # 2 | # Intel MKL (math kernel library) 11.1.2.244 3 | # 4 | 5 | Redistributions of the MKL [1] shared library files under the Intel 6 | EULA (end user license agreement) and the redistributable list 7 | redist.txt. For the license, refer [2]. 8 | 9 | FILES: 10 | 11 | intel64/libmkl_avx.so 12 | intel64/libmkl_avx2.so 13 | intel64/libmkl_core.so 14 | intel64/libmkl_def.so 15 | intel64/libmkl_gnu_thread.so 16 | intel64/libmkl_intel_lp64.so 17 | 18 | REFERENCES: 19 | 20 | [1] Intel Math Kernel Library 21 | http://software.intel.com/en-us/intel-mkl 22 | 23 | [2] Intel Math Kernel Library - Licensing FAQ. 24 | http://software.intel.com/en-us/articles/intel-math-kernel-library-licensing-faq 25 | 26 | -------------------------------------------------------------------------------- /test/data/rcvraw/GMSD7_20121014.rtcm3: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JAXA-SNU/MALIB/3b217d34d8429e04ea095c68e78678d3f9fcecfc/test/data/rcvraw/GMSD7_20121014.rtcm3 -------------------------------------------------------------------------------- /test/data/rcvraw/cres_20080526.bin: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JAXA-SNU/MALIB/3b217d34d8429e04ea095c68e78678d3f9fcecfc/test/data/rcvraw/cres_20080526.bin -------------------------------------------------------------------------------- /test/data/rcvraw/gw10_20110121.sbas: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JAXA-SNU/MALIB/3b217d34d8429e04ea095c68e78678d3f9fcecfc/test/data/rcvraw/gw10_20110121.sbas -------------------------------------------------------------------------------- /test/data/rcvraw/javad_20110115.jps: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JAXA-SNU/MALIB/3b217d34d8429e04ea095c68e78678d3f9fcecfc/test/data/rcvraw/javad_20110115.jps -------------------------------------------------------------------------------- /test/data/rcvraw/oem3_20090410.gps: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JAXA-SNU/MALIB/3b217d34d8429e04ea095c68e78678d3f9fcecfc/test/data/rcvraw/oem3_20090410.gps -------------------------------------------------------------------------------- /test/data/rcvraw/oemv_200911218.gps: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JAXA-SNU/MALIB/3b217d34d8429e04ea095c68e78678d3f9fcecfc/test/data/rcvraw/oemv_200911218.gps -------------------------------------------------------------------------------- /test/data/rcvraw/ss2_20080517.log: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JAXA-SNU/MALIB/3b217d34d8429e04ea095c68e78678d3f9fcecfc/test/data/rcvraw/ss2_20080517.log -------------------------------------------------------------------------------- /test/data/rcvraw/testglo.rtcm3: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JAXA-SNU/MALIB/3b217d34d8429e04ea095c68e78678d3f9fcecfc/test/data/rcvraw/testglo.rtcm3 -------------------------------------------------------------------------------- /test/data/rcvraw/ubx_20080526.ubx: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JAXA-SNU/MALIB/3b217d34d8429e04ea095c68e78678d3f9fcecfc/test/data/rcvraw/ubx_20080526.ubx -------------------------------------------------------------------------------- /test/data/tle/igs17127.erp: -------------------------------------------------------------------------------- 1 | version 2 2 | EOP SOLUTION 3 | MJD X Y UT1-UTC LOD Xsig Ysig UTsig LODsig Nr Nf Nt Xrt Yrt Xrtsig Yrtsig dpsi deps 4 | 10**-6" .1us .1us/d 10**-6" .1us .1us/d 10**-6"/d 10**-6"/d 10**-6 5 | 56228.50 145507 311622 3469742 10253 4 5 0 8 0 0 0 -996 163 13 14 0 0 6 | 56229.50 144461 311497 3460025 9177 4 5 0 8 0 0 0 -812 -69 14 14 0 0 7 | 56230.50 144028 311300 3451192 8620 4 5 0 8 0 0 0 -363 116 14 14 0 0 8 | 56231.50 143704 311395 3443190 7572 4 5 0 9 0 0 0 -595 162 14 14 0 0 9 | 56232.50 142911 311249 3435848 7208 4 5 0 8 0 0 0 -936 43 14 13 0 0 10 | 56233.50 142007 311221 3428848 6896 4 5 0 8 0 0 0 -964 58 14 13 0 0 11 | 56234.50 141038 310783 3421755 7498 4 5 0 8 0 0 0 -851 -602 14 14 0 0 12 | -------------------------------------------------------------------------------- /test/data/tle/prn_name.txt: -------------------------------------------------------------------------------- 1 | # 2 | # Satellite Name of Navigation Satellites 3 | # 4 | #ID SATELLITE NAME # COMMENT 5 | 6 | G01 GPS BIIF-2 # PRN 01 7 | G02 GPS BIIR-13 # PRN 02 8 | G03 GPS BIIA-25 # PRN 03 9 | G04 GPS BIIA-23 # PRN 04 10 | G05 GPS BIIRM-8 # PRN 05 11 | G06 GPS BIIA-24 # PRN 06 12 | G07 GPS BIIRM-6 # PRN 07 13 | G08 GPS BIIA-28 # PRN 08 14 | G09 GPS BIIA-21 # PRN 09 15 | G10 GPS BIIA-26 # PRN 10 16 | G11 GPS BIIR-3 # PRN 11 17 | G12 GPS BIIRM-3 # PRN 12 18 | G13 GPS BIIR-2 # PRN 13 19 | G14 GPS BIIR-6 # PRN 14 20 | G15 GPS BIIRM-4 # PRN 15 21 | G16 GPS BIIR-8 # PRN 16 22 | G17 GPS BIIRM-1 # PRN 17 23 | G18 GPS BIIR-7 # PRN 18 24 | G19 GPS BIIR-11 # PRN 19 25 | G20 GPS BIIR-4 # PRN 20 26 | G21 GPS BIIR-9 # PRN 21 27 | G22 GPS BIIR-10 # PRN 22 28 | G23 GPS BIIR-12 # PRN 23 29 | G24 GPS BIIF-3 # PRN 24 30 | G25 GPS BIIF-1 # PRN 25 31 | G26 GPS BIIA-14 # PRN 26 32 | G27 GPS BIIA-15 # PRN 27 33 | G28 GPS BIIR-5 # PRN 28 34 | G29 GPS BIIRM-5 # PRN 29 35 | G30 GPS BIIA-22 # PRN 30 36 | G31 GPS BIIRM-2 # PRN 31 37 | G32 GPS BIIA-10 # PRN 32 38 | 39 | R01 COSMOS 2456 # 730 40 | R02 COSMOS 2448 # 728 41 | R03 COSMOS 2476 # 744 42 | R04 COSMOS 2474 # 742 43 | R05 COSMOS 2458 # 734 44 | R06 COSMOS 2457 # 733 45 | R07 COSMOS 2477 # 745 46 | R08 COSMOS 2413 # 712 47 | R09 COSMOS 2464 # 736 48 | R10 COSMOS 2426 # 717 49 | R11 COSMOS 2436 # 723 50 | R12 COSMOS 2465 # 737 51 | R13 COSMOS 2434 # 721 52 | R14 COSMOS 2424 # 715 53 | R15 COSMOS 2425 # 716 54 | R16 COSMOS 2466 # 738 55 | R17 COSMOS 2478 # 746 56 | R18 COSMOS 2442 # 724 57 | R19 COSMOS 2433 # 720 58 | R20 COSMOS 2432 # 719 59 | R21 COSMOS 2443 # 725 60 | R22 COSMOS 2459 # 731 61 | R23 COSMOS 2460 # 732 62 | R24 COSMOS 2461 # 735 63 | #R21 COSMOS 2471 # 701K (test) 64 | #R14 COSMOS 2435 # 722 (spares) 65 | #R02 COSMOS 2475 # 743 (spares) 66 | #R17 COSMOS 2419 # 714 (spares) 67 | #R03 COSMOS 2447 # 727 (maintenance) 68 | #R22 COSMOS 2444 # 726 (maintenance) 69 | #R08 COSMOS 2449 # 729 (maintenance) 70 | 71 | E11 GALILEO-PFM # GSAT0101 72 | E12 GALILEO-FM2 # GSAT0102 73 | E?? GALILEO-FM3 # GSAT0103 74 | E?? GALILEO-FM4 # GSAT0104 75 | 76 | J01 QZS-1 # PRN 193,183 77 | 78 | C01 BEIDOU G1 79 | C02 BEIDOU G2 80 | C03 BEIDOU G3 81 | C04 BEIDOU G4 82 | C05 BEIDOU G5 83 | C06 BEIDOU IGSO 1 84 | C07 BEIDOU IGSO 2 85 | C08 BEIDOU IGSO 3 86 | C09 BEIDOU IGSO 4 87 | C10 BEIDOU IGSO 5 88 | C11 BEIDOU M3 89 | C12 BEIDOU M4 90 | C13 BEIDOU M5 91 | C14 BEIDOU M6 92 | C?? BEIDOU G6 93 | C30 BEIDOU M1 94 | 95 | 120 AOR-E # EGNOS/PRN 120 96 | 120 INTELSAT 3-F2 # EGNOS/PRN 120 97 | 124 ARTEMIS # EGNOS/PRN 124 98 | 126 IOR-W # EGNOS/PRN 126 99 | 126 INMARSAT 4-F2 # EGNOS/PRN 126 100 | 127 GSAT 8 # GAGAN/PRN 127 101 | 129 MTSAT-1R # MSAS /PRN 129 102 | 133 AMR # WAAS /PRN 133 103 | 135 CRW # WAAS /PRN 135 104 | 135 GALAXY 15 # WAAS /PRN 135 105 | 135 CRW # WAAS /PRN 135 106 | 137 MTSAT-2 # MSAS /PRN 137 107 | 138 CRE # WAAS /PRN 138 108 | 138 ANIK F1-R # WAAS /PRN 138 109 | 140 LUCH 5A # SDCM /PRN 140 110 | -------------------------------------------------------------------------------- /test/data/tle/tle_sgp4.txt: -------------------------------------------------------------------------------- 1 | TEST_SAT 2 | 1 88888U 80275.98708465 .00073094 13844-3 66816-4 0 8 7 3 | 2 88888 72.8435 115.9689 0086731 52.6988 110.5714 16.05824518 105 8 4 | -------------------------------------------------------------------------------- /test/utest/figtest1.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JAXA-SNU/MALIB/3b217d34d8429e04ea095c68e78678d3f9fcecfc/test/utest/figtest1.jpg -------------------------------------------------------------------------------- /test/utest/figtest2.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JAXA-SNU/MALIB/3b217d34d8429e04ea095c68e78678d3f9fcecfc/test/utest/figtest2.jpg -------------------------------------------------------------------------------- /test/utest/figtest3.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JAXA-SNU/MALIB/3b217d34d8429e04ea095c68e78678d3f9fcecfc/test/utest/figtest3.jpg -------------------------------------------------------------------------------- /test/utest/makefile: -------------------------------------------------------------------------------- 1 | # makefile for rtklib unit test 2 | 3 | SRC = ../../src 4 | #CFLAGS = -Wall -O3 -ansi -pedantic -I$(SRC) -DENAGLO 5 | CFLAGS = -Wall -O3 -ansi -pedantic -I$(SRC) -DTRACE -DENAGLO -DENAQZS 6 | LDLIBS = -lm -llapack -lblas 7 | CC = gcc 8 | 9 | BIN = t_matrix t_time t_coord t_rinex t_lambda t_atmos t_misc t_preceph t_gloeph \ 10 | t_geoid t_ppp t_ionex t_tle 11 | 12 | all : $(BIN) 13 | t_matrix : t_matrix.o rtkcmn.o preceph.o 14 | t_time : t_time.o rtkcmn.o preceph.o 15 | t_coord : t_coord.o rtkcmn.o geoid.o preceph.o 16 | t_rinex : t_rinex.o rtkcmn.o rinex.o preceph.o 17 | t_lambda : t_lambda.o rtkcmn.o lambda.o preceph.o 18 | t_atmos : t_atmos.o rtkcmn.o preceph.o 19 | t_misc : t_misc.o rtkcmn.o preceph.o 20 | t_preceph : t_preceph.o rtkcmn.o preceph.o rinex.o ephemeris.o sbas.o qzslex.o 21 | t_gloeph : t_gloeph.o rtkcmn.o rinex.o ephemeris.o sbas.o preceph.o qzslex.o 22 | t_geoid : t_geoid.o rtkcmn.o preceph.o geoid.o 23 | t_ppp : t_ppp.o rtkcmn.o ephemeris.o preceph.o sbas.o ionex.o pntpos.o ppp.o ppp_ar.o qzslex.o 24 | t_ppp : lambda.o 25 | t_ionex : t_ionex.o rtkcmn.o preceph.o ionex.o 26 | t_tle : t_tle.o rtkcmn.o rinex.o ephemeris.o sbas.o preceph.o tle.o 27 | 28 | rtkcmn.o : $(SRC)/rtklib.h $(SRC)/rtkcmn.c 29 | $(CC) -c $(CFLAGS) $(SRC)/rtkcmn.c 30 | rinex.o : $(SRC)/rtklib.h $(SRC)/rinex.c 31 | $(CC) -c $(CFLAGS) $(SRC)/rinex.c 32 | rtkpos.o : $(SRC)/rtklib.h $(SRC)/rtkpos.c 33 | $(CC) -c $(CFLAGS) $(SRC)/rtkpos.c 34 | lambda.o : $(SRC)/rtklib.h $(SRC)/lambda.c 35 | $(CC) -c $(CFLAGS) $(SRC)/lambda.c 36 | geoid.o : $(SRC)/rtklib.h $(SRC)/geoid.c 37 | $(CC) -c $(CFLAGS) $(SRC)/geoid.c 38 | ephemeris.o: $(SRC)/rtklib.h $(SRC)/ephemeris.c 39 | $(CC) -c $(CFLAGS) $(SRC)/ephemeris.c 40 | sbas.o : $(SRC)/rtklib.h $(SRC)/sbas.c 41 | $(CC) -c $(CFLAGS) $(SRC)/sbas.c 42 | preceph.o : $(SRC)/rtklib.h $(SRC)/preceph.c 43 | $(CC) -c $(CFLAGS) $(SRC)/preceph.c 44 | ppp.o : $(SRC)/rtklib.h $(SRC)/ppp.c 45 | $(CC) -c $(CFLAGS) $(SRC)/ppp.c 46 | ppp_ar.o : $(SRC)/rtklib.h $(SRC)/ppp_ar.c 47 | $(CC) -c $(CFLAGS) $(SRC)/ppp_ar.c 48 | pntpos.o : $(SRC)/rtklib.h $(SRC)/pntpos.c 49 | $(CC) -c $(CFLAGS) $(SRC)/pntpos.c 50 | ionex.o : $(SRC)/rtklib.h $(SRC)/ionex.c 51 | $(CC) -c $(CFLAGS) $(SRC)/ionex.c 52 | tle.o : $(SRC)/rtklib.h $(SRC)/tle.c 53 | $(CC) -c $(CFLAGS) $(SRC)/tle.c 54 | qzslex.o : $(SRC)/rtklib.h $(SRC)/qzslex.c 55 | $(CC) -c $(CFLAGS) $(SRC)/qzslex.c 56 | 57 | utest : utest1 utest2 utest3 utest4 utest5 utest6 utest7 utest8 58 | utest : utest9 utest10 utest11 utest12 utest14 59 | 60 | utest1 : 61 | ./t_matrix > utest1.out 62 | utest2 : 63 | ./t_time > utest2.out 64 | utest3 : 65 | ./t_coord > utest3.out 66 | utest4 : 67 | ./t_rinex > utest4.out 68 | utest5 : 69 | ./t_lambda > utest5.out 70 | utest6 : 71 | ./t_atmos > utest6.out 72 | utest7 : 73 | ./t_misc > utest7.out 74 | utest8 : 75 | ./t_preceph > utest8.out 76 | utest9 : 77 | ./t_gloeph > utest9.out 78 | utest10 : 79 | # ./t_geoid > utest10.out 80 | utest11 : 81 | ./t_ppp > utest11.out 82 | utest12 : 83 | ./t_ionex > utest12.out 84 | utest14 : 85 | ./t_tle > utest14.out 86 | 87 | clean : 88 | rm -f *.o *.out *.exe $(BIN) *.stackdump gmon.out 89 | 90 | -------------------------------------------------------------------------------- /test/utest/plotigp.m: -------------------------------------------------------------------------------- 1 | function plotigp 2 | 3 | figure 4 | 5 | mesh=readmesh; 6 | 7 | gmt('mmap','proj','eq','cent',[135,35],'scale',10,'pos',[0,0,1,1]); 8 | gmt('mcoast'); 9 | gmt('mgrid','gint',2,'lint',10,'color',[.5 .5 .5]); 10 | 11 | for i=1:size(mesh,1) 12 | gmt('mplot',mesh(i,1),mesh(i,2),'r','marker','.','markersize',10); 13 | end 14 | plotarea([36,138],15); 15 | 16 | % plot ipp area ---------------------------------------------------------------- 17 | function plotarea(pos,elmask) 18 | posp=[]; 19 | for az=0:3:360 20 | posp=[posp;igppos(pos*pi/180,[az,elmask]*pi/180)*180/pi]; 21 | end 22 | gmt('mplot',pos(2),pos(1),'b','marker','.','markersize',10); 23 | gmt('mplot',posp(:,2),posp(:,1),'b'); 24 | 25 | % read mesh data --------------------------------------------------------------- 26 | function mesh=readmesh 27 | mesh=[]; 28 | fp=fopen('../../nicttec/vtec/2011/001.txt','r'); 29 | while 1 30 | s=fgets(fp); if ~ischar(s), break; end 31 | v=sscanf(s,' Mesh %d: (%f, %f)'); 32 | if length(v)<2, continue; end 33 | mesh=[mesh;v(2:3)']; 34 | end 35 | fclose(fp); 36 | 37 | % igp position ----------------------------------------------------------------- 38 | function posp=igppos(pos,azel) 39 | re=6380; hion=350; 40 | rp=re/(re+hion)*cos(azel(2)); 41 | ap=pi/2-azel(2)-asin(rp); 42 | sinap=sin(ap); 43 | tanap=tan(ap); 44 | cosaz=cos(azel(1)); 45 | posp(1)=asin(sin(pos(1))*cos(ap)+cos(pos(1))*sinap*cosaz); 46 | posp(2)=pos(2)+asin(sinap*sin(azel(1))/cos(posp(1))); 47 | -------------------------------------------------------------------------------- /test/utest/t_atmos.c: -------------------------------------------------------------------------------- 1 | /*------------------------------------------------------------------------------ 2 | * rtklib unit test driver : atomospheric models 3 | *-----------------------------------------------------------------------------*/ 4 | #include 5 | #include 6 | #include "../../src/rtklib.h" 7 | 8 | /* ionmodel() */ 9 | void utest1(void) 10 | { 11 | double e1[]={2007,1,16, 1,0,0}; 12 | double e2[]={2007,1,16,13,0,0}; 13 | double e3[]={2007,1,16,22,0,0}; 14 | double ion1[]={ 15 | 0.2E-7,-0.8e-8,-0.5e-7, 0.1e-6, 0.2E+6, 0.2e+6,-0.1e+6,-0.1e+7 16 | }; 17 | double ion2[]={ 18 | 0.2E-7,-0.8e-8,-0.5e-7, 0.1e-6, 0.2E+6, 0.2e+6,-0.1e+6,-0.1e+7 19 | }; 20 | double pos1 []={ 35*D2R, 140*D2R, 100.0}; 21 | double pos2 []={-80*D2R,-170*D2R,1000.0}; 22 | double pos3 []={ 10*D2R, 30*D2R, 0.0}; 23 | double azel1[]={ 60*D2R, 75*D2R}; 24 | double azel2[]={190*D2R, 3*D2R}; 25 | double azel3[]={350*D2R, 60*D2R}; 26 | double azel4[]={ 0*D2R, 90*D2R}; 27 | gtime_t t1=epoch2time(e1),t2=epoch2time(e2),t3=epoch2time(e3); 28 | double dion; 29 | 30 | dion=ionmodel(t1,ion1,pos1,azel1); 31 | assert(fabs(dion-6.73590532099438)<1e-8); 32 | 33 | dion=ionmodel(t1,ion1,pos2,azel1); 34 | assert(fabs(dion-3.56895382197387)<1e-8); 35 | 36 | dion=ionmodel(t1,ion1,pos3,azel1); 37 | assert(fabs(dion-3.80716435655161)<1e-8); 38 | 39 | dion=ionmodel(t2,ion1,pos1,azel1); 40 | assert(fabs(dion-5.21796954585452)<1e-8); 41 | 42 | dion=ionmodel(t3,ion1,pos1,azel1); 43 | assert(fabs(dion-5.90190539264777)<1e-8); 44 | 45 | dion=ionmodel(t1,ion1,pos1,azel2); 46 | assert(fabs(dion-21.6345415123632)<1e-8); 47 | 48 | dion=ionmodel(t1,ion1,pos1,azel3); 49 | assert(fabs(dion-7.33844278822561)<1e-8); 50 | 51 | dion=ionmodel(t1,ion1,pos1,azel4); 52 | assert(fabs(dion-6.58339711400694)<1e-8); 53 | 54 | dion=ionmodel(t1,ion2,pos1,azel1); 55 | assert(fabs(dion-6.73590532099438)<1e-8); 56 | 57 | printf("%s utest1 : OK\n",__FILE__); 58 | } 59 | /* ionmapf() */ 60 | void utest2(void) 61 | { 62 | printf("%s utest2 : OK\n",__FILE__); 63 | } 64 | /* tropmodel */ 65 | void utest3(void) 66 | { 67 | gtime_t time={0}; 68 | double pos1 []={ 35*D2R, 140*D2R, 100.0}; 69 | double pos2 []={-80*D2R,-170*D2R,1000.0}; 70 | double pos3 []={-80*D2R,-170*D2R,100000.0}; 71 | double pos4 []={-80*D2R,-170*D2R,-200.0}; 72 | double azel1[]={ 60*D2R, 75*D2R}; 73 | double azel2[]={190*D2R, 3*D2R}; 74 | double azel3[]={190*D2R,-10*D2R}; 75 | double dtrp; 76 | 77 | dtrp=tropmodel(time,pos1,azel1,0.5); 78 | assert(fabs(dtrp-2.44799870144088)<1e-8); 79 | 80 | dtrp=tropmodel(time,pos1,azel2,0.5); 81 | assert(fabs(dtrp-45.1808916506163)<1e-8); 82 | 83 | dtrp=tropmodel(time,pos2,azel1,0.5); 84 | assert(fabs(dtrp-2.17295817298152)<1e-8); 85 | 86 | dtrp=tropmodel(time,pos1,azel3,0.0); 87 | assert(fabs(dtrp-0.00000000000000)<1e-8); 88 | 89 | dtrp=tropmodel(time,pos3,azel1,0.0); 90 | assert(fabs(dtrp-0.00000000000000)<1e-8); 91 | 92 | dtrp=tropmodel(time,pos4,azel1,0.0); 93 | assert(fabs(dtrp-0.00000000000000)<1e-8); 94 | 95 | printf("%s utest3 : OK\n",__FILE__); 96 | } 97 | void utest4(void) 98 | { 99 | double mapfd,mapfw; 100 | double e1[]={2007,1,16,6,0,0},e2[]={2030,12,31,23,59,59}; 101 | double pos1 []={ 35*D2R, 140*D2R, 100.0}; 102 | double pos2 []={-80*D2R,-170*D2R,1000.0}; 103 | double pos3 []={ 10*D2R, 30*D2R, 0.0}; 104 | double azel1[]={ 60*D2R, 75*D2R}; 105 | double azel2[]={190*D2R, 3*D2R}; 106 | double azel3[]={350*D2R, 60*D2R}; 107 | double azel4[]={ 0*D2R, 90*D2R}; 108 | gtime_t t1=epoch2time(e1),t2=epoch2time(e2); 109 | 110 | mapfd=tropmapf(t1,pos1,azel1,&mapfw); 111 | assert(fabs(mapfd-1.035184526466435)<1e-8); 112 | assert(fabs(mapfw-1.035233787448654)<1e-8); 113 | 114 | mapfd=tropmapf(t1,pos1,azel2,&mapfw); 115 | assert(fabs(mapfd-14.643271711748200)<1e-8); 116 | assert(fabs(mapfw-16.455045694559484)<1e-8); 117 | 118 | mapfd=tropmapf(t1,pos1,azel3,&mapfw); 119 | assert(fabs(mapfd-1.154226397147367)<1e-8); 120 | assert(fabs(mapfw-1.154481126139610)<1e-8); 121 | 122 | mapfd=tropmapf(t1,pos1,azel4,&mapfw); 123 | assert(fabs(mapfd-1.000000000000000)<1e-8); 124 | assert(fabs(mapfw-1.000000000000000)<1e-8); 125 | 126 | mapfd=tropmapf(t2,pos1,azel1,&mapfw); 127 | assert(fabs(mapfd-1.035184415128022)<1e-8); 128 | assert(fabs(mapfw-1.035233787448654)<1e-8); 129 | 130 | mapfd=tropmapf(t1,pos2,azel1,&mapfw); 131 | assert(fabs(mapfd-1.035186155749051)<1e-8); 132 | assert(fabs(mapfw-1.035230548304367)<1e-8); 133 | 134 | mapfd=tropmapf(t1,pos3,azel1,&mapfw); 135 | assert(fabs(mapfd-1.035181919429758)<1e-8); 136 | assert(fabs(mapfw-1.035233200318210)<1e-8); 137 | 138 | mapfd=tropmapf(t1,pos1,azel1,NULL); 139 | assert(fabs(mapfd-1.035184526466435)<1e-8); 140 | 141 | printf("%s utest4 : OK\n",__FILE__); 142 | } 143 | int main(void) 144 | { 145 | utest1(); 146 | utest2(); 147 | utest3(); 148 | utest4(); 149 | return 0; 150 | } 151 | -------------------------------------------------------------------------------- /test/utest/t_coord.c: -------------------------------------------------------------------------------- 1 | /*------------------------------------------------------------------------------ 2 | * rtklib unit test driver : coordinates functions 3 | *-----------------------------------------------------------------------------*/ 4 | #include 5 | #include 6 | #include 7 | #include "../../src/rtklib.h" 8 | 9 | /* ecef2pos() */ 10 | void utest1(void) 11 | { 12 | double r1[]={ 0.0, 0.0, 0.0}; 13 | double r2[]={10000000.0, 0.0, 0.0}; 14 | double r3[]={ 0.0,10000000.0, 0.0}; 15 | double r4[]={ 0.0, 0.0, 10000000.0}; 16 | double r5[]={ 0.0, 0.0,-10000000.0}; 17 | double r6[]={-3.5173197701E+06,4.1316679161E+06, 3.3412651227E+06}; 18 | double r7[]={-3.5173197701E+06,4.1316679161E+06,-3.3412651227E+06}; 19 | double pos[3]; 20 | ecef2pos(r1,pos); 21 | assert(pos[2]<0.0); 22 | ecef2pos(r2,pos); 23 | assert(pos[0]==0&&pos[1]==0&&pos[2]>0.0); 24 | ecef2pos(r3,pos); 25 | assert(pos[0]==0&&fabs(pos[1]-PI/2)<1E-6&&pos[2]>0.0); 26 | ecef2pos(r4,pos); 27 | assert(fabs(pos[0]-PI/2)<1E-6&&pos[2]>0.0); 28 | ecef2pos(r5,pos); 29 | assert(fabs(pos[0]+PI/2)<1E-6&&pos[2]>0.0); 30 | ecef2pos(r6,pos); 31 | assert(fabs(pos[0]*R2D-3.1796021375E+01)<1E-7&& 32 | fabs(pos[1]*R2D-1.3040799917E+02)<1E-7&& 33 | fabs(pos[2]-6.8863206206E+01)<1E-4); 34 | ecef2pos(r7,pos); 35 | assert(fabs(pos[0]*R2D+3.1796021375E+01)<1E-7&& 36 | fabs(pos[1]*R2D-1.3040799917E+02)<1E-7&& 37 | fabs(pos[2]-6.8863206206E+01)<1E-4); 38 | 39 | printf("%s utset1 : OK\n",__FILE__); 40 | } 41 | /* pos2ecef() */ 42 | void utest2(void) 43 | { 44 | double lat,lon,h,pos[3],posi[3]; 45 | double r[3]; 46 | for (lat=-90.0;lat<=90.0;lat+=5.0) { 47 | for (lon=-180.0;lon<180.0;lon+=5.0) { 48 | for (h=-10.0;h<10000.0;h+=100.0) { 49 | pos[0]=lat*D2R; pos[1]=lon*D2R; pos[2]=h; 50 | pos2ecef(pos,r); 51 | ecef2pos(r,posi); 52 | assert(fabs(lat-posi[0]*R2D)<1E-7&& 53 | (lat==-90.0||lat==90.0?1:fabs(lon-posi[1]*R2D)<1E-7)&& 54 | fabs(h-posi[2])<1E-4); 55 | } 56 | } 57 | } 58 | 59 | printf("%s utset2 : OK\n",__FILE__); 60 | } 61 | /* ecef2enu(), enu2ecef() */ 62 | void utest3(void) 63 | { 64 | double pos1[]={ 0.000*D2R, 0.000*D2R,0.0}; 65 | double pos2[]={35.000*D2R,140.000*D2R,0.0}; 66 | double r1[]={1.0,0.0,0.0}; 67 | double r2[]={0.0,1.0,0.0}; 68 | double r3[]={0.0,0.0,1.0}; 69 | double r4[]={0.3,0.4,0.5}; 70 | double e[3],r[3]; 71 | ecef2enu(pos1,r1,e); 72 | assert(e[0]==0.0&&e[1]==0.0&&e[2]==1.0); 73 | ecef2enu(pos1,r2,e); 74 | assert(e[0]==1.0&&e[1]==0.0&&e[2]==0.0); 75 | ecef2enu(pos1,r3,e); 76 | assert(e[0]==0.0&&e[1]==1.0&&e[2]==0.0); 77 | ecef2enu(pos2,r4,e); 78 | assert(fabs(e[0]+0.499254)<1E-6&& 79 | fabs(e[1]-0.393916)<1E-6&& 80 | fabs(e[2]-0.309152)<1E-6); 81 | enu2ecef(pos2,e,r); 82 | assert(fabs(r[0]-r4[0])<1E-6&& 83 | fabs(r[1]-r4[1])<1E-6&& 84 | fabs(r[2]-r4[2])<1E-6); 85 | 86 | printf("%s utset3 : OK\n",__FILE__); 87 | } 88 | int main(void) 89 | { 90 | utest1(); 91 | utest2(); 92 | utest3(); 93 | return 0; 94 | } 95 | -------------------------------------------------------------------------------- /test/utest/t_corrperf.c: -------------------------------------------------------------------------------- 1 | /* correlator performence test */ 2 | #include 3 | #include "sdr.h" 4 | 5 | int main(int argc, char **argc) 6 | { 7 | double f_s[]={38.192e6,16.368e6,8.184e6}; 8 | double taums[]={1,2,4,8,16}; 9 | double tau,ns,crate,coff,freq,phi0,ti; 10 | double I[3],Q[3]; 11 | char *data; 12 | int i,j,k,dtype,sat,s,nc,nt,n; 13 | 14 | dtype=1; 15 | sat =1; 16 | freq =9.548e6; 17 | crate=1023000; 18 | coff =1234.5; 19 | s =20; 20 | 21 | for (i=0;i<4;i++) for (j=0;j<5;j++) { 22 | 23 | printf('sampling rate=%.3fMHz\n',f_s/1e6); 24 | 25 | tau =taums[j]*1e-3; 26 | ns =tau*f_s[i]; 27 | if (dtype) nt=ns*2; else nt=ns; 28 | phi0 =0.1234; 29 | data=int8((rand(1,nt)-0.5)*4); 30 | ti =1/f_s; 31 | n =100000/taums; 32 | 33 | tic, 34 | for (k=0;k 2 | 3 | static void printmat(const double *A, int n, int m) 4 | { 5 | int i,j; 6 | for (i=0;i 5 | #include 6 | #include 7 | #include "../../src/rtklib.h" 8 | 9 | /* latitude, longitude, geoid height (m) */ 10 | /* reference : http://sps.unavco.org/geoid */ 11 | static double poss[][3]={ 12 | { 90.001*D2R, 80.000*D2R, 0.000}, 13 | {-90.001*D2R, 80.000*D2R, 0.000}, 14 | { 30.000*D2R, 360.000*D2R, 0.000}, 15 | {-30.000*D2R,-360.001*D2R, 0.000}, 16 | {-90.000*D2R, 359.999*D2R,-29.534}, 17 | { 90.000*D2R, 80.000*D2R, 13.606}, 18 | {-90.000*D2R, -60.000*D2R,-29.534}, 19 | { 30.000*D2R,-360.000*D2R, 35.387}, 20 | {-30.000*D2R, 359.999*D2R, 21.409}, 21 | { 10.000*D2R, 45.000*D2R,-20.486}, 22 | {-60.123*D2R, 135.123*D2R,-33.152}, 23 | { 19.999*D2R, 135.000*D2R, 41.602}, 24 | { 50.001*D2R, 135.000*D2R, 20.555}, 25 | { 35.000*D2R, 119.999*D2R, 4.386}, 26 | { 35.000*D2R, 150.001*D2R, 14.779}, 27 | { 20.000*D2R, 120.000*D2R, 21.269}, 28 | { 50.000*D2R, 150.000*D2R, 20.277}, 29 | { 35.000*D2R, 135.000*D2R, 36.355}, 30 | { 45.402*D2R, 141.750*D2R, 27.229}, /* wakkanai */ 31 | { 24.454*D2R, 122.942*D2R, 21.652}, /* ishigaki */ 32 | { 33.120*D2R, 139.797*D2R, 43.170}, /* hachijo */ 33 | { 30.000*D2R, 135.000*D2R, 36.017}, /* taiheiyo */ 34 | {0,0,0} 35 | }; 36 | #define DATADIR "../../../../data/geoiddata/" 37 | static char *file1=DATADIR "WW15MGH.DAC"; 38 | static char *file2=DATADIR "Und_min1x1_egm2008_isw=82_WGS84_TideFree_SE"; 39 | static char *file3=DATADIR "Und_min2.5x2.5_egm2008_isw=82_WGS84_TideFree_SE"; 40 | static char *file4=DATADIR "gsigeome.ver4"; 41 | 42 | /* opengeoid(), closegeoid() */ 43 | void utest1(void) 44 | { 45 | int ret; 46 | 47 | ret=opengeoid(10,file1); 48 | assert(ret==0); /* no model */ 49 | ret=opengeoid(GEOID_EGM96_M150,"../../../geoiddata/WW15MGH.DAA"); 50 | assert(ret==0); /* no file */ 51 | ret=opengeoid(GEOID_EMBEDDED,""); 52 | assert(ret==1); 53 | closegeoid(); 54 | ret=opengeoid(GEOID_EGM96_M150,file1); 55 | assert(ret==1); 56 | closegeoid(); 57 | ret=opengeoid(GEOID_EGM2008_M10,file2); 58 | assert(ret==1); 59 | closegeoid(); 60 | ret=opengeoid(GEOID_EGM2008_M25,file3); 61 | assert(ret==1); 62 | closegeoid(); 63 | ret=opengeoid(GEOID_GSI2000_M15,file4); 64 | assert(ret==1); 65 | closegeoid(); 66 | 67 | printf("%s utset1 : OK\n",__FILE__); 68 | } 69 | /* print difference */ 70 | void printgeoid(const double *pos, double *h, int n) 71 | { 72 | int i; 73 | printf("%7.3f %8.3f %9.4f: ",pos[0]*R2D,pos[1]*R2D,pos[2]); 74 | for (i=0;ifabs(dhmax[k])) dhmax[k]=dh; 156 | } 157 | } 158 | printf("max difference :"); 159 | for (i=1;i<5;i++) { 160 | printf(" %9.4f",dhmax[i]); 161 | assert(fabs(dhmax[i])<10.0); 162 | } 163 | printf("\n"); 164 | printf("%s utset3 : OK\n",__FILE__); 165 | } 166 | int main(void) 167 | { 168 | utest1(); 169 | utest2(); 170 | utest3(); 171 | return 0; 172 | } 173 | -------------------------------------------------------------------------------- /test/utest/t_gloeph.c: -------------------------------------------------------------------------------- 1 | /*------------------------------------------------------------------------------ 2 | * rtklib unit test driver : glonass ephemeris function 3 | *-----------------------------------------------------------------------------*/ 4 | #include 5 | #include 6 | #include "../../src/rtklib.h" 7 | 8 | static void dumpgeph(geph_t *geph, int n) 9 | { 10 | char s1[64],s2[64]; 11 | int i; 12 | for (i=0;i0); 36 | dumpgeph(nav.geph,nav.ng); 37 | 38 | printf("%s utest1 : OK\n",__FILE__); 39 | } 40 | /* readsp3() */ 41 | void utest2(void) 42 | { 43 | char *file1="../data/sp3/igl15253.sp4"; 44 | char *file2="../data/sp3/igl15253.sp3"; 45 | nav_t nav={0}; 46 | double tow,*pos; 47 | int i,week,sat; 48 | 49 | sat=satno(SYS_GLO,13); 50 | 51 | readsp3(file1,&nav,0); 52 | assert(nav.ne<=0); 53 | readsp3(file2,&nav,0); 54 | assert(nav.ne>0); 55 | 56 | for (i=0;i0.0); 62 | } 63 | printf("\n"); 64 | 65 | printf("%s utest2 : OK\n",__FILE__); 66 | } 67 | /* broadcast ephemeris */ 68 | void utest3(void) 69 | { 70 | gtime_t time; 71 | char file[]="../data/rinex/brdc0910.09g"; 72 | nav_t nav={0}; 73 | double ep[]={2009,4,1,0,0,0}; 74 | double tspan=86400.0,tint=30.0,tow; 75 | double rs[6],dts[2]; 76 | double var; 77 | int i,sat,week,svh; 78 | 79 | sat=satno(SYS_GLO,7); 80 | 81 | readrnx(file,1,"",NULL,&nav,NULL); 82 | 83 | for (i=0;i0.0); 90 | assert(norm(rs+3,3)>0.0); 91 | assert(dts[0]!=0.0); 92 | assert(dts[1]!=0.0); 93 | } 94 | printf("\n"); 95 | 96 | printf("%s utest3 : OK\n",__FILE__); 97 | } 98 | /* precise ephemeris */ 99 | void utest4(void) 100 | { 101 | gtime_t time; 102 | char *file="../data/sp3/igl15253.sp3"; 103 | nav_t nav={0}; 104 | double ep[]={2009,4,1,0,0,0}; 105 | double tspan=86400.0,tint=30.0,tow; 106 | double rs[6],dts[2]; 107 | double var; 108 | int i,sat,week,svh; 109 | 110 | sat=satno(SYS_GLO,7); 111 | 112 | readsp3(file,&nav,0); 113 | 114 | for (i=0;i0.0); 121 | assert(norm(rs+3,3)>0.0); 122 | assert(dts[0]!=0.0); 123 | } 124 | printf("\n"); 125 | 126 | printf("%s utest4 : OK\n",__FILE__); 127 | } 128 | /* readsap() */ 129 | void utest5(void) 130 | { 131 | char *file="../../data/igs05.atx",id[32]; 132 | double ep[]={2009,4,1,0,0,0}; 133 | gtime_t time=epoch2time(ep); 134 | nav_t nav={0}; 135 | int i,stat; 136 | 137 | stat=readsap(file,time,&nav); 138 | 139 | for (i=0;i 5 | #include 6 | #include "../../src/rtklib.h" 7 | 8 | static void dumptec(const tec_t *tec, int n, int level) 9 | { 10 | const tec_t *p; 11 | char s[64]; 12 | int i,j,k,m; 13 | 14 | for (i=0;itime,s,3); 17 | printf("(%2d) time =%s ndata=%d %d %d\n",i+1,s,p->ndata[0],p->ndata[1],p->ndata[2]); 18 | if (level<1) continue; 19 | printf("lats =%6.1f %6.1f %6.1f\n",p->lats[0],p->lats[1],p->lats[2]); 20 | printf("lons =%6.1f %6.1f %6.1f\n",p->lons[0],p->lons[1],p->lons[2]); 21 | printf("hgts =%6.1f %6.1f %6.1f\n",p->hgts[0],p->hgts[1],p->hgts[2]); 22 | printf("data =\n"); 23 | for (j=0;jndata[2];j++) { /* hgt */ 24 | for (k=0;kndata[0];k++) { /* lat */ 25 | printf("lat=%.1f lon=%.1f:%.1f hgt=%.1f\n",p->lats[0]+k*p->lats[2], 26 | p->lons[0],p->lons[1],p->hgts[0]+j*p->hgts[2]); 27 | for (m=0;mndata[1];m++) { /* lon */ 28 | if (m>0&&m%16==0) printf("\n"); 29 | printf("%5.1f ",p->data[k+p->ndata[0]*(m+p->ndata[1]*j)]); 30 | } 31 | printf("\n"); 32 | } 33 | printf("\n"); 34 | } 35 | printf("rms =\n"); 36 | for (j=0;jndata[2];j++) { /* hgt */ 37 | for (k=0;kndata[0];k++) { /* lat */ 38 | printf("lat=%.1f lon=%.1f:%.1f hgt=%.1f\n",p->lats[0]+k*p->lats[2], 39 | p->lons[0],p->lons[1],p->hgts[0]+j*p->hgts[2]); 40 | for (m=0;mndata[1];m++) { /* lon */ 41 | if (m>0&&m%16==0) printf("\n"); 42 | printf("%5.1f ",p->rms[k+p->ndata[0]*(m+p->ndata[1]*j)]); 43 | } 44 | printf("\n"); 45 | } 46 | printf("\n"); 47 | } 48 | } 49 | } 50 | static void dumpdcb(const nav_t *nav) 51 | { 52 | int i; 53 | printf("dcbs=\n"); 54 | for (i=0;icbias[i][0]/CLIGHT*1E9); /* ns */ 56 | } 57 | } 58 | /* readtec() */ 59 | void utest1(void) 60 | { 61 | char *file1="../data/sp3/igrg3380.10j"; 62 | char *file2="../data/sp3/igrg3380.10i"; 63 | char *file3="../data/sp3/igrg33*0.10i"; 64 | nav_t nav={0}; 65 | 66 | printf("file=%s\n",file1); 67 | readtec(file1,&nav,0); 68 | assert(nav.nt==0); 69 | 70 | printf("file=%s\n",file2); 71 | readtec(file2,&nav,0); 72 | assert(nav.nt==13); 73 | dumptec(nav.tec,nav.nt,1); 74 | 75 | printf("file=%s\n",file3); 76 | readtec(file3,&nav,0); 77 | assert(nav.nt==25); 78 | dumptec(nav.tec,nav.nt,0); 79 | 80 | dumptec(nav.tec ,1,1); 81 | dumptec(nav.tec+12,1,1); 82 | dumpdcb(&nav); 83 | 84 | printf("%s utest1 : OK\n",__FILE__); 85 | } 86 | /* iontec() 1 */ 87 | void utest2(void) 88 | { 89 | char *file3="../data/sp3/igrg33*0.10i"; 90 | nav_t nav={0}; 91 | gtime_t time1,time2,time3,time4; 92 | double ep1 []={2010,12, 4, 0, 0, 0}; 93 | double ep2 []={2010,12, 5,23,59,59}; 94 | double ep3 []={2010,12, 3,23,59,59}; /* error */ 95 | double ep4 []={2010,12, 6, 0, 0, 0}; /* error */ 96 | double pos1 []={ 45.1*D2R, 135.7*D2R,0.0}; 97 | double pos2 []={-45.1*D2R,-170.7*D2R,0.0}; 98 | double pos3 []={-45.1*D2R, 189.3*D2R,0.0}; 99 | double pos4 []={ 87.6*D2R, 0.0*D2R,0.0}; /* out of grid */ 100 | double pos5 []={-87.6*D2R, 0.0*D2R,0.0}; /* out of grid */ 101 | double azel1[]={ 0.0,90.0*D2R}; 102 | double azel2[]={120.0,30.0*D2R}; 103 | double azel3[]={ 0.0,-0.1*D2R}; /* error */ 104 | double delay1,var1,delay2=0,var2; 105 | int stat; 106 | 107 | time1=epoch2time(ep1); 108 | time2=epoch2time(ep2); 109 | time3=epoch2time(ep3); 110 | time4=epoch2time(ep4); 111 | 112 | readtec(file3,&nav,0); 113 | stat=iontec(time1,&nav,pos1,azel1,1,&delay1,&var1); 114 | assert(stat==1); 115 | stat=iontec(time2,&nav,pos1,azel1,1,&delay1,&var1); 116 | assert(stat==1); 117 | stat=iontec(time3,&nav,pos1,azel1,1,&delay1,&var1); 118 | assert(stat==0); 119 | stat=iontec(time4,&nav,pos1,azel1,1,&delay1,&var1); 120 | assert(stat==0); 121 | stat=iontec(time1,&nav,pos2,azel1,1,&delay1,&var1); 122 | assert(stat==1); 123 | stat=iontec(time1,&nav,pos3,azel1,1,&delay2,&var2); 124 | assert(stat==1); 125 | assert(fabs(delay1-delay2)<1E-4); 126 | assert(fabs(var1-var2)<1E-8); 127 | stat=iontec(time1,&nav,pos4,azel1,1,&delay1,&var1); 128 | assert(stat==1); 129 | stat=iontec(time1,&nav,pos5,azel1,1,&delay1,&var1); 130 | assert(stat==1); 131 | stat=iontec(time1,&nav,pos1,azel2,1,&delay1,&var1); 132 | assert(stat==1); 133 | stat=iontec(time1,&nav,pos1,azel3,1,&delay1,&var1); 134 | assert(stat==1&&delay1==0.0); 135 | 136 | printf("%s utest2 : OK\n",__FILE__); 137 | } 138 | /* iontec() 2 */ 139 | void utest3(void) 140 | { 141 | FILE *fp; 142 | char *file3="../data/sp3/igrg33*0.10i"; 143 | nav_t nav={0}; 144 | gtime_t time1; 145 | double ep1[]={2010,12, 5, 0, 0, 0}; 146 | double delay,var,pos[3]={0},azel[]={0.0,PI/2}; 147 | int i,j; 148 | 149 | time1=epoch2time(ep1); 150 | readtec(file3,&nav,0); 151 | 152 | fp=fopen("testionex3.m","w"); 153 | assert(fp); 154 | 155 | fprintf(fp,"tec=[\n"); 156 | for (i=90;i>=-90;i-=2) { 157 | for (j=0;j<=360;j+=2) { 158 | pos[0]=i*D2R; 159 | pos[1]=j*D2R; 160 | if (iontec(time1,&nav,pos,azel,1,&delay,&var)) { 161 | fprintf(fp,"%4.2f ",delay); 162 | } 163 | else { 164 | fprintf(fp," nan "); 165 | } 166 | } 167 | fprintf(fp,"\n"); 168 | } 169 | fprintf(fp,"];\n"); 170 | fclose(fp); 171 | 172 | fp=fopen("testionex3.m","a"); 173 | assert(fp); 174 | 175 | fprintf(fp,"rms=[\n"); 176 | for (i=90;i>=-90;i-=2) { 177 | for (j=0;j<=360;j+=2) { 178 | pos[0]=i*D2R; 179 | pos[1]=j*D2R; 180 | if (iontec(time1,&nav,pos,azel,1,&delay,&var)) { 181 | fprintf(fp,"%4.2f ",sqrt(var)); 182 | } 183 | else { 184 | fprintf(fp," nan "); 185 | } 186 | } 187 | fprintf(fp,"\n"); 188 | } 189 | fprintf(fp,"];\n"); 190 | fclose(fp); 191 | 192 | printf("%s utest3 : OK\n",__FILE__); 193 | } 194 | /* iontec() 3 */ 195 | void utest4(void) 196 | { 197 | FILE *fp; 198 | char *file3="../data/sp3/igrg33*0.10i"; 199 | nav_t nav={0}; 200 | gtime_t time1; 201 | double ep1[]={2010,12, 3,12, 0, 0}; 202 | double delay,var,pos[3]={25*D2R,135*D2R,0}; 203 | double azel[]={75*D2R,90*D2R}; 204 | int i; 205 | 206 | time1=epoch2time(ep1); 207 | readtec(file3,&nav,0); 208 | 209 | fp=fopen("testionex4.m","w"); 210 | assert(fp); 211 | 212 | fprintf(fp,"tec=[\n"); 213 | for (i=0;i<=86400*3;i+=30) { 214 | if (iontec(timeadd(time1,i),&nav,pos,azel,1,&delay,&var)) { 215 | fprintf(fp,"%6d %5.3f %5.3f\n",i,delay,sqrt(var)); 216 | } 217 | else { 218 | fprintf(fp,"%6d nan nan\n",i); 219 | } 220 | } 221 | fprintf(fp,"];\n"); 222 | fclose(fp); 223 | 224 | printf("%s utest4 : OK\n",__FILE__); 225 | } 226 | int main(int argc, char **argv) 227 | { 228 | utest1(); 229 | utest2(); 230 | utest3(); 231 | utest4(); 232 | return 0; 233 | } 234 | -------------------------------------------------------------------------------- /test/utest/t_lambda.c: -------------------------------------------------------------------------------- 1 | /*------------------------------------------------------------------------------ 2 | * rtklib unit test driver : lambda/mlambda integer least square 3 | *-----------------------------------------------------------------------------*/ 4 | #include 5 | #include 6 | #include "../../src/rtklib.h" 7 | 8 | static double a1[]={ 9 | 1585184.171, 10 | -6716599.430, 11 | 3915742.905, 12 | 7627233.455, 13 | 9565990.879, 14 | 989457273.200 15 | }; 16 | static double Q1[]={ 17 | 0.227134, 0.112202, 0.112202, 0.112202, 0.112202, 0.103473, 18 | 0.112202, 0.227134, 0.112202, 0.112202, 0.112202, 0.103473, 19 | 0.112202, 0.112202, 0.227134, 0.112202, 0.112202, 0.103473, 20 | 0.112202, 0.112202, 0.112202, 0.227134, 0.112202, 0.103473, 21 | 0.112202, 0.112202, 0.112202, 0.112202, 0.227134, 0.103473, 22 | 0.103473, 0.103473, 0.103473, 0.103473, 0.103473, 0.434339 23 | }; 24 | static double F1[]={ 25 | 1585184.000000, 1585184.000000, 26 | -6716599.000000, -6716600.000000, 27 | 3915743.000000, 3915743.000000, 28 | 7627234.000000, 7627233.000000, 29 | 9565991.000000, 9565991.000000, 30 | 989457273.000000,989457273.000000 31 | }; 32 | static double s1[]={ 33 | 3.507984, 3.708456, 34 | }; 35 | static double a2[]={ 36 | -13324172.755747, 37 | -10668894.713608, 38 | -7157225.010770, 39 | -6149367.974367, 40 | -7454133.571066, 41 | -5969200.494550, 42 | 8336734.058423, 43 | 6186974.084502, 44 | -17549093.883655, 45 | -13970158.922370 46 | }; 47 | static double Q2[]={ 48 | 0.446320, 0.223160, 0.223160, 0.223160, 0.223160, 0.572775, 0.286388, 0.286388, 0.286388, 0.286388, 49 | 0.223160, 0.446320, 0.223160, 0.223160, 0.223160, 0.286388, 0.572775, 0.286388, 0.286388, 0.286388, 50 | 0.223160, 0.223160, 0.446320, 0.223160, 0.223160, 0.286388, 0.286388, 0.572775, 0.286388, 0.286388, 51 | 0.223160, 0.223160, 0.223160, 0.446320, 0.223160, 0.286388, 0.286388, 0.286388, 0.572775, 0.286388, 52 | 0.223160, 0.223160, 0.223160, 0.223160, 0.446320, 0.286388, 0.286388, 0.286388, 0.286388, 0.572775, 53 | 0.572775, 0.286388, 0.286388, 0.286388, 0.286388, 0.735063, 0.367531, 0.367531, 0.367531, 0.367531, 54 | 0.286388, 0.572775, 0.286388, 0.286388, 0.286388, 0.367531, 0.735063, 0.367531, 0.367531, 0.367531, 55 | 0.286388, 0.286388, 0.572775, 0.286388, 0.286388, 0.367531, 0.367531, 0.735063, 0.367531, 0.367531, 56 | 0.286388, 0.286388, 0.286388, 0.572775, 0.286388, 0.367531, 0.367531, 0.367531, 0.735063, 0.367531, 57 | 0.286388, 0.286388, 0.286388, 0.286388, 0.572775, 0.367531, 0.367531, 0.367531, 0.367531, 0.735063 58 | }; 59 | static double F2[]={ 60 | -13324188.000000,-13324188.000000, 61 | -10668901.000000,-10668908.000000, 62 | -7157236.000000, -7157236.000000, 63 | -6149379.000000, -6149379.000000, 64 | -7454143.000000, -7454143.000000, 65 | -5969220.000000, -5969220.000000, 66 | 8336726.000000, 8336717.000000, 67 | 6186960.000000, 6186960.000000, 68 | -17549108.000000,-17549108.000000, 69 | -13970171.000000,-13970171.000000 70 | }; 71 | static double s2[]={ 72 | 1506.435789, 1612.811795 73 | }; 74 | 75 | void utest1(void) 76 | { 77 | int i,j,n,m,info; 78 | double F[6*2],s[2]; 79 | 80 | n=6; m=2; 81 | info=lambda(n,m,a1,Q1,F,s); 82 | assert(info==0); 83 | 84 | for (j=0;j 5 | #include 6 | #include "../../src/rtklib.h" 7 | 8 | void dbout1(double *x, double *y, double *P, double *H, double *R, int n, int m) 9 | { 10 | printf("x=[\n"); matprint(x,n,1,8,4); printf("];\n"); 11 | printf("y=[\n"); matprint(y,m,1,8,4); printf("];\n"); 12 | printf("P=[\n"); matprint(P,n,n,8,4); printf("];\n"); 13 | printf("H=[\n"); matprint(H,m,n,8,4); printf("];\n"); 14 | printf("R=[\n"); matprint(R,m,m,8,4); printf("];\n"); 15 | } 16 | void dbout2(double *x, double *P, int n) 17 | { 18 | printf("xu=[\n"); matprint(x,n,1,8,4); printf("];\n"); 19 | printf("Pu=[\n"); matprint(P,n,n,8,4); printf("];\n"); 20 | printf("K=P*H'/(H*P*H'+R);\n"); 21 | 22 | printf("xd=x+K*y;\n"); 23 | printf("Pd=P-K*H*P\n"); 24 | printf("xu-xd,Pu-Pd\n"); 25 | } 26 | /* mat(),imat(),zeros(),eye() */ 27 | void utest1(void) 28 | { 29 | int i,j,n=100,m=200,*b; 30 | double *a; 31 | a=mat(0,0); assert(a==NULL); 32 | a=mat(0,1); assert(a==NULL); 33 | a=mat(1,0); assert(a==NULL); 34 | a=mat(1,1); assert(a!=NULL); 35 | free(a); 36 | /* a=mat(1000000,1000000); assert(a==NULL); */ 37 | a=zeros(0,m); assert(a==NULL); 38 | a=zeros(n,0); assert(a==NULL); 39 | a=zeros(n,m); assert(a!=NULL); 40 | for (i=0;i 5 | #include 6 | #include "../../src/rtklib.h" 7 | 8 | /* expath() */ 9 | static void utest11(const char *path) 10 | { 11 | char s[32][256],*paths[32]; 12 | int i,n; 13 | for (i=0;i<32;i++) paths[i]=s[i]; 14 | n=expath(path,paths,32); 15 | printf("\npath =%s\n",path); 16 | printf("paths=\n"); 17 | for (i=0;i 5 | #include 6 | #include 7 | #include "../../src/rtklib.h" 8 | 9 | /* eci2ecef() */ 10 | void utest1(void) 11 | { 12 | double ep1[]={1999,3,4,0,0,0}; 13 | double gmst,U[9]; 14 | double U1[]={ 15 | -0.947378027425279, 0.320116956820115, -8.43090456427539e-005, 16 | -0.32011695222455, -0.947378030590727, -6.36592598714651e-005, 17 | -0.00010025094616549, -3.33206293083182e-005, 0.999999994419742 18 | }; 19 | double erpv[5]={0.06740*D2R/3600,0.24713*D2R/3600,0.649232}; 20 | int i,j; 21 | 22 | eci2ecef(epoch2time(ep1),erpv,U,&gmst); 23 | 24 | for (i=0;i<3;i++) for (j=0;j<3;j++) { 25 | printf("U(%d,%d)=%15.12f %15.12f %15.12f\n",i,j, 26 | U[i+j*3],U1[j+i*3],U[i+j*3]-U1[j+i*3]); 27 | assert(fabs(U[i+j*3]-U1[j+i*3])<1E-11); 28 | } 29 | printf("%s utset1 : OK\n",__FILE__); 30 | } 31 | /* sunmoonpos() */ 32 | void utest2(void) 33 | { 34 | double ep1[]={2010,12,31,8,9,10}; /* utc */ 35 | double rs[]={70842740307.0837,115293403265.153,-57704700666.9715}; /* de405 */ 36 | double rm[]={350588081.147922,29854134.6432052,-136870369.169738}; 37 | double rsun[3],rmoon[3],erpv[5]={0}; 38 | int i; 39 | 40 | sunmoonpos(epoch2time(ep1),erpv,rsun,rmoon,NULL); 41 | printf("X_sun =%15.0f %15.0f %7.4f\n",rsun [0],rs[0],(rsun [0]-rs[0])/rsun [0]); 42 | printf("Y_sun =%15.0f %15.0f %7.4f\n",rsun [1],rs[1],(rsun [1]-rs[1])/rsun [1]); 43 | printf("Z_sun =%15.0f %15.0f %7.4f\n",rsun [2],rs[2],(rsun [2]-rs[2])/rsun [2]); 44 | printf("X_moon=%15.0f %15.0f %7.4f\n",rmoon[0],rm[0],(rmoon[0]-rm[0])/rmoon[0]); 45 | printf("Y_moon=%15.0f %15.0f %7.4f\n",rmoon[1],rm[1],(rmoon[1]-rm[1])/rmoon[1]); 46 | printf("Z_moon=%15.0f %15.0f %7.4f\n",rmoon[2],rm[2],(rmoon[2]-rm[2])/rmoon[2]); 47 | 48 | for (i=0;i<3;i++) { 49 | assert(fabs((rsun [i]-rs[i])/rsun [i])<0.03); 50 | assert(fabs((rmoon[i]-rm[i])/rmoon[i])<0.03); 51 | } 52 | printf("%s utset2 : OK\n",__FILE__); 53 | } 54 | /* tidedisp() */ 55 | void utest3(void) 56 | { 57 | double ep1[]={2010,6,7,1,2,3}; 58 | double rr[]={-3957198.431,3310198.621,3737713.474}; /* TSKB */ 59 | double dp[]={-0.05294,0.075607,0.03644}; 60 | double dr[3]={0}; 61 | int i; 62 | 63 | tidedisp(epoch2time(ep1),rr,1,NULL,NULL,dr); 64 | 65 | printf("X_disp=%8.5f %8.5f %8.5f\n",dr[0],dp[0],dr[0]-dp[0]); 66 | printf("Y_disp=%8.5f %8.5f %8.5f\n",dr[1],dp[1],dr[1]-dp[1]); 67 | printf("Z_disp=%8.5f %8.5f %8.5f\n",dr[2],dp[2],dr[2]-dp[2]); 68 | 69 | for (i=0;i<3;i++) { 70 | assert(fabs(dr[i]-dp[i])<0.001); 71 | } 72 | printf("%s utset3 : OK\n",__FILE__); 73 | } 74 | int main(void) 75 | { 76 | utest1(); 77 | utest2(); 78 | utest3(); 79 | return 0; 80 | } 81 | -------------------------------------------------------------------------------- /test/utest/t_preceph.c: -------------------------------------------------------------------------------- 1 | /*------------------------------------------------------------------------------ 2 | * rtklib unit test driver : precise ephemeris function 3 | *-----------------------------------------------------------------------------*/ 4 | #include 5 | #include 6 | #include "../../src/rtklib.h" 7 | 8 | static void dumpeph(peph_t *peph, int n) 9 | { 10 | char s[64]; 11 | int i,j; 12 | for (i=0;ioff[0][0],pcv->off[0][1],pcv->off[0][2]); 81 | } 82 | time=epoch2time(ep2); 83 | for (i=0;ioff[0][0],pcv->off[0][1],pcv->off[0][2]); 86 | } 87 | 88 | printf("%s utest2 : OK\n",__FILE__); 89 | } 90 | /* readrnxc() */ 91 | void utest3(void) 92 | { 93 | char *file1="../data/sp3/igs15904.cls"; 94 | char *file2="../data/sp3/igs15904.clk"; 95 | char *file3="../data/sp3/igs1590*.clk"; 96 | nav_t nav={0}; 97 | 98 | printf("file=%s\n",file1); 99 | readrnxc(file1,&nav); 100 | assert(nav.nc==0); 101 | 102 | printf("file=%s\n",file2); 103 | readrnxc(file2,&nav); 104 | assert(nav.nc>0); 105 | dumpclk(nav.pclk,nav.nc); 106 | free(nav.pclk); nav.pclk=NULL; nav.nc=nav.ncmax=0; 107 | 108 | printf("file=%s\n",file3); 109 | readrnxc(file3,&nav); 110 | assert(nav.nc>0); 111 | dumpclk(nav.pclk,nav.nc); 112 | free(nav.pclk); nav.pclk=NULL; nav.nc=nav.ncmax=0; 113 | 114 | printf("%s utest3 : OK\n",__FILE__); 115 | } 116 | /* peph2pos() */ 117 | void utest4(void) 118 | { 119 | FILE *fp; 120 | char *file1="../data/sp3/igs1590*.sp3"; /* 2010/7/1 */ 121 | char *file2="../data/sp3/igs1590*.clk"; /* 2010/7/1 */ 122 | nav_t nav={0}; 123 | int i,j,stat,sat; 124 | double ep[]={2010,7,1,0,0,0}; 125 | double rs[6]={0},dts[2]={0}; 126 | double var; 127 | gtime_t t,time; 128 | 129 | time=epoch2time(ep); 130 | 131 | readsp3(file1,&nav,0); 132 | assert(nav.ne>0); 133 | readrnxc(file2,&nav); 134 | assert(nav.nc>0); 135 | stat=peph2pos(time,0,&nav,0,rs,dts,&var); 136 | assert(!stat); 137 | stat=peph2pos(time,160,&nav,0,rs,dts,&var); 138 | assert(!stat); 139 | 140 | fp=fopen("testpeph1.out","w"); 141 | 142 | sat=4; 143 | 144 | for (i=0;i<86400*2;i+=30) { 145 | t=timeadd(time,(double)i); 146 | for (j=0;j<6;j++) rs [j]=0.0; 147 | for (j=0;j<2;j++) dts[j]=0.0; 148 | peph2pos(t,sat,&nav,0,rs,dts,&var); 149 | fprintf(fp,"%02d %6d %14.3f %14.3f %14.3f %14.3f %10.3f %10.3f %10.3f %10.3f\n", 150 | sat,i,rs[0],rs[1],rs[2],dts[0]*1E9,rs[3],rs[4],rs[5],dts[1]*1E9); 151 | } 152 | fclose(fp); 153 | printf("%s utest4 : OK\n",__FILE__); 154 | } 155 | /* satpos() */ 156 | void utest5(void) 157 | { 158 | FILE *fp; 159 | char *file1="../data/sp3/igs1590*.sp3"; /* 2010/7/1 */ 160 | char *file2="../data/sp3/igs1590*.clk"; /* 2010/7/1 */ 161 | char *file3="../../data/igs05.atx"; 162 | char *file4="../data/rinex/brdc*.10n"; 163 | pcvs_t pcvs={0}; 164 | pcv_t *pcv; 165 | nav_t nav={0}; 166 | int i,stat,sat,svh; 167 | double ep[]={2010,7,1,0,0,0}; 168 | double rs1[6]={0},dts1[2]={0},rs2[6]={0},dts2[2]={0}; 169 | double var; 170 | gtime_t t,time; 171 | 172 | time=epoch2time(ep); 173 | 174 | readsp3(file1,&nav,0); 175 | assert(nav.ne>0); 176 | readrnxc(file2,&nav); 177 | assert(nav.nc>0); 178 | stat=readpcv(file3,&pcvs); 179 | assert(stat); 180 | readrnx(file4,1,"",NULL,&nav,NULL); 181 | assert(nav.n>0); 182 | for (i=0;i 5 | #include 6 | #include "../../src/rtklib.h" 7 | 8 | static void dumpobs(obs_t *obs) 9 | { 10 | gtime_t time={0}; 11 | int i; 12 | char str[64]; 13 | printf("obs : n=%d\n",obs->n); 14 | for (i=0;in;i++) { 15 | time2str(obs->data[i].time,str,3); 16 | printf("%s : %2d %2d %13.3f %13.3f %13.3f %13.3f %d %d\n",str,obs->data[i].sat, 17 | obs->data[i].rcv,obs->data[i].L[0],obs->data[i].L[1], 18 | obs->data[i].P[0],obs->data[i].P[1],obs->data[i].LLI[0],obs->data[i].LLI[1]); 19 | 20 | assert(1<=obs->data[i].sat&&obs->data[i].sat<=32); 21 | assert(timediff(obs->data[i].time,time)>=-DTTOL); 22 | 23 | time=obs->data[i].time; 24 | } 25 | } 26 | static void dumpnav(nav_t *nav) 27 | { 28 | int i; 29 | char str[64],s1[64],s2[64]; 30 | printf("nav : n=%d\n",nav->n); 31 | for (i=0;in;i++) { 32 | time2str(nav->eph[i].toe,str,3); 33 | time2str(nav->eph[i].toc,s1,0); 34 | time2str(nav->eph[i].ttr,s2,0); 35 | printf("%s : %2d %s %s %3d %3d %2d\n",str,nav->eph[i].sat,s1,s2, 36 | nav->eph[i].iode,nav->eph[i].iodc,nav->eph[i].svh); 37 | 38 | assert(nav->eph[i].iode==(nav->eph[i].iodc&0xFF)); 39 | } 40 | } 41 | static void dumpsta(sta_t *sta) 42 | { 43 | printf("name = %s\n",sta->name); 44 | printf("marker = %s\n",sta->marker); 45 | printf("antdes = %s\n",sta->antdes); 46 | printf("antsno = %s\n",sta->antsno); 47 | printf("rectype = %s\n",sta->rectype); 48 | printf("recver = %s\n",sta->recver); 49 | printf("recsno = %s\n",sta->recsno); 50 | printf("antsetup= %d\n",sta->antsetup); 51 | printf("itrf = %d\n",sta->itrf); 52 | printf("deltype = %d\n",sta->deltype); 53 | printf("pos = %.3f %.3f %.3f\n",sta->pos[0],sta->pos[1],sta->pos[2]); 54 | printf("del = %.3f %.3f %.3f\n",sta->del[0],sta->del[1],sta->del[2]); 55 | printf("hgt = %.3f\n",sta->hgt); 56 | } 57 | /* readrnx(), sortobs(), uniqnav() */ 58 | void utest1(void) 59 | { 60 | char file1[]="abc.00o"; 61 | char file2[]="bcd.00n"; 62 | char file3[]="../data/rinex/07590920.05o"; 63 | char file4[]="../data/rinex/07590920.05n"; 64 | char file5[]="../data/rinex/30400920.05o"; 65 | char file6[]="../data/rinex/30400920.05n"; 66 | obs_t obs={0}; 67 | nav_t nav={0}; 68 | sta_t sta={""}; 69 | int n,stat; 70 | 71 | stat=readrnx(file1,1,"",&obs,&nav,&sta); 72 | assert(stat==0&&obs.n==0&&nav.n==0&&nav.ng==0&&nav.ns==0); 73 | stat=readrnx(file2,1,"",&obs,&nav,&sta); 74 | assert(stat==0&&obs.n==0&&nav.n==0&&nav.ng==0&&nav.ns==0); 75 | stat=readrnx(file3,1,"",&obs,&nav,&sta); 76 | assert(stat==1); 77 | stat=readrnx(file4,1,"",&obs,&nav,&sta); 78 | assert(stat==1); 79 | stat=readrnx(file5,2,"",&obs,&nav,&sta); 80 | assert(stat==1); 81 | stat=readrnx(file6,2,"",&obs,&nav,&sta); 82 | assert(stat==1); 83 | n=sortobs(&obs); 84 | assert(n==171); 85 | uniqnav(&nav); 86 | assert(nav.n==167); 87 | dumpobs(&obs); dumpnav(&nav); dumpsta(&sta); 88 | assert(obs.data&&obs.n>0&&nav.eph&&nav.n>0); 89 | free(obs.data); 90 | free(nav.eph); 91 | free(nav.geph); 92 | free(nav.seph); 93 | 94 | printf("%s utest1 : OK\n",__FILE__); 95 | } 96 | /* readrnxt() */ 97 | void utest2(void) 98 | { 99 | gtime_t t0={0},ts,te; 100 | double ep1[]={2005,4,2,1,0,0},ep2[]={2005,4,2,2,0,0}; 101 | char file1[]="../data/rinex/07590920.05o"; 102 | char file2[]="../data/rinex/07590920.05n"; 103 | int n; 104 | obs_t obs={0}; 105 | nav_t nav={0}; 106 | sta_t sta={""}; 107 | 108 | ts=epoch2time(ep1); 109 | te=epoch2time(ep2); 110 | n=readrnxt(file1,1,ts,te,0.0,"",&obs,&nav,&sta); 111 | printf("\n\nn=%d\n",n); 112 | n=readrnxt(file2,1,ts,te,0.0,"",&obs,&nav,&sta); 113 | dumpobs(&obs); 114 | free(obs.data); obs.data=NULL; obs.n=obs.nmax=0; 115 | n=readrnxt(file1,1,t0,t0,240.0,"",&obs,&nav,&sta); 116 | printf("\n\nn=%d\n",n); 117 | dumpobs(&obs); 118 | free(obs.data); 119 | 120 | printf("%s utset2 : OK\n",__FILE__); 121 | } 122 | static rnxopt_t opt1={{0}}; 123 | static rnxopt_t opt2= { 124 | {0},{0},0.0,0.0,2.10,SYS_ALL,OBSTYPE_ALL,FREQTYPE_ALL,{{0}}, 125 | "STAID", 126 | "RROG567890123456789012345678901", 127 | "RUNBY67890123456789012345678901", 128 | "MARKER789012345678901234567890123456789012345678901234567890123", 129 | "MARKNO7890123456789012345678901", 130 | "MARKTY7890123456789012345678901", 131 | {"OBSERVER90123456789012345678901", 132 | "AGENCY7890123456789012345678901"}, 133 | {"RCV1567890123456789012345678901", 134 | "RCV2567890123456789012345678901", 135 | "RCV3567890123456789012345678901"}, 136 | {"ANT1567890123456789012345678901", 137 | "ANT2567890123456789012345678901", 138 | "ANT3567890123456789012345678901"}, 139 | {12345678.123,99999999.999,100000000.000}, 140 | {123.0345,890123.9012,34567.0001}, 141 | {"COMMENT1 012345678901234567890123456789012345678901234567890123", 142 | "COMMENT2 012345678901234567890123456789012345678901234567890123", 143 | "COMMENT3 012345678901234567890123456789012345678901234567890123", 144 | "COMMENT4 012345678901234567890123456789012345678901234567890123", 145 | "COMMENT5 012345678901234567890123456789012345678901234567890123"}, 146 | "",{0},1,1,1,1,1, 147 | {0},{0},{0} 148 | }; 149 | /* outrneobsh() */ 150 | void utest3(void) 151 | { 152 | nav_t nav={0}; 153 | 154 | outrnxobsh(stdout,&opt1,&nav); 155 | outrnxobsh(stdout,&opt2,&nav); 156 | 157 | printf("%s utest3 : OK\n",__FILE__); 158 | } 159 | /* outrneobsb() */ 160 | void utest4(void) 161 | { 162 | char file[]="../data/rinex/07590920.05o"; 163 | obs_t obs={0}; 164 | int i,j; 165 | 166 | readrnx(file,1,"",&obs,NULL,NULL); 167 | outrnxobsb(stdout,&opt2,obs.data,8,9); 168 | outrnxobsb(stdout,&opt2,obs.data,8,0); 169 | 170 | for (i=j=0;i 5 | #include 6 | #include "../../src/rtklib.h" 7 | 8 | #define OUT stdout 9 | 10 | /* dump tle ------------------------------------------------------------------*/ 11 | static void dumptle(FILE *fp, const tle_t *tle) 12 | { 13 | int i; 14 | 15 | for (i=0;in;i++) { 16 | fprintf(fp,"(%2d) name = %s\n", i+1,tle->data[i].name ); 17 | fprintf(fp,"(%2d) satno= %s\n", i+1,tle->data[i].satno); 18 | fprintf(fp,"(%2d) class= %c\n", i+1,tle->data[i].satclass); 19 | fprintf(fp,"(%2d) desig= %s\n", i+1,tle->data[i].desig); 20 | fprintf(fp,"(%2d) epoch= %s\n", i+1,time_str(tle->data[i].epoch,0)); 21 | fprintf(fp,"(%2d) etype= %d\n", i+1,tle->data[i].etype); 22 | fprintf(fp,"(%2d) eleno= %d\n", i+1,tle->data[i].eleno); 23 | fprintf(fp,"(%2d) ndot = %19.12e\n",i+1,tle->data[i].ndot ); 24 | fprintf(fp,"(%2d) nddot= %19.12e\n",i+1,tle->data[i].nddot); 25 | fprintf(fp,"(%2d) bstar= %19.12e\n",i+1,tle->data[i].bstar); 26 | fprintf(fp,"(%2d) inc = %19.12e\n",i+1,tle->data[i].inc ); 27 | fprintf(fp,"(%2d) OMG = %19.12e\n",i+1,tle->data[i].OMG ); 28 | fprintf(fp,"(%2d) ecc = %19.12e\n",i+1,tle->data[i].ecc ); 29 | fprintf(fp,"(%2d) omg = %19.12e\n",i+1,tle->data[i].omg ); 30 | fprintf(fp,"(%2d) M = %19.12e\n",i+1,tle->data[i].M ); 31 | fprintf(fp,"(%2d) n = %19.12e\n",i+1,tle->data[i].n ); 32 | fprintf(fp,"(%2d) rev = %d\n", i+1,tle->data[i].rev ); 33 | } 34 | } 35 | /* tle_read() ----------------------------------------------------------------*/ 36 | static void utest1(void) 37 | { 38 | const char *file1="../data/tle/tle_sgp4.err"; 39 | const char *file2="../data/tle/tle_sgp4.txt"; 40 | const char *file3="../data/tle/tle_nav.txt"; 41 | tle_t tle={0}; 42 | int stat; 43 | 44 | stat=tle_read(file1,&tle); 45 | assert(!stat); 46 | 47 | stat=tle_read(file2,&tle); 48 | assert(stat); 49 | assert(tle.n==1); 50 | 51 | stat=tle_read(file3,&tle); 52 | assert(stat); 53 | assert(tle.n==114); 54 | #if 0 /* for debug */ 55 | dumptle(OUT,&tle); 56 | #endif 57 | 58 | fprintf(OUT,"%s utest1 : OK\n",__FILE__); 59 | } 60 | /* tle_pos() -----------------------------------------------------------------*/ 61 | static void utest2(void) 62 | { 63 | const char *file2="../data/tle/tle_sgp4.txt"; 64 | const double ep0[6]={1980,1,1}; 65 | tle_t tle={0}; 66 | gtime_t epoch; 67 | double min,rs[6]; 68 | int i,stat; 69 | 70 | epoch=utc2gpst(timeadd(epoch2time(ep0),274.98708465*86400.0)); 71 | 72 | stat=tle_read(file2,&tle); 73 | assert(stat); 74 | 75 | stat=tle_pos(epoch,"TEST_ERR","","",&tle,NULL,rs); 76 | assert(!stat); 77 | 78 | for (i=0;i<5;i++) { 79 | min=360.0*i; 80 | 81 | stat=tle_pos(timeadd(epoch,min*60.0),"TEST_SAT","","",&tle,NULL,rs); 82 | assert(stat); 83 | 84 | fprintf(OUT,"%4.0f: %14.8f %14.8f %14.8f %11.8f %11.8f %11.8f\n",min, 85 | rs[0]/1e3,rs[1]/1e3,rs[2]/1e3,rs[3]/1e3,rs[4]/1e3,rs[5]/1e3); 86 | } 87 | fprintf(OUT,"%s utest2 : OK\n",__FILE__); 88 | } 89 | /* tle_pos() accuracy --------------------------------------------------------*/ 90 | static void utest3(void) 91 | { 92 | const char *file1="../data/tle/brdc3050.12*"; 93 | const char *file2="../data/tle/TLE_GNSS_20121101.txt"; 94 | const char *file3="../data/tle/igs17127.erp"; 95 | const double ep[6]={2012,10,31,0,0,0}; 96 | nav_t nav={0}; 97 | erp_t erp={0}; 98 | tle_t tle={0}; 99 | gtime_t time; 100 | char sat[32]; 101 | double rs1[6],rs2[6],ds[6],dts[2],var; 102 | int i,j,k,stat,svh; 103 | 104 | readrnx(file1,0,"",NULL,&nav,NULL); 105 | assert(nav.n>0); 106 | 107 | stat=readerp(file3,&erp); 108 | assert(stat); 109 | 110 | stat=tle_read(file2,&tle); 111 | assert(stat); 112 | 113 | for (i=0;i 70.0*pi/180& tan(ap)*cos(azel(1))>tan(pi/2-pos(1)))|... 32 | % (pos(1)>-70.0*pi/180&-tan(ap)*cos(azel(1))>tan(pi/2-pos(1))) % DO229C 33 | 34 | if (pos(1)> 70.0*pi/180& tan(ap)*cos(azel(1))>tan(pi/2-pos(1)))|... 35 | (pos(1)<-70.0*pi/180&-tan(ap)*cos(azel(1))>tan(pi/2+pos(1))) % corrected 36 | 37 | posp(2)=pos(2)+pi-asin(sin(ap)*sin(azel(1))/cos(posp(1))); 38 | else 39 | posp(2)=pos(2)+asin(sin(ap)*sin(azel(1))/cos(posp(1))); 40 | end 41 | posp=posp*180/pi; 42 | if posp(2)>180, posp(2)=posp(2)-360; end 43 | -------------------------------------------------------------------------------- /test/utest/testpeph1.m: -------------------------------------------------------------------------------- 1 | function testpeph1 2 | 3 | C=299792458.0; 4 | dirs='../data/sp3'; 5 | td=caltomjd([2010,7,1]); 6 | time=0:30:86400*2-30; 7 | 8 | ephs=textread('testpeph1.out'); 9 | ephs(ephs==0)=nan; 10 | 11 | sat=sprintf('GPS%02d',ephs(1,1)); 12 | 13 | ephr=readeph(td,time,{sat},dirs,'igs',24,'interp'); 14 | clkr=readclk(td,time,{sat},dirs,'igs',24,'interp'); 15 | 16 | for i=1:length(time) 17 | clkr(i,1)=clkr(i,1)-2*ephr(i,1:3)*ephr(i,4:6)'/C^2; 18 | end 19 | dpos=ephs(:,3:6)-[ephr(:,1:3),clkr(:,1)*1E9]; 20 | 21 | figure('color','w'), hold on, box on, grid on 22 | plot(time/3600,dpos) 23 | xlabel('time (hr)'); 24 | ylabel('error (m)'); 25 | xlim(time([1,end])/3600); 26 | ylim([-0.05,0.05]); 27 | legend({'x','y','z','clk'}) 28 | text(0.02,0.95,sprintf('STD: X=%.4f Y=%.4f Z=%.4f CLK=%.4fm',... 29 | std(dpos(~isnan(dpos(:,1)),1:3)),std(dpos(~isnan(dpos(:,4)),4))),... 30 | 'units','normalized') 31 | title(sprintf('testpeph: interpolation error %s',sat)); 32 | moveax 33 | -------------------------------------------------------------------------------- /test/utest/testpeph2.m: -------------------------------------------------------------------------------- 1 | function testpeph2 2 | 3 | C=299792458.0; 4 | dirs='../data/sp3'; 5 | td=caltomjd([2010,4,1]); 6 | time=0:30:86400*2-30; 7 | 8 | ephs=textread('testpeph2.out'); 9 | ephs(ephs==0)=nan; 10 | 11 | sat=sprintf('GPS%02d',ephs(1,1)); 12 | 13 | ephr=readeph(td,time,{sat},dirs,'igs',24,'interp'); 14 | clkr=readclk(td,time,{sat},dirs,'igs',24,'interp'); 15 | 16 | for i=1:length(time) 17 | clkr(i,1)=clkr(i,1)-2*ephr(i,1:3)*ephr(i,4:6)'/C^2; 18 | end 19 | dpos=ephs(:,3:6)-ephs(:,7:10); 20 | 21 | figure('color','w'), hold on, box on, grid on 22 | plot(time/3600,dpos) 23 | xlabel('time (hr)'); 24 | ylabel('error (m)'); 25 | xlim(time([1,end])/3600); 26 | ylim([-10,10]); 27 | legend({'x','y','z','clk'}) 28 | text(0.02,0.95,sprintf('STD: X=%.4f Y=%.4f Z=%.4f CLK=%.4fm',... 29 | std(dpos(~isnan(dpos(:,1)),1:3)),std(dpos(~isnan(dpos(:,4)),4))),... 30 | 'units','normalized') 31 | title(sprintf('testpeph: brdc-prec ephemeris %s',sat)); 32 | moveax 33 | -------------------------------------------------------------------------------- /test/utest/utest_eph.m: -------------------------------------------------------------------------------- 1 | function utest_eph 2 | % matlab script for rtklib unit test 3 | % after executing utest for rtklib, execute it 4 | % need gt 0.6.4 5 | 6 | testpeph1 7 | testpeph2 8 | testgloeph 9 | 10 | -------------------------------------------------------------------------------- /util/gencrc/crc16.c: -------------------------------------------------------------------------------- 1 | static const uint16_t tbl_CRC16[]={ 2 | 0x0000,0x1021,0x2042,0x3063,0x4084,0x50A5,0x60C6,0x70E7, 3 | 0x8108,0x9129,0xA14A,0xB16B,0xC18C,0xD1AD,0xE1CE,0xF1EF, 4 | 0x1231,0x0210,0x3273,0x2252,0x52B5,0x4294,0x72F7,0x62D6, 5 | 0x9339,0x8318,0xB37B,0xA35A,0xD3BD,0xC39C,0xF3FF,0xE3DE, 6 | 0x2462,0x3443,0x0420,0x1401,0x64E6,0x74C7,0x44A4,0x5485, 7 | 0xA56A,0xB54B,0x8528,0x9509,0xE5EE,0xF5CF,0xC5AC,0xD58D, 8 | 0x3653,0x2672,0x1611,0x0630,0x76D7,0x66F6,0x5695,0x46B4, 9 | 0xB75B,0xA77A,0x9719,0x8738,0xF7DF,0xE7FE,0xD79D,0xC7BC, 10 | 0x48C4,0x58E5,0x6886,0x78A7,0x0840,0x1861,0x2802,0x3823, 11 | 0xC9CC,0xD9ED,0xE98E,0xF9AF,0x8948,0x9969,0xA90A,0xB92B, 12 | 0x5AF5,0x4AD4,0x7AB7,0x6A96,0x1A71,0x0A50,0x3A33,0x2A12, 13 | 0xDBFD,0xCBDC,0xFBBF,0xEB9E,0x9B79,0x8B58,0xBB3B,0xAB1A, 14 | 0x6CA6,0x7C87,0x4CE4,0x5CC5,0x2C22,0x3C03,0x0C60,0x1C41, 15 | 0xEDAE,0xFD8F,0xCDEC,0xDDCD,0xAD2A,0xBD0B,0x8D68,0x9D49, 16 | 0x7E97,0x6EB6,0x5ED5,0x4EF4,0x3E13,0x2E32,0x1E51,0x0E70, 17 | 0xFF9F,0xEFBE,0xDFDD,0xCFFC,0xBF1B,0xAF3A,0x9F59,0x8F78, 18 | 0x9188,0x81A9,0xB1CA,0xA1EB,0xD10C,0xC12D,0xF14E,0xE16F, 19 | 0x1080,0x00A1,0x30C2,0x20E3,0x5004,0x4025,0x7046,0x6067, 20 | 0x83B9,0x9398,0xA3FB,0xB3DA,0xC33D,0xD31C,0xE37F,0xF35E, 21 | 0x02B1,0x1290,0x22F3,0x32D2,0x4235,0x5214,0x6277,0x7256, 22 | 0xB5EA,0xA5CB,0x95A8,0x8589,0xF56E,0xE54F,0xD52C,0xC50D, 23 | 0x34E2,0x24C3,0x14A0,0x0481,0x7466,0x6447,0x5424,0x4405, 24 | 0xA7DB,0xB7FA,0x8799,0x97B8,0xE75F,0xF77E,0xC71D,0xD73C, 25 | 0x26D3,0x36F2,0x0691,0x16B0,0x6657,0x7676,0x4615,0x5634, 26 | 0xD94C,0xC96D,0xF90E,0xE92F,0x99C8,0x89E9,0xB98A,0xA9AB, 27 | 0x5844,0x4865,0x7806,0x6827,0x18C0,0x08E1,0x3882,0x28A3, 28 | 0xCB7D,0xDB5C,0xEB3F,0xFB1E,0x8BF9,0x9BD8,0xABBB,0xBB9A, 29 | 0x4A75,0x5A54,0x6A37,0x7A16,0x0AF1,0x1AD0,0x2AB3,0x3A92, 30 | 0xFD2E,0xED0F,0xDD6C,0xCD4D,0xBDAA,0xAD8B,0x9DE8,0x8DC9, 31 | 0x7C26,0x6C07,0x5C64,0x4C45,0x3CA2,0x2C83,0x1CE0,0x0CC1, 32 | 0xEF1F,0xFF3E,0xCF5D,0xDF7C,0xAF9B,0xBFBA,0x8FD9,0x9FF8, 33 | 0x6E17,0x7E36,0x4E55,0x5E74,0x2E93,0x3EB2,0x0ED1,0x1EF0 34 | }; 35 | -------------------------------------------------------------------------------- /util/gencrc/crc24.c: -------------------------------------------------------------------------------- 1 | static const uint32_t tbl_CRC24Q[]={ 2 | 0x000000,0x864CFB,0x8AD50D,0x0C99F6,0x93E6E1,0x15AA1A,0x1933EC,0x9F7F17, 3 | 0xA18139,0x27CDC2,0x2B5434,0xAD18CF,0x3267D8,0xB42B23,0xB8B2D5,0x3EFE2E, 4 | 0xC54E89,0x430272,0x4F9B84,0xC9D77F,0x56A868,0xD0E493,0xDC7D65,0x5A319E, 5 | 0x64CFB0,0xE2834B,0xEE1ABD,0x685646,0xF72951,0x7165AA,0x7DFC5C,0xFBB0A7, 6 | 0x0CD1E9,0x8A9D12,0x8604E4,0x00481F,0x9F3708,0x197BF3,0x15E205,0x93AEFE, 7 | 0xAD50D0,0x2B1C2B,0x2785DD,0xA1C926,0x3EB631,0xB8FACA,0xB4633C,0x322FC7, 8 | 0xC99F60,0x4FD39B,0x434A6D,0xC50696,0x5A7981,0xDC357A,0xD0AC8C,0x56E077, 9 | 0x681E59,0xEE52A2,0xE2CB54,0x6487AF,0xFBF8B8,0x7DB443,0x712DB5,0xF7614E, 10 | 0x19A3D2,0x9FEF29,0x9376DF,0x153A24,0x8A4533,0x0C09C8,0x00903E,0x86DCC5, 11 | 0xB822EB,0x3E6E10,0x32F7E6,0xB4BB1D,0x2BC40A,0xAD88F1,0xA11107,0x275DFC, 12 | 0xDCED5B,0x5AA1A0,0x563856,0xD074AD,0x4F0BBA,0xC94741,0xC5DEB7,0x43924C, 13 | 0x7D6C62,0xFB2099,0xF7B96F,0x71F594,0xEE8A83,0x68C678,0x645F8E,0xE21375, 14 | 0x15723B,0x933EC0,0x9FA736,0x19EBCD,0x8694DA,0x00D821,0x0C41D7,0x8A0D2C, 15 | 0xB4F302,0x32BFF9,0x3E260F,0xB86AF4,0x2715E3,0xA15918,0xADC0EE,0x2B8C15, 16 | 0xD03CB2,0x567049,0x5AE9BF,0xDCA544,0x43DA53,0xC596A8,0xC90F5E,0x4F43A5, 17 | 0x71BD8B,0xF7F170,0xFB6886,0x7D247D,0xE25B6A,0x641791,0x688E67,0xEEC29C, 18 | 0x3347A4,0xB50B5F,0xB992A9,0x3FDE52,0xA0A145,0x26EDBE,0x2A7448,0xAC38B3, 19 | 0x92C69D,0x148A66,0x181390,0x9E5F6B,0x01207C,0x876C87,0x8BF571,0x0DB98A, 20 | 0xF6092D,0x7045D6,0x7CDC20,0xFA90DB,0x65EFCC,0xE3A337,0xEF3AC1,0x69763A, 21 | 0x578814,0xD1C4EF,0xDD5D19,0x5B11E2,0xC46EF5,0x42220E,0x4EBBF8,0xC8F703, 22 | 0x3F964D,0xB9DAB6,0xB54340,0x330FBB,0xAC70AC,0x2A3C57,0x26A5A1,0xA0E95A, 23 | 0x9E1774,0x185B8F,0x14C279,0x928E82,0x0DF195,0x8BBD6E,0x872498,0x016863, 24 | 0xFAD8C4,0x7C943F,0x700DC9,0xF64132,0x693E25,0xEF72DE,0xE3EB28,0x65A7D3, 25 | 0x5B59FD,0xDD1506,0xD18CF0,0x57C00B,0xC8BF1C,0x4EF3E7,0x426A11,0xC426EA, 26 | 0x2AE476,0xACA88D,0xA0317B,0x267D80,0xB90297,0x3F4E6C,0x33D79A,0xB59B61, 27 | 0x8B654F,0x0D29B4,0x01B042,0x87FCB9,0x1883AE,0x9ECF55,0x9256A3,0x141A58, 28 | 0xEFAAFF,0x69E604,0x657FF2,0xE33309,0x7C4C1E,0xFA00E5,0xF69913,0x70D5E8, 29 | 0x4E2BC6,0xC8673D,0xC4FECB,0x42B230,0xDDCD27,0x5B81DC,0x57182A,0xD154D1, 30 | 0x26359F,0xA07964,0xACE092,0x2AAC69,0xB5D37E,0x339F85,0x3F0673,0xB94A88, 31 | 0x87B4A6,0x01F85D,0x0D61AB,0x8B2D50,0x145247,0x921EBC,0x9E874A,0x18CBB1, 32 | 0xE37B16,0x6537ED,0x69AE1B,0xEFE2E0,0x709DF7,0xF6D10C,0xFA48FA,0x7C0401, 33 | 0x42FA2F,0xC4B6D4,0xC82F22,0x4E63D9,0xD11CCE,0x575035,0x5BC9C3,0xDD8538 34 | }; 35 | -------------------------------------------------------------------------------- /util/gencrc/gencrc.c: -------------------------------------------------------------------------------- 1 | /*------------------------------------------------------------------------------ 2 | * gencrc.c : generate crc table 3 | * 4 | * Copyright (C) 2013 by T.TAKASU, All rights reserved. 5 | * 6 | * version : $Revision:$ $Date:$ 7 | * history : 2013/02/28 1.0 new 8 | *-----------------------------------------------------------------------------*/ 9 | #include 10 | #include 11 | 12 | static const char rcsid[]="$Id:$"; 13 | 14 | #define POLYCRC16 0x1021u /* CRC16 polynomial for BINEX,NVS */ 15 | #define POLYCRC24Q 0x1864CFBu /* CRC24Q polynomial for SBAS */ 16 | 17 | /* generate crc-16 parity table -----------------------------------------------*/ 18 | static void gen_crc16(FILE *fp) 19 | { 20 | uint16_t crcs[256]={0}; 21 | int i,j; 22 | 23 | for (i=0;i<256;i++) { 24 | crcs[i]=(uint16_t)i<<8; 25 | for (j=0;j<8;j++) { 26 | if (crcs[i]&0x8000) crcs[i]=(crcs[i]<<1)^POLYCRC16; 27 | else crcs[i]<<=1; 28 | } 29 | } 30 | fprintf(fp,"static const uint16_t tbl_CRC16[]={\n"); 31 | 32 | for (i=0;i<32;i++) { 33 | fprintf(fp," "); 34 | for (j=0;j<8;j++) { 35 | fprintf(fp,"0x%04X%s",crcs[j+i*8],i==31&&j==7?"":","); 36 | } 37 | fprintf(fp,"\n"); 38 | } 39 | fprintf(fp,"};\n"); 40 | } 41 | /* generate crc-24q parity table ---------------------------------------------*/ 42 | static void gen_crc24(FILE *fp) 43 | { 44 | uint32_t crcs[256]={0}; 45 | int i,j; 46 | 47 | for (i=0;i<256;i++) { 48 | crcs[i]=(uint32_t)i<<16; 49 | for (j=0;j<8;j++) if ((crcs[i]<<=1)&0x1000000) crcs[i]^=POLYCRC24Q; 50 | } 51 | fprintf(fp,"static const uint32_t tbl_CRC24Q[]={\n"); 52 | 53 | for (i=0;i<32;i++) { 54 | fprintf(fp," "); 55 | for (j=0;j<8;j++) { 56 | fprintf(fp,"0x%06X%s",crcs[j+i*8],i==31&&j==7?"":","); 57 | } 58 | fprintf(fp,"\n"); 59 | } 60 | fprintf(fp,"};\n"); 61 | } 62 | /* main ----------------------------------------------------------------------*/ 63 | int main(int argc, char **argv) 64 | { 65 | FILE *fp=stdout; 66 | int i,crc=0; 67 | 68 | for (i=1;i 5 | #include 6 | 7 | static const int pos[8][85]={ 8 | { 9,10,12,13,15,17,19,20,22,24,26,28,30,32,34,35,37,39,41,43,45,47,49,51,53,55,57,59,61,63,65,66,68,70,72,74,76,78,80,82,84,0}, 9 | { 9,11,12,14,15,18,19,21,22,25,26,29,30,33,34,36,37,40,41,44,45,48,49,52,53,56,57,60,61,64,65,67,68,71,72,75,76,79,80,83,84,0}, 10 | {10,11,12,16,17,18,19,23,24,25,26,31,32,33,34,38,39,40,41,46,47,48,49,54,55,56,57,62,63,64,65,69,70,71,72,77,78,79,80,85,0}, 11 | {13,14,15,16,17,18,19,27,28,29,30,31,32,33,34,42,43,44,45,46,47,48,49,58,59,60,61,62,63,64,65,73,74,75,76,77,78,79,80,0}, 12 | {20,21,22,23,24,25,26,27,28,29,30,31,32,33,34,50,51,52,53,54,55,56,57,58,59,60,61,62,63,64,65,81,82,83,84,85,0}, 13 | {35,36,37,38,39,40,41,42,43,44,45,46,47,48,49,50,51,52,53,54,55,56,57,58,59,60,61,62,63,64,65,0}, 14 | {66,67,68,69,70,71,72,73,74,75,76,77,78,79,80,81,82,83,84,85,0}, 15 | { 9,10,11,12,13,14,15,16,17,18,19,20,21,22,23,24,25,26,27,28,29,30,31,32,33,34,35,36,37,38,39,40,41,42,43,44,45,46,47,48,49,50, 16 | 51,52,53,54,55,56,57,58,59,60,61,62,63,64,65,66,67,68,69,70,71,72,73,74,75,76,77,78,79,80,81,82,83,84,85,0}, 17 | }; 18 | 19 | int main(int argc, char **argv) 20 | { 21 | int i,j,bits[11],p; 22 | 23 | printf("const uint8_t mask[][11]={\n"); 24 | for (i=0;i<8;i++) { 25 | for (j=0;j<11;j++) bits[j]=0; 26 | for (j=0;pos[i][j];j++) { 27 | p=85-pos[i][j]; 28 | bits[p/8]|=1<<(7-p%8); 29 | } 30 | printf(" {"); 31 | for (j=0;j<10;j++) printf("0x%02X%s",bits[j],j<9?",":""); 32 | printf("}%s\n",i<7?",":""); 33 | } 34 | printf("};\n"); 35 | return 0; 36 | } 37 | -------------------------------------------------------------------------------- /util/gencrc/genxor.c: -------------------------------------------------------------------------------- 1 | /*------------------------------------------------------------------------------ 2 | * genxor.c: generate xor table 3 | *-----------------------------------------------------------------------------*/ 4 | #include 5 | 6 | int main(int argc, char **argv) 7 | { 8 | int i,j,b; 9 | 10 | printf("const uint8_t xor_bits[]={\n"); 11 | 12 | for (i=0;i<256;i++) { 13 | for (j=b=0;j<8;j++) b^=((i>>j)&1); 14 | printf("%d%s",b,i==255?"\n":(i%32==31?",\n":",")); 15 | } 16 | printf("};\n"); 17 | return 0; 18 | } 19 | -------------------------------------------------------------------------------- /util/gencrc/makefile: -------------------------------------------------------------------------------- 1 | # makefile for gencrc 2 | 3 | BINDIR = /usr/local/bin 4 | SRC = ../../../src 5 | CFLAGS = -Wall -O3 -ansi -pedantic 6 | LDLIBS = -lm 7 | 8 | all : gencrc genxor genmsk 9 | gencrc : gencrc.o 10 | genxor : genxor.o 11 | genmsk : genmsk.o 12 | 13 | clean: 14 | rm -f gencrc genxor genmsk *.o 15 | 16 | test: 17 | ./gencrc -16 > crc16.c 18 | ./gencrc -24 > crc24.c 19 | ./genxor > xor.c 20 | ./genmsk > msk.c 21 | -------------------------------------------------------------------------------- /util/geniono/estiono.c: -------------------------------------------------------------------------------- 1 | /*------------------------------------------------------------------------------ 2 | * geniono.c : ionosphere correction estimation 3 | * 4 | * Copyright (C) 2012 by T.TAKASU, All rights reserved. 5 | * 6 | * version : $Revision:$ $Date:$ 7 | * history : 2012/09/15 1.0 new 8 | *-----------------------------------------------------------------------------*/ 9 | #include "rtklib.h" 10 | 11 | static const char rcsid[]="$Id:$"; 12 | 13 | #define SQR(x) ((x)*(x)) 14 | #define MIN(x,y) ((x)<=(y)?(x):(y)) 15 | 16 | #define FACT_LG 0.4 17 | #define SIG_ERR_A 0.003 18 | #define SIG_ERR_B 0.003 19 | #define RATIO_ERR 100.0 20 | 21 | #define PRN_IONO SQR(1E-3) /* process noise variance of iono delay (m^2/s) */ 22 | #define VAR_IONO SQR(10.0) /* initial variance of vertical iono delay (m^2) */ 23 | 24 | #define II(s) ((s)-1) /* state index of ionos */ 25 | #define IB(s) (MAXSAT+(s)-1) /* state index of phase bias */ 26 | #define NX (MAXSAT*2) /* number of estimated states */ 27 | 28 | typedef struct { /* satellite status type */ 29 | gtime_t time; /* time */ 30 | double azel[2]; /* azimuth/elevation (rad) */ 31 | double gf; /* geometry-free phase value (m) */ 32 | } stat_t; 33 | 34 | /* initialize state and covariance -------------------------------------------*/ 35 | static void initx(double *x, double *P, int nx, int i, double xi, double var) 36 | { 37 | int j; 38 | x[i]=xi; 39 | for (j=0;jL[0]!=0.0&&obs->L[1]!=0.0) { 49 | G0=stat[obs->sat-1].gf; 50 | stat[obs->sat-1].gf=G1=obs->L[0]-obs->L[1]; 51 | if (fabs(G1-G0)>THRES_SLIP) return 1; 52 | } 53 | return (obs->LLI[0]&3)||(obs->LLI[1]&3); 54 | } 55 | /* initizlize ionosphere parameter --------------------------------------------*/ 56 | static void init_iono(const obsd_t *obs, const double *azel, double *x, 57 | double *P, int nx) 58 | { 59 | double map,iono; 60 | if (obs->P[0]==0||obs->P[1]==0) return; 61 | map=ionmapf(pos,azel); 62 | iono=(obs->P[0]-obs->P[1])/map; 63 | initx(x,P,nx,II(obs->sat),iono,VAR_IONO); 64 | } 65 | /* initizlize bias parameter --------------------------------------------------*/ 66 | static void init_bias(const obsd_t *obs, double *x, double *P, int nx) 67 | { 68 | double bias; 69 | if (obs->L[0]==0||obs->L[1]==0||obs->P[0]==0||obs->P[1]==0) return; 70 | bias=(obs->L[0]-obs->L[1])-(obs->P[0]-obs->P[1]); 71 | initx(x,P,nx,IB(obs->sat),bias,VAR_BIAS); 72 | } 73 | /* temporal update of states --------------------------------------------------*/ 74 | static void udstate(const obsd_t *obs, int n, const nav_t *nav, double *x, 75 | double *P, int nx, ssat_t *ssat) 76 | { 77 | gtime_t time; 78 | double tt; 79 | int i,sat; 80 | 81 | for (i=0;iMAXGAP_BIAS) { 95 | init_bias(obs+i,nav,x,P,nx); 96 | } 97 | } 98 | ssat[sat-1].time=time; 99 | } 100 | } 101 | /* measurement error standard deviation --------------------------------------*/ 102 | static double std_err(const double *azel) 103 | { 104 | return FACT_LG*(SIG_ERR_A+SIG_ERR_B/sin(azel[1])); 105 | } 106 | /* satellite azimuth/elevation angle -----------------------------------------*/ 107 | static void sat_azel(const obsd_t *obs, int n, const nav_t *nav, 108 | const double *pos, double *azel) 109 | { 110 | double rs[MAXOBS*6],dts[MAXOBS*2],var[MAXOBS],r,e[3]; 111 | int svh[MAXOBS]; 112 | 113 | /* satellite positions and clocks */ 114 | satposs(obs[0].time,obs,n,nav,EPHOPT_BRDC,rs,dts,var,svh); 115 | 116 | for (i=0;i0.0) satazel(pos,e,azel+i*2); 118 | } 119 | } 120 | /* ionosphere residuals ------------------------------------------------------*/ 121 | static int res_iono(const obsd_t *obs, int n, const double *azel, 122 | const double *x, int nx, double *v, double *H, double *R) 123 | { 124 | double *sig,L1,L2,P1,P2,map; 125 | int i,j,nv=0,sat; 126 | 127 | sig=mat(1,2*n); 128 | 129 | for (i=0;iL[0]*lam[0]; 132 | L2=obs->L[1]*lam[1]; 133 | P1=obs->P[0]; 134 | P2=obs->P[1]; 135 | if (L1==0||L2==0||P1==0||P2==0) continue; 136 | 137 | /* ionosphere mapping function */ 138 | map=ionmapf(pos,azel+i*2); 139 | 140 | /* residuals of ionosphere (geometriy-free) LC */ 141 | v[nv ]=(L1-L2)+map*x[II(sat)]-x[IB(sat)]; 142 | v[nv+1]=(P1-P2)-map*x[II(sat)]; 143 | 144 | /* partial derivatives */ 145 | for (j=0;jn;i++) { 190 | for (n=1;i+nn;n++) { 191 | if (timediff(obs[i].time,obs->data[i+n].time)>1E-3) break; 192 | } 193 | /* satellite azimuth/elevation angle */ 194 | sat_azel(obs+i,n,nav,pos,azel); 195 | 196 | /* time update of parameters */ 197 | ud_state(obs+i,n,azel,x,P,nx,ssat); 198 | 199 | /* ionosphere residuals */ 200 | if ((nv=res_iono(obs+i,n,azel,x,nx,v,H,R))<=0) break; 201 | 202 | /* filter */ 203 | if ((info=filter(x,P,H,v,R,nx,nv))) break; 204 | 205 | /* output ionopshere parameters */ 206 | out_iono(obs[i].time,x,P,nx,fp); 207 | } 208 | free(x); free(P); free(v); free(H); free(R); 209 | 210 | return 1; 211 | } 212 | /* main ----------------------------------------------------------------------*/ 213 | int main(int argc, char **argv) 214 | { 215 | FILE *fp=stdout; 216 | nav_t nav={0}; 217 | obs_t obs={0}; 218 | double rr[3]={0}; 219 | char *ifile[32],*ofile=""; 220 | int i,j,n=0; 221 | 222 | for (i=1;i1E-3) break; 69 | 70 | /* for each satellite */ 71 | for (sat=1;sat<=MAXSAT;sat++) { 72 | 73 | /* interpolation of ionosphere */ 74 | if (!interp_ion(nav,t0,t1,sat,n,index,dist,iono+sat-1,&rate, 75 | &var,&brk)) { 76 | continue; 77 | } 78 | if (!fp) { 79 | sprintf(file,"%s/%c%4.0f_%c%5.0f.stec",dir, 80 | pos[0]<0.0?'S':'N',fabs(pos[0])*R2D*100.0, 81 | pos[1]<0.0?'W':'E',fabs(pos[1])*R2D*100.0); 82 | 83 | if (!(fp=fopen(file,"w"))) { 84 | fprintf(stderr,"file open error: %s\n",file); 85 | continue; 86 | } 87 | out_head(t1,pos,fp); 88 | } 89 | /* output ionosphere delay */ 90 | out_iono(t1,sat,brk,iono[sat-1],rate,var,fp); 91 | } 92 | } 93 | if (fp) fclose(fp); 94 | } 95 | /* interpolation of stec -----------------------------------------------------*/ 96 | static void interp_stec(const nav_t *nav, gtime_t ts, gtime_t te, double tint, 97 | const double *ew, const double *ns, double gint, 98 | const char *dir) 99 | { 100 | double lat,lon,pos[3]={0}; 101 | int i,j; 102 | 103 | for (i=0;;i++) { /* N -> S */ 104 | if ((lat=ns[0]-gint*i) E */ 107 | if ((lon=ew[1]+gint*j)>ew[0]+1E-6) break; 108 | 109 | pos[0]=lat*D2R; 110 | pos[1]=lon*D2R; 111 | 112 | /* interpolation of stec to grid */ 113 | interp_grid(nav,ts,te,tint,pos,dir); 114 | } 115 | } 116 | } 117 | /* main ----------------------------------------------------------------------*/ 118 | int main(int argc, char **argv) 119 | { 120 | nav_t nav={0}; 121 | gtime_t ts={0},te={0}; 122 | double eps[6]={2011,1,1,0,0,0},epe[6]={2011,1,3,23,59,59},tint=30.0; 123 | double ew[2]={AREA_E,AREA_W},ns[2]={AREA_N,AREA_S},gint=GRID_INT; 124 | char *ifile="",*dir="."; 125 | int i; 126 | 127 | for (i=1;i 5 | #include "rtklib.h" 6 | 7 | #define HEADLEN 76 8 | 9 | /* main ----------------------------------------------------------------------*/ 10 | int main(int argc, int argv) 11 | { 12 | FILE *ifp,*itagfp,*ofp,*otagfp; 13 | gtime_t time0; 14 | char ifiles[32]={},*ofile=""; 15 | char itagfile[1024],otagfile[1024]; 16 | int i,n=0; 17 | uint32_t tick0,tick1,tick,fpos; 18 | uint8_t buff[4096],tagbuff[64]; 19 | 20 | for (i=0;ibuff,rtcm->nbyte,1,fp)<1) break; 66 | } 67 | } 68 | /* generate rtcm nav data messages -------------------------------------------*/ 69 | static void gen_rtcm_nav(gtime_t time, rtcm_t *rtcm, const nav_t *nav, 70 | int *index, const int *type, int n, FILE *fp) 71 | { 72 | int i,j,sat,prn; 73 | 74 | for (i=index[0];in;i++) { 75 | 76 | if (time.time&&timediff(nav->eph[i].ttr,time)>-0.1) continue; 77 | sat=nav->eph[i].sat; 78 | rtcm->time=nav->eph[i].ttr; 79 | rtcm->nav.eph[sat-1]=nav->eph[i]; 80 | rtcm->ephsat=sat; 81 | 82 | for (j=0;jbuff,rtcm->nbyte,1,fp)<1) break; 87 | } 88 | index[0]=i+1; 89 | } 90 | for (i=index[1];ing;i++) { 91 | 92 | if (time.time&&timediff(nav->geph[i].tof,time)>-0.1) continue; 93 | sat=nav->geph[i].sat; 94 | if (satsys(sat,&prn)!=SYS_GLO) continue; 95 | rtcm->time=nav->geph[i].tof; 96 | rtcm->nav.geph[prn-1]=nav->geph[i]; 97 | rtcm->ephsat=sat; 98 | 99 | for (j=0;jbuff,rtcm->nbyte,1,fp)<1) break; 104 | } 105 | index[1]=i+1; 106 | } 107 | } 108 | /* generate rtcm antenna info messages ---------------------------------------*/ 109 | static void gen_rtcm_ant(rtcm_t *rtcm, const int *type, int n, FILE *fp) 110 | { 111 | int i; 112 | 113 | for (i=0;ibuff,rtcm->nbyte,1,fp)<1) break; 118 | } 119 | } 120 | /* convert to rtcm messages --------------------------------------------------*/ 121 | static int conv_rtcm(const int *type, int n, const char *outfile, 122 | const obs_t *obs, const nav_t *nav, const sta_t *sta, 123 | int staid) 124 | { 125 | FILE *fp=stdout; 126 | gtime_t time0={0}; 127 | rtcm_t rtcm={0}; 128 | eph_t eph0={0}; 129 | geph_t geph0={0}; 130 | int i,j,prn,index[2]={0}; 131 | 132 | if (!(rtcm.nav.eph =(eph_t *)malloc(sizeof(eph_t )*MAXSAT ))|| 133 | !(rtcm.nav.geph=(geph_t *)malloc(sizeof(geph_t)*MAXPRNGLO))) return 0; 134 | 135 | rtcm.staid=staid; 136 | rtcm.sta=*sta; 137 | 138 | for (i=0;ing;i++) { 143 | if (satsys(nav->geph[i].sat,&prn)!=SYS_GLO) continue; 144 | rtcm.nav.geph[prn-1]=nav->geph[i]; 145 | } 146 | if (*outfile&&!(fp=fopen(outfile,"wb"))) { 147 | fprintf(stderr,"file open error: %s\n",outfile); 148 | return 0; 149 | } 150 | /* gerate rtcm antenna info messages */ 151 | gen_rtcm_ant(&rtcm,type,n,fp); 152 | 153 | for (i=0;in;i=j) { 154 | 155 | /* extract epoch obs data */ 156 | for (j=i+1;jn;j++) { 157 | if (timediff(obs->data[j].time,obs->data[i].time)>DTTOL) break; 158 | } 159 | rtcm.time=obs->data[i].time; 160 | rtcm.seqno++; 161 | rtcm.obs.data=obs->data+i; 162 | rtcm.obs.n=j-i; 163 | 164 | /* generate rtcm obs data messages */ 165 | gen_rtcm_obs(&rtcm,type,n,fp); 166 | 167 | /* generate rtcm nav data messages */ 168 | gen_rtcm_nav(rtcm.time,&rtcm,nav,index,type,n,fp); 169 | 170 | fprintf(stderr,"%s: NOBS=%2d\r",time_str(rtcm.time,0),rtcm.obs.n); 171 | } 172 | /* gerate rtcm nav data messages */ 173 | gen_rtcm_nav(time0,&rtcm,nav,index,type,n,fp); 174 | 175 | fclose(fp); 176 | 177 | /* print statistics */ 178 | fprintf(stderr,"\n MT # OF MSGS\n"); 179 | 180 | for (i=1;i<299;i++) { 181 | if (!rtcm.nmsg3[i]) continue; 182 | fprintf(stderr,"%04d %10d\n",1000+i,rtcm.nmsg3[i]); 183 | } 184 | fprintf(stderr,"\n"); 185 | free(rtcm.nav.eph); 186 | free(rtcm.nav.geph); 187 | return 1; 188 | } 189 | /* main ----------------------------------------------------------------------*/ 190 | int main(int argc, char **argv) 191 | { 192 | gtime_t ts={0},te={0}; 193 | obs_t obs={0}; 194 | nav_t nav={0}; 195 | sta_t sta={{0}}; 196 | double es[6]={0},ee[6]={0},tint=0.0; 197 | char *infile[16]={0},*outfile="",buff[1024],*p; 198 | int i,n=0,m=0,type[16],trlevel=0,staid=0,ret=0; 199 | 200 | for (i=1;i0) { 221 | traceopen(TRACEFILE); 222 | tracelevel(trlevel); 223 | } 224 | if (es[0]>0.0) ts=epoch2time(es); 225 | if (ee[0]>0.0) te=epoch2time(ee); 226 | 227 | /* read rinex files */ 228 | for (i=0;i0) { 241 | traceclose(); 242 | } 243 | return ret; 244 | } 245 | -------------------------------------------------------------------------------- /util/simobs/gcc/makefile: -------------------------------------------------------------------------------- 1 | # makefile for simobs 2 | 3 | BINDIR = /usr/local/bin 4 | SRC = ../../../src 5 | CFLAGS = -Wall -O3 -ansi -pedantic -I$(SRC) -DTRACE -DENAGLO -DENAGAL -DENAQZS -DNFREQ=4 -DMAXOBS=128 6 | LDLIBS = -lm 7 | 8 | simobs : simobs.o rinex.o rtkcmn.o 9 | 10 | simobs.o : ../simobs.c 11 | $(CC) -c $(CFLAGS) ../simobs.c 12 | rinex.o : $(SRC)/rinex.c 13 | $(CC) -c $(CFLAGS) $(SRC)/rinex.c 14 | rtkcmn.o : $(SRC)/rtkcmn.c 15 | $(CC) -c $(CFLAGS) $(SRC)/rtkcmn.c 16 | 17 | simobs.o : $(SRC)/rtklib.h 18 | rtkcmn.o : $(SRC)/rtklib.h 19 | 20 | install: 21 | cp simobs $(BINDIR) 22 | 23 | clean: 24 | rm -f simobs simobs.exe *.o 25 | 26 | OPT0=-ts 2009/4/1 -te 2009/4/2 -ti 10 27 | OPT1=../sim/brdc0910.09n ../sim/brdc0910.09g ../sim/brdc0910.09l 28 | OPT2=-r 36.106114294 140.087190410 70.3010 29 | OPT3=-r 36.103635125 140.086307150 69.7442 30 | OPT4=-r 36.031339503 140.202443500 70.9029 31 | OPT5=-r 36.263268936 140.174264100 94.2843 32 | 33 | sim: 34 | ./simobs $(OPT0) $(OPT1) $(OPT2) -o ../sim/base_20080509.obs 35 | ./simobs $(OPT0) $(OPT1) $(OPT3) -o ../sim/rov0_20080509.obs 36 | ./simobs $(OPT0) $(OPT1) $(OPT4) -o ../sim/rov1_20080509.obs 37 | ./simobs $(OPT0) $(OPT1) $(OPT5) -o ../sim/rov2_20080509.obs 38 | -------------------------------------------------------------------------------- /util/testeph/diffeph.c: -------------------------------------------------------------------------------- 1 | /*------------------------------------------------------------------------------ 2 | * diffeph.c : output difference between ephemerides 3 | * 4 | * history : 2010/06/17 0.1 new 5 | * 2011/09/17 0.2 add comparison of 2 precise ephemeris 6 | *-----------------------------------------------------------------------------*/ 7 | #include 8 | #include "rtklib.h" 9 | 10 | static const char *usage[]={ 11 | "Synopsys", 12 | " diffeph [-t0 y/m/d h:m:s][-ts ts][-ti ti][-s s][-1 r][-2 b][-t]", 13 | " [-o][-u lat lon][-x level] file ...", 14 | "", 15 | "Description", 16 | "compute ephemeris and clock error and output errors.", 17 | "", 18 | "Options [default]", 19 | "-t0 y/m/d h:m:s start time expressed in gpst", 20 | "-ts ts time span (hr) [24]", 21 | "-ti ti time interval (s) [30]", 22 | "-s s satellite number (all)", 23 | "-1 r compared ephemeris type (0:broadcast,1:precise,2:sbas,3:ssrapc,5:lex)", 24 | "-2 b reference ephemeris type (same as above)", 25 | "-t output time as yyyy/mm/dd hh:mm:ss", 26 | "-e output difference as ecef-x/y/z [radial/along-trk/cross-trk]", 27 | "-o output satellite position/clock-bias", 28 | "-u lat lon refrence position latitude and longitude for ure", 29 | "-x level trace level", 30 | "file ... compared ephemeris files and antenna parameters file", 31 | NULL}; 32 | 33 | /* print usage ---------------------------------------------------------------*/ 34 | static void prusage(void) 35 | { 36 | int i; 37 | for (i=0;usage[i];i++) fprintf(stderr,"%s\n",usage[i]); 38 | } 39 | /* update rtcm struct --------------------------------------------------------*/ 40 | static void updatertcm(gtime_t time, rtcm_t *rtcm, nav_t *nav, FILE *fp) 41 | { 42 | char s1[32],s2[32]; 43 | int i; 44 | 45 | while (input_rtcm3f(rtcm,fp)>=0) { 46 | time2str(time ,s1,0); 47 | time2str(rtcm->time,s2,0); 48 | trace(2,"rtcm.time=%s time=%s\n",s1,s2); 49 | 50 | if (timediff(rtcm->time,time)>=5.0) break; 51 | } 52 | for (i=0;issr[i]=rtcm->ssr[i]; 53 | } 54 | /* update lex ephemeris ------------------------------------------------------*/ 55 | static int updatelex(int index, gtime_t time, lex_t *lex, nav_t *nav) 56 | { 57 | gtime_t tof; 58 | 59 | for (;indexn;index++) { 60 | if (!lexupdatecorr(lex->msgs+index,nav,&tof)) continue; 61 | if (timediff(tof,time)>=0.0) break; 62 | } 63 | return index; 64 | } 65 | /* print difference ----------------------------------------------------------*/ 66 | static void printephdiff(gtime_t time, int sat, int eph1, int eph2, 67 | const nav_t *nav1, const nav_t *nav2, int topt, 68 | int eopt, int mopt, const double *pos) 69 | { 70 | double tow,rs1[6],rs2[6],dts1[2],dts2[2],var1,var2; 71 | double drs[3],drss[3],rc[3],er[3],ea[3],ec[3]; 72 | double rr[3],e[3],rr1[3],rr2[3],r1,r2,azel[2]; 73 | int i,week,svh1,svh2; 74 | char tstr[32]; 75 | 76 | if (!satpos(time,time,sat,eph1,nav1,rs1,dts1,&var1,&svh1)) return; 77 | if (!satpos(time,time,sat,eph2,nav2,rs2,dts2,&var2,&svh2)) return; 78 | if (svh1||svh2) return; 79 | 80 | for (i=0;i<3;i++) drs[i]=rs1[i]-rs2[i]; 81 | if (!normv3(rs2+3,ea)) return; 82 | cross3(rs2,rs2+3,rc); 83 | if (!normv3(rc,ec)) return; 84 | cross3(ea,ec,er); 85 | drss[0]=dot(drs,er,3); /* radial/along-trk/cross-trk */ 86 | drss[1]=dot(drs,ea,3); 87 | drss[2]=dot(drs,ec,3); 88 | 89 | if (topt) { 90 | time2str(time,tstr,0); 91 | printf("%s ",tstr); 92 | } 93 | else { 94 | tow=time2gpst(time,&week); 95 | printf("%4d %6.0f",week,tow); 96 | } 97 | printf("%3d ",sat); 98 | 99 | if (mopt) { 100 | printf("%8.3f %8.3f %8.3f ",drss[0],drss[1],drss[2]); 101 | } 102 | else { 103 | printf("%8.3f %8.3f %8.3f ",drs[0],drs[1],drs[2]); 104 | } 105 | printf("%8.3f ",dts1[0]==0.0||dts2[0]==0.0?0.0:(dts1[0]-dts2[0])*CLIGHT); 106 | if (mopt) { 107 | printf(" %13.3f %13.3f %13.3f %12.3f",rs1[0],rs1[1],rs1[2],dts1[0]*CLIGHT); 108 | } 109 | if (norm(pos,3)>0.0) { 110 | pos2ecef(pos,rr); 111 | for (i=0;i<3;i++) { 112 | rr1[i]=rs1[i]-rr[i]; 113 | rr2[i]=rs2[i]-rr[i]; 114 | } 115 | r1=norm(rr1,3); 116 | r2=norm(rr2,3); 117 | for (i=0;i<3;i++) e[i]=rr2[i]/r2; 118 | satazel(pos,e,azel); 119 | printf(" %8.3f %5.1f",(r1-r2)-(dts1[0]-dts2[0])*CLIGHT,azel[1]*R2D); 120 | } 121 | printf("\n"); 122 | } 123 | /* main ----------------------------------------------------------------------*/ 124 | int main(int argc, char **argv) 125 | { 126 | FILE *fp=NULL; 127 | nav_t nav={0},nav2={0}; 128 | rtcm_t rtcm; 129 | lex_t lex={0}; 130 | gtime_t t0,time; 131 | double ep0[]={2000,1,1,0,0,0},tspan=24.0,tint=300,pos[]={0}; 132 | int i,s,n=0,nx=0,sat=0,topt=0,eopt=0,mopt=0,trl=0,index=0; 133 | int eph1=EPHOPT_BRDC,eph2=EPHOPT_PREC; 134 | char *files[32],*ext; 135 | 136 | t0=epoch2time(ep0); 137 | 138 | init_rtcm(&rtcm); 139 | rtcm.time=t0; 140 | 141 | for (i=1;i0) { 169 | traceopen("diffeph.trace"); 170 | tracelevel(trl); 171 | } 172 | t0=epoch2time(ep0); 173 | 174 | init_rtcm(&rtcm); 175 | rtcm.time=t0; 176 | 177 | for (i=0;i0) { 182 | readsp3(files[i],&nav2); /* second precise ephemeris */ 183 | } 184 | else { 185 | readsp3(files[i],&nav); 186 | } 187 | } 188 | else if (!strcmp(ext,".atx")) { 189 | readsap(files[i],t0,&nav); 190 | } 191 | else if (!strcmp(ext,".rtcm3")||!strcmp(ext,".log")) { 192 | if (!(fp=fopen(files[i],"rb"))) { 193 | fprintf(stderr,"file open error: %s\n",files[i]); 194 | return -1; 195 | } 196 | } 197 | else if (!strcmp(ext,".lex")) { 198 | if (!lexreadmsg(files[i],0,&lex)) { 199 | fprintf(stderr,"file read error: %s\n",files[i]); 200 | return -1; 201 | } 202 | } 203 | else files[nx++]=files[i]; /* rinex clock */ 204 | } 205 | for (i=0;i0) { 208 | readrnxc(files[i],&nav2); /* second precise clock */ 209 | } 210 | else { 211 | readrnxc(files[i],&nav); 212 | } 213 | } 214 | for (i=0;i<(int)(tspan*3600.0/tint);i++) { 215 | time=timeadd(t0,tint*i); 216 | 217 | fprintf(stderr,"time=%s\r",time_str(time,0)); 218 | 219 | /* update ephemeris in navigation data */ 220 | if (fp) { 221 | updatertcm(time,&rtcm,&nav,fp); 222 | } 223 | else if (lex.n>0) { 224 | index=updatelex(index,time,&lex,&nav); 225 | } 226 | for (s=1;s<=MAXSAT;s++) { 227 | if (sat&&s!=sat) continue; 228 | 229 | printephdiff(time,s,eph1,eph2,&nav,eph1==1&&eph2==1?&nav2:&nav,topt, 230 | eopt,mopt,pos); 231 | } 232 | } 233 | if (fp) fclose(fp); 234 | if (trl>0) traceclose(); 235 | return 0; 236 | } 237 | -------------------------------------------------------------------------------- /util/testeph/dumpssr.c: -------------------------------------------------------------------------------- 1 | /*------------------------------------------------------------------------------ 2 | * dumpssr.c : dump ssr messages in rtcm log 3 | * 4 | * 2010/06/10 new 5 | *-----------------------------------------------------------------------------*/ 6 | #include 7 | #include "rtklib.h" 8 | 9 | /* print ssr messages --------------------------------------------------------*/ 10 | static void printhead(int topt, int mopt) 11 | { 12 | int i; 13 | 14 | printf("%% %s SAT ",topt?" DAY TIME ":" GPST "); 15 | 16 | if (mopt&1) { 17 | printf(" UDI IOD URA REF "); 18 | } 19 | if (mopt&2) { 20 | printf("%8s %8s %8s %8s %8s %8s ","DR","DA","DC","DDR","DDA","DDC"); 21 | } 22 | if (mopt&4) { 23 | printf("%8s %8s %8s %8s ","DCLK","DDCLK","DDDCLK","HRCLK"); 24 | } 25 | if (mopt&8) { 26 | for (i=0;i<12;i++) printf(" B%02d ",i+1); 27 | } 28 | printf("\n"); 29 | } 30 | /* print ssr messages --------------------------------------------------------*/ 31 | static void printssrmsg(int sat, const ssr_t *ssr, int topt, int mopt) 32 | { 33 | double tow; 34 | int week; 35 | char tstr[32],id[16]; 36 | 37 | if (topt) { 38 | time2str(ssr->t0,tstr,0); 39 | printf("%s ",tstr); 40 | } 41 | else { 42 | tow=time2gpst(ssr->t0,&week); 43 | printf("%4d %6.0f ",week,tow); 44 | } 45 | satno2id(sat,id); 46 | printf("%4s ",id); 47 | 48 | if (mopt&1) { 49 | printf("%4.0f %3d %3d %3d ",ssr->udint,ssr->iode,ssr->ura,ssr->refd); 50 | } 51 | if (mopt&2) { 52 | printf("%8.3f %8.3f %8.3f %8.3f %8.3f %8.3f ",ssr->deph[0],ssr->deph[1], 53 | ssr->deph[2],ssr->ddeph[0],ssr->ddeph[1],ssr->ddeph[2]); 54 | } 55 | if (mopt&4) { 56 | printf("%8.3f %8.3f %8.3f %8.3f ",ssr->dclk[0],ssr->dclk[1],ssr->dclk[2], 57 | ssr->hrclk); 58 | } 59 | if (mopt&8) { 60 | printf("%6.2f %6.2f %6.2f %6.2f %6.2f %6.2f %6.2f %6.2f %6.2f %6.2f %6.2f %6.2f ", 61 | ssr->cbias[0],ssr->cbias[1],ssr->cbias[2],ssr->cbias[3], 62 | ssr->cbias[4],ssr->cbias[5],ssr->cbias[6],ssr->cbias[7], 63 | ssr->cbias[8],ssr->cbias[9],ssr->cbias[10],ssr->cbias[11]); 64 | } 65 | printf("\n"); 66 | } 67 | /* dump ssr messages ---------------------------------------------------------*/ 68 | static void dumpssrmsg(FILE *fp, int sat, int topt, int mopt) 69 | { 70 | static rtcm_t rtcm; 71 | static gtime_t t0[MAXSAT]={{0}}; 72 | int i,stat; 73 | 74 | init_rtcm(&rtcm); 75 | 76 | while ((stat=input_rtcm3f(&rtcm,fp))>=0) { 77 | 78 | if (stat!=10) continue; /* ssr message */ 79 | 80 | for (i=0;i0) { 120 | traceopen("dumpssr.trace"); 121 | tracelevel(trl); 122 | } 123 | printhead(topt,mopt); 124 | 125 | dumpssrmsg(fp,sat,topt,mopt); 126 | 127 | fclose(fp); 128 | traceclose(); 129 | 130 | return 0; 131 | } 132 | -------------------------------------------------------------------------------- /util/testeph/makefile: -------------------------------------------------------------------------------- 1 | # makefile for diffeph dumpssr 2 | 3 | SRC = ../../src 4 | CFLAGS = -Wall -O3 -ansi -pedantic -I$(SRC) -DTRACE -DENAQZS -DENAGLO -DEXTLEX 5 | LDFLAGS = -lm 6 | 7 | all : diffeph dumpssr 8 | 9 | diffeph : rtkcmn.o ephemeris.o sbas.o rinex.o preceph.o rtcm.o rtcm2.o rtcm3.o 10 | diffeph : ionex.o pntpos.o ppp.o ppp_ar.o stec.o qzslex.o 11 | dumpssr : rtkcmn.o preceph.o rtcm.o rtcm2.o rtcm3.o 12 | 13 | rtkcmn.o : $(SRC)/rtklib.h $(SRC)/rtkcmn.c 14 | $(CC) -c $(CFLAGS) $(SRC)/rtkcmn.c 15 | ephemeris.o: $(SRC)/rtklib.h $(SRC)/ephemeris.c 16 | $(CC) -c $(CFLAGS) $(SRC)/ephemeris.c 17 | sbas.o : $(SRC)/rtklib.h $(SRC)/sbas.c 18 | $(CC) -c $(CFLAGS) $(SRC)/sbas.c 19 | rinex.o : $(SRC)/rtklib.h $(SRC)/rinex.c 20 | $(CC) -c $(CFLAGS) $(SRC)/rinex.c 21 | preceph.o : $(SRC)/rtklib.h $(SRC)/preceph.c 22 | $(CC) -c $(CFLAGS) $(SRC)/preceph.c 23 | rtcm.o : $(SRC)/rtklib.h $(SRC)/rtcm.c 24 | $(CC) -c $(CFLAGS) $(SRC)/rtcm.c 25 | rtcm2.o : $(SRC)/rtklib.h $(SRC)/rtcm2.c 26 | $(CC) -c $(CFLAGS) $(SRC)/rtcm2.c 27 | rtcm3.o : $(SRC)/rtklib.h $(SRC)/rtcm3.c 28 | $(CC) -c $(CFLAGS) $(SRC)/rtcm3.c 29 | ionex.o : $(SRC)/rtklib.h $(SRC)/ionex.c 30 | $(CC) -c $(CFLAGS) $(SRC)/ionex.c 31 | pntpos.o : $(SRC)/rtklib.h $(SRC)/pntpos.c 32 | $(CC) -c $(CFLAGS) $(SRC)/pntpos.c 33 | ppp.o : $(SRC)/rtklib.h $(SRC)/ppp.c 34 | $(CC) -c $(CFLAGS) $(SRC)/ppp.c 35 | ppp_ar.o : $(SRC)/rtklib.h $(SRC)/ppp_ar.c 36 | $(CC) -c $(CFLAGS) $(SRC)/ppp_ar.c 37 | stec.o : $(SRC)/rtklib.h $(SRC)/stec.c 38 | $(CC) -c $(CFLAGS) $(SRC)/stec.c 39 | qzslex.o : $(SRC)/rtklib.h $(SRC)/qzslex.c 40 | $(CC) -c $(CFLAGS) $(SRC)/qzslex.c 41 | 42 | install: 43 | cp -f diffeph.exe /usr/local/bin 44 | cp -f dumpssr.exe /usr/local/bin 45 | 46 | clean: 47 | rm -f *.o *.stackdump *.trace *.out *.exe 48 | 49 | -------------------------------------------------------------------------------- /util/testlex/20130428_lex.jaxa: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JAXA-SNU/MALIB/3b217d34d8429e04ea095c68e78678d3f9fcecfc/util/testlex/20130428_lex.jaxa -------------------------------------------------------------------------------- /util/testlex/20130429_lex.jaxa: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/JAXA-SNU/MALIB/3b217d34d8429e04ea095c68e78678d3f9fcecfc/util/testlex/20130429_lex.jaxa -------------------------------------------------------------------------------- /util/testlex/convlex.c: -------------------------------------------------------------------------------- 1 | /*------------------------------------------------------------------------------ 2 | * convlex.c : convert lex binary to lex log 3 | * 4 | * history : 2010/08/24 1.0 new 5 | * 2011/07/01 1.1 add -h option 6 | *-----------------------------------------------------------------------------*/ 7 | #include "rtklib.h" 8 | 9 | /* main ----------------------------------------------------------------------*/ 10 | int main(int argc, char **argv) 11 | { 12 | const char *usage="lexconvbin [-h] [-t type] infile [-o outfile]"; 13 | char *infile="",*outfile=""; 14 | int i,type=0,format=0; 15 | 16 | for (i=0;i0) { 28 | traceopen("dumplex.trace"); 29 | tracelevel(trl); 30 | } 31 | if (!lexreadmsg(file,0,&lex)) { 32 | fprintf(stderr,"file read error: %s\n",file); 33 | return -1; 34 | } 35 | for (i=0;i0) traceclose(); 39 | return 0; 40 | } 41 | -------------------------------------------------------------------------------- /util/testlex/dumpssr.c: -------------------------------------------------------------------------------- 1 | /*------------------------------------------------------------------------------ 2 | * dumpssr.c : dump ssr messages in rtcm log 3 | * 4 | * 2010/06/10 new 5 | *-----------------------------------------------------------------------------*/ 6 | #include 7 | #include "rtklib.h" 8 | 9 | /* print ssr messages --------------------------------------------------------*/ 10 | static void printhead(int topt, int mopt) 11 | { 12 | int i; 13 | 14 | printf("%% %s SAT ",topt?" DAY TIME ":" GPST "); 15 | 16 | if (mopt&1) { 17 | printf(" UDI IOD URA REF "); 18 | } 19 | if (mopt&2) { 20 | printf("%8s %8s %8s %8s %8s %8s ","DR","DA","DC","DDR","DDA","DDC"); 21 | } 22 | if (mopt&4) { 23 | printf("%8s %8s %8s %8s ","DCLK","DDCLK","DDDCLK","HRCLK"); 24 | } 25 | if (mopt&8) { 26 | for (i=0;i<12;i++) printf(" B%02d ",i+1); 27 | } 28 | printf("\n"); 29 | } 30 | /* print ssr messages --------------------------------------------------------*/ 31 | static void printssrmsg(int sat, const ssr_t *ssr, int topt, int mopt) 32 | { 33 | double tow; 34 | int week; 35 | char tstr[32],id[16]; 36 | 37 | if (topt) { 38 | time2str(ssr->t0,tstr,0); 39 | printf("%s ",tstr); 40 | } 41 | else { 42 | tow=time2gpst(ssr->t0,&week); 43 | printf("%4d %6.0f ",week,tow); 44 | } 45 | satno2id(sat,id); 46 | printf("%4s ",id); 47 | 48 | if (mopt&1) { 49 | printf("%4.0f %3d %3d %3d ",ssr->udint,ssr->iode,ssr->ura,ssr->refd); 50 | } 51 | if (mopt&2) { 52 | printf("%8.3f %8.3f %8.3f %8.3f %8.3f %8.3f ",ssr->deph[0],ssr->deph[1], 53 | ssr->deph[2],ssr->ddeph[0],ssr->ddeph[1],ssr->ddeph[2]); 54 | } 55 | if (mopt&4) { 56 | printf("%8.3f %8.3f %8.3f %8.3f ",ssr->dclk[0],ssr->dclk[1],ssr->dclk[2], 57 | ssr->hrclk); 58 | } 59 | if (mopt&8) { 60 | printf("%6.2f %6.2f %6.2f %6.2f %6.2f %6.2f %6.2f %6.2f %6.2f %6.2f %6.2f %6.2f ", 61 | ssr->cbias[0],ssr->cbias[1],ssr->cbias[2],ssr->cbias[3], 62 | ssr->cbias[4],ssr->cbias[5],ssr->cbias[6],ssr->cbias[7], 63 | ssr->cbias[8],ssr->cbias[9],ssr->cbias[10],ssr->cbias[11]); 64 | } 65 | printf("\n"); 66 | } 67 | /* dump ssr messages ---------------------------------------------------------*/ 68 | static void dumpssrmsg(FILE *fp, int sat, int topt, int mopt) 69 | { 70 | static rtcm_t rtcm; 71 | static gtime_t t0[MAXSAT]={{0}}; 72 | int s,stat; 73 | 74 | init_rtcm(&rtcm); 75 | 76 | while ((stat=input_rtcm3f(&rtcm,fp))>=0) { 77 | 78 | if (stat!=10) continue; /* ssr message */ 79 | 80 | for (s=1;s<=MAXSAT;s++) { 81 | if (timediff(rtcm.ssr[s-1].t0,t0[s-1])==0.0) continue; 82 | t0[s-1]=rtcm.ssr[s-1].t0; 83 | 84 | if (!sat||s==sat) { 85 | printssrmsg(s,rtcm.ssr+s-1,topt,mopt); 86 | } 87 | } 88 | } 89 | } 90 | /* main ----------------------------------------------------------------------*/ 91 | int main(int argc, char **argv) 92 | { 93 | const char *usage="dumpssr [-t][-s sat][-i][-o][-c][-b][-h][-x tr] file"; 94 | 95 | FILE *fp; 96 | char *file=""; 97 | int i,sat=0,topt=0,mopt=0,trl=0; 98 | 99 | for (i=0;i0) { 120 | traceopen("dumpssr.trace"); 121 | tracelevel(trl); 122 | } 123 | printhead(topt,mopt); 124 | 125 | dumpssrmsg(fp,sat,topt,mopt); 126 | 127 | fclose(fp); 128 | traceclose(); 129 | 130 | return 0; 131 | } 132 | -------------------------------------------------------------------------------- /util/testlex/makefile: -------------------------------------------------------------------------------- 1 | # makefile for testlex 2 | 3 | SRC = ../../src 4 | #CFLAGS = -Wall -O3 -ansi -pedantic -I$(SRC) -DTRACE -DENAQZS -DENAGLO -DENALEX 5 | CFLAGS = -Wall -O3 -ansi -pedantic -I$(SRC) -DTRACE -DENAQZS -DENAGLO 6 | LDFLAGS= -lm -lrt 7 | 8 | all : convlex dumplex dumpssr outlexion 9 | 10 | convlex : rtkcmn.o preceph.o qzslex.o 11 | dumplex : rtkcmn.o preceph.o qzslex.o 12 | dumpssr : rtkcmn.o preceph.o rtcm.o rtcm3.o rtcm2.o dumpssr.o 13 | outlexion : rtkcmn.o preceph.o qzslex.o 14 | 15 | rtkcmn.o : $(SRC)/rtklib.h $(SRC)/rtkcmn.c 16 | $(CC) -c $(CFLAGS) $(SRC)/rtkcmn.c 17 | preceph.o : $(SRC)/rtklib.h $(SRC)/preceph.c 18 | $(CC) -c $(CFLAGS) $(SRC)/preceph.c 19 | qzslex.o : $(SRC)/rtklib.h $(SRC)/qzslex.c 20 | $(CC) -c $(CFLAGS) $(SRC)/qzslex.c 21 | rtcm.o : $(SRC)/rtklib.h $(SRC)/rtcm.c 22 | $(CC) -c $(CFLAGS) $(SRC)/rtcm.c 23 | rtcm3.o : $(SRC)/rtklib.h $(SRC)/rtcm3.c 24 | $(CC) -c $(CFLAGS) $(SRC)/rtcm3.c 25 | rtcm2.o : $(SRC)/rtklib.h $(SRC)/rtcm2.c 26 | $(CC) -c $(CFLAGS) $(SRC)/rtcm2.c 27 | 28 | install: 29 | cp -f convlex.exe /usr/local/bin 30 | cp -f dumplex.exe /usr/local/bin 31 | cp -f outlexion.exe /usr/local/bin 32 | 33 | clean: 34 | rm -f *.o *.stackdump *.trace *.out *.exe 35 | 36 | DIR1=../lexdata 37 | DIR2=../lexerrdata 38 | 39 | test1: 40 | ./convlex $(DIR1)/LEX_20100704.bin -o $(DIR1)/LEX_20100704.lex 41 | ./convlex $(DIR1)/LEX_20100725.bin -o $(DIR1)/LEX_20100725.lex 42 | ./convlex $(DIR1)/LEX_20100803.bin -o $(DIR1)/LEX_20100803.lex 43 | ./convlex $(DIR1)/LEX_20101204.bin -o $(DIR1)/LEX_20101204.lex 44 | ./convlex $(DIR1)/LEX_20101205.bin -o $(DIR1)/LEX_20101205.lex 45 | 46 | test2: 47 | # ./diffeph -t0 2010/07/04 0:00:00 -ts 24 -ti 30 -1 5 $(DIR1)/LEX_20100704.lex $(DIR2)/igs15910.* $(DIR2)/igs05_1604.atx -x 2 > LEX_20100704.diff 48 | # ./diffeph -t0 2010/07/25 0:00:00 -ts 24 -ti 30 -1 5 $(DIR1)/LEX_20100725.lex $(DIR2)/igs15940.* $(DIR2)/igs05_1604.atx -x 2 > LEX_20100725.diff 49 | # ./diffeph -t0 2010/08/03 0:00:00 -ts 24 -ti 30 -1 5 $(DIR1)/LEX_20100803.lex $(DIR2)/igs15952.* $(DIR2)/igs05_1604.atx -x 2 > LEX_20100803.diff 50 | # ./diffeph -t0 2010/12/04 0:00:00 -ts 24 -ti 30 -1 5 $(DIR1)/LEX_20101204.lex $(DIR2)/igr161*.* $(DIR2)/igs05_1604.atx -x 2 > LEX_20101204.diff 51 | # ./diffeph -t0 2010/12/05 0:00:00 -ts 24 -ti 30 -1 5 $(DIR1)/LEX_20101205.lex $(DIR2)/igr161*.* $(DIR2)/igs05_1604.atx -x 2 > LEX_20101205.diff 52 | 53 | test3: 54 | # ./diffeph -t0 2010/12/04 0:00:00 -ts 24 -ti 30 -1 3 $(DIR2)/brdc33*0.10n $(DIR2)/clk11_201012040000.rtcm3 $(DIR2)/igr161*.* $(DIR2)/igs05_1604.atx -x 2 > SSR_20101204.diff 55 | ./diffeph -t0 2010/12/04 0:00:00 -ts 24 -ti 30 -1 3 $(DIR2)/brdc33*0.10n $(DIR2)/clk20_201012040000.rtcm3 $(DIR2)/igr161*.* $(DIR2)/igs05_1604.atx -x 2 > SSR_20101204.diff 56 | 57 | test4: 58 | ./outlexion -t0 2010/12/04 0:00:00 -ts 24 $(DIR1)/LEX_20101204.lex -o LEXION_20101204.m 59 | -------------------------------------------------------------------------------- /util/testlex/outlexion.c: -------------------------------------------------------------------------------- 1 | /*------------------------------------------------------------------------------ 2 | * outlexion.c : output lex ionosphere correction as matrix 3 | * 4 | * 2010/12/09 0.1 new 5 | *-----------------------------------------------------------------------------*/ 6 | #include 7 | #include "rtklib.h" 8 | 9 | /* update lex ephemeris ------------------------------------------------------*/ 10 | static int updatelex(int index, gtime_t time, lex_t *lex, nav_t *nav) 11 | { 12 | gtime_t tof; 13 | 14 | for (;indexn;index++) { 15 | if (!lexupdatecorr(lex->msgs+index,nav,&tof)) continue; 16 | fprintf(stderr,"%6d: tof=%s\r",index,time_str(tof,0)); 17 | if (timediff(tof,time)>=0.0) break; 18 | } 19 | return index; 20 | } 21 | /* print tec grid data -------------------------------------------------------*/ 22 | static void printtec(int index, gtime_t time, double sec, const nav_t *nav, 23 | const double *rpos, int nlat, int nlon, double dpos, 24 | FILE *fp) 25 | { 26 | int i,j; 27 | double lat0,lon0,pos[3]={0},azel[]={0,PI/2.0},ion,var; 28 | 29 | lat0=rpos[0]+dpos*((nlat-1)/2); 30 | lon0=rpos[1]-dpos*((nlon-1)/2); 31 | 32 | if (index==1) { 33 | fprintf(fp,"lons =["); 34 | for (i=0;i tecu */ 49 | fprintf(fp,"%7.3f ",ion); 50 | } 51 | else { 52 | fprintf(fp,"%7s ","nan"); 53 | } 54 | } 55 | fprintf(fp,"\n"); 56 | } 57 | fprintf(fp,"];\n"); 58 | } 59 | /* main ----------------------------------------------------------------------*/ 60 | int main(int argc, char **argv) 61 | { 62 | FILE *fp=NULL; 63 | nav_t nav={0}; 64 | lex_t lex={0}; 65 | gtime_t t0,time; 66 | double ep0[]={2000,1,1,0,0,0},tspan=24.0,tint=7200,dpos=1; 67 | double rpos[]={35,137}; 68 | char *ifile="",*ofile=""; 69 | int i,trl=0,index=0,nlat=45,nlon=45; 70 | 71 | t0=epoch2time(ep0); 72 | 73 | for (i=1;i0) { 97 | traceopen("diffeph.trace"); 98 | tracelevel(trl); 99 | } 100 | t0=epoch2time(ep0); 101 | 102 | if (!lexreadmsg(ifile,0,&lex)) { 103 | fprintf(stderr,"file read error: %s\n",ifile); 104 | return -1; 105 | } 106 | if (!(fp=fopen(ofile,"w"))) { 107 | fprintf(stderr,"file open error: %s\n",ofile); 108 | return -1; 109 | } 110 | fprintf(fp,"epoch=[%.0f %.0f %.0f %.0f %.0f %.0f];\n", 111 | ep0[0],ep0[1],ep0[2],ep0[3],ep0[4],ep0[5]); 112 | 113 | for (i=0;i<(int)(tspan*3600.0/tint);i++) { 114 | time=timeadd(t0,tint*i); 115 | 116 | fprintf(stderr,"time=%s\r",time_str(time,0)); 117 | 118 | index=updatelex(index,time,&lex,&nav); 119 | 120 | printtec(i+1,time,tint*i,&nav,rpos,nlat,nlon,dpos,fp); 121 | } 122 | fclose(fp); 123 | if (trl>0) traceclose(); 124 | return 0; 125 | } 126 | -------------------------------------------------------------------------------- /util/testlex/plotlexeph.m: -------------------------------------------------------------------------------- 1 | function plotlexeph(file,sats,trange) 2 | % 3 | % plot lex ephemeris error 4 | % 5 | % 2010/12/09 0.1 new 6 | 7 | if nargin<1, file='diffeph.out'; end 8 | if nargin<2, sats=1:32; end 9 | if nargin<3, trange=[0 24]; end % time range [tstart tend] (hr) 10 | fn='Times New Roman'; 11 | 12 | v=textread(file); 13 | 14 | figure('color','w'), hold on, box on, grid on 15 | 16 | i=find(v(:,3)==2); % reference clock = PRN2 17 | tclk=v(i,2)-floor(v(1,2)/86400)*86400; 18 | clk0=v(i,5); 19 | satlabel={}; 20 | rmserr=[]; 21 | range=3; 22 | 23 | disp(sprintf('SAT : %4s %4s %11s %11s %11s %11s %11s (m)','NE','NC','3D','Radial','AlongTrk','CrossTrk','Clock')); 24 | 25 | for sat=sats 26 | i=find(v(:,3)==sat); 27 | 28 | if isempty(i), continue; end 29 | timep=v(i,2)-floor(v(1,2)/86400)*86400; 30 | poserr=[sqrt(sum(v(i,4:6).^2,2)),v(i,4:6)]; 31 | 32 | [timec,j,k]=intersect(timep,tclk); 33 | clkerr=v(i(j),5)-clk0(k,:); 34 | 35 | i=find(trange(1)*3600<=timep&timep