So here’s an update:
CONFIG:
“Vinnie” the Landrover:
Frame: Motorized wheelchair. New batteries - 24v system
Motor controller: Sabertooth 2x25, mixed mode RC, microprocessor mode
Telemetry/communications: highpower Wifi (have also tried 933MHz radios, and will probably end up with 4G because of crosstalk/interference)
RTK: NavIO RAW on rover, will probably switch to NavIO+ very soon. Skytraq raw receiver at base; base in house, running strsvr (from RTKLIB) on indoors machine which also runs Mission Planner. The “both-apm.conf” file is attached to this to show you how it is all set up.
RC radio: cheap FlySky 6 channel, with channel 7 on the receiver actually receiving channel 6 from the RC transmitter, and parameters in Mission Planner adjusted accordingly. I aim to get rid of the RC radio entirely soon and just use the 4G telemetry set up for control. But for now it is easier to test.
Attached are the “both-apm.conf” file for configuring rtkrcv, and my rc.local file (which autostarts everything).
Remember to make sure you start rtkrcv FIRST, and wait a bit (sleep 20)… otherwise APMrover2.elf won’t run with the -E switch (btw Igor, shouldn’t it be the case that if APMrover2.elf doesn’t find the second GPS named at the -E switch, that it allows the APMrover2.elf file to still execute, but with a message to that effect? Would be much better that way…)
You can watch rtkrcv at telnet:(RPi IP):12347
Local files are created in a local “temp” directory with info from rtkrcv also.
Problems to be solved:
-
failsafe — with Sabertooth in this mode, there is no local failsafe for the motors, which means that when APMrover2 loses radio signal (or failsafe’s for whatever other reason), the Sabertooth just keeps doing whatever is was doing before (bad idea, IMO). So I have to add another failsafe to shut down the power or something. ANy ideas?
-
long-range telemetry (probably pretty easy with some config changes, as soon as I can bring myself to pay for a 4G account for this project) (any ideas? It needs to be reliable to about 1-2km)
-
cm RTK resolution — I won’t really know what the resolution is until I get the rover outside and play with it awhile (snow on the ground now). I have heard there is a “usage issue” regarding the way (float vs int) things are sent to Mission Planner… Anybody got any more info on this? Anybody trying RTK on a quad or plane?
Here is the both-apm.conf file:
console-passwd =admin
console-timetype =gpst # (0:gpst,1:utc,2:jst,3:tow)
console-soltype =dms # (0:dms,1:deg,2:xyz,3:enu,4:pyl)
console-solflag =1 # (0:off,1:std+2:age/ratio/ns)
inpstr1-type =tcpsvr # (0:off,1:serial,2:file,3:tcpsvr,4:tcpcli,7:ntripcli,8:ftp,9:http,10:spi)
inpstr2-type =tcpcli # (0:off,1:serial,2:file,3:tcpsvr,4:tcpcli,7:ntripcli,8:ftp,9:http,10:spi)
inpstr3-type =ftp # (0:off,1:serial,2:file,3:tcpsvr,4:tcpcli,7:ntripcli,8:ftp,9:http,10:spi)
inpstr1-path =127.0.0.1:12345
inpstr2-path =192.168.0.6:50011
inpstr3-path =cddis.gsfc.nasa.gov/gps/products/%W/igu%W%D%hb.sp3.Z
inpstr1-format =ubx # (0:rtcm2,1:rtcm3,2:oem4,3:oem3,4:ubx,5:ss2,6:hemis,7:skytraq,14:sp3)
inpstr2-format =skytraq # (0:rtcm2,1:rtcm3,2:oem4,3:oem3,4:ubx,5:ss2,6:hemis,7:skytraq,14:sp3)
inpstr3-format =sp3 # (0:rtcm2,1:rtcm3,2:oem4,3:oem3,4:ubx,5:ss2,6:hemis,7:skytraq,14:sp3)
inpstr2-nmeareq =off # (0:off,1:latlon,2:single)
inpstr2-nmealat =0 # (deg)
inpstr2-nmealon =0 # (deg)
outstr1-type =tcpsvr # (0:off,1:serial,2:file,3:tcpsvr,4:tcpcli,6:ntripsvr)
outstr2-type =file # (0:off,1:serial,2:file,3:tcpsvr,4:tcpcli,6:ntripsvr)
outstr1-path =127.0.0.1:12346
outstr2-path =/home/pi/rtkdata/sol2_%Y%m%d%h%M.pos
outstr1-format =nmea # (0:llh,1:xyz,2:enu,3:nmea)
outstr2-format =nmea # (0:llh,1:xyz,2:enu,3:nmea)
logstr1-type =off # (0:off,1:serial,2:file,3:tcpsvr,4:tcpcli,6:ntripsvr)
logstr2-type =off # (0:off,1:serial,2:file,3:tcpsvr,4:tcpcli,6:ntripsvr)
logstr3-type =off # (0:off,1:serial,2:file,3:tcpsvr,4:tcpcli,6:ntripsvr)
logstr1-path =/home/pi/rtkdata/rov_%Y%m%d%h%M.log
logstr2-path =/home/pi/rtkdata/ref_%Y%m%d%h%M.log
logstr3-path =/home/pi/rtkdata/cor_%Y%m%d%h%M.log
misc-svrcycle =10 # (ms)
misc-timeout =30000 # (ms)
misc-reconnect =30000 # (ms)
misc-nmeacycle =5000 # (ms)
misc-buffsize =32768 # (bytes)
misc-navmsgsel =rover # (0:all,1:rover,1:base,2:corr)
misc-startcmd =
misc-stopcmd =
file-cmdfile1 =/home/pi/RTKLIB-master/data/ubx_spi_raw_5hz.cmd
file-cmdfile2 =/home/pi/RTKLIB-master/data/skytraq_raw_5hz.cmd
file-cmdfile3 =
pos1-posmode =kinematic # (0:single,1:dgps,2:kinematic,3:static,4:movingbase,5:fixed,6:ppp-kine,7:ppp-static)
pos1-frequency =l1 # (1:l1,2:l1+l2,3:l1+l2+l5)
pos1-soltype =combined # (0:forward,1:backward,2:combined)
pos1-elmask =15 # (deg)
pos1-snrmask =20 # (dBHz)
pos1-dynamics =on # (0:off,1:on)
pos1-tidecorr =off # (0:off,1:on)
pos1-ionoopt =brdc # (0:off,1:brdc,2:sbas,3:dual-freq,4:est-stec)
pos1-tropopt =saas # (0:off,1:saas,2:sbas,3:est-ztd,4:est-ztdgrad)
pos1-sateph =brdc # (0:brdc,1:precise,2:brdc+sbas,3:brdc+ssrapc,4:brdc+ssrcom)
pos1-exclsats = # (prn …)
pos1-navsys =3 # (1:gps+2:sbas+4:glo+8:gal+16:qzs+32:comp)
pos2-armode =off # (0:off,1:continuous,2:instantaneous,3:fix-and-hold)
pos2-gloarmode =off # (0:off,1:on,2:autocal)
pos2-arthres =5
pos2-arlockcnt =0
pos2-arelmask =0 # (deg)
pos2-aroutcnt =5
pos2-arminfix =10
pos2-slipthres =0.05 # (m)
pos2-maxage =30 # (s)
pos2-rejionno =30 # (m)
pos2-niter =1
pos2-baselen =0 # (m)
pos2-basesig =0 # (m)
out-solformat =llh # (0:llh,1:xyz,2:enu,3:nmea)
out-outhead =on # (0:off,1:on)
out-outopt =off # (0:off,1:on)
out-timesys =gpst # (0:gpst,1:utc,2:jst)
out-timeform =tow # (0:tow,1:hms)
out-timendec =3
out-degform =deg # (0:deg,1:dms)
out-fieldsep =
out-height =ellipsoidal # (0:ellipsoidal,1:geodetic)
out-geoid =internal # (0:internal,1:egm96,2:egm08_2.5,3:egm08_1,4:gsi2000)
out-solstatic =all # (0:all,1:single)
out-nmeaintv1 =0 # (s)
out-nmeaintv2 =0 # (s)
out-outstat =off # (0:off,1:state,2:residual)
stats-errratio =100
stats-errphase =0.003 # (m)
stats-errphaseel =0.003 # (m)
stats-errphasebl =0 # (m/10km)
stats-errdoppler =1 # (Hz)
stats-stdbias =30 # (m)
stats-stdiono =0.03 # (m)
stats-stdtrop =0.3 # (m)
stats-prnaccelh =1 # (m/s^2)
stats-prnaccelv =0.1 # (m/s^2)
stats-prnbias =0.0001 # (m)
stats-prniono =0.001 # (m)
stats-prntrop =0.0001 # (m)
stats-clkstab =5e-12 # (s/s)
ant1-postype =llh # (0:llh,1:xyz,2:single,3:posfile,4:rinexhead,5:rtcm)
ant1-pos1 =34.87031095 # (deg|m)
ant1-pos2 =-98.21211167 # (deg|m)
ant1-pos3 =400 # (m|m)
ant1-anttype =
ant1-antdele =0 # (m)
ant1-antdeln =0 # (m)
ant1-antdelu =0 # (m)
ant2-postype =llh # (0:llh,1:xyz,2:single,3:posfile,4:rinexhead,5:rtcm)
ant2-pos1 =0 # (deg|m)
ant2-pos2 =0 # (deg|m)
ant2-pos3 =0 # (m|m)
ant2-anttype =
ant2-antdele =0 # (m)
ant2-antdeln =0 # (m)
ant2-antdelu =0 # (m)
misc-timeinterp =off # (0:off,1:on)
misc-sbasatsel =0 # (0:all)
file-satantfile =/home/pi/RTKLIB-master/data/igs05.atx
file-rcvantfile =/home/pi/RTKLIB-master/data/igs05.atx
file-staposfile =/home/pi/RTKLIB-master/data/station.pos
file-geoidfile =
file-dcbfile =/home/pi/RTKLIB-master/data/P1C1_ALL.DCB
file-tempdir =/home/pi/rtkdata
file-geexefile =
file-solstatfile =
file-tracefile =
and add these to your rc.local file:
sudo /home/pi/RTKLIB-master/bin-rpi/rtkrcv -s -p 12347 -o /home/pi/RTKLIB-master/bin-rpi/both-apm.conf &
sleep 20
sudo /home/pi/ardupilot/APMrover2/APMrover2.elf -A udp:192.168.0.6:14550 -E tcp:127.0.0.1:12346 > /home/pi/startup_log &