Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/Tools/geotag/geotag.sh
Views: 1798
#!/usr/bin/env bash12# Advanced geotagging tool by André Kjellstrup3###################################################################### VARIABLES ########################45version="v1.1"6mode=1 # 0=geotag, 1=jpg distance(s) , 2=CAM distance in sec7loglinenum=1 # last read log line number8loglinenummatched=0 # last read log line number used - reverting to this +1 when looking back9logline="start" #current line, placeholder for start10logtimemsprev=011logended=0 #true if log ended.12logtarget=0 #true if we got log type we wanted13logmatch=1 # true if we accepted lo line as matching14loggotpos=0 #true if log contains pos messages (enables fallback)15typical_offset="notset" #contains time offset of first picture vs log.16jpgtot=0 #number of jpg files in folder17jpgtagged=0 #number of correctly tagged photos18jpgmiss=0 #number of missing photos19jpgnotinlog=0 #counting jpg's with timestamp outside log20camindex=0 #number of last CAM message used.21camtot=0 #number of CAM lines found22trigtot=0 #number of TRIG lines found23logmiss=0 #missed CAM messages24revjumps=0 #count how many time we have backed up25difflimit=10 # POS message difflimit 10 gives 0.06sec , 20 has proved useful26running=127cmdarg=$* #save command line parameters28FILE=jpglist29ML="false"30logsdone=0 #counts processed logs31SKIPIMG=032333435###########################3637while [[ $# > 0 ]]38do39key="$1"4041case $key in42-w|--write)43WRITE="true"44;;45-r|--readonly)46WRITE="false"47;;48-f|--find)49WRITE="false"50FIND="true"51;;52-p|--pos)53MODE="POS"54typical_offset="$2"55shift # get past argument56;;57-dl|--difflimit)58difflimit="$2"59shift # get past argument60;;61-c|--cam)62MODE="CAM"63;;64-t|--trig)65MODE="TRIG"66;;67-ns|--nosubsec)68NS="true"69;;70-ml|--multilog)71ML="true"72;;73-del|--delorg)74DELORG="true"75;;76-sp|--skipphoto)77SKIPIMG="$2"78shift # get past argument79;;80-sc|--skipcam)81SKIPCAM="$2"82shift # get past argument83;;84-st|--skiptrig)85SKIPTRIG="$2"86shift # get past argument87;;88-sl|--skiplog)89SKIPLOG="$2"90shift # get past argument91;;9293-h|--help)94HELP="true"95;;96*)97# unknown option98;;99esac100shift # past argument or value101done102103#echo FILE EXTENSION = "${EXTENSION}"104#echo SEARCH PATH = "${SEARCHPATH}"105#echo LIBRARY PATH = "${LIBPATH}"106107if [[ "$HELP" == "true" ]] || [[ "$WRITE" == "" ]] #|| [[ "$MODE" == "" ]]108then109echo "Geotagging script by André Kjellstrup. $version"110echo "execute inside a folder containing .JPG and .BIN"111echo "example: geotag.sh -c -sp 2 -r"112echo ""113echo "-w or --write Enables photo processing"114echo "-r or --readonly Enables photo processing"115echo "-f or --readonly, finds CAM to exif spacing for +/- 10 skipped photos, and +/- 10 skipped CAM messages"116echo "-sp x or --skipphoto x Skips x photos counting from the start"117echo "-sc x or --skipcam x Skips x CAM entrys from the start"118echo "-sl x or --skiplog x Skips x POS entrys from the start"119echo "-st x or --skiptrig x Skips x TRIG entrys from the start"120echo "-p x or --pos x Use POS log only (if camera was independendly trigged) x=offset in seconds"121echo "-dl x or --difflimit x Acceptable limit in 10ms steps for POS-log vs photo differance 10=0.1s (default)"122echo "-c or --cam Use CAM log only (do not fall back to POS pessages)"123echo "-t or --trig Use TRIG log only (if camera shutter is sensed)"124echo "-ns or --nosubsec Do not look for subsecond EXIF tag."125echo "-ml or --multilog Grab and combine all .BIN files (for processing photos from more then one flight."126echo "-del or --delorg : Delete JPG_original (backups)."127echo "EXAMPLE:"128echo "Multiple flights dataset from S100; geotag.sh -p 0 -ns -dl 30 -w -ml -del"129echo "simgle CAM flight; geotag.sh -c -w -del"130exit 1131fi132133##ADD DEPENDENCIES HERE134command -v mavlogdump.py >/dev/null 2>&1 || { echo >&2 "I require mavlogdump.py but it's not installed. Aborting."; exit 1; }135command -v exiftool >/dev/null 2>&1 || { echo >&2 "I require exiftool but it's not installed. Aborting."; exit 1; }136##command -v foo >/dev/null 2>&1 || { echo >&2 "I require foo but it's not installed. Aborting."; exit 1; }137138if [[ "$WRITE" == "true" ]]139then140echo "INFO: will backup and modify photos" | tee geotag.log141fi142143if [[ "$WRITE" == "false" ]]144then145echo "INFO: dry run only, no photos will be modified" | tee geotag.log146fi147148if [[ "$MODE" == "POS" ]]149then150echo "INFO: use POS records only, expected offset of $typical_offset , poslimit (time of photo vs log is $poslimit)" | tee geotag.log151fi152153if [[ "$MODE" == "CAM" ]]154then155echo "INFO: use CAM records only" | tee geotag.log156fi157158159if [[ "$MODE" == "TRIG" ]]160then161echo "INFO: use TRIG records only" | tee geotag.log162fi163164if [[ "$NS" == "true" ]]165then166echo "INFO: Do not look for subsecond-time in EXIF" | tee geotag.log167fi168169170if [[ "$SKIPIMG" -gt "0" ]]171then172echo "INFO: will skip first $SKIPIMG photos" | tee geotag.log173fi174175if [[ "$SKIPCAM" -gt "0" ]]176then177echo "INFO: will skip first $SKIPCAM CAM logs" | tee geotag.log178fi179180if [[ "$SKIPTRIG" -gt "0" ]]181then182echo "INFO: will skip first $SKIPTRIG TRIG logs" | tee geotag.log183fi184185186if [[ "$SKIPLOG" -gt "0" ]]187then188echo "INFO: will skip first $SKIPLOG POS logs" | tee geotag.log189loglinenum=$SKIPLOG190fi191192if [ "$difflimit" != 10 ]193then194echo "INFO: Difflimit is changed to $difflimit (10=0.1s)" | tee geotag.log195fi196197198echo "INFO: using arguments $cmdarg " | tee geotag.log199200jpglistindex=$(( 1 + $SKIPIMG)) #which file to read from jpg list201202203#========================= FUNCTION readexif ======================================================204# get exif data for filename in $jpgname,205# return: $jpgdate 20-12-2010 ,$jpgtime 14:10:20.22 ,$jpgtimems 0.22 (220ms)206function readexif207{208if [[ "$NS" == "true" ]]209then210jpgdatetime=$(exiftool -ee -p '$datetimeoriginal' "$jpgname" -n)211jpgdatetime="$jpgdatetime.50"212else213jpgdatetime=$(exiftool -ee -p '$subsecdatetimeoriginal' "$jpgname" -n)214fi215216217jpgdate=$(echo -n "$jpgdatetime" | head -c10)218jpgdate=$(echo "$jpgdate" | tr : -) #replace : with -219jpgtime=$(echo -n "$jpgdatetime" | tail -c-11)220jpgtimems=$(echo -n "$jpgtime" | tail -c-2)221jpgtimems=$(echo "scale=2; ($jpgtimems /100)" | bc -l)222#echo "DEBUG $jpgname date $jpgdate time $jpgtime "223##read -p "Press any key to continue... " -n1 -s224######browse log until we find CAM message225}226227#========================= FUNCTION readlog ======================================================228# extract needed date from logline string $logline229# return: $logdate 20-12-2010 ,$logtime 14:10:20.22 ,$logtimems 0.22 (220ms)230# return: $lat $lon $alt(m AMSL)231#232###### We Prefer TRIG , then CAM, then fallback to POS233# in log they look alike:234#1970-01-01 01:01:12.55: CAM {TimeUS : 72553489, GPSTime : 0, GPSWeek : 0, Lat : 0.0, Lng : 0.0, Alt : -0.01, RelAlt : -0.01, GPSAlt : 0.0, Roll : 1.4, Pitch : 0.41, Yaw : 82.49}235#1970-01-01 01:01:15.80: TRIG {TimeUS : 75803571, GPSTime : 0, GPSWeek : 0, Lat : 0.0, Lng : 0.0, Alt : -0.01, RelAlt : -0.01, GPSAlt : 0.0, Roll : 1.43, Pitch : 0.43, Yaw : 82.62}236237function readlog238{239logdate=$(echo "$logline"| grep -o '^\S*') #till first space240logtime=$(echo "$logline"| awk -F" " '{print $2}')241logtime=$(echo -n "$logtime" | head -c-1) #remove trailing :242logtimems=$(echo -n "$logtime" | tail -c-2)243logtimems=$(echo "scale=2; ($logtimems /100)" | bc -l)244245if [[ "$logline" == *POS* ]]246then247lat=$(echo "$logline"| grep -o -P '(?<=Lat : ).*(?=, Lng)')248lon=$(echo "$logline"| grep -o -P '(?<=Lng : ).*(?=, Alt)')249alt=$(echo "$logline"| grep -o -P '(?<= Alt : ).*(?=, RelHomeAlt)')250fi251252253if [[ "$logline" == *CAM* ]]254then255lat=$(echo "$logline"| grep -o -P '(?<=Lat : ).*(?=, Lng)')256lon=$(echo "$logline"| grep -o -P '(?<=Lng : ).*(?=, Alt)')257alt=$(echo "$logline"| grep -o -P '(?<=Alt : ).*(?=, RelAlt)')258fi259260261#rol=$(echo "$logline"| grep -o -P '(?<=Roll : ).*(?=, Pitch)')262#pit=$(echo "$logline"| grep -o -P '(?<=Pitch : ).*(?=, Yaw)')263#yaw=$(echo "$logline"| grep -o -P '(?<=Yaw : ).*(?=})')264#echo "$logdate $logtime CAM=$cam Lat=$lat Lng=$lng Alt= $alt"265266}267268#========================= FUNCTION geotag ======================================================269# converts to WGS84 and tags photos with data found in lat,lon,alt.270function geotag271272{273#jpgname="test.JPG"274#lat=69.6041115275#lon=23.2757452276#alt=122.8374277278posWGS84=( $(echo "$lon $lat $alt" | cs2cs +proj=latlong +datum=WGS84)) # returns position as 22d16'32.683"E 69d36'14.801"N 123.837 in {posWGS84[0...2]}279lonWGS84ref=$(echo -n "${posWGS84[0]}" | tail -c-1)280lonWGS84pos=$(echo -n "${posWGS84[0]}" | head -c-1)281latWGS84ref=$(echo -n "${posWGS84[1]}" | tail -c-1)282latWGS84pos=$(echo -n "${posWGS84[1]}" | head -c-1)283284#echo $lonWGS84pos285#echo $lonWGS84ref286#echo $latWGS84pos287#echo $latWGS84ref288#echo "original:"289#echo ${posWGS84[0]}290#echo ${posWGS84[1]}291#echo ${posWGS84[2]}292293if [[ "$WRITE" == "true" ]]294then295exiftool -exif:gpsmapdatum="WGS-84" -exif:gpsaltitude="$alt" -exif:gpsaltituderef="Above Sea Level" -exif:gpslongitude="$lonWGS84pos" -exif:gpslongituderef="$lonWGS84ref" -exif:gpslatitude="$latWGS84pos" -exif:gpslatituderef="$latWGS84ref" "$jpgname" >/dev/null &296fi297let "jpgtagged++"298echo "ALT= "$alt" LON= "$lonWGS84pos" LATref= "$lonWGS84ref" LAT= "$latWGS84pos" LATref= "$latWGS84ref""299}300301302#========================= FUNCTION report ======================================================303function report304{305echo "Report:" | tee -a geotag.log306echo "Found $jpgtot photos" | tee -a geotag.log307echo "Found $camtot CAM log lines" | tee -a geotag.log308echo "Found $trigtot TRIG log lines" | tee -a geotag.log309echo "Time between first photo and log was ""$typical_offset""s" | tee -a geotag.log310311if [[ "$WRITE" == "true" ]]312then313echo "Tagged $jpgtagged photos" | tee -a geotag.log314else315echo "Could have tagged $jpgtagged photos" | tee -a geotag.log316fi317318if [[ "$MODE" != "POS" ]]319then320echo "Detected $jpgmiss missing photos" | tee -a geotag.log321echo "Detected $logmiss missing $MODE messages" | tee -a geotag.log322else323echo "(Unable to detect and report missing pictures and CAM messages in POS mode)" | tee -a geotag.log324fi325if [[ "$jpgnotinlog" -gt 0 ]]326then327echo "FAILED: to tag $jpgnotinlog jpg file(s) where no POS log matched (maybe increase difflimit?)" | tee -a geotag.log328fi329330331if [[ "$DELORG" == "true" ]]332then333echo "INFO: Deleting original .JPG that were cloned by EXIF" | tee -a geotag.log334sleep 1s335rm *.JPG_original336fi337338if [[ "$WRITE" == "true" ]]339then340mv geotag.log geotagwrite.log341fi342343}344345346#========================= FUNCTION load log to memory ======================================================347function loadlogdump348{349echo "INFO: Loading logdump into memory..." | tee -a geotag.log350OLDIFS=$IFS351IFS=$'\012' # \012 is a linefeed352logarray=( $(<logdump) )353IFS=$OLDIFS354logarraysize=${#logarray[@]}355echo "INFO: done, loaded $logarraysize lines." | tee -a geotag.log356}357358#========================= FUNCTION load camdump to memory ======================================================359function loadcamdump360{361echo "INFO: Loading camdump into memory..." | tee -a geotag.log362OLDIFS=$IFS363IFS=$'\012' # \012 is a linefeed364logarray=( $(<camdump) )365IFS=$OLDIFS366logarraysize=${#logarray[@]}367echo "INFO: done, loaded $logarraysize lines." | tee -a geotag.log368}369370371##############################################################################################################372##############################################################################################################373##############################################################################################################374##############################################################################################################375##############################################################################################################376##############################################################################################################377#========================= FUNCTION CAM only loop ======================================================378function posloop379{380echo "INFO: Searching within POS log..." | tee -a geotag.log381loggotpos=0382383384###############get JPG file#########385while [[ "$running" == 1 ]]386do387388if [ "$logmatch" == 1 ]389then #read next picture only if log line accepted390jpgname=$(awk 'NR=="'"$jpglistindex"'"{print;exit}' jpglist)391392if [ "$jpgname" == "" ]393then394echo "END: Last photo processed" | tee -a geotag.log395running=0396report397exit 1398fi399readexif400fi401402###############lookup LOG#########403logtarget=0 #reset, for new search404if [[ "$loglinereverse" -eq 1 || "$camindex" -eq "$camtot" || "$MODE" == "POS" ]]405then406POSONLY="true"407else408POSONLY="false"409fi410411while [ "$logtarget" -eq 0 ]412do413let "loglinenum++"414415#### check if we are out of log messages.416if [[ "$loglinenum" -gt "$logarraysize" ]]417then418echo "ERROR: Log ended at $loglinenum of $logarraysize while looking for $MODE message for filename $jpgname , maybe this photo is not a part of dataset, or in log, ignoring." | tee -a geotag.log419420#read next picture only if log line accepted421jpgname=$(awk 'NR=="'"$jpglistindex"'"{print;exit}' jpglist)422let "loglinenum = loglinenummatched" # revert to last known good position in log - or to START, to mach photos in random order..423let "jpglistindex++" #move on to next424if [ "$jpgname" == "" ]425then426echo "END: Last photo processed" | tee -a geotag.log427running=0428report429exit 1430fi431readexif432fi433434logline=${logarray["$loglinenum"]}435436437if [[ "$logline" == *CAM* ]]438then439logtype="CAM"440let "camindex++"441logtarget=1442readlog443# echo "DEBUG: at $loglinenum $logline"444fi445if [[ "$logline" == *POS* ]] && [[ "$POSONLY" == "true" || "$loglinereverse" -eq 1 ]]446then447loggotpos=1448logtype="POS"449logtarget=1450readlog451#echo "DEBUG: at $loglinenum $logline"452fi453454if [[ "$SKIPCAM" -gt 0 ]] && [[ "$logtarget" -eq 1 ]]455then456let "SKIPCAM--"457logtarget=0458fi459460461462done463464#### check if we are out of suitable log messages.465if [[ "$loglinenum" -gt "$logarraysize" ]]466then467echo "ERROR: Log ended at $loglinenum of $logarraysize while looking for CAM message for filename $jpgname maybe there are too many photos" | tee -a geotag.log468running=0469report470exit 1471fi472473#echo "DEBUG relevant logline found loglinenumber=$loglinenum logline=$logline "474######process log line475476######## Calculate offset477diff=$(( ( $(date -ud "$jpgdate $jpgtime" +'%s') - $(date -ud "$logdate $logtime" +'%s') ) )) #get differance in seconds (integer)478difftot=$(echo "scale=2; ($diff+($jpgtimems - $logtimems))" | bc -l) # return floting point479######## Calculate time since last trigger command480differr=$(( ( $(date -ud "$logdate $logtime" +'%s') - $(date -ud "$logdateprev $logtimeprev" +'%s') ) )) #get differance in seconds (integer)481difftoterr=$(echo "scale=2; ($differr+($logtimems - $logtimemsprev))" | bc -l) # return floting point482difftotoff=$(echo "scale=2; ($difftot - $typical_offset)" | bc -l)483difftoterroff=$(echo "scale=2; ($differr - $typical_offset)" | bc -l) # return floting point484if [ "$typical_offset" == "notset" ]485then486typical_offset=$difftot487echo "INFO: Expected time offset between camera and log is ""$typical_offset""s (positive = camera is ahead)" | tee -a geotag.log488fi489490491492###############compare offset to previous offset to detect skipped photos493494diffeee=$(echo "(($difftot - $typical_offset)*100)" | bc -l | cut -f1 -d"." ) #keep integer495if [[ "$diffeee" -gt "$difflimit" ]] || [[ "$diffeee" -lt -"$difflimit" ]]496497then498if [[ "$MODE" == "POS" ]] #Do fail analysis ONLY in CAM mode499then ##Speed up POS mode500logmatch=0501if [[ "$diffeee" -gt 50 ]] # are we more than 1 sec behind ?502then503let "loglinenum=loglinenum+25"504#echo "DEBUG: > 1 sec behind, jumping ahead"505fi506if [[ "$diffeee" -lt -25 ]] # are we more than 0.5 sec ahead ?507then508let "loglinenum=loglinenum-30"509let "revjumps++"510#echo "DEBUG: > 0.5 sec ahead, jumping back"511512if [[ "$revjumps" -gt 30 ]] ## we have backed up too many times, the image must be invalid for this log !513then514echo "ERROR: Failed to find log time for image $jpgname, it's not in log or does not belong to this dataset.( maybe try higher difflimit ?)" | tee -a geotag.log515let "jpgnotinlog++"516let "jpglistindex++" #move on to next517let "revjumps=0"518logmatch=1 #trigger lookup of next picture519520fi521fi522523##do CAM mode analysis524525fi526#logmatch=1 ###############################################################ACCEPT ANYTHING527#let "jpglistindex=jpglistindex+1" ###############################################################ACCEPT ANYTHING528529else ## PHOTO AND LOG MATCHING530531percent=$(echo "scale=2; (($jpglistindex/$jpgtot)*100)" | bc -l | cut -f1 -d".")532echo "MATCHED: ""$percent""% Done, time diff.: ""$difftotoff""s between $jpgname $jpgdate $jpgtime & $logtype log $loglinenum $logdate $logtime" | tee -a geotag.log533let "revjumps=0"534geotag535logmatch=1536#logmatcgfailinrow=0537let "jpglistindex++"538let "loglinenummatched = loglinenum + 1" # if we need to go back for POS message, go here539#loglinereverse=0540fi #save first image camera vs log offset541542logdateprev=$logdate #for calculation of picture spacing543logtimeprev=$logtime #for calculation of picture spacing544logtimemsprev=$logtimems #for calculation of picture spacing545logtarget=0 #reset so we are looking for next logline next time546547done #running548}549550##### END POS loop ###########################################################################################551##############################################################################################################552##############################################################################################################553##############################################################################################################554##############################################################################################################555##############################################################################################################556557##############################################################################################################558##############################################################################################################559##############################################################################################################560##############################################################################################################561##############################################################################################################562##############################################################################################################563#========================= FUNCTION CAM only loop ======================================================564# In case of missing photo: try next log entry565# in case of missing log entry: do not tag photo566function camloop567{568echo "INFO: Searching for CAM only..." | tee -a geotag.log569loggotpos=0570571572###############get JPG file#########573while [[ "$running" == 1 ]] ; do574if [ "$logmatch" == 1 ]575then #read next picture only if log line accepted576jpgname=$(awk 'NR=="'"$jpglistindex"'"{print;exit}' jpglist)577if [ "$jpgname" == "" ] ; then578echo "END: Last photo processed" | tee -a geotag.log579running=0580report581exit 1582fi583readexif584fi585586###############lookup LOG#########587logtarget=0 #reset, for new search588589while [ "$logtarget" -eq 0 ] ; do590let "loglinenum++"591logline=${logarray["$loglinenum"]}592593if [[ "$logline" == *"$MODE"* ]] ; then594logtype="$MODE"595logtarget=1596readlog597#echo "DEBUG: at $loglinenum $logline"598fi599600#skip CAM lines if needded601if [[ "$MODE" == "CAM" && "$SKIPCAM" -gt 0 ]] && [[ "$logtarget" -eq 1 ]] ; then602let "SKIPCAM--"603echo "INFO: Skipped a CAM log line." | tee -a geotag.log604logtarget=0605fi606607#skip TRIG lines if needded608if [[ "$MODE" == "TRIG" && "$SKIPTRIG" -gt 0 ]] && [[ "$logtarget" -eq 1 ]] ; then609let "SKIPTRIG--"610logtarget=0611fi612613done614615#### check if we are out of suitable log messages.616if [[ "$loglinenum" -gt "$logarraysize" ]] ; then617echo "ERROR: Log ended at $loglinenum of $logarraysize while looking for $MODE message for filename $jpgname maybe there are too many photos" | tee -a geotag.log618running=0619report620exit 1621fi622623######## Calculate offset624diff=$(( ( $(date -ud "$jpgdate $jpgtime" +'%s') - $(date -ud "$logdate $logtime" +'%s') ) )) #get differance in seconds (integer)625difftot=$(echo "scale=2; ($diff+($jpgtimems - $logtimems))" | bc -l) # return floting point626######## Calculate time since last trigger command627differr=$(( ( $(date -ud "$logdate $logtime" +'%s') - $(date -ud "$logdateprev $logtimeprev" +'%s') ) )) #get differance in seconds (integer)628difftoterr=$(echo "scale=2; ($differr+($logtimems - $logtimemsprev))" | bc -l) # return floting point629difftotoff=$(echo "scale=2; ($difftot - $typical_offset)" | bc -l)630difftoterroff=$(echo "scale=2; ($differr - $typical_offset)" | bc -l) # return floting point631if [ "$typical_offset" == "notset" ] ; then632typical_offset=$difftot633echo "INFO: Expected time offset between camera and log is ""$typical_offset""s (positive = camera is ahead)" | tee -a geotag.log634fi635636difflimit=100 # CAM difflimit 1sec variation between command and exif637638639###############compare offset to previous offset to detect skipped photos640diffeee=$(echo "(($difftot - $typical_offset)*100)" | bc -l | cut -f1 -d"." ) #keep integer641if [[ "$diffeee" -gt "$difflimit" ]] || [[ "$diffeee" -lt -"$difflimit" ]]642then ##TOO MUCH DIFFERENCE643logmatch=0644if [[ "$diffeee" -lt -100 ]] ; then # are we more than 1 sec ahead ?645#let "loglinenum=loglinenum-10"646echo "WARNING: Found extra photo for which there is no $MODE event. I am at logline $loglinenum (Details below)"647echo "WARNING: Big Time diff.: ""$difftotoff""s between $jpgname date $jpgtime and $logtype logline $loglinenum $logdate $logtime Time since last $MODE event was ""$difftoterr""s" | tee -a geotag.log648logmatch=1 #make the log-fetcher get next picture649let "loglinenum=loglinenummatched" #make log-fetcher keep the log line for next picture650let "jpglistindex++" #move on to next picture651let "logmiss++" #count missing log items652653fi654655656else ## PHOTO AND LOG MATCHING657658if [[ $logmatch -eq 0 ]] && [[ "$logmatcgfailinrow" -lt 5 ]] ; then659let "jpgmiss++"660echo "ERROR: MISSING PHOTO #$jpgmiss detected, matched current photo with next logged $logtype logline" | tee -a geotag.log661fi662if [[ $logmatch -eq 0 ]] && [[ "$logmatcgfailinrow" -gt 4 ]] ; then663let "logmiss++"664echo "ERROR: MISSING $MODE log entry detected, matched current photo with logged $logtype logline" | tee -a geotag.log665fi666667percent=$(echo "scale=2; (($jpglistindex/$jpgtot)*100)" | bc -l | cut -f1 -d".")668echo "MATCHED: ""$percent""% Done, time diff.: ""$difftotoff""s between $jpgname $jpgdate $jpgtime & $logtype log $loglinenum $logdate $logtime Time since last $MODE command ""$difftoterr""s" | tee -a geotag.log669geotag670logmatch=1671logmatcgfailinrow=0672let "jpglistindex++"673let "loglinenummatched = loglinenum + 1" # if we need to go back for POS message, go here674loglinereverse=0675fi #save first image camera vs log offset676677logdateprev=$logdate #for calculation of picture spacing678logtimeprev=$logtime #for calculation of picture spacing679logtimemsprev=$logtimems #for calculation of picture spacing680logtarget=0 #reset so we are looking for next logline next time681682done #running683}684685##### END CAM only loop ######################################################################################686##############################################################################################################687##############################################################################################################688##############################################################################################################689##############################################################################################################690##############################################################################################################691692693###################################################################### List JPG's694find . -maxdepth 1 -name "*.[Jj][Pp][Gg]" | sort >jpglist695jpgtot=$(wc -l < jpglist)696echo "INFO: Found $jpgtot photos" | tee -a geotag.log697698699700###################################################################### look for logdump, create if needed701if [ -f ./logdump ]; then702echo "INFO: found logdump"703else704binname=$(find . -maxdepth 1 -name "*.[Bb][Ii][Nn]")705if [[ "$binname" == "" ]]; then706echo "ERROR: .BIN log not found, make sure directory contain a .BIN or .bin log or logdump file." | tee -a geotag.log707exit 1708fi709for binname in $(find . -maxdepth 1 -name "*.[Bb][Ii][Nn]"); do710if [[ "$ML" == "true" ]]; then711echo "INFO: adding $binname to logdump..." | tee -a geotag.log712mavlogdump.py --types POS,CAM,TRIG --format standard "$binname" >> logdump713else714if [[ "$logsdone" < 1 ]]; then715echo "INFO: dumping $binname to logdump..." | tee -a geotag.log716mavlogdump.py --types POS,CAM,TRIG --format standard "$binname" > logdump717fi718fi719let "logsdone ++"720done721fi722echo "INFO: done" | tee -a geotag.log723724###################################################################### DUMP camdump725if [ ! -f ./camdump ] && [[ "$MODE" != "POS" ]]; then726echo "INFO: no camdump found, exporting loglines from .bin to camdump..." | tee -a geotag.log727mavlogdump.py --types CAM,TRIG --format standard "$binname" > camdump728echo "INFO: done" | tee -a geotag.log729else730echo "INFO: camdump found" | tee -a geotag.log731fi732733734###################################################################### DUMP exiflog735#if [ ! -f ./exifdump ]; then736# echo "INFO: no exifdump found, exporting exif names and timestamps exifdump..." | tee -a geotag.log737# #mavlogdump.py --types POS,CAM,TRIG --format standard "$binname" > logdump738# echo "INFO: done" | tee -a geotag.log739#else740# echo "INFO: exifdump found" | tee -a geotag.log741#fi742743744###################################################################### Count CAM events745camtot=$(grep CAM logdump | wc -l)746echo "INFO: Found $camtot CAM log lines (camera shutter sensed)" | tee -a geotag.log747748###################################################################### Count TRIG events749trigtot=$(grep TRIG logdump | wc -l)750echo "INFO: Found $trigtot TRIG log lines (commands to shoot)" | tee -a geotag.log751752753754###################################################################### LOAD exifs to memory755#echo "INFO: Loading Photo data into memory..." | tee -a geotag.log756#OLDIFS=$IFS757#IFS=$'\012' # \012 is a linefeed758#logarray=( $(<exifdump) )759#IFS=$OLDIFS760#logarraysize=${#exifarray[@]}761#echo "INFO: done, loaded $exifarraysize lines." | tee -a geotag.log762763764765###################################################################### Are we searching or processing ?766#if [ "$FIND" == "true" ]767#then768# loadcamdump769# camloop770#else771loadlogdump772if [[ "$MODE" == "POS" ]]; then773posloop774else775camloop776fi777#fi778779780781