Merge commit 'f95a912' into cmake
commit
85519c498d
|
|
@ -1,5 +1,7 @@
|
|||
set(files
|
||||
__init__.py
|
||||
alos2App.py
|
||||
alos2burstApp.py
|
||||
dataTileManager.py
|
||||
dem.py
|
||||
demdb.py
|
||||
|
|
@ -22,6 +24,7 @@ set(files
|
|||
upsampleDem.py
|
||||
waterMask.py
|
||||
wbd.py
|
||||
wbd_with_correction.py
|
||||
wbdStitcher.py
|
||||
)
|
||||
|
||||
|
|
|
|||
|
|
@ -78,7 +78,10 @@ listFiles = ['mdx.py',
|
|||
'wbd.py',
|
||||
'downsampleDEM.py',
|
||||
'gdal2isce_xml.py',
|
||||
'scansarApp.py']
|
||||
'alos2App.py',
|
||||
'alos2burstApp.py',
|
||||
'scansarApp.py',
|
||||
'wbd_with_correction.py']
|
||||
# 'isce2he5.py']
|
||||
|
||||
envapplications.Install(install, listFiles)
|
||||
|
|
|
|||
File diff suppressed because it is too large
Load Diff
File diff suppressed because it is too large
Load Diff
|
|
@ -0,0 +1,23 @@
|
|||
#!/usr/bin/env python3
|
||||
|
||||
#
|
||||
# Author: Cunren Liang
|
||||
# Copyright 2020
|
||||
#
|
||||
|
||||
|
||||
import sys
|
||||
import isce
|
||||
from isceobj.Alos2Proc.runDownloadDem import download_wbd
|
||||
|
||||
|
||||
if __name__=="__main__":
|
||||
|
||||
if len(sys.argv) < 5:
|
||||
print("usage: wbd_with_correction.py s n w e")
|
||||
print("where s, n, w, e are latitude, longitude bounds in degrees")
|
||||
sys.exit(0)
|
||||
|
||||
snwe = list(map(float,sys.argv[1:]))
|
||||
|
||||
download_wbd(snwe[0], snwe[1], snwe[2], snwe[3])
|
||||
|
|
@ -0,0 +1,949 @@
|
|||
#
|
||||
# Author: Cunren Liang
|
||||
# Copyright 2015-present, NASA-JPL/Caltech
|
||||
#
|
||||
|
||||
import os
|
||||
import logging
|
||||
import logging.config
|
||||
from iscesys.Component.Component import Component
|
||||
from iscesys.DateTimeUtil.DateTimeUtil import DateTimeUtil as DTU
|
||||
from iscesys.Compatibility import Compatibility
|
||||
|
||||
|
||||
MASTER_DATE = Component.Parameter('masterDate',
|
||||
public_name='master date',
|
||||
default=None,
|
||||
type=str,
|
||||
mandatory=True,
|
||||
doc='master acquistion date')
|
||||
|
||||
SLAVE_DATE = Component.Parameter('slaveDate',
|
||||
public_name='slave date',
|
||||
default=None,
|
||||
type=str,
|
||||
mandatory=True,
|
||||
doc='slave acquistion date')
|
||||
|
||||
MODE_COMBINATION = Component.Parameter('modeCombination',
|
||||
public_name='mode combination',
|
||||
default=None,
|
||||
type=int,
|
||||
mandatory=True,
|
||||
doc='mode combination')
|
||||
|
||||
MASTER_FRAMES = Component.Parameter('masterFrames',
|
||||
public_name = 'master frames',
|
||||
default = None,
|
||||
type=str,
|
||||
container=list,
|
||||
mandatory=False,
|
||||
doc = 'master frames to process')
|
||||
|
||||
SLAVE_FRAMES = Component.Parameter('slaveFrames',
|
||||
public_name = 'slave frames',
|
||||
default = None,
|
||||
type=str,
|
||||
container=list,
|
||||
mandatory=False,
|
||||
doc = 'slave frames to process')
|
||||
|
||||
STARTING_SWATH = Component.Parameter('startingSwath',
|
||||
public_name='starting swath',
|
||||
default=1,
|
||||
type=int,
|
||||
mandatory=False,
|
||||
doc="starting swath to process")
|
||||
|
||||
ENDING_SWATH = Component.Parameter('endingSwath',
|
||||
public_name='ending swath',
|
||||
default=5,
|
||||
type=int,
|
||||
mandatory=False,
|
||||
doc="ending swath to process")
|
||||
|
||||
BURST_UNSYNCHRONIZED_TIME = Component.Parameter('burstUnsynchronizedTime',
|
||||
public_name = 'burst unsynchronized time',
|
||||
default = None,
|
||||
type = float,
|
||||
mandatory = False,
|
||||
doc = 'burst unsynchronized time in second')
|
||||
|
||||
BURST_SYNCHRONIZATION = Component.Parameter('burstSynchronization',
|
||||
public_name = 'burst synchronization',
|
||||
default = None,
|
||||
type = float,
|
||||
mandatory = False,
|
||||
doc = 'average burst synchronization of all swaths and frames in percentage')
|
||||
|
||||
SWATH_RANGE_OFFSET_GEOMETRICAL_MASTER = Component.Parameter('swathRangeOffsetGeometricalMaster',
|
||||
public_name = 'swath range offset from geometry master',
|
||||
default = None,
|
||||
type = float,
|
||||
mandatory = True,
|
||||
container = list,
|
||||
doc = 'swath range offset from geometry master')
|
||||
|
||||
SWATH_AZIMUTH_OFFSET_GEOMETRICAL_MASTER = Component.Parameter('swathAzimuthOffsetGeometricalMaster',
|
||||
public_name = 'swath azimuth offset from geometry master',
|
||||
default = None,
|
||||
type = float,
|
||||
mandatory = True,
|
||||
container = list,
|
||||
doc = 'swath azimuth offset from geometry master')
|
||||
|
||||
SWATH_RANGE_OFFSET_MATCHING_MASTER = Component.Parameter('swathRangeOffsetMatchingMaster',
|
||||
public_name = 'swath range offset from matching master',
|
||||
default = None,
|
||||
type = float,
|
||||
mandatory = True,
|
||||
container = list,
|
||||
doc = 'swath range offset from matching master')
|
||||
|
||||
SWATH_AZIMUTH_OFFSET_MATCHING_MASTER = Component.Parameter('swathAzimuthOffsetMatchingMaster',
|
||||
public_name = 'swath azimuth offset from matching master',
|
||||
default = None,
|
||||
type = float,
|
||||
mandatory = True,
|
||||
container = list,
|
||||
doc = 'swath azimuth offset from matching master')
|
||||
|
||||
SWATH_RANGE_OFFSET_GEOMETRICAL_SLAVE = Component.Parameter('swathRangeOffsetGeometricalSlave',
|
||||
public_name = 'swath range offset from geometry slave',
|
||||
default = None,
|
||||
type = float,
|
||||
mandatory = True,
|
||||
container = list,
|
||||
doc = 'swath range offset from geometry slave')
|
||||
|
||||
SWATH_AZIMUTH_OFFSET_GEOMETRICAL_SLAVE = Component.Parameter('swathAzimuthOffsetGeometricalSlave',
|
||||
public_name = 'swath azimuth offset from geometry slave',
|
||||
default = None,
|
||||
type = float,
|
||||
mandatory = True,
|
||||
container = list,
|
||||
doc = 'swath azimuth offset from geometry slave')
|
||||
|
||||
SWATH_RANGE_OFFSET_MATCHING_SLAVE = Component.Parameter('swathRangeOffsetMatchingSlave',
|
||||
public_name = 'swath range offset from matching slave',
|
||||
default = None,
|
||||
type = float,
|
||||
mandatory = True,
|
||||
container = list,
|
||||
doc = 'swath range offset from matching slave')
|
||||
|
||||
SWATH_AZIMUTH_OFFSET_MATCHING_SLAVE = Component.Parameter('swathAzimuthOffsetMatchingSlave',
|
||||
public_name = 'swath azimuth offset from matching slave',
|
||||
default = None,
|
||||
type = float,
|
||||
mandatory = True,
|
||||
container = list,
|
||||
doc = 'swath azimuth offset from matching slave')
|
||||
|
||||
|
||||
|
||||
FRAME_RANGE_OFFSET_GEOMETRICAL_MASTER = Component.Parameter('frameRangeOffsetGeometricalMaster',
|
||||
public_name = 'frame range offset from geometry master',
|
||||
default = None,
|
||||
type = float,
|
||||
mandatory = True,
|
||||
container = list,
|
||||
doc = 'frame range offset from geometry master')
|
||||
|
||||
FRAME_AZIMUTH_OFFSET_GEOMETRICAL_MASTER = Component.Parameter('frameAzimuthOffsetGeometricalMaster',
|
||||
public_name = 'frame azimuth offset from geometry master',
|
||||
default = None,
|
||||
type = float,
|
||||
mandatory = True,
|
||||
container = list,
|
||||
doc = 'frame azimuth offset from geometry master')
|
||||
|
||||
FRAME_RANGE_OFFSET_MATCHING_MASTER = Component.Parameter('frameRangeOffsetMatchingMaster',
|
||||
public_name = 'frame range offset from matching master',
|
||||
default = None,
|
||||
type = float,
|
||||
mandatory = True,
|
||||
container = list,
|
||||
doc = 'frame range offset from matching master')
|
||||
|
||||
FRAME_AZIMUTH_OFFSET_MATCHING_MASTER = Component.Parameter('frameAzimuthOffsetMatchingMaster',
|
||||
public_name = 'frame azimuth offset from matching master',
|
||||
default = None,
|
||||
type = float,
|
||||
mandatory = True,
|
||||
container = list,
|
||||
doc = 'frame azimuth offset from matching master')
|
||||
|
||||
FRAME_RANGE_OFFSET_GEOMETRICAL_SLAVE = Component.Parameter('frameRangeOffsetGeometricalSlave',
|
||||
public_name = 'frame range offset from geometry slave',
|
||||
default = None,
|
||||
type = float,
|
||||
mandatory = True,
|
||||
container = list,
|
||||
doc = 'frame range offset from geometry slave')
|
||||
|
||||
FRAME_AZIMUTH_OFFSET_GEOMETRICAL_SLAVE = Component.Parameter('frameAzimuthOffsetGeometricalSlave',
|
||||
public_name = 'frame azimuth offset from geometry slave',
|
||||
default = None,
|
||||
type = float,
|
||||
mandatory = True,
|
||||
container = list,
|
||||
doc = 'frame azimuth offset from geometry slave')
|
||||
|
||||
FRAME_RANGE_OFFSET_MATCHING_SLAVE = Component.Parameter('frameRangeOffsetMatchingSlave',
|
||||
public_name = 'frame range offset from matching slave',
|
||||
default = None,
|
||||
type = float,
|
||||
mandatory = True,
|
||||
container = list,
|
||||
doc = 'frame range offset from matching slave')
|
||||
|
||||
FRAME_AZIMUTH_OFFSET_MATCHING_SLAVE = Component.Parameter('frameAzimuthOffsetMatchingSlave',
|
||||
public_name = 'frame azimuth offset from matching slave',
|
||||
default = None,
|
||||
type = float,
|
||||
mandatory = True,
|
||||
container = list,
|
||||
doc = 'frame azimuth offset from matching slave')
|
||||
|
||||
NUMBER_RANGE_LOOKS1 = Component.Parameter('numberRangeLooks1',
|
||||
public_name='number of range looks 1',
|
||||
default=None,
|
||||
type=int,
|
||||
mandatory=False,
|
||||
doc="number of range looks when forming interferogram")
|
||||
|
||||
NUMBER_AZIMUTH_LOOKS1 = Component.Parameter('numberAzimuthLooks1',
|
||||
public_name='number of azimuth looks 1',
|
||||
default=None,
|
||||
type=int,
|
||||
mandatory=False,
|
||||
doc="number of azimuth looks when forming interferogram")
|
||||
|
||||
NUMBER_RANGE_LOOKS2 = Component.Parameter('numberRangeLooks2',
|
||||
public_name='number of range looks 2',
|
||||
default=None,
|
||||
type=int,
|
||||
mandatory=False,
|
||||
doc="number of range looks for further multiple looking")
|
||||
|
||||
NUMBER_AZIMUTH_LOOKS2 = Component.Parameter('numberAzimuthLooks2',
|
||||
public_name='number of azimuth looks 2',
|
||||
default=None,
|
||||
type=int,
|
||||
mandatory=False,
|
||||
doc="number of azimuth looks for further multiple looking")
|
||||
|
||||
NUMBER_RANGE_LOOKS_SIM = Component.Parameter('numberRangeLooksSim',
|
||||
public_name='number of range looks sim',
|
||||
default=None,
|
||||
type=int,
|
||||
mandatory=False,
|
||||
doc="number of range looks when simulating radar image")
|
||||
|
||||
NUMBER_AZIMUTH_LOOKS_SIM = Component.Parameter('numberAzimuthLooksSim',
|
||||
public_name='number of azimuth looks sim',
|
||||
default=None,
|
||||
type=int,
|
||||
mandatory=False,
|
||||
doc="number of azimuth looks when simulating radar image")
|
||||
|
||||
NUMBER_RANGE_LOOKS_ION = Component.Parameter('numberRangeLooksIon',
|
||||
public_name='number of range looks ion',
|
||||
default=None,
|
||||
type=int,
|
||||
mandatory=False,
|
||||
doc="number of range looks for ionospheric correction")
|
||||
|
||||
NUMBER_AZIMUTH_LOOKS_ION = Component.Parameter('numberAzimuthLooksIon',
|
||||
public_name='number of azimuth looks ion',
|
||||
default=None,
|
||||
type=int,
|
||||
mandatory=False,
|
||||
doc="number of azimuth looks for ionospheric correction")
|
||||
|
||||
SUBBAND_RADAR_WAVLENGTH = Component.Parameter('subbandRadarWavelength',
|
||||
public_name='lower and upper radar wavelength for ionosphere correction',
|
||||
default=None,
|
||||
type=float,
|
||||
mandatory=False,
|
||||
container = list,
|
||||
doc="lower and upper radar wavelength for ionosphere correction")
|
||||
|
||||
RADAR_DEM_AFFINE_TRANSFORM = Component.Parameter('radarDemAffineTransform',
|
||||
public_name = 'radar dem affine transform parameters',
|
||||
default = None,
|
||||
type = float,
|
||||
mandatory = True,
|
||||
container = list,
|
||||
doc = 'radar dem affine transform parameters')
|
||||
|
||||
|
||||
MASTER_SLC = Component.Parameter('masterSlc',
|
||||
public_name='master slc',
|
||||
default=None,
|
||||
type=str,
|
||||
mandatory=False,
|
||||
doc='master slc file')
|
||||
|
||||
SLAVE_SLC = Component.Parameter('slaveSlc',
|
||||
public_name='slave slc',
|
||||
default=None,
|
||||
type=str,
|
||||
mandatory=False,
|
||||
doc='slave slc file')
|
||||
|
||||
MASTER_SWATH_OFFSET = Component.Parameter('masterSwathOffset',
|
||||
public_name='master swath offset',
|
||||
default=None,
|
||||
type=str,
|
||||
mandatory=False,
|
||||
doc='master swath offset file')
|
||||
|
||||
SLAVE_SWATH_OFFSET = Component.Parameter('slaveSwathOffset',
|
||||
public_name='slave swath offset',
|
||||
default=None,
|
||||
type=str,
|
||||
mandatory=False,
|
||||
doc='slave swath offset file')
|
||||
|
||||
MASTER_FRAME_OFFSET = Component.Parameter('masterFrameOffset',
|
||||
public_name='master frame offset',
|
||||
default=None,
|
||||
type=str,
|
||||
mandatory=False,
|
||||
doc='master frame offset file')
|
||||
|
||||
SLAVE_FRAME_OFFSET = Component.Parameter('slaveFrameOffset',
|
||||
public_name='slave frame offset',
|
||||
default=None,
|
||||
type=str,
|
||||
mandatory=False,
|
||||
doc='slave frame offset file')
|
||||
|
||||
MASTER_FRAME_PARAMETER = Component.Parameter('masterFrameParameter',
|
||||
public_name='master frame parameter',
|
||||
default=None,
|
||||
type=str,
|
||||
mandatory=False,
|
||||
doc='master frame parameter file')
|
||||
|
||||
SLAVE_FRAME_PARAMETER = Component.Parameter('slaveFrameParameter',
|
||||
public_name='slave frame parameter',
|
||||
default=None,
|
||||
type=str,
|
||||
mandatory=False,
|
||||
doc='slave frame parameter file')
|
||||
|
||||
MASTER_TRACK_PARAMETER = Component.Parameter('masterTrackParameter',
|
||||
public_name='master track parameter',
|
||||
default=None,
|
||||
type=str,
|
||||
mandatory=False,
|
||||
doc='master track parameter file')
|
||||
|
||||
SLAVE_TRACK_PARAMETER = Component.Parameter('slaveTrackParameter',
|
||||
public_name='slave track parameter',
|
||||
default=None,
|
||||
type=str,
|
||||
mandatory=False,
|
||||
doc='slave track parameter file')
|
||||
|
||||
DEM = Component.Parameter('dem',
|
||||
public_name='dem for coregistration',
|
||||
default=None,
|
||||
type=str,
|
||||
mandatory=False,
|
||||
doc='dem for coregistration file')
|
||||
|
||||
DEM_GEO = Component.Parameter('demGeo',
|
||||
public_name='dem for geocoding',
|
||||
default=None,
|
||||
type=str,
|
||||
mandatory=False,
|
||||
doc='dem for geocoding file')
|
||||
|
||||
WBD = Component.Parameter('wbd',
|
||||
public_name='water body',
|
||||
default=None,
|
||||
type=str,
|
||||
mandatory=False,
|
||||
doc='water body file')
|
||||
|
||||
WBD_OUT = Component.Parameter('wbdOut',
|
||||
public_name='output water body',
|
||||
default=None,
|
||||
type=str,
|
||||
mandatory=False,
|
||||
doc='output water body file')
|
||||
|
||||
INTERFEROGRAM = Component.Parameter('interferogram',
|
||||
public_name='interferogram',
|
||||
default=None,
|
||||
type=str,
|
||||
mandatory=False,
|
||||
doc='interferogram file')
|
||||
|
||||
AMPLITUDE = Component.Parameter('amplitude',
|
||||
public_name='amplitude',
|
||||
default=None,
|
||||
type=str,
|
||||
mandatory=False,
|
||||
doc='amplitude file')
|
||||
|
||||
DIFFERENTIAL_INTERFEROGRAM = Component.Parameter('differentialInterferogram',
|
||||
public_name='differential interferogram',
|
||||
default=None,
|
||||
type=str,
|
||||
mandatory=False,
|
||||
doc='differential interferogram file')
|
||||
|
||||
MULTILOOK_DIFFERENTIAL_INTERFEROGRAM = Component.Parameter('multilookDifferentialInterferogram',
|
||||
public_name='multilook differential interferogram',
|
||||
default=None,
|
||||
type=str,
|
||||
mandatory=False,
|
||||
doc='multilook differential interferogram file')
|
||||
|
||||
MULTILOOK_DIFFERENTIAL_INTERFEROGRAM_ORIGINAL = Component.Parameter('multilookDifferentialInterferogramOriginal',
|
||||
public_name='original multilook differential interferogram',
|
||||
default=None,
|
||||
type=str,
|
||||
mandatory=False,
|
||||
doc='original multilook differential interferogram file')
|
||||
|
||||
MULTILOOK_AMPLITUDE = Component.Parameter('multilookAmplitude',
|
||||
public_name='multilook amplitude',
|
||||
default=None,
|
||||
type=str,
|
||||
mandatory=False,
|
||||
doc='multilook amplitude file')
|
||||
|
||||
MULTILOOK_COHERENCE = Component.Parameter('multilookCoherence',
|
||||
public_name='multilook coherence',
|
||||
default=None,
|
||||
type=str,
|
||||
mandatory=False,
|
||||
doc='multilook coherence file')
|
||||
|
||||
MULTILOOK_PHSIG = Component.Parameter('multilookPhsig',
|
||||
public_name='multilook phase sigma',
|
||||
default=None,
|
||||
type=str,
|
||||
mandatory=False,
|
||||
doc='multilook phase sigma file')
|
||||
|
||||
FILTERED_INTERFEROGRAM = Component.Parameter('filteredInterferogram',
|
||||
public_name='filtered interferogram',
|
||||
default=None,
|
||||
type=str,
|
||||
mandatory=False,
|
||||
doc='filtered interferogram file')
|
||||
|
||||
UNWRAPPED_INTERFEROGRAM = Component.Parameter('unwrappedInterferogram',
|
||||
public_name='unwrapped interferogram',
|
||||
default=None,
|
||||
type=str,
|
||||
mandatory=False,
|
||||
doc='unwrapped interferogram file')
|
||||
|
||||
UNWRAPPED_MASKED_INTERFEROGRAM = Component.Parameter('unwrappedMaskedInterferogram',
|
||||
public_name='unwrapped masked interferogram',
|
||||
default=None,
|
||||
type=str,
|
||||
mandatory=False,
|
||||
doc='unwrapped masked interferogram file')
|
||||
|
||||
LATITUDE = Component.Parameter('latitude',
|
||||
public_name='latitude',
|
||||
default=None,
|
||||
type=str,
|
||||
mandatory=False,
|
||||
doc='latitude file')
|
||||
|
||||
LONGITUDE = Component.Parameter('longitude',
|
||||
public_name='longitude',
|
||||
default=None,
|
||||
type=str,
|
||||
mandatory=False,
|
||||
doc='longitude file')
|
||||
|
||||
HEIGHT = Component.Parameter('height',
|
||||
public_name='height',
|
||||
default=None,
|
||||
type=str,
|
||||
mandatory=False,
|
||||
doc='height file')
|
||||
|
||||
LOS = Component.Parameter('los',
|
||||
public_name='los',
|
||||
default=None,
|
||||
type=str,
|
||||
mandatory=False,
|
||||
doc='los file')
|
||||
|
||||
SIM = Component.Parameter('sim',
|
||||
public_name='sim',
|
||||
default=None,
|
||||
type=str,
|
||||
mandatory=False,
|
||||
doc='sim file')
|
||||
|
||||
MSK = Component.Parameter('msk',
|
||||
public_name='msk',
|
||||
default=None,
|
||||
type=str,
|
||||
mandatory=False,
|
||||
doc='msk file')
|
||||
|
||||
RANGE_OFFSET = Component.Parameter('rangeOffset',
|
||||
public_name='range offset',
|
||||
default=None,
|
||||
type=str,
|
||||
mandatory=False,
|
||||
doc='range offset file')
|
||||
|
||||
AZIMUTH_OFFSET = Component.Parameter('azimuthOffset',
|
||||
public_name='azimuth offset',
|
||||
default=None,
|
||||
type=str,
|
||||
mandatory=False,
|
||||
doc='azimuth offset file')
|
||||
|
||||
|
||||
MULTILOOK_LOS = Component.Parameter('multilookLos',
|
||||
public_name='multilook los',
|
||||
default=None,
|
||||
type=str,
|
||||
mandatory=False,
|
||||
doc='multilook los file')
|
||||
|
||||
MULTILOOK_MSK = Component.Parameter('multilookMsk',
|
||||
public_name='multilook msk',
|
||||
default=None,
|
||||
type=str,
|
||||
mandatory=False,
|
||||
doc='multilook msk file')
|
||||
|
||||
MULTILOOK_WBD_OUT = Component.Parameter('multilookWbdOut',
|
||||
public_name='multilook wbdOut',
|
||||
default=None,
|
||||
type=str,
|
||||
mandatory=False,
|
||||
doc='multilook output water body file')
|
||||
|
||||
MULTILOOK_LATITUDE = Component.Parameter('multilookLatitude',
|
||||
public_name='multilook latitude',
|
||||
default=None,
|
||||
type=str,
|
||||
mandatory=False,
|
||||
doc='multilook latitude file')
|
||||
|
||||
MULTILOOK_LONGITUDE = Component.Parameter('multilookLongitude',
|
||||
public_name='multilook longitude',
|
||||
default=None,
|
||||
type=str,
|
||||
mandatory=False,
|
||||
doc='multilook longitude file')
|
||||
|
||||
MULTILOOK_HEIGHT = Component.Parameter('multilookHeight',
|
||||
public_name='multilook height',
|
||||
default=None,
|
||||
type=str,
|
||||
mandatory=False,
|
||||
doc='multilook height file')
|
||||
|
||||
MULTILOOK_ION = Component.Parameter('multilookIon',
|
||||
public_name='multilook ionospheric phase',
|
||||
default=None,
|
||||
type=str,
|
||||
mandatory=False,
|
||||
doc='multilook ionospheric phase file')
|
||||
|
||||
RECT_RANGE_OFFSET = Component.Parameter('rectRangeOffset',
|
||||
public_name='rectified range offset',
|
||||
default=None,
|
||||
type=str,
|
||||
mandatory=False,
|
||||
doc='rectified range offset file')
|
||||
|
||||
GEO_INTERFEROGRAM = Component.Parameter('geoInterferogram',
|
||||
public_name='geocoded interferogram',
|
||||
default=None,
|
||||
type=str,
|
||||
mandatory=False,
|
||||
doc='geocoded interferogram file')
|
||||
|
||||
GEO_MASKED_INTERFEROGRAM = Component.Parameter('geoMaskedInterferogram',
|
||||
public_name='geocoded masked interferogram',
|
||||
default=None,
|
||||
type=str,
|
||||
mandatory=False,
|
||||
doc='geocoded masked interferogram file')
|
||||
|
||||
GEO_COHERENCE = Component.Parameter('geoCoherence',
|
||||
public_name='geocoded coherence',
|
||||
default=None,
|
||||
type=str,
|
||||
mandatory=False,
|
||||
doc='geocoded coherence file')
|
||||
|
||||
GEO_LOS = Component.Parameter('geoLos',
|
||||
public_name='geocoded los',
|
||||
default=None,
|
||||
type=str,
|
||||
mandatory=False,
|
||||
doc='geocoded los file')
|
||||
|
||||
GEO_ION = Component.Parameter('geoIon',
|
||||
public_name='geocoded ionospheric phase',
|
||||
default=None,
|
||||
type=str,
|
||||
mandatory=False,
|
||||
doc='geocoded ionospheric phase file')
|
||||
###################################################################
|
||||
|
||||
#for dense offset
|
||||
OFFSET_IMAGE_TOPOFFSET = Component.Parameter('offsetImageTopoffset',
|
||||
public_name='offset image top offset',
|
||||
default=None,
|
||||
type=int,
|
||||
mandatory=False,
|
||||
doc="offset image top offset in samples")
|
||||
|
||||
OFFSET_IMAGE_LEFTOFFSET = Component.Parameter('offsetImageLeftoffset',
|
||||
public_name='offset image left offset',
|
||||
default=None,
|
||||
type=int,
|
||||
mandatory=False,
|
||||
doc="offset image left offset in samples")
|
||||
|
||||
SLAVE_SLC_COREGISTERED = Component.Parameter('slaveSlcCoregistered',
|
||||
public_name='coregistered slave slc',
|
||||
default=None,
|
||||
type=str,
|
||||
mandatory=False,
|
||||
doc='coregistered slave slc file')
|
||||
|
||||
DENSE_OFFSET = Component.Parameter('denseOffset',
|
||||
public_name='dense offset',
|
||||
default=None,
|
||||
type=str,
|
||||
mandatory=False,
|
||||
doc='dense offset file')
|
||||
|
||||
DENSE_OFFSET_SNR = Component.Parameter('denseOffsetSnr',
|
||||
public_name='dense offset snr',
|
||||
default=None,
|
||||
type=str,
|
||||
mandatory=False,
|
||||
doc='dense offset snr file')
|
||||
|
||||
DENSE_OFFSET_COV = Component.Parameter('denseOffsetCov',
|
||||
public_name='dense offset covariance',
|
||||
default=None,
|
||||
type=str,
|
||||
mandatory=False,
|
||||
doc='dense offset covariance file')
|
||||
|
||||
DENSE_OFFSET_FILT = Component.Parameter('denseOffsetFilt',
|
||||
public_name='filtered dense offset',
|
||||
default=None,
|
||||
type=str,
|
||||
mandatory=False,
|
||||
doc='filtered dense offset file')
|
||||
|
||||
GEO_DENSE_OFFSET = Component.Parameter('GeoDenseOffset',
|
||||
public_name='geocoded dense offset',
|
||||
default=None,
|
||||
type=str,
|
||||
mandatory=False,
|
||||
doc='geocoded dense offset file')
|
||||
|
||||
GEO_DENSE_OFFSET_SNR = Component.Parameter('GeoDenseOffsetSnr',
|
||||
public_name='geocoded dense offset snr',
|
||||
default=None,
|
||||
type=str,
|
||||
mandatory=False,
|
||||
doc='geocoded dense offset snr file')
|
||||
|
||||
GEO_DENSE_OFFSET_FILT = Component.Parameter('GeoDenseOffsetFilt',
|
||||
public_name='geocoded dense offset with filtering',
|
||||
default=None,
|
||||
type=str,
|
||||
mandatory=False,
|
||||
doc='geocoded dense offset with filtering')
|
||||
###################################################################
|
||||
|
||||
class Alos2Proc(Component):
|
||||
"""
|
||||
This class holds the properties, along with methods (setters and getters)
|
||||
to modify and return their values.
|
||||
"""
|
||||
|
||||
parameter_list = (MASTER_DATE,
|
||||
SLAVE_DATE,
|
||||
MODE_COMBINATION,
|
||||
MASTER_FRAMES,
|
||||
SLAVE_FRAMES,
|
||||
STARTING_SWATH,
|
||||
ENDING_SWATH,
|
||||
BURST_UNSYNCHRONIZED_TIME,
|
||||
BURST_SYNCHRONIZATION,
|
||||
SWATH_RANGE_OFFSET_GEOMETRICAL_MASTER,
|
||||
SWATH_AZIMUTH_OFFSET_GEOMETRICAL_MASTER,
|
||||
SWATH_RANGE_OFFSET_MATCHING_MASTER,
|
||||
SWATH_AZIMUTH_OFFSET_MATCHING_MASTER,
|
||||
SWATH_RANGE_OFFSET_GEOMETRICAL_SLAVE,
|
||||
SWATH_AZIMUTH_OFFSET_GEOMETRICAL_SLAVE,
|
||||
SWATH_RANGE_OFFSET_MATCHING_SLAVE,
|
||||
SWATH_AZIMUTH_OFFSET_MATCHING_SLAVE,
|
||||
FRAME_RANGE_OFFSET_GEOMETRICAL_MASTER,
|
||||
FRAME_AZIMUTH_OFFSET_GEOMETRICAL_MASTER,
|
||||
FRAME_RANGE_OFFSET_MATCHING_MASTER,
|
||||
FRAME_AZIMUTH_OFFSET_MATCHING_MASTER,
|
||||
FRAME_RANGE_OFFSET_GEOMETRICAL_SLAVE,
|
||||
FRAME_AZIMUTH_OFFSET_GEOMETRICAL_SLAVE,
|
||||
FRAME_RANGE_OFFSET_MATCHING_SLAVE,
|
||||
FRAME_AZIMUTH_OFFSET_MATCHING_SLAVE,
|
||||
NUMBER_RANGE_LOOKS1,
|
||||
NUMBER_AZIMUTH_LOOKS1,
|
||||
NUMBER_RANGE_LOOKS2,
|
||||
NUMBER_AZIMUTH_LOOKS2,
|
||||
NUMBER_RANGE_LOOKS_SIM,
|
||||
NUMBER_AZIMUTH_LOOKS_SIM,
|
||||
NUMBER_RANGE_LOOKS_ION,
|
||||
NUMBER_AZIMUTH_LOOKS_ION,
|
||||
SUBBAND_RADAR_WAVLENGTH,
|
||||
RADAR_DEM_AFFINE_TRANSFORM,
|
||||
MASTER_SLC,
|
||||
SLAVE_SLC,
|
||||
MASTER_SWATH_OFFSET,
|
||||
SLAVE_SWATH_OFFSET,
|
||||
MASTER_FRAME_OFFSET,
|
||||
SLAVE_FRAME_OFFSET,
|
||||
MASTER_FRAME_PARAMETER,
|
||||
SLAVE_FRAME_PARAMETER,
|
||||
MASTER_TRACK_PARAMETER,
|
||||
SLAVE_TRACK_PARAMETER,
|
||||
DEM,
|
||||
DEM_GEO,
|
||||
WBD,
|
||||
WBD_OUT,
|
||||
INTERFEROGRAM,
|
||||
AMPLITUDE,
|
||||
DIFFERENTIAL_INTERFEROGRAM,
|
||||
MULTILOOK_DIFFERENTIAL_INTERFEROGRAM,
|
||||
MULTILOOK_DIFFERENTIAL_INTERFEROGRAM_ORIGINAL,
|
||||
MULTILOOK_AMPLITUDE,
|
||||
MULTILOOK_COHERENCE,
|
||||
MULTILOOK_PHSIG,
|
||||
FILTERED_INTERFEROGRAM,
|
||||
UNWRAPPED_INTERFEROGRAM,
|
||||
UNWRAPPED_MASKED_INTERFEROGRAM,
|
||||
LATITUDE,
|
||||
LONGITUDE,
|
||||
HEIGHT,
|
||||
LOS,
|
||||
SIM,
|
||||
MSK,
|
||||
RANGE_OFFSET,
|
||||
AZIMUTH_OFFSET,
|
||||
MULTILOOK_LOS,
|
||||
MULTILOOK_MSK,
|
||||
MULTILOOK_WBD_OUT,
|
||||
MULTILOOK_LATITUDE,
|
||||
MULTILOOK_LONGITUDE,
|
||||
MULTILOOK_HEIGHT,
|
||||
MULTILOOK_ION,
|
||||
RECT_RANGE_OFFSET,
|
||||
GEO_INTERFEROGRAM,
|
||||
GEO_MASKED_INTERFEROGRAM,
|
||||
GEO_COHERENCE,
|
||||
GEO_LOS,
|
||||
GEO_ION,
|
||||
OFFSET_IMAGE_TOPOFFSET,
|
||||
OFFSET_IMAGE_LEFTOFFSET,
|
||||
SLAVE_SLC_COREGISTERED,
|
||||
DENSE_OFFSET,
|
||||
DENSE_OFFSET_SNR,
|
||||
DENSE_OFFSET_COV,
|
||||
DENSE_OFFSET_FILT,
|
||||
GEO_DENSE_OFFSET,
|
||||
GEO_DENSE_OFFSET_SNR,
|
||||
GEO_DENSE_OFFSET_FILT)
|
||||
|
||||
facility_list = ()
|
||||
|
||||
|
||||
family='alos2context'
|
||||
|
||||
def __init__(self, name='', procDoc=None):
|
||||
#self.updatePrivate()
|
||||
|
||||
super().__init__(family=self.__class__.family, name=name)
|
||||
self.procDoc = procDoc
|
||||
return None
|
||||
|
||||
def setFilename(self, masterDate, slaveDate, nrlks1, nalks1, nrlks2, nalks2):
|
||||
|
||||
# if masterDate == None:
|
||||
# masterDate = self.masterDate
|
||||
# if slaveDate == None:
|
||||
# slaveDate = self.slaveDate
|
||||
# if nrlks1 == None:
|
||||
# nrlks1 = self.numberRangeLooks1
|
||||
# if nalks1 == None:
|
||||
# nalks1 = self.numberAzimuthLooks1
|
||||
# if nrlks2 == None:
|
||||
# nrlks2 = self.numberRangeLooks2
|
||||
# if nalks2 == None:
|
||||
# nalks2 = self.numberAzimuthLooks2
|
||||
|
||||
ms = masterDate + '-' + slaveDate
|
||||
ml1 = '_{}rlks_{}alks'.format(nrlks1, nalks1)
|
||||
ml2 = '_{}rlks_{}alks'.format(nrlks1*nrlks2, nalks1*nalks2)
|
||||
|
||||
self.masterSlc = masterDate + '.slc'
|
||||
self.slaveSlc = slaveDate + '.slc'
|
||||
self.masterSwathOffset = 'swath_offset_' + masterDate + '.txt'
|
||||
self.slaveSwathOffset = 'swath_offset_' + slaveDate + '.txt'
|
||||
self.masterFrameOffset = 'frame_offset_' + masterDate + '.txt'
|
||||
self.slaveFrameOffset = 'frame_offset_' + slaveDate + '.txt'
|
||||
self.masterFrameParameter = masterDate + '.frame.xml'
|
||||
self.slaveFrameParameter = slaveDate + '.frame.xml'
|
||||
self.masterTrackParameter = masterDate + '.track.xml'
|
||||
self.slaveTrackParameter = slaveDate + '.track.xml'
|
||||
#self.dem =
|
||||
#self.demGeo =
|
||||
#self.wbd =
|
||||
self.interferogram = ms + ml1 + '.int'
|
||||
self.amplitude = ms + ml1 + '.amp'
|
||||
self.differentialInterferogram = 'diff_' + ms + ml1 + '.int'
|
||||
self.multilookDifferentialInterferogram = 'diff_' + ms + ml2 + '.int'
|
||||
self.multilookDifferentialInterferogramOriginal = 'diff_' + ms + ml2 + '_ori.int'
|
||||
self.multilookAmplitude = ms + ml2 + '.amp'
|
||||
self.multilookCoherence = ms + ml2 + '.cor'
|
||||
self.multilookPhsig = ms + ml2 + '.phsig'
|
||||
self.filteredInterferogram = 'filt_' + ms + ml2 + '.int'
|
||||
self.unwrappedInterferogram = 'filt_' + ms + ml2 + '.unw'
|
||||
self.unwrappedMaskedInterferogram = 'filt_' + ms + ml2 + '_msk.unw'
|
||||
self.latitude = ms + ml1 + '.lat'
|
||||
self.longitude = ms + ml1 + '.lon'
|
||||
self.height = ms + ml1 + '.hgt'
|
||||
self.los = ms + ml1 + '.los'
|
||||
self.sim = ms + ml1 + '.sim'
|
||||
self.msk = ms + ml1 + '.msk'
|
||||
self.wbdOut = ms + ml1 + '.wbd'
|
||||
self.rangeOffset = ms + ml1 + '_rg.off'
|
||||
self.azimuthOffset = ms + ml1 + '_az.off'
|
||||
self.multilookLos = ms + ml2 + '.los'
|
||||
self.multilookWbdOut = ms + ml2 + '.wbd'
|
||||
self.multilookMsk = ms + ml2 + '.msk'
|
||||
self.multilookLatitude = ms + ml2 + '.lat'
|
||||
self.multilookLongitude = ms + ml2 + '.lon'
|
||||
self.multilookHeight = ms + ml2 + '.hgt'
|
||||
self.multilookIon = ms + ml2 + '.ion'
|
||||
self.rectRangeOffset = ms + ml1 + '_rg_rect.off'
|
||||
self.geoInterferogram = 'filt_' + ms + ml2 + '.unw.geo'
|
||||
self.geoMaskedInterferogram = 'filt_' + ms + ml2 + '_msk.unw.geo'
|
||||
self.geoCoherence = ms + ml2 + '.cor.geo'
|
||||
self.geoLos = ms + ml2 + '.los.geo'
|
||||
#dense offset field
|
||||
self.slaveSlcCoregistered = slaveDate + '_coreg.slc'
|
||||
self.denseOffset = ms + '_denseoffset.off'
|
||||
self.denseOffsetSnr = ms + '_denseoffset.snr'
|
||||
self.denseOffsetCov = ms + '_denseoffset.cov'
|
||||
self.denseOffsetFilt = 'filt_' + ms + '_denseoffset.off'
|
||||
self.GeoDenseOffset = ms + '_denseoffset.off.geo'
|
||||
self.GeoDenseOffsetSnr = ms + '_denseoffset.snr.geo'
|
||||
self.GeoDenseOffsetFilt = 'filt_' + ms + '_denseoffset.off.geo'
|
||||
self.geoIon = ms + ml2 + '.ion.geo'
|
||||
|
||||
|
||||
def loadProduct(self, xmlname):
|
||||
'''
|
||||
Load the product using Product Manager.
|
||||
'''
|
||||
|
||||
from iscesys.Component.ProductManager import ProductManager as PM
|
||||
|
||||
pm = PM()
|
||||
pm.configure()
|
||||
|
||||
obj = pm.loadProduct(xmlname)
|
||||
|
||||
return obj
|
||||
|
||||
|
||||
def saveProduct(self, obj, xmlname):
|
||||
'''
|
||||
Save the product to an XML file using Product Manager.
|
||||
'''
|
||||
|
||||
from iscesys.Component.ProductManager import ProductManager as PM
|
||||
|
||||
pm = PM()
|
||||
pm.configure()
|
||||
|
||||
pm.dumpProduct(obj, xmlname)
|
||||
|
||||
return None
|
||||
|
||||
|
||||
def loadTrack(self, master=True):
|
||||
'''
|
||||
Load the track using Product Manager.
|
||||
'''
|
||||
if master:
|
||||
track = self.loadProduct(self.masterTrackParameter)
|
||||
else:
|
||||
track = self.loadProduct(self.slaveTrackParameter)
|
||||
|
||||
track.frames = []
|
||||
for i, frameNumber in enumerate(self.masterFrames):
|
||||
os.chdir('f{}_{}'.format(i+1, frameNumber))
|
||||
if master:
|
||||
track.frames.append(self.loadProduct(self.masterFrameParameter))
|
||||
else:
|
||||
track.frames.append(self.loadProduct(self.slaveFrameParameter))
|
||||
os.chdir('../')
|
||||
|
||||
return track
|
||||
|
||||
|
||||
def saveTrack(self, track, master=True):
|
||||
'''
|
||||
Save the track to XML files using Product Manager.
|
||||
'''
|
||||
if master:
|
||||
self.saveProduct(track, self.masterTrackParameter)
|
||||
else:
|
||||
self.saveProduct(track, self.slaveTrackParameter)
|
||||
|
||||
for i, frameNumber in enumerate(self.masterFrames):
|
||||
os.chdir('f{}_{}'.format(i+1, frameNumber))
|
||||
if master:
|
||||
self.saveProduct(track.frames[i], self.masterFrameParameter)
|
||||
else:
|
||||
self.saveProduct(track.frames[i], self.slaveFrameParameter)
|
||||
os.chdir('../')
|
||||
|
||||
return None
|
||||
|
||||
|
||||
def hasGPU(self):
|
||||
'''
|
||||
Determine if GPU modules are available.
|
||||
'''
|
||||
|
||||
flag = False
|
||||
try:
|
||||
from zerodop.GPUtopozero.GPUtopozero import PyTopozero
|
||||
from zerodop.GPUgeo2rdr.GPUgeo2rdr import PyGeo2rdr
|
||||
flag = True
|
||||
except:
|
||||
pass
|
||||
|
||||
return flag
|
||||
|
||||
File diff suppressed because it is too large
Load Diff
|
|
@ -0,0 +1,37 @@
|
|||
InstallSameDir(
|
||||
__init__.py
|
||||
Alos2Proc.py
|
||||
Alos2ProcPublic.py
|
||||
Factories.py
|
||||
denseOffsetNote.txt
|
||||
runCoherence.py
|
||||
runDenseOffset.py
|
||||
runDiffInterferogram.py
|
||||
runDownloadDem.py
|
||||
runFilt.py
|
||||
runFiltOffset.py
|
||||
runFormInterferogram.py
|
||||
runFrameMosaic.py
|
||||
runFrameOffset.py
|
||||
runGeo2Rdr.py
|
||||
runGeocode.py
|
||||
runGeocodeOffset.py
|
||||
runIonFilt.py
|
||||
runIonSubband.py
|
||||
runIonUwrap.py
|
||||
runLook.py
|
||||
runPrepareSlc.py
|
||||
runPreprocessor.py
|
||||
runRdr2Geo.py
|
||||
runRdrDemOffset.py
|
||||
runRectRangeOffset.py
|
||||
runSlcMatch.py
|
||||
runSlcMosaic.py
|
||||
runSlcOffset.py
|
||||
runSwathMosaic.py
|
||||
runSwathOffset.py
|
||||
runUnwrapSnaphu.py
|
||||
srtm_no_swbd_tiles.txt
|
||||
srtm_tiles.txt
|
||||
swbd_tiles.txt
|
||||
)
|
||||
|
|
@ -0,0 +1,105 @@
|
|||
#
|
||||
# Author: Piyush Agram
|
||||
# Copyright 2016
|
||||
#
|
||||
|
||||
# Path to the _RunWrapper factories
|
||||
_PATH = "isceobj.Alos2Proc."
|
||||
|
||||
## A factory to make _RunWrapper factories
|
||||
def _factory(name, other_name=None):
|
||||
"""create_run_wrapper = _factory(name)
|
||||
name is the module and class function name
|
||||
"""
|
||||
other_name = other_name or name
|
||||
module = __import__(
|
||||
_PATH+name, fromlist=[""]
|
||||
)
|
||||
cls = getattr(module, other_name)
|
||||
def creater(other, *args, **kwargs):
|
||||
"""_RunWrapper for object calling %s"""
|
||||
return _RunWrapper(other, cls)
|
||||
return creater
|
||||
|
||||
## Put in "_" to prevernt import on "from Factorties import *"
|
||||
class _RunWrapper(object):
|
||||
"""_RunWrapper(other, func)(*args, **kwargs)
|
||||
|
||||
executes:
|
||||
|
||||
func(other, *args, **kwargs)
|
||||
|
||||
(like a method)
|
||||
"""
|
||||
def __init__(self, other, func):
|
||||
self.method = func
|
||||
self.other = other
|
||||
return None
|
||||
|
||||
def __call__(self, *args, **kwargs):
|
||||
return self.method(self.other, *args, **kwargs)
|
||||
|
||||
pass
|
||||
|
||||
def createUnwrapper(other, do_unwrap = None, unwrapperName = None,
|
||||
unwrap = None):
|
||||
if not do_unwrap and not unwrap:
|
||||
#if not defined create an empty method that does nothing
|
||||
def runUnwrap(self):
|
||||
return None
|
||||
elif unwrapperName.lower() == 'snaphu':
|
||||
from .runUnwrapSnaphu import runUnwrap
|
||||
elif unwrapperName.lower() == 'snaphu_mcf':
|
||||
from .runUnwrapSnaphu import runUnwrapMcf as runUnwrap
|
||||
elif unwrapperName.lower() == 'downsample_snaphu':
|
||||
from .run_downsample_unwrapper import runUnwrap
|
||||
elif unwrapperName.lower() == 'icu':
|
||||
from .runUnwrapIcu import runUnwrap
|
||||
elif unwrapperName.lower() == 'grass':
|
||||
from .runUnwrapGrass import runUnwrap
|
||||
return _RunWrapper(other, runUnwrap)
|
||||
|
||||
def createUnwrap2Stage(other, do_unwrap_2stage = None, unwrapperName = None):
|
||||
if (not do_unwrap_2stage) or (unwrapperName.lower() == 'icu') or (unwrapperName.lower() == 'grass'):
|
||||
#if not defined create an empty method that does nothing
|
||||
def runUnwrap2Stage(*arg, **kwargs):
|
||||
return None
|
||||
else:
|
||||
try:
|
||||
import pulp
|
||||
from .runUnwrap2Stage import runUnwrap2Stage
|
||||
except ImportError:
|
||||
raise Exception('Please install PuLP Linear Programming API to run 2stage unwrap')
|
||||
return _RunWrapper(other, runUnwrap2Stage)
|
||||
|
||||
|
||||
createPreprocessor = _factory("runPreprocessor")
|
||||
createDownloadDem = _factory("runDownloadDem")
|
||||
createPrepareSlc = _factory("runPrepareSlc")
|
||||
createSlcOffset = _factory("runSlcOffset")
|
||||
createFormInterferogram = _factory("runFormInterferogram")
|
||||
createSwathOffset = _factory("runSwathOffset")
|
||||
createSwathMosaic = _factory("runSwathMosaic")
|
||||
createFrameOffset = _factory("runFrameOffset")
|
||||
createFrameMosaic = _factory("runFrameMosaic")
|
||||
createRdr2Geo = _factory("runRdr2Geo")
|
||||
createGeo2Rdr = _factory("runGeo2Rdr")
|
||||
createRdrDemOffset = _factory("runRdrDemOffset")
|
||||
createRectRangeOffset = _factory("runRectRangeOffset")
|
||||
createDiffInterferogram = _factory("runDiffInterferogram")
|
||||
createLook = _factory("runLook")
|
||||
createCoherence = _factory("runCoherence")
|
||||
createIonSubband = _factory("runIonSubband")
|
||||
createIonUwrap = _factory("runIonUwrap")
|
||||
createIonFilt = _factory("runIonFilt")
|
||||
createFilt = _factory("runFilt")
|
||||
createUnwrapSnaphu = _factory("runUnwrapSnaphu")
|
||||
createGeocode = _factory("runGeocode")
|
||||
|
||||
createSlcMosaic = _factory("runSlcMosaic")
|
||||
createSlcMatch = _factory("runSlcMatch")
|
||||
createDenseOffset = _factory("runDenseOffset")
|
||||
createFiltOffset = _factory("runFiltOffset")
|
||||
createGeocodeOffset = _factory("runGeocodeOffset")
|
||||
|
||||
|
||||
|
|
@ -0,0 +1,45 @@
|
|||
#! /usr/bin/env python
|
||||
|
||||
#~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
|
||||
# Copyright 2012 California Institute of Technology. ALL RIGHTS RESERVED.
|
||||
#
|
||||
# Licensed under the Apache License, Version 2.0 (the "License");
|
||||
# you may not use this file except in compliance with the License.
|
||||
# You may obtain a copy of the License at
|
||||
#
|
||||
# http://www.apache.org/licenses/LICENSE-2.0
|
||||
#
|
||||
# Unless required by applicable law or agreed to in writing, software
|
||||
# distributed under the License is distributed on an "AS IS" BASIS,
|
||||
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||
# See the License for the specific language governing permissions and
|
||||
# limitations under the License.
|
||||
#
|
||||
# United States Government Sponsorship acknowledged. This software is subject to
|
||||
# U.S. export control laws and regulations and has been classified as 'EAR99 NLR'
|
||||
# (No [Export] License Required except when exporting to an embargoed country,
|
||||
# end user, or in support of a prohibited end use). By downloading this software,
|
||||
# the user agrees to comply with all applicable U.S. export laws and regulations.
|
||||
# The user has the responsibility to obtain export licenses, or other export
|
||||
# authority as may be required before exporting this software to any 'EAR99'
|
||||
# embargoed foreign country or citizen of those countries.
|
||||
#
|
||||
# Author: Eric Gurrola
|
||||
#~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
#!/usr/bin/env python
|
||||
import os
|
||||
|
||||
Import('envisceobj')
|
||||
package = envisceobj['PACKAGE']
|
||||
project = 'Alos2Proc'
|
||||
|
||||
install = os.path.join(envisceobj['PRJ_SCONS_INSTALL'],package,project)
|
||||
|
||||
listFiles = ['__init__.py', 'Factories.py', 'Alos2Proc.py', 'Alos2ProcPublic.py', 'runPreprocessor.py', 'runDownloadDem.py', 'runPrepareSlc.py', 'runSlcOffset.py', 'runFormInterferogram.py', 'runSwathOffset.py', 'runSwathMosaic.py', 'runFrameOffset.py', 'runFrameMosaic.py', 'runRdr2Geo.py', 'runGeo2Rdr.py', 'runRdrDemOffset.py', 'runRectRangeOffset.py', 'runDiffInterferogram.py', 'runLook.py', 'runCoherence.py', 'runIonSubband.py', 'runIonUwrap.py', 'runIonFilt.py', 'runFilt.py', 'runUnwrapSnaphu.py', 'runGeocode.py', 'srtm_no_swbd_tiles.txt', 'srtm_tiles.txt', 'swbd_tiles.txt', 'runSlcMosaic.py', 'runSlcMatch.py', 'runDenseOffset.py', 'runFiltOffset.py', 'runGeocodeOffset.py', 'denseOffsetNote.txt']
|
||||
envisceobj.Install(install,listFiles)
|
||||
envisceobj.Alias('install',install)
|
||||
|
|
@ -0,0 +1,22 @@
|
|||
#
|
||||
# Author: Piyush Agram
|
||||
# Copyright 2016
|
||||
#
|
||||
|
||||
from .Alos2Proc import *
|
||||
from .Factories import *
|
||||
|
||||
def getFactoriesInfo():
|
||||
return {'Alos2Proc':
|
||||
{'args':
|
||||
{
|
||||
'procDoc':{'value':None,'type':'Catalog','optional':True}
|
||||
},
|
||||
'factory':'createAlos2Proc'
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
def createAlos2Proc(name=None, procDoc= None):
|
||||
from .Alos2Proc import Alos2Proc
|
||||
return Alos2Proc(name = name,procDoc = procDoc)
|
||||
|
|
@ -0,0 +1,31 @@
|
|||
on the following paramters might be changed in the denseoffset steps:
|
||||
=======================================================================
|
||||
if self.frameOffsetMatching == False:
|
||||
self._insar.frameRangeOffsetMatchingMaster = offsetMaster[2]
|
||||
self._insar.frameAzimuthOffsetMatchingMaster = offsetMaster[3]
|
||||
self._insar.frameRangeOffsetMatchingSlave = offsetSlave[2]
|
||||
self._insar.frameAzimuthOffsetMatchingSlave = offsetSlave[3]
|
||||
|
||||
|
||||
Therefore these denseoffset steps could be moved to after 'frame_mosaic' step
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
|
@ -0,0 +1,131 @@
|
|||
#
|
||||
# Author: Cunren Liang
|
||||
# Copyright 2015-present, NASA-JPL/Caltech
|
||||
#
|
||||
|
||||
import os
|
||||
import logging
|
||||
import numpy as np
|
||||
|
||||
import isceobj
|
||||
from isceobj.Alos2Proc.Alos2ProcPublic import runCmd
|
||||
|
||||
logger = logging.getLogger('isce.alos2insar.runCoherence')
|
||||
|
||||
def runCoherence(self):
|
||||
'''Extract images.
|
||||
'''
|
||||
catalog = isceobj.Catalog.createCatalog(self._insar.procDoc.name)
|
||||
self.updateParamemetersFromUser()
|
||||
|
||||
#masterTrack = self._insar.loadTrack(master=True)
|
||||
#slaveTrack = self._insar.loadTrack(master=False)
|
||||
|
||||
insarDir = 'insar'
|
||||
if not os.path.exists(insarDir):
|
||||
os.makedirs(insarDir)
|
||||
os.chdir(insarDir)
|
||||
|
||||
numberRangeLooks = self._insar.numberRangeLooks1 * self._insar.numberRangeLooks2
|
||||
numberAzimuthLooks = self._insar.numberAzimuthLooks1 * self._insar.numberAzimuthLooks2
|
||||
|
||||
#here we choose not to scale interferogram and amplitude
|
||||
#scaleAmplitudeInterferogram
|
||||
|
||||
#if (numberRangeLooks >= 5) and (numberAzimuthLooks >= 5):
|
||||
if (numberRangeLooks * numberAzimuthLooks >= 9):
|
||||
cmd = "imageMath.py -e='sqrt(b_0*b_1);abs(a)/(b_0+(b_0==0))/(b_1+(b_1==0))*(b_0!=0)*(b_1!=0)' --a={} --b={} -o {} -t float -s BIL".format(
|
||||
self._insar.multilookDifferentialInterferogram,
|
||||
self._insar.multilookAmplitude,
|
||||
self._insar.multilookCoherence)
|
||||
runCmd(cmd)
|
||||
else:
|
||||
#estimate coherence using a moving window
|
||||
coherence(self._insar.multilookAmplitude, self._insar.multilookDifferentialInterferogram, self._insar.multilookCoherence,
|
||||
method="cchz_wave", windowSize=5)
|
||||
os.chdir('../')
|
||||
|
||||
catalog.printToLog(logger, "runCoherence")
|
||||
self._insar.procDoc.addAllFromCatalog(catalog)
|
||||
|
||||
|
||||
from isceobj.Util.decorators import use_api
|
||||
@use_api
|
||||
def coherence(amplitudeFile, interferogramFile, coherenceFile, method="cchz_wave", windowSize=5):
|
||||
'''
|
||||
compute coherence using a window
|
||||
'''
|
||||
import operator
|
||||
from mroipac.correlation.correlation import Correlation
|
||||
|
||||
CORRELATION_METHOD = {
|
||||
'phase_gradient' : operator.methodcaller('calculateEffectiveCorrelation'),
|
||||
'cchz_wave' : operator.methodcaller('calculateCorrelation')
|
||||
}
|
||||
|
||||
ampImage = isceobj.createAmpImage()
|
||||
ampImage.load(amplitudeFile + '.xml')
|
||||
ampImage.setAccessMode('read')
|
||||
ampImage.createImage()
|
||||
|
||||
intImage = isceobj.createIntImage()
|
||||
intImage.load(interferogramFile + '.xml')
|
||||
intImage.setAccessMode('read')
|
||||
intImage.createImage()
|
||||
|
||||
#there is no coherence image in the isceobj/Image
|
||||
cohImage = isceobj.createOffsetImage()
|
||||
cohImage.setFilename(coherenceFile)
|
||||
cohImage.setWidth(ampImage.width)
|
||||
cohImage.setAccessMode('write')
|
||||
cohImage.createImage()
|
||||
|
||||
cor = Correlation()
|
||||
cor.configure()
|
||||
cor.wireInputPort(name='amplitude', object=ampImage)
|
||||
cor.wireInputPort(name='interferogram', object=intImage)
|
||||
cor.wireOutputPort(name='correlation', object=cohImage)
|
||||
|
||||
cor.windowSize = windowSize
|
||||
|
||||
cohImage.finalizeImage()
|
||||
intImage.finalizeImage()
|
||||
ampImage.finalizeImage()
|
||||
|
||||
try:
|
||||
CORRELATION_METHOD[method](cor)
|
||||
except KeyError:
|
||||
print("Unrecognized correlation method")
|
||||
sys.exit(1)
|
||||
pass
|
||||
return None
|
||||
|
||||
|
||||
def scaleAmplitudeInterferogram(amplitudeFile, interferogramFile, ratio=100000.0):
|
||||
'''
|
||||
scale amplitude and interferogram, and balace the two channels of amplitude image
|
||||
according to equation (2) in
|
||||
Howard A. Zebker and Katherine Chen, Accurate Estimation of Correlation in InSAR Observations
|
||||
IEEE GEOSCIENCE AND REMOTE SENSING LETTERS, VOL. 2, NO. 2, APRIL 2005.
|
||||
the operation of the program does not affect coherence estimation
|
||||
'''
|
||||
ampObj = isceobj.createImage()
|
||||
ampObj.load(amplitudeFile+'.xml')
|
||||
width = ampObj.width
|
||||
length = ampObj.length
|
||||
|
||||
inf = np.fromfile(interferogramFile, dtype=np.complex64).reshape(length, width)
|
||||
amp = np.fromfile(amplitudeFile, dtype=np.complex64).reshape(length, width)
|
||||
|
||||
flag = (inf!=0)*(amp.real!=0)*(amp.imag!=0)
|
||||
nvalid = np.sum(flag, dtype=np.float64)
|
||||
|
||||
mpwr1 = np.sqrt(np.sum(amp.real * amp.real * flag, dtype=np.float64) / nvalid)
|
||||
mpwr2 = np.sqrt(np.sum(amp.imag * amp.imag * flag, dtype=np.float64) / nvalid)
|
||||
|
||||
amp.real = amp.real / ratio
|
||||
amp.imag = amp.imag / ratio * mpwr1 / mpwr2
|
||||
inf = inf / ratio / ratio * mpwr1 / mpwr2
|
||||
|
||||
amp.astype(np.complex64).tofile(inps.amp)
|
||||
inf.astype(np.complex64).tofile(inps.inf)
|
||||
|
|
@ -0,0 +1,327 @@
|
|||
#
|
||||
# Author: Cunren Liang
|
||||
# Copyright 2015-present, NASA-JPL/Caltech
|
||||
#
|
||||
|
||||
import os
|
||||
import logging
|
||||
import numpy as np
|
||||
|
||||
import isceobj
|
||||
from isceobj.Util.decorators import use_api
|
||||
|
||||
logger = logging.getLogger('isce.alos2insar.runDenseOffset')
|
||||
|
||||
def runDenseOffset(self):
|
||||
'''estimate offset fied
|
||||
'''
|
||||
if not self.doDenseOffset:
|
||||
return
|
||||
if not ((self._insar.modeCombination == 0) or (self._insar.modeCombination == 1)):
|
||||
return
|
||||
|
||||
catalog = isceobj.Catalog.createCatalog(self._insar.procDoc.name)
|
||||
self.updateParamemetersFromUser()
|
||||
|
||||
denseOffsetDir = 'dense_offset'
|
||||
if not os.path.exists(denseOffsetDir):
|
||||
os.makedirs(denseOffsetDir)
|
||||
os.chdir(denseOffsetDir)
|
||||
|
||||
#masterTrack = self._insar.loadProduct(self._insar.masterTrackParameter)
|
||||
#slaveTrack = self._insar.loadProduct(self._insar.slaveTrackParameter)
|
||||
|
||||
#########################################################################################
|
||||
|
||||
if self.useGPU and self._insar.hasGPU():
|
||||
runDenseOffsetGPU(self)
|
||||
#define null value. Lijun said there is actually no such null value in GPU ampcor.
|
||||
nullValue = -10000.0
|
||||
else:
|
||||
runDenseOffsetCPU(self)
|
||||
#define null value
|
||||
nullValue = -10000.0
|
||||
|
||||
#null value set to zero
|
||||
img = isceobj.createImage()
|
||||
img.load(self._insar.denseOffset+'.xml')
|
||||
width = img.width
|
||||
length = img.length
|
||||
offset=np.memmap(self._insar.denseOffset, dtype='float32', mode='r+', shape=(length*2, width))
|
||||
snr=np.memmap(self._insar.denseOffsetSnr, dtype='float32', mode='r+', shape=(length, width))
|
||||
offsetband1 = offset[0:length*2:2, :]
|
||||
offsetband2 = offset[1:length*2:2, :]
|
||||
index = np.nonzero(np.logical_or(offsetband1==nullValue, offsetband2==nullValue))
|
||||
offsetband1[index] = 0
|
||||
offsetband2[index] = 0
|
||||
snr[index] = 0
|
||||
del offset, offsetband1, offsetband2, snr
|
||||
|
||||
#areas covered by water body set to zero
|
||||
if self.maskOffsetWithWbd:
|
||||
img = isceobj.createImage()
|
||||
img.load('wbd.rdr.xml')
|
||||
width0 = img.width
|
||||
length0 = img.length
|
||||
|
||||
img = isceobj.createImage()
|
||||
img.load(self._insar.denseOffset+'.xml')
|
||||
width = img.width
|
||||
length = img.length
|
||||
|
||||
#get water body mask
|
||||
wbd0=np.memmap('wbd.rdr', dtype=np.int8, mode='r', shape=(length0, width0))
|
||||
wbd0=wbd0[0+self._insar.offsetImageTopoffset:length0:self.offsetSkipHeight,
|
||||
0+self._insar.offsetImageLeftoffset:width0:self.offsetSkipWidth]
|
||||
wbd = np.zeros((length+100, width+100), dtype=np.int8)
|
||||
wbd[0:wbd0.shape[0], 0:wbd0.shape[1]]=wbd0
|
||||
|
||||
#mask offset and snr
|
||||
offset=np.memmap(self._insar.denseOffset, dtype='float32', mode='r+', shape=(length*2, width))
|
||||
snr=np.memmap(self._insar.denseOffsetSnr, dtype='float32', mode='r+', shape=(length, width))
|
||||
(offset[0:length*2:2, :])[np.nonzero(wbd[0:length, 0:width]==-1)]=0
|
||||
(offset[1:length*2:2, :])[np.nonzero(wbd[0:length, 0:width]==-1)]=0
|
||||
snr[np.nonzero(wbd[0:length, 0:width]==-1)]=0
|
||||
|
||||
del wbd0, wbd, offset, snr
|
||||
|
||||
|
||||
#########################################################################################
|
||||
|
||||
os.chdir('../')
|
||||
catalog.printToLog(logger, "runDenseOffset")
|
||||
self._insar.procDoc.addAllFromCatalog(catalog)
|
||||
|
||||
|
||||
#@use_api
|
||||
def runDenseOffsetCPU(self):
|
||||
'''
|
||||
Estimate dense offset field between a pair of SLCs.
|
||||
'''
|
||||
from mroipac.ampcor.DenseAmpcor import DenseAmpcor
|
||||
from isceobj.Alos2Proc.Alos2ProcPublic import runCmd
|
||||
|
||||
####For this module currently, we need to create an actual file on disk
|
||||
for infile in [self._insar.masterSlc, self._insar.slaveSlcCoregistered]:
|
||||
if os.path.isfile(infile):
|
||||
continue
|
||||
cmd = 'gdal_translate -of ENVI {0}.vrt {0}'.format(infile)
|
||||
runCmd(cmd)
|
||||
|
||||
m = isceobj.createSlcImage()
|
||||
m.load(self._insar.masterSlc + '.xml')
|
||||
m.setAccessMode('READ')
|
||||
|
||||
s = isceobj.createSlcImage()
|
||||
s.load(self._insar.slaveSlcCoregistered + '.xml')
|
||||
s.setAccessMode('READ')
|
||||
|
||||
#objOffset.numberThreads = 1
|
||||
print('\n************* dense offset estimation parameters *************')
|
||||
print('master SLC: %s' % (self._insar.masterSlc))
|
||||
print('slave SLC: %s' % (self._insar.slaveSlcCoregistered))
|
||||
print('dense offset estimation window width: %d' % (self.offsetWindowWidth))
|
||||
print('dense offset estimation window hight: %d' % (self.offsetWindowHeight))
|
||||
print('dense offset search window width: %d' % (self.offsetSearchWindowWidth))
|
||||
print('dense offset search window hight: %d' % (self.offsetSearchWindowHeight))
|
||||
print('dense offset skip width: %d' % (self.offsetSkipWidth))
|
||||
print('dense offset skip hight: %d' % (self.offsetSkipHeight))
|
||||
print('dense offset covariance surface oversample factor: %d' % (self.offsetCovarianceOversamplingFactor))
|
||||
print('dense offset covariance surface oversample window size: %d\n' % (self.offsetCovarianceOversamplingWindowsize))
|
||||
|
||||
|
||||
objOffset = DenseAmpcor(name='dense')
|
||||
objOffset.configure()
|
||||
|
||||
if m.dataType.startswith('C'):
|
||||
objOffset.setImageDataType1('complex')
|
||||
else:
|
||||
objOffset.setImageDataType1('real')
|
||||
if s.dataType.startswith('C'):
|
||||
objOffset.setImageDataType2('complex')
|
||||
else:
|
||||
objOffset.setImageDataType2('real')
|
||||
|
||||
objOffset.offsetImageName = self._insar.denseOffset
|
||||
objOffset.snrImageName = self._insar.denseOffsetSnr
|
||||
objOffset.covImageName = self._insar.denseOffsetCov
|
||||
|
||||
objOffset.setWindowSizeWidth(self.offsetWindowWidth)
|
||||
objOffset.setWindowSizeHeight(self.offsetWindowHeight)
|
||||
#NOTE: actual number of resulting correlation pixels: self.offsetSearchWindowWidth*2+1
|
||||
objOffset.setSearchWindowSizeWidth(self.offsetSearchWindowWidth)
|
||||
objOffset.setSearchWindowSizeHeight(self.offsetSearchWindowHeight)
|
||||
objOffset.setSkipSampleAcross(self.offsetSkipWidth)
|
||||
objOffset.setSkipSampleDown(self.offsetSkipHeight)
|
||||
objOffset.setOversamplingFactor(self.offsetCovarianceOversamplingFactor)
|
||||
objOffset.setZoomWindowSize(self.offsetCovarianceOversamplingWindowsize)
|
||||
objOffset.setAcrossGrossOffset(0)
|
||||
objOffset.setDownGrossOffset(0)
|
||||
#these are azimuth scaling factor
|
||||
#Matching Scale for Sample/Line Directions (-) = 1.000000551500 1.000002373200
|
||||
objOffset.setFirstPRF(1.0)
|
||||
objOffset.setSecondPRF(1.0)
|
||||
|
||||
objOffset.denseampcor(m, s)
|
||||
|
||||
### Store params for later
|
||||
self._insar.offsetImageTopoffset = objOffset.locationDown[0][0]
|
||||
self._insar.offsetImageLeftoffset = objOffset.locationAcross[0][0]
|
||||
|
||||
#change band order
|
||||
width=objOffset.offsetCols
|
||||
length=objOffset.offsetLines
|
||||
|
||||
offset1 = np.fromfile(self._insar.denseOffset, dtype=np.float32).reshape(length*2, width)
|
||||
offset2 = np.zeros((length*2, width), dtype=np.float32)
|
||||
offset2[0:length*2:2, :] = offset1[1:length*2:2, :]
|
||||
offset2[1:length*2:2, :] = offset1[0:length*2:2, :]
|
||||
|
||||
os.remove(self._insar.denseOffset)
|
||||
os.remove(self._insar.denseOffset+'.vrt')
|
||||
os.remove(self._insar.denseOffset+'.xml')
|
||||
|
||||
offset2.astype(np.float32).tofile(self._insar.denseOffset)
|
||||
outImg = isceobj.createImage()
|
||||
outImg.setDataType('FLOAT')
|
||||
outImg.setFilename(self._insar.denseOffset)
|
||||
outImg.setBands(2)
|
||||
outImg.scheme = 'BIL'
|
||||
outImg.setWidth(width)
|
||||
outImg.setLength(length)
|
||||
outImg.addDescription('two-band pixel offset file. 1st band: range offset, 2nd band: azimuth offset')
|
||||
outImg.setAccessMode('read')
|
||||
outImg.renderHdr()
|
||||
|
||||
return (objOffset.offsetCols, objOffset.offsetLines)
|
||||
|
||||
|
||||
def runDenseOffsetGPU(self):
|
||||
'''
|
||||
Estimate dense offset field between a pair of SLCs.
|
||||
'''
|
||||
from contrib.PyCuAmpcor import PyCuAmpcor
|
||||
from isceobj.Alos2Proc.Alos2ProcPublic import runCmd
|
||||
from isceobj.Alos2Proc.Alos2ProcPublic import create_xml
|
||||
|
||||
############################################################################################
|
||||
# #different from minyan's script: cuDenseOffsets.py: deramp method (0: mag, 1: complex)
|
||||
# objOffset.derampMethod = 2 #
|
||||
# #varying-gross-offset parameters not set
|
||||
|
||||
# #not set in minyan's script: cuDenseOffsets.py
|
||||
# objOffset.corrSurfaceZoomInWindow
|
||||
# objOffset.grossOffsetAcrossStatic = 0
|
||||
# objOffset.grossOffsetDownStatic = 0
|
||||
############################################################################################
|
||||
|
||||
|
||||
####For this module currently, we need to create an actual file on disk
|
||||
for infile in [self._insar.masterSlc, self._insar.slaveSlcCoregistered]:
|
||||
if os.path.isfile(infile):
|
||||
continue
|
||||
cmd = 'gdal_translate -of ENVI {0}.vrt {0}'.format(infile)
|
||||
runCmd(cmd)
|
||||
|
||||
m = isceobj.createSlcImage()
|
||||
m.load(self._insar.masterSlc + '.xml')
|
||||
m.setAccessMode('READ')
|
||||
|
||||
s = isceobj.createSlcImage()
|
||||
s.load(self._insar.slaveSlcCoregistered + '.xml')
|
||||
s.setAccessMode('READ')
|
||||
|
||||
print('\n************* dense offset estimation parameters *************')
|
||||
print('master SLC: %s' % (self._insar.masterSlc))
|
||||
print('slave SLC: %s' % (self._insar.slaveSlcCoregistered))
|
||||
print('dense offset estimation window width: %d' % (self.offsetWindowWidth))
|
||||
print('dense offset estimation window hight: %d' % (self.offsetWindowHeight))
|
||||
print('dense offset search window width: %d' % (self.offsetSearchWindowWidth))
|
||||
print('dense offset search window hight: %d' % (self.offsetSearchWindowHeight))
|
||||
print('dense offset skip width: %d' % (self.offsetSkipWidth))
|
||||
print('dense offset skip hight: %d' % (self.offsetSkipHeight))
|
||||
print('dense offset covariance surface oversample factor: %d' % (self.offsetCovarianceOversamplingFactor))
|
||||
print('dense offset covariance surface oversample window size: %d\n' % (self.offsetCovarianceOversamplingWindowsize))
|
||||
|
||||
|
||||
objOffset = PyCuAmpcor.PyCuAmpcor()
|
||||
objOffset.algorithm = 0
|
||||
objOffset.deviceID = -1
|
||||
objOffset.nStreams = 2
|
||||
#original ampcor program in roi_pac uses phase gradient to deramp
|
||||
objOffset.derampMethod = 2
|
||||
objOffset.masterImageName = self._insar.masterSlc
|
||||
objOffset.masterImageHeight = m.length
|
||||
objOffset.masterImageWidth = m.width
|
||||
objOffset.slaveImageName = self._insar.slaveSlcCoregistered
|
||||
objOffset.slaveImageHeight = s.length
|
||||
objOffset.slaveImageWidth = s.width
|
||||
objOffset.offsetImageName = self._insar.denseOffset
|
||||
objOffset.snrImageName = self._insar.denseOffsetSnr
|
||||
|
||||
objOffset.windowSizeWidth = self.offsetWindowWidth
|
||||
objOffset.windowSizeHeight = self.offsetWindowHeight
|
||||
#objOffset.halfSearchRangeAcross = int(self.offsetSearchWindowWidth / 2 + 0.5)
|
||||
#objOffset.halfSearchRangeDown = int(self.offsetSearchWindowHeight / 2 + 0.5)
|
||||
objOffset.halfSearchRangeAcross = self.offsetSearchWindowWidth
|
||||
objOffset.halfSearchRangeDown = self.offsetSearchWindowHeight
|
||||
objOffset.skipSampleDown = self.offsetSkipHeight
|
||||
objOffset.skipSampleAcross = self.offsetSkipWidth
|
||||
#Oversampling method for correlation surface(0=fft,1=sinc)
|
||||
objOffset.corrSufaceOverSamplingMethod = 0
|
||||
objOffset.corrSurfaceOverSamplingFactor = self.offsetCovarianceOversamplingFactor
|
||||
objOffset.corrSurfaceZoomInWindow = self.offsetCovarianceOversamplingWindowsize
|
||||
objOffset.grossOffsetAcrossStatic = 0
|
||||
objOffset.grossOffsetDownStatic = 0
|
||||
|
||||
objOffset.masterStartPixelDownStatic = self.offsetWindowHeight//2
|
||||
objOffset.masterStartPixelAcrossStatic = self.offsetWindowWidth//2
|
||||
|
||||
objOffset.numberWindowDown = (m.length - 2*self.offsetSearchWindowHeight - self.offsetWindowHeight) // self.offsetSkipHeight
|
||||
objOffset.numberWindowAcross = (m.width - 2*self.offsetSearchWindowWidth - self.offsetWindowWidth) // self.offsetSkipWidth
|
||||
|
||||
# generic control
|
||||
objOffset.numberWindowDownInChunk = 8
|
||||
objOffset.numberWindowAcrossInChunk = 8
|
||||
objOffset.mmapSize = 16
|
||||
|
||||
objOffset.setupParams()
|
||||
objOffset.setConstantGrossOffset(0, 0)
|
||||
objOffset.checkPixelInImageRange()
|
||||
objOffset.runAmpcor()
|
||||
|
||||
### Store params for later
|
||||
self._insar.offsetImageTopoffset = objOffset.halfSearchRangeDown
|
||||
self._insar.offsetImageLeftoffset = objOffset.halfSearchRangeAcross
|
||||
|
||||
|
||||
width = objOffset.numberWindowAcross
|
||||
length = objOffset.numberWindowDown
|
||||
offsetBIP = np.fromfile(objOffset.offsetImageName.decode('utf-8'), dtype=np.float32).reshape(length, width*2)
|
||||
offsetBIL = np.zeros((length*2, width), dtype=np.float32)
|
||||
offsetBIL[0:length*2:2, :] = offsetBIP[:, 1:width*2:2]
|
||||
offsetBIL[1:length*2:2, :] = offsetBIP[:, 0:width*2:2]
|
||||
os.remove(objOffset.offsetImageName.decode('utf-8'))
|
||||
offsetBIL.astype(np.float32).tofile(objOffset.offsetImageName.decode('utf-8'))
|
||||
|
||||
outImg = isceobj.createImage()
|
||||
outImg.setDataType('FLOAT')
|
||||
outImg.setFilename(objOffset.offsetImageName.decode('utf-8'))
|
||||
outImg.setBands(2)
|
||||
outImg.scheme = 'BIL'
|
||||
outImg.setWidth(objOffset.numberWindowAcross)
|
||||
outImg.setLength(objOffset.numberWindowDown)
|
||||
outImg.addDescription('two-band pixel offset file. 1st band: range offset, 2nd band: azimuth offset')
|
||||
outImg.setAccessMode('read')
|
||||
outImg.renderHdr()
|
||||
|
||||
snrImg = isceobj.createImage()
|
||||
snrImg.setFilename( objOffset.snrImageName.decode('utf8'))
|
||||
snrImg.setDataType('FLOAT')
|
||||
snrImg.setBands(1)
|
||||
snrImg.setWidth(objOffset.numberWindowAcross)
|
||||
snrImg.setLength(objOffset.numberWindowDown)
|
||||
snrImg.setAccessMode('read')
|
||||
snrImg.renderHdr()
|
||||
|
||||
return (objOffset.numberWindowAcross, objOffset.numberWindowDown)
|
||||
|
|
@ -0,0 +1,41 @@
|
|||
#
|
||||
# Author: Cunren Liang
|
||||
# Copyright 2015-present, NASA-JPL/Caltech
|
||||
#
|
||||
|
||||
import os
|
||||
import logging
|
||||
import numpy as np
|
||||
|
||||
import isceobj
|
||||
from isceobj.Alos2Proc.Alos2ProcPublic import runCmd
|
||||
|
||||
logger = logging.getLogger('isce.alos2insar.runDiffInterferogram')
|
||||
|
||||
def runDiffInterferogram(self):
|
||||
'''Extract images.
|
||||
'''
|
||||
catalog = isceobj.Catalog.createCatalog(self._insar.procDoc.name)
|
||||
self.updateParamemetersFromUser()
|
||||
|
||||
masterTrack = self._insar.loadTrack(master=True)
|
||||
|
||||
insarDir = 'insar'
|
||||
if not os.path.exists(insarDir):
|
||||
os.makedirs(insarDir)
|
||||
os.chdir(insarDir)
|
||||
|
||||
|
||||
rangePixelSize = self._insar.numberRangeLooks1 * masterTrack.rangePixelSize
|
||||
radarWavelength = masterTrack.radarWavelength
|
||||
|
||||
cmd = "imageMath.py -e='a*exp(-1.0*J*b*4.0*{}*{}/{}) * (b!=0)' --a={} --b={} -o {} -t cfloat".format(np.pi, rangePixelSize, radarWavelength, self._insar.interferogram, self._insar.rectRangeOffset, self._insar.differentialInterferogram)
|
||||
runCmd(cmd)
|
||||
|
||||
|
||||
os.chdir('../')
|
||||
|
||||
catalog.printToLog(logger, "runDiffInterferogram")
|
||||
self._insar.procDoc.addAllFromCatalog(catalog)
|
||||
|
||||
|
||||
|
|
@ -0,0 +1,204 @@
|
|||
#
|
||||
# Author: Cunren Liang
|
||||
# Copyright 2015-present, NASA-JPL/Caltech
|
||||
#
|
||||
|
||||
import os
|
||||
import glob
|
||||
import logging
|
||||
import numpy as np
|
||||
|
||||
import isceobj
|
||||
from isceobj.Alos2Proc.Alos2ProcPublic import runCmd
|
||||
from isceobj.Alos2Proc.Alos2ProcPublic import getBboxGeo
|
||||
|
||||
logger = logging.getLogger('isce.alos2insar.runDownloadDem')
|
||||
|
||||
def runDownloadDem(self):
|
||||
'''download DEM and water body
|
||||
'''
|
||||
catalog = isceobj.Catalog.createCatalog(self._insar.procDoc.name)
|
||||
self.updateParamemetersFromUser()
|
||||
|
||||
masterTrack = self._insar.loadTrack(master=True)
|
||||
slaveTrack = self._insar.loadTrack(master=False)
|
||||
|
||||
bboxGeo = getBboxGeo(masterTrack)
|
||||
bbox = np.array(bboxGeo)
|
||||
bboxStr = '{} {} {} {}'.format(np.int(np.floor(bbox[0])), np.int(np.ceil(bbox[1])), np.int(np.floor(bbox[2])), np.int(np.ceil(bbox[3])))
|
||||
|
||||
|
||||
#get 1 arcsecond dem for coregistration
|
||||
if self.dem == None:
|
||||
demDir = 'dem_1_arcsec'
|
||||
if not os.path.exists(demDir):
|
||||
os.makedirs(demDir)
|
||||
os.chdir(demDir)
|
||||
|
||||
downloadUrl = 'http://e4ftl01.cr.usgs.gov/MEASURES/SRTMGL1.003/2000.02.11'
|
||||
cmd = 'dem.py -a stitch -b {} -k -s 1 -c -f -u {}'.format(
|
||||
bboxStr,
|
||||
downloadUrl
|
||||
)
|
||||
runCmd(cmd)
|
||||
cmd = 'fixImageXml.py -i demLat_*_*_Lon_*_*.dem.wgs84 -f'
|
||||
runCmd(cmd)
|
||||
cmd = 'rm *.hgt* *.log demLat_*_*_Lon_*_*.dem demLat_*_*_Lon_*_*.dem.vrt demLat_*_*_Lon_*_*.dem.xml'
|
||||
runCmd(cmd)
|
||||
os.chdir('../')
|
||||
|
||||
self.dem = glob.glob(os.path.join(demDir, 'demLat_*_*_Lon_*_*.dem.wgs84'))[0]
|
||||
|
||||
#get 3 arcsecond dem for geocoding
|
||||
if self.demGeo == None:
|
||||
demGeoDir = 'dem_3_arcsec'
|
||||
if not os.path.exists(demGeoDir):
|
||||
os.makedirs(demGeoDir)
|
||||
os.chdir(demGeoDir)
|
||||
|
||||
downloadUrl = 'http://e4ftl01.cr.usgs.gov/MEASURES/SRTMGL3.003/2000.02.11'
|
||||
cmd = 'dem.py -a stitch -b {} -k -s 3 -c -f -u {}'.format(
|
||||
bboxStr,
|
||||
downloadUrl
|
||||
)
|
||||
runCmd(cmd)
|
||||
cmd = 'fixImageXml.py -i demLat_*_*_Lon_*_*.dem.wgs84 -f'
|
||||
runCmd(cmd)
|
||||
cmd = 'rm *.hgt* *.log demLat_*_*_Lon_*_*.dem demLat_*_*_Lon_*_*.dem.vrt demLat_*_*_Lon_*_*.dem.xml'
|
||||
runCmd(cmd)
|
||||
os.chdir('../')
|
||||
|
||||
self.demGeo = glob.glob(os.path.join(demGeoDir, 'demLat_*_*_Lon_*_*.dem.wgs84'))[0]
|
||||
|
||||
#get water body for masking interferogram
|
||||
if self.wbd == None:
|
||||
wbdDir = 'wbd_1_arcsec'
|
||||
if not os.path.exists(wbdDir):
|
||||
os.makedirs(wbdDir)
|
||||
os.chdir(wbdDir)
|
||||
|
||||
#cmd = 'wbd.py {}'.format(bboxStr)
|
||||
#runCmd(cmd)
|
||||
download_wbd(np.int(np.floor(bbox[0])), np.int(np.ceil(bbox[1])), np.int(np.floor(bbox[2])), np.int(np.ceil(bbox[3])))
|
||||
cmd = 'fixImageXml.py -i swbdLat_*_*_Lon_*_*.wbd -f'
|
||||
runCmd(cmd)
|
||||
cmd = 'rm *.log'
|
||||
runCmd(cmd)
|
||||
os.chdir('../')
|
||||
|
||||
self.wbd = glob.glob(os.path.join(wbdDir, 'swbdLat_*_*_Lon_*_*.wbd'))[0]
|
||||
|
||||
self._insar.dem = self.dem
|
||||
self._insar.demGeo = self.demGeo
|
||||
self._insar.wbd = self.wbd
|
||||
|
||||
|
||||
catalog.printToLog(logger, "runDownloadDem")
|
||||
self._insar.procDoc.addAllFromCatalog(catalog)
|
||||
|
||||
|
||||
|
||||
def download_wbd(s, n, w, e):
|
||||
'''
|
||||
download water body
|
||||
water body. (0) --- land; (-1) --- water; (-2) --- no data.
|
||||
|
||||
set no-value pixel inside of latitude [-56, 60] to -1
|
||||
set no-value pixel outside of latitidue [-56, 60] to -2
|
||||
|
||||
look at this figure for SRTM coverage:
|
||||
https://www2.jpl.nasa.gov/srtm/images/SRTM_2-24-2016.gif
|
||||
'''
|
||||
import os
|
||||
import numpy as np
|
||||
import isceobj
|
||||
from iscesys.DataManager import createManager
|
||||
|
||||
latMin = np.floor(s)
|
||||
latMax = np.ceil(n)
|
||||
lonMin = np.floor(w)
|
||||
lonMax = np.ceil(e)
|
||||
|
||||
############################################################
|
||||
#1. download and stitch wbd
|
||||
############################################################
|
||||
sw = createManager('wbd')
|
||||
sw.configure()
|
||||
|
||||
outputFile = sw.defaultName([latMin,latMax,lonMin,lonMax])
|
||||
if os.path.exists(outputFile) and os.path.exists(outputFile+'.xml'):
|
||||
print('water body file: {}'.format(outputFile))
|
||||
print('exists, do not download and correct')
|
||||
return outputFile
|
||||
|
||||
#download and stitch the SWBD tiles
|
||||
sw.noFilling = False
|
||||
sw._fillingValue = -1
|
||||
sw.stitch([latMin,latMax],[lonMin,lonMax])
|
||||
|
||||
|
||||
############################################################
|
||||
#2. replace 'areas with SRTM but no SWBD' with zeros (land)
|
||||
############################################################
|
||||
print('post-process water body file')
|
||||
|
||||
print('get SRTM tiles')
|
||||
srtmListFile = os.path.join(os.path.dirname(os.path.realpath(__file__)), 'srtm_tiles.txt')
|
||||
with open(srtmListFile) as f:
|
||||
srtmList = f.readlines()
|
||||
srtmList = [x[0:7] for x in srtmList]
|
||||
|
||||
#get tiles that have SRTM DEM, but no SWBD, these are mostly tiles that do not have water body
|
||||
print('get tiles with SRTM and without SWBD')
|
||||
noSwbdListFile = os.path.join(os.path.dirname(os.path.realpath(__file__)), 'srtm_no_swbd_tiles.txt')
|
||||
with open(noSwbdListFile) as f:
|
||||
noSwbdList = f.readlines()
|
||||
noSwbdList = [x[0:7] for x in noSwbdList]
|
||||
|
||||
print('get SWBD tiles')
|
||||
swbdListFile = os.path.join(os.path.dirname(os.path.realpath(__file__)), 'swbd_tiles.txt')
|
||||
with open(swbdListFile) as f:
|
||||
swbdList = f.readlines()
|
||||
swbdList = [x[0:7] for x in swbdList]
|
||||
|
||||
|
||||
#read resulting mosaicked water body
|
||||
wbdImage = isceobj.createDemImage()
|
||||
wbdImage.load(outputFile+'.xml')
|
||||
#using memmap instead, which should be faster, since we only have a few pixels to change
|
||||
wbd=np.memmap(outputFile, dtype=np.int8, mode='r+', shape=(wbdImage.length, wbdImage.width))
|
||||
|
||||
#replace 'areas with SRTM but no SWBD' with zeros (land)
|
||||
names, nlats, nlons = sw.createNameListFromBounds([latMin,latMax],[lonMin,lonMax])
|
||||
sign={'S':-1, 'N':1, 'W':-1, 'E':1}
|
||||
for tile in names:
|
||||
print('checking tile: {}'.format(tile))
|
||||
firstLatitude = sign[tile[0].upper()]*int(tile[1:3])+1
|
||||
firstLongitude = sign[tile[3].upper()]*int(tile[4:7])
|
||||
lineOffset = np.int32((firstLatitude - wbdImage.firstLatitude) / wbdImage.deltaLatitude + 0.5)
|
||||
sampleOffset = np.int32((firstLongitude - wbdImage.firstLongitude) / wbdImage.deltaLongitude + 0.5)
|
||||
|
||||
#first line/sample of mosaicked SWBD is integer lat/lon, but it does not include last integer lat/lon line/sample
|
||||
#so here the size is 3600*3600 instead of 3601*3601
|
||||
|
||||
#assuming areas without swbd are water
|
||||
if tile[0:7] not in swbdList:
|
||||
wbd[0+lineOffset:3600+lineOffset, 0+sampleOffset:3600+sampleOffset] = -1
|
||||
#assuming areas with srtm and without swbd are land
|
||||
if tile[0:7] in noSwbdList:
|
||||
wbd[0+lineOffset:3600+lineOffset, 0+sampleOffset:3600+sampleOffset] = 0
|
||||
|
||||
|
||||
############################################################
|
||||
#3. set values outside of lat[-56, 60] to -2 (no data)
|
||||
############################################################
|
||||
print('check water body file')
|
||||
print('set areas outside of lat[-56, 60] to -2 (no data)')
|
||||
for i in range(wbdImage.length):
|
||||
lat = wbdImage.firstLatitude + wbdImage.deltaLatitude * i
|
||||
if lat > 60.0 or lat < -56.0:
|
||||
wbd[i, :] = -2
|
||||
del wbd, wbdImage
|
||||
|
||||
|
||||
return outputFile
|
||||
|
|
@ -0,0 +1,171 @@
|
|||
#
|
||||
# Author: Cunren Liang
|
||||
# Copyright 2015-present, NASA-JPL/Caltech
|
||||
#
|
||||
|
||||
import os
|
||||
import logging
|
||||
import shutil
|
||||
import numpy as np
|
||||
|
||||
import isceobj
|
||||
from mroipac.filter.Filter import Filter
|
||||
from contrib.alos2filter.alos2filter import psfilt1
|
||||
from mroipac.icu.Icu import Icu
|
||||
from isceobj.Alos2Proc.Alos2ProcPublic import runCmd
|
||||
from isceobj.Alos2Proc.Alos2ProcPublic import renameFile
|
||||
from isceobj.Alos2Proc.Alos2ProcPublic import create_xml
|
||||
|
||||
logger = logging.getLogger('isce.alos2insar.runFilt')
|
||||
|
||||
def runFilt(self):
|
||||
'''filter interferogram
|
||||
'''
|
||||
catalog = isceobj.Catalog.createCatalog(self._insar.procDoc.name)
|
||||
self.updateParamemetersFromUser()
|
||||
|
||||
#masterTrack = self._insar.loadTrack(master=True)
|
||||
#slaveTrack = self._insar.loadTrack(master=False)
|
||||
|
||||
insarDir = 'insar'
|
||||
if not os.path.exists(insarDir):
|
||||
os.makedirs(insarDir)
|
||||
os.chdir(insarDir)
|
||||
|
||||
|
||||
############################################################
|
||||
# STEP 1. filter interferogram
|
||||
############################################################
|
||||
print('\nfilter interferogram: {}'.format(self._insar.multilookDifferentialInterferogram))
|
||||
|
||||
toBeFiltered = self._insar.multilookDifferentialInterferogram
|
||||
if self.removeMagnitudeBeforeFiltering:
|
||||
toBeFiltered = 'tmp.int'
|
||||
cmd = "imageMath.py -e='a/(abs(a)+(a==0))' --a={} -o {} -t cfloat -s BSQ".format(self._insar.multilookDifferentialInterferogram, toBeFiltered)
|
||||
runCmd(cmd)
|
||||
|
||||
#if shutil.which('psfilt1') != None:
|
||||
if True:
|
||||
intImage = isceobj.createIntImage()
|
||||
intImage.load(toBeFiltered + '.xml')
|
||||
width = intImage.width
|
||||
length = intImage.length
|
||||
# cmd = "psfilt1 {int} {filtint} {width} {filterstrength} 64 16".format(
|
||||
# int = toBeFiltered,
|
||||
# filtint = self._insar.filteredInterferogram,
|
||||
# width = width,
|
||||
# filterstrength = self.filterStrength
|
||||
# )
|
||||
# runCmd(cmd)
|
||||
windowSize = self.filterWinsize
|
||||
stepSize = self.filterStepsize
|
||||
psfilt1(toBeFiltered, self._insar.filteredInterferogram, width, self.filterStrength, windowSize, stepSize)
|
||||
create_xml(self._insar.filteredInterferogram, width, length, 'int')
|
||||
else:
|
||||
#original
|
||||
intImage = isceobj.createIntImage()
|
||||
intImage.load(toBeFiltered + '.xml')
|
||||
intImage.setAccessMode('read')
|
||||
intImage.createImage()
|
||||
width = intImage.width
|
||||
length = intImage.length
|
||||
|
||||
#filtered
|
||||
filtImage = isceobj.createIntImage()
|
||||
filtImage.setFilename(self._insar.filteredInterferogram)
|
||||
filtImage.setWidth(width)
|
||||
filtImage.setAccessMode('write')
|
||||
filtImage.createImage()
|
||||
|
||||
#looks like the ps filtering program keep the original interferogram magnitude, which is bad for phase unwrapping?
|
||||
filters = Filter()
|
||||
filters.wireInputPort(name='interferogram',object=intImage)
|
||||
filters.wireOutputPort(name='filtered interferogram',object=filtImage)
|
||||
filters.goldsteinWerner(alpha=self.filterStrength)
|
||||
intImage.finalizeImage()
|
||||
filtImage.finalizeImage()
|
||||
del intImage, filtImage, filters
|
||||
|
||||
if self.removeMagnitudeBeforeFiltering:
|
||||
os.remove(toBeFiltered)
|
||||
os.remove(toBeFiltered + '.vrt')
|
||||
os.remove(toBeFiltered + '.xml')
|
||||
|
||||
#restore original magnitude
|
||||
tmpFile = 'tmp.int'
|
||||
renameFile(self._insar.filteredInterferogram, tmpFile)
|
||||
cmd = "imageMath.py -e='a*abs(b)' --a={} --b={} -o {} -t cfloat -s BSQ".format(tmpFile, self._insar.multilookDifferentialInterferogram, self._insar.filteredInterferogram)
|
||||
runCmd(cmd)
|
||||
os.remove(tmpFile)
|
||||
os.remove(tmpFile + '.vrt')
|
||||
os.remove(tmpFile + '.xml')
|
||||
|
||||
|
||||
############################################################
|
||||
# STEP 2. create phase sigma using filtered interferogram
|
||||
############################################################
|
||||
print('\ncreate phase sigma using: {}'.format(self._insar.filteredInterferogram))
|
||||
|
||||
#recreate filtered image
|
||||
filtImage = isceobj.createIntImage()
|
||||
filtImage.load(self._insar.filteredInterferogram + '.xml')
|
||||
filtImage.setAccessMode('read')
|
||||
filtImage.createImage()
|
||||
|
||||
#amplitude image
|
||||
ampImage = isceobj.createAmpImage()
|
||||
ampImage.load(self._insar.multilookAmplitude + '.xml')
|
||||
ampImage.setAccessMode('read')
|
||||
ampImage.createImage()
|
||||
|
||||
#phase sigma correlation image
|
||||
phsigImage = isceobj.createImage()
|
||||
phsigImage.setFilename(self._insar.multilookPhsig)
|
||||
phsigImage.setWidth(width)
|
||||
phsigImage.dataType='FLOAT'
|
||||
phsigImage.bands = 1
|
||||
phsigImage.setImageType('cor')
|
||||
phsigImage.setAccessMode('write')
|
||||
phsigImage.createImage()
|
||||
|
||||
icu = Icu(name='insarapp_filter_icu')
|
||||
icu.configure()
|
||||
icu.unwrappingFlag = False
|
||||
icu.icu(intImage = filtImage, ampImage=ampImage, phsigImage=phsigImage)
|
||||
|
||||
phsigImage.renderHdr()
|
||||
|
||||
filtImage.finalizeImage()
|
||||
ampImage.finalizeImage()
|
||||
phsigImage.finalizeImage()
|
||||
|
||||
del filtImage
|
||||
del ampImage
|
||||
del phsigImage
|
||||
del icu
|
||||
|
||||
|
||||
############################################################
|
||||
# STEP 3. mask filtered interferogram using water body
|
||||
############################################################
|
||||
print('\nmask filtered interferogram using: {}'.format(self._insar.multilookWbdOut))
|
||||
|
||||
if self.waterBodyMaskStartingStep=='filt':
|
||||
if not os.path.exists(self._insar.multilookWbdOut):
|
||||
catalog.addItem('warning message', 'requested masking interferogram with water body, but water body does not exist', 'runFilt')
|
||||
else:
|
||||
wbd = np.fromfile(self._insar.multilookWbdOut, dtype=np.int8).reshape(length, width)
|
||||
phsig=np.memmap(self._insar.multilookPhsig, dtype='float32', mode='r+', shape=(length, width))
|
||||
phsig[np.nonzero(wbd==-1)]=0
|
||||
del phsig
|
||||
filt=np.memmap(self._insar.filteredInterferogram, dtype='complex64', mode='r+', shape=(length, width))
|
||||
filt[np.nonzero(wbd==-1)]=0
|
||||
del filt
|
||||
del wbd
|
||||
|
||||
|
||||
os.chdir('../')
|
||||
|
||||
catalog.printToLog(logger, "runFilt")
|
||||
self._insar.procDoc.addAllFromCatalog(catalog)
|
||||
|
||||
|
|
@ -0,0 +1,104 @@
|
|||
#
|
||||
# Author: Cunren Liang
|
||||
# Copyright 2015-present, NASA-JPL/Caltech
|
||||
#
|
||||
|
||||
import os
|
||||
import logging
|
||||
import statistics
|
||||
import numpy as np
|
||||
from scipy.ndimage.filters import median_filter
|
||||
|
||||
import isceobj
|
||||
|
||||
logger = logging.getLogger('isce.alos2insar.runFiltOffset')
|
||||
|
||||
def runFiltOffset(self):
|
||||
'''filt offset fied
|
||||
'''
|
||||
if not self.doDenseOffset:
|
||||
return
|
||||
if not ((self._insar.modeCombination == 0) or (self._insar.modeCombination == 1)):
|
||||
return
|
||||
|
||||
catalog = isceobj.Catalog.createCatalog(self._insar.procDoc.name)
|
||||
self.updateParamemetersFromUser()
|
||||
|
||||
denseOffsetDir = 'dense_offset'
|
||||
if not os.path.exists(denseOffsetDir):
|
||||
os.makedirs(denseOffsetDir)
|
||||
os.chdir(denseOffsetDir)
|
||||
|
||||
#masterTrack = self._insar.loadProduct(self._insar.masterTrackParameter)
|
||||
#slaveTrack = self._insar.loadProduct(self._insar.slaveTrackParameter)
|
||||
|
||||
#########################################################################################
|
||||
|
||||
if not self.doOffsetFiltering:
|
||||
print('offset field filtering is not requested.')
|
||||
os.chdir('../')
|
||||
catalog.printToLog(logger, "runFiltOffset")
|
||||
self._insar.procDoc.addAllFromCatalog(catalog)
|
||||
return
|
||||
|
||||
windowSize = self.offsetFilterWindowsize
|
||||
nullValue = 0
|
||||
snrThreshold = self.offsetFilterSnrThreshold
|
||||
|
||||
if windowSize < 3:
|
||||
raise Exception('dense offset field filter window size must >= 3')
|
||||
if windowSize % 2 != 1:
|
||||
windowSize += 1
|
||||
print('dense offset field filter window size is not odd, changed to: {}'.format(windowSize))
|
||||
|
||||
print('\noffset filter parameters:')
|
||||
print('**************************************')
|
||||
print('filter window size: {}'.format(windowSize))
|
||||
print('filter null value: {}'.format(nullValue))
|
||||
print('filter snr threshold: {}\n'.format(snrThreshold))
|
||||
|
||||
|
||||
img = isceobj.createImage()
|
||||
img.load(self._insar.denseOffset+'.xml')
|
||||
width = img.width
|
||||
length = img.length
|
||||
|
||||
offset = np.fromfile(self._insar.denseOffset, dtype=np.float32).reshape(length*2, width)
|
||||
snr = np.fromfile(self._insar.denseOffsetSnr, dtype=np.float32).reshape(length, width)
|
||||
offsetFilt = np.zeros((length*2, width), dtype=np.float32)
|
||||
|
||||
edge = int((windowSize-1)/2+0.5)
|
||||
for k in range(2):
|
||||
print('filtering band {} of {}'.format(k+1, 2))
|
||||
band = offset[k:length*2:2, :]
|
||||
bandFilt = offsetFilt[k:length*2:2, :]
|
||||
for i in range(0+edge, length-edge):
|
||||
for j in range(0+edge, width-edge):
|
||||
bandSub = band[i-edge:i+edge+1, j-edge:j+edge+1]
|
||||
snrSub = snr[i-edge:i+edge+1, j-edge:j+edge+1]
|
||||
#bandSubUsed is 1-d numpy array
|
||||
bandSubUsed = bandSub[np.nonzero(np.logical_and(snrSub>snrThreshold, bandSub!=nullValue))]
|
||||
if bandSubUsed.size == 0:
|
||||
bandFilt[i, j] = nullValue
|
||||
else:
|
||||
bandFilt[i, j] = statistics.median(bandSubUsed)
|
||||
|
||||
offsetFilt.astype(np.float32).tofile(self._insar.denseOffsetFilt)
|
||||
outImg = isceobj.createImage()
|
||||
outImg.setDataType('FLOAT')
|
||||
outImg.setFilename(self._insar.denseOffsetFilt)
|
||||
outImg.setBands(2)
|
||||
outImg.scheme = 'BIL'
|
||||
outImg.setWidth(width)
|
||||
outImg.setLength(length)
|
||||
outImg.addDescription('two-band pixel offset file. 1st band: range offset, 2nd band: azimuth offset')
|
||||
outImg.setAccessMode('read')
|
||||
outImg.renderHdr()
|
||||
|
||||
#########################################################################################
|
||||
|
||||
os.chdir('../')
|
||||
catalog.printToLog(logger, "runFiltOffset")
|
||||
self._insar.procDoc.addAllFromCatalog(catalog)
|
||||
|
||||
|
||||
|
|
@ -0,0 +1,134 @@
|
|||
#
|
||||
# Author: Cunren Liang
|
||||
# Copyright 2015-present, NASA-JPL/Caltech
|
||||
#
|
||||
|
||||
import os
|
||||
import logging
|
||||
import numpy as np
|
||||
|
||||
import isceobj
|
||||
import stdproc
|
||||
from iscesys.StdOEL.StdOELPy import create_writer
|
||||
from isceobj.Alos2Proc.Alos2ProcPublic import readOffset
|
||||
from isceobj.Alos2Proc.Alos2ProcPublic import runCmd
|
||||
|
||||
logger = logging.getLogger('isce.alos2insar.runFormInterferogram')
|
||||
|
||||
def runFormInterferogram(self):
|
||||
'''form interferograms.
|
||||
'''
|
||||
catalog = isceobj.Catalog.createCatalog(self._insar.procDoc.name)
|
||||
self.updateParamemetersFromUser()
|
||||
|
||||
masterTrack = self._insar.loadTrack(master=True)
|
||||
slaveTrack = self._insar.loadTrack(master=False)
|
||||
|
||||
for i, frameNumber in enumerate(self._insar.masterFrames):
|
||||
frameDir = 'f{}_{}'.format(i+1, frameNumber)
|
||||
os.chdir(frameDir)
|
||||
for j, swathNumber in enumerate(range(self._insar.startingSwath, self._insar.endingSwath + 1)):
|
||||
swathDir = 's{}'.format(swathNumber)
|
||||
os.chdir(swathDir)
|
||||
|
||||
print('forming interferogram frame {}, swath {}'.format(frameNumber, swathNumber))
|
||||
|
||||
masterSwath = masterTrack.frames[i].swaths[j]
|
||||
slaveSwath = slaveTrack.frames[i].swaths[j]
|
||||
|
||||
|
||||
#############################################
|
||||
#1. form interferogram
|
||||
#############################################
|
||||
refinedOffsets = readOffset('cull.off')
|
||||
intWidth = int(masterSwath.numberOfSamples / self._insar.numberRangeLooks1)
|
||||
intLength = int(masterSwath.numberOfLines / self._insar.numberAzimuthLooks1)
|
||||
dopplerVsPixel = [i/slaveSwath.prf for i in slaveSwath.dopplerVsPixel]
|
||||
|
||||
#master slc
|
||||
mSLC = isceobj.createSlcImage()
|
||||
mSLC.load(self._insar.masterSlc+'.xml')
|
||||
mSLC.setAccessMode('read')
|
||||
mSLC.createImage()
|
||||
|
||||
#slave slc
|
||||
sSLC = isceobj.createSlcImage()
|
||||
sSLC.load(self._insar.slaveSlc+'.xml')
|
||||
sSLC.setAccessMode('read')
|
||||
sSLC.createImage()
|
||||
|
||||
#interferogram
|
||||
interf = isceobj.createIntImage()
|
||||
interf.setFilename(self._insar.interferogram)
|
||||
interf.setWidth(intWidth)
|
||||
interf.setAccessMode('write')
|
||||
interf.createImage()
|
||||
|
||||
#amplitdue
|
||||
amplitude = isceobj.createAmpImage()
|
||||
amplitude.setFilename(self._insar.amplitude)
|
||||
amplitude.setWidth(intWidth)
|
||||
amplitude.setAccessMode('write')
|
||||
amplitude.createImage()
|
||||
|
||||
#create a writer for resamp
|
||||
stdWriter = create_writer("log", "", True, filename="resamp.log")
|
||||
stdWriter.setFileTag("resamp", "log")
|
||||
stdWriter.setFileTag("resamp", "err")
|
||||
stdWriter.setFileTag("resamp", "out")
|
||||
|
||||
|
||||
#set up resampling program now
|
||||
#The setting has been compared with resamp_roi's setting in ROI_pac item by item.
|
||||
#The two kinds of setting are exactly the same. The number of setting items are
|
||||
#exactly the same
|
||||
objResamp = stdproc.createResamp()
|
||||
objResamp.wireInputPort(name='offsets', object=refinedOffsets)
|
||||
objResamp.stdWriter = stdWriter
|
||||
objResamp.setNumberFitCoefficients(6)
|
||||
objResamp.setNumberRangeBin1(masterSwath.numberOfSamples)
|
||||
objResamp.setNumberRangeBin2(slaveSwath.numberOfSamples)
|
||||
objResamp.setStartLine(1)
|
||||
objResamp.setNumberLines(masterSwath.numberOfLines)
|
||||
objResamp.setFirstLineOffset(1)
|
||||
objResamp.setDopplerCentroidCoefficients(dopplerVsPixel)
|
||||
objResamp.setRadarWavelength(slaveTrack.radarWavelength)
|
||||
objResamp.setSlantRangePixelSpacing(slaveSwath.rangePixelSize)
|
||||
objResamp.setNumberRangeLooks(self._insar.numberRangeLooks1)
|
||||
objResamp.setNumberAzimuthLooks(self._insar.numberAzimuthLooks1)
|
||||
objResamp.setFlattenWithOffsetFitFlag(0)
|
||||
objResamp.resamp(mSLC, sSLC, interf, amplitude)
|
||||
|
||||
#finialize images
|
||||
mSLC.finalizeImage()
|
||||
sSLC.finalizeImage()
|
||||
interf.finalizeImage()
|
||||
amplitude.finalizeImage()
|
||||
stdWriter.finalize()
|
||||
|
||||
|
||||
#############################################
|
||||
#2. trim amplitude
|
||||
#############################################
|
||||
# tmpAmplitude = 'tmp.amp'
|
||||
# cmd = "imageMath.py -e='a_0*(a_1>0);a_1*(a_0>0)' --a={} -o={} -s BIP -t float".format(
|
||||
# self._insar.amplitude,
|
||||
# tmpAmplitude
|
||||
# )
|
||||
# runCmd(cmd)
|
||||
# os.remove(self._insar.amplitude)
|
||||
# os.remove(tmpAmplitude+'.xml')
|
||||
# os.remove(tmpAmplitude+'.vrt')
|
||||
# os.rename(tmpAmplitude, self._insar.amplitude)
|
||||
|
||||
#using memmap instead, which should be faster, since we only have a few pixels to change
|
||||
amp=np.memmap(self._insar.amplitude, dtype='complex64', mode='r+', shape=(intLength, intWidth))
|
||||
index = np.nonzero( (np.real(amp)==0) + (np.imag(amp)==0) )
|
||||
amp[index]=0
|
||||
del amp
|
||||
|
||||
os.chdir('../')
|
||||
os.chdir('../')
|
||||
|
||||
catalog.printToLog(logger, "runFormInterferogram")
|
||||
self._insar.procDoc.addAllFromCatalog(catalog)
|
||||
|
|
@ -0,0 +1,552 @@
|
|||
#
|
||||
# Author: Cunren Liang
|
||||
# Copyright 2015-present, NASA-JPL/Caltech
|
||||
#
|
||||
|
||||
import os
|
||||
import glob
|
||||
import logging
|
||||
import datetime
|
||||
import numpy as np
|
||||
|
||||
import isceobj
|
||||
from isceobj.Alos2Proc.Alos2ProcPublic import create_xml
|
||||
|
||||
logger = logging.getLogger('isce.alos2insar.runFrameMosaic')
|
||||
|
||||
def runFrameMosaic(self):
|
||||
'''mosaic frames
|
||||
'''
|
||||
catalog = isceobj.Catalog.createCatalog(self._insar.procDoc.name)
|
||||
self.updateParamemetersFromUser()
|
||||
|
||||
masterTrack = self._insar.loadTrack(master=True)
|
||||
slaveTrack = self._insar.loadTrack(master=False)
|
||||
|
||||
mosaicDir = 'insar'
|
||||
if not os.path.exists(mosaicDir):
|
||||
os.makedirs(mosaicDir)
|
||||
os.chdir(mosaicDir)
|
||||
|
||||
numberOfFrames = len(masterTrack.frames)
|
||||
if numberOfFrames == 1:
|
||||
import shutil
|
||||
frameDir = os.path.join('f1_{}/mosaic'.format(self._insar.masterFrames[0]))
|
||||
if not os.path.isfile(self._insar.interferogram):
|
||||
os.symlink(os.path.join('../', frameDir, self._insar.interferogram), self._insar.interferogram)
|
||||
#shutil.copy2() can overwrite
|
||||
shutil.copy2(os.path.join('../', frameDir, self._insar.interferogram+'.vrt'), self._insar.interferogram+'.vrt')
|
||||
shutil.copy2(os.path.join('../', frameDir, self._insar.interferogram+'.xml'), self._insar.interferogram+'.xml')
|
||||
if not os.path.isfile(self._insar.amplitude):
|
||||
os.symlink(os.path.join('../', frameDir, self._insar.amplitude), self._insar.amplitude)
|
||||
shutil.copy2(os.path.join('../', frameDir, self._insar.amplitude+'.vrt'), self._insar.amplitude+'.vrt')
|
||||
shutil.copy2(os.path.join('../', frameDir, self._insar.amplitude+'.xml'), self._insar.amplitude+'.xml')
|
||||
|
||||
# os.rename(os.path.join('../', frameDir, self._insar.interferogram), self._insar.interferogram)
|
||||
# os.rename(os.path.join('../', frameDir, self._insar.interferogram+'.vrt'), self._insar.interferogram+'.vrt')
|
||||
# os.rename(os.path.join('../', frameDir, self._insar.interferogram+'.xml'), self._insar.interferogram+'.xml')
|
||||
# os.rename(os.path.join('../', frameDir, self._insar.amplitude), self._insar.amplitude)
|
||||
# os.rename(os.path.join('../', frameDir, self._insar.amplitude+'.vrt'), self._insar.amplitude+'.vrt')
|
||||
# os.rename(os.path.join('../', frameDir, self._insar.amplitude+'.xml'), self._insar.amplitude+'.xml')
|
||||
|
||||
#update track parameters
|
||||
#########################################################
|
||||
#mosaic size
|
||||
masterTrack.numberOfSamples = masterTrack.frames[0].numberOfSamples
|
||||
masterTrack.numberOfLines = masterTrack.frames[0].numberOfLines
|
||||
#NOTE THAT WE ARE STILL USING SINGLE LOOK PARAMETERS HERE
|
||||
#range parameters
|
||||
masterTrack.startingRange = masterTrack.frames[0].startingRange
|
||||
masterTrack.rangeSamplingRate = masterTrack.frames[0].rangeSamplingRate
|
||||
masterTrack.rangePixelSize = masterTrack.frames[0].rangePixelSize
|
||||
#azimuth parameters
|
||||
masterTrack.sensingStart = masterTrack.frames[0].sensingStart
|
||||
masterTrack.prf = masterTrack.frames[0].prf
|
||||
masterTrack.azimuthPixelSize = masterTrack.frames[0].azimuthPixelSize
|
||||
masterTrack.azimuthLineInterval = masterTrack.frames[0].azimuthLineInterval
|
||||
|
||||
#update track parameters, slave
|
||||
#########################################################
|
||||
#mosaic size
|
||||
slaveTrack.numberOfSamples = slaveTrack.frames[0].numberOfSamples
|
||||
slaveTrack.numberOfLines = slaveTrack.frames[0].numberOfLines
|
||||
#NOTE THAT WE ARE STILL USING SINGLE LOOK PARAMETERS HERE
|
||||
#range parameters
|
||||
slaveTrack.startingRange = slaveTrack.frames[0].startingRange
|
||||
slaveTrack.rangeSamplingRate = slaveTrack.frames[0].rangeSamplingRate
|
||||
slaveTrack.rangePixelSize = slaveTrack.frames[0].rangePixelSize
|
||||
#azimuth parameters
|
||||
slaveTrack.sensingStart = slaveTrack.frames[0].sensingStart
|
||||
slaveTrack.prf = slaveTrack.frames[0].prf
|
||||
slaveTrack.azimuthPixelSize = slaveTrack.frames[0].azimuthPixelSize
|
||||
slaveTrack.azimuthLineInterval = slaveTrack.frames[0].azimuthLineInterval
|
||||
|
||||
else:
|
||||
#choose offsets
|
||||
if self.frameOffsetMatching:
|
||||
rangeOffsets = self._insar.frameRangeOffsetMatchingMaster
|
||||
azimuthOffsets = self._insar.frameAzimuthOffsetMatchingMaster
|
||||
else:
|
||||
rangeOffsets = self._insar.frameRangeOffsetGeometricalMaster
|
||||
azimuthOffsets = self._insar.frameAzimuthOffsetGeometricalMaster
|
||||
|
||||
#list of input files
|
||||
inputInterferograms = []
|
||||
inputAmplitudes = []
|
||||
for i, frameNumber in enumerate(self._insar.masterFrames):
|
||||
frameDir = 'f{}_{}'.format(i+1, frameNumber)
|
||||
inputInterferograms.append(os.path.join('../', frameDir, 'mosaic', self._insar.interferogram))
|
||||
inputAmplitudes.append(os.path.join('../', frameDir, 'mosaic', self._insar.amplitude))
|
||||
|
||||
#note that track parameters are updated after mosaicking
|
||||
#mosaic amplitudes
|
||||
frameMosaic(masterTrack, inputAmplitudes, self._insar.amplitude,
|
||||
rangeOffsets, azimuthOffsets, self._insar.numberRangeLooks1, self._insar.numberAzimuthLooks1,
|
||||
updateTrack=False, phaseCompensation=False, resamplingMethod=0)
|
||||
#mosaic interferograms
|
||||
frameMosaic(masterTrack, inputInterferograms, self._insar.interferogram,
|
||||
rangeOffsets, azimuthOffsets, self._insar.numberRangeLooks1, self._insar.numberAzimuthLooks1,
|
||||
updateTrack=True, phaseCompensation=True, resamplingMethod=1)
|
||||
|
||||
create_xml(self._insar.amplitude, masterTrack.numberOfSamples, masterTrack.numberOfLines, 'amp')
|
||||
create_xml(self._insar.interferogram, masterTrack.numberOfSamples, masterTrack.numberOfLines, 'int')
|
||||
|
||||
#update slave parameters here
|
||||
#do not match for slave, always use geometrical
|
||||
rangeOffsets = self._insar.frameRangeOffsetGeometricalSlave
|
||||
azimuthOffsets = self._insar.frameAzimuthOffsetGeometricalSlave
|
||||
frameMosaicParameters(slaveTrack, rangeOffsets, azimuthOffsets, self._insar.numberRangeLooks1, self._insar.numberAzimuthLooks1)
|
||||
|
||||
os.chdir('../')
|
||||
#save parameter file
|
||||
self._insar.saveProduct(masterTrack, self._insar.masterTrackParameter)
|
||||
self._insar.saveProduct(slaveTrack, self._insar.slaveTrackParameter)
|
||||
|
||||
catalog.printToLog(logger, "runFrameMosaic")
|
||||
self._insar.procDoc.addAllFromCatalog(catalog)
|
||||
|
||||
|
||||
def frameMosaic(track, inputFiles, outputfile, rangeOffsets, azimuthOffsets, numberOfRangeLooks, numberOfAzimuthLooks, updateTrack=False, phaseCompensation=False, resamplingMethod=0):
|
||||
'''
|
||||
mosaic frames
|
||||
|
||||
track: track
|
||||
inputFiles: input file list
|
||||
output file: output mosaic file
|
||||
rangeOffsets: range offsets
|
||||
azimuthOffsets: azimuth offsets
|
||||
numberOfRangeLooks: number of range looks of the input files
|
||||
numberOfAzimuthLooks: number of azimuth looks of the input files
|
||||
updateTrack: whether update track parameters
|
||||
phaseCompensation: whether do phase compensation for each frame
|
||||
resamplingMethod: 0: amp resampling. 1: int resampling. 2: slc resampling
|
||||
'''
|
||||
import numpy as np
|
||||
|
||||
from contrib.alos2proc_f.alos2proc_f import rect_with_looks
|
||||
from contrib.alos2proc.alos2proc import resamp
|
||||
from isceobj.Alos2Proc.runSwathMosaic import readImage
|
||||
from isceobj.Alos2Proc.runSwathMosaic import findNonzero
|
||||
from isceobj.Alos2Proc.Alos2ProcPublic import create_xml
|
||||
from isceobj.Alos2Proc.Alos2ProcPublic import find_vrt_file
|
||||
from isceobj.Alos2Proc.Alos2ProcPublic import find_vrt_keyword
|
||||
|
||||
numberOfFrames = len(track.frames)
|
||||
frames = track.frames
|
||||
|
||||
rectWidth = []
|
||||
rectLength = []
|
||||
for i in range(numberOfFrames):
|
||||
infImg = isceobj.createImage()
|
||||
infImg.load(inputFiles[i]+'.xml')
|
||||
rectWidth.append(infImg.width)
|
||||
rectLength.append(infImg.length)
|
||||
|
||||
#convert original offset to offset for images with looks
|
||||
#use list instead of np.array to make it consistent with the rest of the code
|
||||
rangeOffsets1 = [i/numberOfRangeLooks for i in rangeOffsets]
|
||||
azimuthOffsets1 = [i/numberOfAzimuthLooks for i in azimuthOffsets]
|
||||
|
||||
#get offset relative to the first frame
|
||||
rangeOffsets2 = [0.0]
|
||||
azimuthOffsets2 = [0.0]
|
||||
for i in range(1, numberOfFrames):
|
||||
rangeOffsets2.append(0.0)
|
||||
azimuthOffsets2.append(0.0)
|
||||
for j in range(1, i+1):
|
||||
rangeOffsets2[i] += rangeOffsets1[j]
|
||||
azimuthOffsets2[i] += azimuthOffsets1[j]
|
||||
|
||||
#resample each frame
|
||||
rinfs = []
|
||||
for i, inf in enumerate(inputFiles):
|
||||
rinfs.append("{}_{}{}".format(os.path.splitext(os.path.basename(inf))[0], i, os.path.splitext(os.path.basename(inf))[1]))
|
||||
#do not resample first frame
|
||||
if i == 0:
|
||||
rinfs[i] = inf
|
||||
else:
|
||||
infImg = isceobj.createImage()
|
||||
infImg.load(inf+'.xml')
|
||||
rangeOffsets2Frac = rangeOffsets2[i] - int(rangeOffsets2[i])
|
||||
azimuthOffsets2Frac = azimuthOffsets2[i] - int(azimuthOffsets2[i])
|
||||
|
||||
if resamplingMethod == 0:
|
||||
rect_with_looks(inf,
|
||||
rinfs[i],
|
||||
infImg.width, infImg.length,
|
||||
infImg.width, infImg.length,
|
||||
1.0, 0.0,
|
||||
0.0, 1.0,
|
||||
rangeOffsets2Frac, azimuthOffsets2Frac,
|
||||
1,1,
|
||||
1,1,
|
||||
'COMPLEX',
|
||||
'Bilinear')
|
||||
if infImg.getImageType() == 'amp':
|
||||
create_xml(rinfs[i], infImg.width, infImg.length, 'amp')
|
||||
else:
|
||||
create_xml(rinfs[i], infImg.width, infImg.length, 'int')
|
||||
|
||||
elif resamplingMethod == 1:
|
||||
#decompose amplitude and phase
|
||||
phaseFile = 'phase'
|
||||
amplitudeFile = 'amplitude'
|
||||
data = np.fromfile(inf, dtype=np.complex64).reshape(infImg.length, infImg.width)
|
||||
phase = np.exp(np.complex64(1j) * np.angle(data))
|
||||
phase[np.nonzero(data==0)] = 0
|
||||
phase.astype(np.complex64).tofile(phaseFile)
|
||||
amplitude = np.absolute(data)
|
||||
amplitude.astype(np.float32).tofile(amplitudeFile)
|
||||
|
||||
#resampling
|
||||
phaseRectFile = 'phaseRect'
|
||||
amplitudeRectFile = 'amplitudeRect'
|
||||
rect_with_looks(phaseFile,
|
||||
phaseRectFile,
|
||||
infImg.width, infImg.length,
|
||||
infImg.width, infImg.length,
|
||||
1.0, 0.0,
|
||||
0.0, 1.0,
|
||||
rangeOffsets2Frac, azimuthOffsets2Frac,
|
||||
1,1,
|
||||
1,1,
|
||||
'COMPLEX',
|
||||
'Sinc')
|
||||
rect_with_looks(amplitudeFile,
|
||||
amplitudeRectFile,
|
||||
infImg.width, infImg.length,
|
||||
infImg.width, infImg.length,
|
||||
1.0, 0.0,
|
||||
0.0, 1.0,
|
||||
rangeOffsets2Frac, azimuthOffsets2Frac,
|
||||
1,1,
|
||||
1,1,
|
||||
'REAL',
|
||||
'Bilinear')
|
||||
|
||||
#recombine amplitude and phase
|
||||
phase = np.fromfile(phaseRectFile, dtype=np.complex64).reshape(infImg.length, infImg.width)
|
||||
amplitude = np.fromfile(amplitudeRectFile, dtype=np.float32).reshape(infImg.length, infImg.width)
|
||||
(phase*amplitude).astype(np.complex64).tofile(rinfs[i])
|
||||
|
||||
#tidy up
|
||||
os.remove(phaseFile)
|
||||
os.remove(amplitudeFile)
|
||||
os.remove(phaseRectFile)
|
||||
os.remove(amplitudeRectFile)
|
||||
if infImg.getImageType() == 'amp':
|
||||
create_xml(rinfs[i], infImg.width, infImg.length, 'amp')
|
||||
else:
|
||||
create_xml(rinfs[i], infImg.width, infImg.length, 'int')
|
||||
else:
|
||||
resamp(inf,
|
||||
rinfs[i],
|
||||
'fake',
|
||||
'fake',
|
||||
infImg.width, infImg.length,
|
||||
frames[i].swaths[0].prf,
|
||||
frames[i].swaths[0].dopplerVsPixel,
|
||||
[rangeOffsets2Frac, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0],
|
||||
[azimuthOffsets2Frac, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0])
|
||||
create_xml(rinfs[i], infImg.width, infImg.length, 'slc')
|
||||
|
||||
#determine output width and length
|
||||
#actually no need to calculate in azimuth direction
|
||||
xs = []
|
||||
xe = []
|
||||
ys = []
|
||||
ye = []
|
||||
for i in range(numberOfFrames):
|
||||
if i == 0:
|
||||
xs.append(0)
|
||||
xe.append(rectWidth[i] - 1)
|
||||
ys.append(0)
|
||||
ye.append(rectLength[i] - 1)
|
||||
else:
|
||||
xs.append(0 - int(rangeOffsets2[i]))
|
||||
xe.append(rectWidth[i] - 1 - int(rangeOffsets2[i]))
|
||||
ys.append(0 - int(azimuthOffsets2[i]))
|
||||
ye.append(rectLength[i] - 1 - int(azimuthOffsets2[i]))
|
||||
|
||||
(xmin, xminIndex) = min((v,i) for i,v in enumerate(xs))
|
||||
(xmax, xmaxIndex) = max((v,i) for i,v in enumerate(xe))
|
||||
(ymin, yminIndex) = min((v,i) for i,v in enumerate(ys))
|
||||
(ymax, ymaxIndex) = max((v,i) for i,v in enumerate(ye))
|
||||
|
||||
outWidth = xmax - xmin + 1
|
||||
outLength = ymax - ymin + 1
|
||||
|
||||
|
||||
#prepare for mosaicing using numpy
|
||||
xs = [x-xmin for x in xs]
|
||||
xe = [x-xmin for x in xe]
|
||||
ys = [y-ymin for y in ys]
|
||||
ye = [y-ymin for y in ye]
|
||||
|
||||
|
||||
#compute phase offset
|
||||
if phaseCompensation:
|
||||
phaseOffsetPolynomials = [np.array([0.0])]
|
||||
for i in range(1, numberOfFrames):
|
||||
upperframe = np.zeros((ye[i-1]-ys[i]+1, outWidth), dtype=np.complex128)
|
||||
lowerframe = np.zeros((ye[i-1]-ys[i]+1, outWidth), dtype=np.complex128)
|
||||
#upper frame
|
||||
if os.path.isfile(rinfs[i-1]):
|
||||
upperframe[:,xs[i-1]:xe[i-1]+1] = readImage(rinfs[i-1], rectWidth[i-1], rectLength[i-1], 0, rectWidth[i-1]-1, ys[i]-ys[i-1], ye[i-1]-ys[i-1])
|
||||
else:
|
||||
upperframe[:,xs[i-1]:xe[i-1]+1] = readImageFromVrt(rinfs[i-1], 0, rectWidth[i-1]-1, ys[i]-ys[i-1], ye[i-1]-ys[i-1])
|
||||
#lower frame
|
||||
if os.path.isfile(rinfs[i]):
|
||||
lowerframe[:,xs[i]:xe[i]+1] = readImage(rinfs[i], rectWidth[i], rectLength[i], 0, rectWidth[i]-1, 0, ye[i-1]-ys[i])
|
||||
else:
|
||||
lowerframe[:,xs[i]:xe[i]+1] = readImageFromVrt(rinfs[i], 0, rectWidth[i]-1, 0, ye[i-1]-ys[i])
|
||||
#get a polynomial
|
||||
diff = np.sum(upperframe * np.conj(lowerframe), axis=0)
|
||||
(firstLine, lastLine, firstSample, lastSample) = findNonzero(np.reshape(diff, (1, outWidth)))
|
||||
#here i use mean value(deg=0) in case difference is around -pi or pi.
|
||||
deg = 0
|
||||
p = np.polyfit(np.arange(firstSample, lastSample+1), np.angle(diff[firstSample:lastSample+1]), deg)
|
||||
phaseOffsetPolynomials.append(p)
|
||||
|
||||
|
||||
#check fit result
|
||||
DEBUG = False
|
||||
if DEBUG:
|
||||
#create a dir and work in this dir
|
||||
diffDir = 'frame_mosaic'
|
||||
if not os.path.exists(diffDir):
|
||||
os.makedirs(diffDir)
|
||||
os.chdir(diffDir)
|
||||
|
||||
#dump phase difference
|
||||
diffFilename = 'phase_difference_frame{}-frame{}.int'.format(i, i+1)
|
||||
(upperframe * np.conj(lowerframe)).astype(np.complex64).tofile(diffFilename)
|
||||
create_xml(diffFilename, outWidth, ye[i-1]-ys[i]+1, 'int')
|
||||
|
||||
#plot phase difference vs range
|
||||
import matplotlib.pyplot as plt
|
||||
x = np.arange(firstSample, lastSample+1)
|
||||
y = np.angle(diff[firstSample:lastSample+1])
|
||||
plt.plot(x, y, label='original phase difference')
|
||||
plt.plot(x, np.polyval(p, x), label='fitted phase difference')
|
||||
plt.legend()
|
||||
|
||||
plt.minorticks_on()
|
||||
plt.tick_params('both', length=10, which='major')
|
||||
plt.tick_params('both', length=5, which='minor')
|
||||
|
||||
plt.xlabel('Range Sample Number [Samples]')
|
||||
plt.ylabel('Phase Difference [Rad]')
|
||||
plt.savefig('phase_difference_frame{}-frame{}.pdf'.format(i, i+1))
|
||||
|
||||
os.chdir('../')
|
||||
|
||||
|
||||
#mosaic file
|
||||
outFp = open(outputfile,'wb')
|
||||
for i in range(numberOfFrames):
|
||||
print('adding frame: {}'.format(i+1))
|
||||
|
||||
#phase offset in the polynomials
|
||||
if phaseCompensation:
|
||||
cJ = np.complex64(1j)
|
||||
phaseOffset = np.ones(outWidth, dtype=np.complex64)
|
||||
for j in range(i+1):
|
||||
phaseOffset *= np.exp(cJ*np.polyval(phaseOffsetPolynomials[j], np.arange(outWidth)))
|
||||
|
||||
#get start line number (starts with zero)
|
||||
if i == 0:
|
||||
ys1 = 0
|
||||
else:
|
||||
ys1 = int((ye[i-1]+ys[i])/2.0) + 1 - ys[i]
|
||||
#get end line number (start with zero)
|
||||
if i == numberOfFrames-1:
|
||||
ye1 = rectLength[i] - 1
|
||||
else:
|
||||
ye1 = int((ye[i]+ys[i+1])/2.0) - ys[i]
|
||||
|
||||
#get image format
|
||||
inputimage = find_vrt_file(rinfs[i]+'.vrt', 'SourceFilename', relative_path=True)
|
||||
byteorder = find_vrt_keyword(rinfs[i]+'.vrt', 'ByteOrder')
|
||||
if byteorder == 'LSB':
|
||||
swapByte = False
|
||||
else:
|
||||
swapByte = True
|
||||
imageoffset = int(find_vrt_keyword(rinfs[i]+'.vrt', 'ImageOffset'))
|
||||
lineoffset = int(find_vrt_keyword(rinfs[i]+'.vrt', 'LineOffset'))
|
||||
|
||||
#read image
|
||||
with open(inputimage,'rb') as fp:
|
||||
for j in range(ys1, ye1+1):
|
||||
fp.seek(imageoffset+j*lineoffset, 0)
|
||||
data = np.zeros(outWidth, dtype=np.complex64)
|
||||
if swapByte:
|
||||
tmp = np.fromfile(fp, dtype='>f', count=2*rectWidth[i])
|
||||
cJ = np.complex64(1j)
|
||||
data[xs[i]:xe[i]+1] = tmp[0::2] + cJ * tmp[1::2]
|
||||
else:
|
||||
data[xs[i]:xe[i]+1] = np.fromfile(fp, dtype=np.complex64, count=rectWidth[i])
|
||||
if phaseCompensation:
|
||||
data *= phaseOffset
|
||||
data.astype(np.complex64).tofile(outFp)
|
||||
outFp.close()
|
||||
|
||||
|
||||
#delete files. DO NOT DELETE THE FIRST ONE!!!
|
||||
for i in range(numberOfFrames):
|
||||
if i == 0:
|
||||
continue
|
||||
os.remove(rinfs[i])
|
||||
os.remove(rinfs[i]+'.vrt')
|
||||
os.remove(rinfs[i]+'.xml')
|
||||
|
||||
|
||||
#update frame parameters
|
||||
if updateTrack:
|
||||
#mosaic size
|
||||
track.numberOfSamples = outWidth
|
||||
track.numberOfLines = outLength
|
||||
#NOTE THAT WE ARE STILL USING SINGLE LOOK PARAMETERS HERE
|
||||
#range parameters
|
||||
track.startingRange = frames[0].startingRange + (int(rangeOffsets2[0]) - int(rangeOffsets2[xminIndex])) * numberOfRangeLooks * frames[0].rangePixelSize
|
||||
track.rangeSamplingRate = frames[0].rangeSamplingRate
|
||||
track.rangePixelSize = frames[0].rangePixelSize
|
||||
#azimuth parameters
|
||||
track.sensingStart = frames[0].sensingStart
|
||||
track.prf = frames[0].prf
|
||||
track.azimuthPixelSize = frames[0].azimuthPixelSize
|
||||
track.azimuthLineInterval = frames[0].azimuthLineInterval
|
||||
|
||||
|
||||
def frameMosaicParameters(track, rangeOffsets, azimuthOffsets, numberOfRangeLooks, numberOfAzimuthLooks):
|
||||
'''
|
||||
mosaic frames (this simplified version of frameMosaic to only update parameters)
|
||||
|
||||
track: track
|
||||
rangeOffsets: range offsets
|
||||
azimuthOffsets: azimuth offsets
|
||||
numberOfRangeLooks: number of range looks of the input files
|
||||
numberOfAzimuthLooks: number of azimuth looks of the input files
|
||||
'''
|
||||
|
||||
numberOfFrames = len(track.frames)
|
||||
frames = track.frames
|
||||
|
||||
rectWidth = []
|
||||
rectLength = []
|
||||
for i in range(numberOfFrames):
|
||||
rectWidth.append(frames[i].numberOfSamples)
|
||||
rectLength.append(frames[i].numberOfLines)
|
||||
|
||||
#convert original offset to offset for images with looks
|
||||
#use list instead of np.array to make it consistent with the rest of the code
|
||||
rangeOffsets1 = [i/numberOfRangeLooks for i in rangeOffsets]
|
||||
azimuthOffsets1 = [i/numberOfAzimuthLooks for i in azimuthOffsets]
|
||||
|
||||
#get offset relative to the first frame
|
||||
rangeOffsets2 = [0.0]
|
||||
azimuthOffsets2 = [0.0]
|
||||
for i in range(1, numberOfFrames):
|
||||
rangeOffsets2.append(0.0)
|
||||
azimuthOffsets2.append(0.0)
|
||||
for j in range(1, i+1):
|
||||
rangeOffsets2[i] += rangeOffsets1[j]
|
||||
azimuthOffsets2[i] += azimuthOffsets1[j]
|
||||
|
||||
#determine output width and length
|
||||
#actually no need to calculate in azimuth direction
|
||||
xs = []
|
||||
xe = []
|
||||
ys = []
|
||||
ye = []
|
||||
for i in range(numberOfFrames):
|
||||
if i == 0:
|
||||
xs.append(0)
|
||||
xe.append(rectWidth[i] - 1)
|
||||
ys.append(0)
|
||||
ye.append(rectLength[i] - 1)
|
||||
else:
|
||||
xs.append(0 - int(rangeOffsets2[i]))
|
||||
xe.append(rectWidth[i] - 1 - int(rangeOffsets2[i]))
|
||||
ys.append(0 - int(azimuthOffsets2[i]))
|
||||
ye.append(rectLength[i] - 1 - int(azimuthOffsets2[i]))
|
||||
|
||||
(xmin, xminIndex) = min((v,i) for i,v in enumerate(xs))
|
||||
(xmax, xmaxIndex) = max((v,i) for i,v in enumerate(xe))
|
||||
(ymin, yminIndex) = min((v,i) for i,v in enumerate(ys))
|
||||
(ymax, ymaxIndex) = max((v,i) for i,v in enumerate(ye))
|
||||
|
||||
outWidth = xmax - xmin + 1
|
||||
outLength = ymax - ymin + 1
|
||||
|
||||
#update frame parameters
|
||||
#mosaic size
|
||||
track.numberOfSamples = outWidth
|
||||
track.numberOfLines = outLength
|
||||
#NOTE THAT WE ARE STILL USING SINGLE LOOK PARAMETERS HERE
|
||||
#range parameters
|
||||
track.startingRange = frames[0].startingRange + (int(rangeOffsets2[0]) - int(rangeOffsets2[xminIndex])) * numberOfRangeLooks * frames[0].rangePixelSize
|
||||
track.rangeSamplingRate = frames[0].rangeSamplingRate
|
||||
track.rangePixelSize = frames[0].rangePixelSize
|
||||
#azimuth parameters
|
||||
track.sensingStart = frames[0].sensingStart
|
||||
track.prf = frames[0].prf
|
||||
track.azimuthPixelSize = frames[0].azimuthPixelSize
|
||||
track.azimuthLineInterval = frames[0].azimuthLineInterval
|
||||
|
||||
|
||||
def readImageFromVrt(inputfile, startSample, endSample, startLine, endLine):
|
||||
'''
|
||||
read a chunk of image
|
||||
the indexes (startSample, endSample, startLine, endLine) are included and start with zero
|
||||
|
||||
memmap is not used, because it is much slower
|
||||
|
||||
tested against readImage in runSwathMosaic.py
|
||||
'''
|
||||
import os
|
||||
from isceobj.Alos2Proc.Alos2ProcPublic import find_vrt_keyword
|
||||
from isceobj.Alos2Proc.Alos2ProcPublic import find_vrt_file
|
||||
|
||||
inputimage = find_vrt_file(inputfile+'.vrt', 'SourceFilename', relative_path=True)
|
||||
byteorder = find_vrt_keyword(inputfile+'.vrt', 'ByteOrder')
|
||||
if byteorder == 'LSB':
|
||||
swapByte = False
|
||||
else:
|
||||
swapByte = True
|
||||
imageoffset = int(find_vrt_keyword(inputfile+'.vrt', 'ImageOffset'))
|
||||
lineoffset = int(find_vrt_keyword(inputfile+'.vrt', 'LineOffset'))
|
||||
|
||||
data = np.zeros((endLine-startLine+1, endSample-startSample+1), dtype=np.complex64)
|
||||
with open(inputimage,'rb') as fp:
|
||||
#fp.seek(imageoffset, 0)
|
||||
#for i in range(endLine-startLine+1):
|
||||
for i in range(startLine, endLine+1):
|
||||
fp.seek(imageoffset+i*lineoffset+startSample*8, 0)
|
||||
if swapByte:
|
||||
tmp = np.fromfile(fp, dtype='>f', count=2*(endSample-startSample+1))
|
||||
cJ = np.complex64(1j)
|
||||
data[i-startLine] = tmp[0::2] + cJ * tmp[1::2]
|
||||
else:
|
||||
data[i-startLine] = np.fromfile(fp, dtype=np.complex64, count=endSample-startSample+1)
|
||||
return data
|
||||
|
|
@ -0,0 +1,287 @@
|
|||
#
|
||||
# Author: Cunren Liang
|
||||
# Copyright 2015-present, NASA-JPL/Caltech
|
||||
#
|
||||
|
||||
import os
|
||||
import logging
|
||||
|
||||
import isceobj
|
||||
|
||||
logger = logging.getLogger('isce.alos2insar.runFrameOffset')
|
||||
|
||||
def runFrameOffset(self):
|
||||
'''estimate frame offsets.
|
||||
'''
|
||||
catalog = isceobj.Catalog.createCatalog(self._insar.procDoc.name)
|
||||
self.updateParamemetersFromUser()
|
||||
|
||||
masterTrack = self._insar.loadTrack(master=True)
|
||||
slaveTrack = self._insar.loadTrack(master=False)
|
||||
|
||||
mosaicDir = 'insar'
|
||||
if not os.path.exists(mosaicDir):
|
||||
os.makedirs(mosaicDir)
|
||||
os.chdir(mosaicDir)
|
||||
|
||||
if len(masterTrack.frames) > 1:
|
||||
if (self._insar.modeCombination == 21) or \
|
||||
(self._insar.modeCombination == 22) or \
|
||||
(self._insar.modeCombination == 31) or \
|
||||
(self._insar.modeCombination == 32):
|
||||
matchingMode=0
|
||||
else:
|
||||
matchingMode=1
|
||||
|
||||
#compute swath offset
|
||||
offsetMaster = frameOffset(masterTrack, self._insar.masterSlc, self._insar.masterFrameOffset,
|
||||
crossCorrelation=self.frameOffsetMatching, matchingMode=matchingMode)
|
||||
#only use geometrical offset for slave
|
||||
offsetSlave = frameOffset(slaveTrack, self._insar.slaveSlc, self._insar.slaveFrameOffset,
|
||||
crossCorrelation=False, matchingMode=matchingMode)
|
||||
|
||||
self._insar.frameRangeOffsetGeometricalMaster = offsetMaster[0]
|
||||
self._insar.frameAzimuthOffsetGeometricalMaster = offsetMaster[1]
|
||||
self._insar.frameRangeOffsetGeometricalSlave = offsetSlave[0]
|
||||
self._insar.frameAzimuthOffsetGeometricalSlave = offsetSlave[1]
|
||||
if self.frameOffsetMatching:
|
||||
self._insar.frameRangeOffsetMatchingMaster = offsetMaster[2]
|
||||
self._insar.frameAzimuthOffsetMatchingMaster = offsetMaster[3]
|
||||
#self._insar.frameRangeOffsetMatchingSlave = offsetSlave[2]
|
||||
#self._insar.frameAzimuthOffsetMatchingSlave = offsetSlave[3]
|
||||
|
||||
|
||||
os.chdir('../')
|
||||
|
||||
catalog.printToLog(logger, "runFrameOffset")
|
||||
self._insar.procDoc.addAllFromCatalog(catalog)
|
||||
|
||||
|
||||
def frameOffset(track, image, outputfile, crossCorrelation=True, matchingMode=0):
|
||||
'''
|
||||
compute frame offset
|
||||
track: track object
|
||||
image: image for doing matching
|
||||
outputfile: output txt file for saving frame offset
|
||||
crossCorrelation: whether do matching
|
||||
matchingMode: how to match images. 0: ScanSAR full-aperture image, 1: regular image
|
||||
'''
|
||||
|
||||
rangeOffsetGeometrical = []
|
||||
azimuthOffsetGeometrical = []
|
||||
rangeOffsetMatching = []
|
||||
azimuthOffsetMatching = []
|
||||
|
||||
for j in range(len(track.frames)):
|
||||
frameNumber = track.frames[j].frameNumber
|
||||
swathNumber = track.frames[j].swaths[0].swathNumber
|
||||
swathDir = 'f{}_{}/s{}'.format(j+1, frameNumber, swathNumber)
|
||||
|
||||
print('estimate offset frame {}'.format(frameNumber))
|
||||
|
||||
if j == 0:
|
||||
rangeOffsetGeometrical.append(0.0)
|
||||
azimuthOffsetGeometrical.append(0.0)
|
||||
rangeOffsetMatching.append(0.0)
|
||||
azimuthOffsetMatching.append(0.0)
|
||||
swathDirLast = swathDir
|
||||
continue
|
||||
|
||||
image1 = os.path.join('../', swathDirLast, image)
|
||||
image2 = os.path.join('../', swathDir, image)
|
||||
#swath1 = frame.swaths[j-1]
|
||||
#swath2 = frame.swaths[j]
|
||||
swath1 = track.frames[j-1].swaths[0]
|
||||
swath2 = track.frames[j].swaths[0]
|
||||
|
||||
|
||||
#offset from geometry
|
||||
offsetGeometrical = computeFrameOffset(swath1, swath2)
|
||||
rangeOffsetGeometrical.append(offsetGeometrical[0])
|
||||
azimuthOffsetGeometrical.append(offsetGeometrical[1])
|
||||
|
||||
#offset from cross-correlation
|
||||
if crossCorrelation:
|
||||
offsetMatching = estimateFrameOffset(swath1, swath2, image1, image2, matchingMode=matchingMode)
|
||||
if offsetMatching != None:
|
||||
rangeOffsetMatching.append(offsetMatching[0])
|
||||
azimuthOffsetMatching.append(offsetMatching[1])
|
||||
else:
|
||||
print('******************************************************************')
|
||||
print('WARNING: bad matching offset, we are forced to use')
|
||||
print(' geometrical offset for frame mosaicking')
|
||||
print('******************************************************************')
|
||||
rangeOffsetMatching.append(offsetGeometrical[0])
|
||||
azimuthOffsetMatching.append(offsetGeometrical[1])
|
||||
|
||||
swathDirLast = swathDir
|
||||
|
||||
|
||||
if crossCorrelation:
|
||||
offsetComp = "\n\ncomparision of offsets:\n\n"
|
||||
offsetComp += "offset type i geometrical match difference\n"
|
||||
offsetComp += "+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++\n"
|
||||
for i, (offset1, offset2) in enumerate(zip(rangeOffsetGeometrical, rangeOffsetMatching)):
|
||||
offsetComp += "range offset {:2d} {:13.3f} {:13.3f} {:13.3f}\n".format(i, offset1, offset2, offset1 - offset2)
|
||||
for i, (offset1, offset2) in enumerate(zip(azimuthOffsetGeometrical, azimuthOffsetMatching)):
|
||||
offsetComp += "azimuth offset {:2d} {:13.3f} {:13.3f} {:13.3f}\n".format(i, offset1, offset2, offset1 - offset2)
|
||||
|
||||
#write and report offsets
|
||||
with open(outputfile, 'w') as f:
|
||||
f.write(offsetComp)
|
||||
print("{}".format(offsetComp))
|
||||
|
||||
|
||||
if crossCorrelation:
|
||||
return (rangeOffsetGeometrical, azimuthOffsetGeometrical, rangeOffsetMatching, azimuthOffsetMatching)
|
||||
else:
|
||||
return (rangeOffsetGeometrical, azimuthOffsetGeometrical)
|
||||
|
||||
|
||||
def computeFrameOffset(swath1, swath2):
|
||||
|
||||
rangeOffset = -(swath2.startingRange - swath1.startingRange) / swath1.rangePixelSize
|
||||
azimuthOffset = -((swath2.sensingStart - swath1.sensingStart).total_seconds()) / swath1.azimuthLineInterval
|
||||
|
||||
return (rangeOffset, azimuthOffset)
|
||||
|
||||
|
||||
def estimateFrameOffset(swath1, swath2, image1, image2, matchingMode=0):
|
||||
'''
|
||||
estimate offset of two adjacent frames using matching
|
||||
matchingMode: 0: ScanSAR full-aperture image
|
||||
1: regular image
|
||||
'''
|
||||
import isceobj
|
||||
from isceobj.Alos2Proc.Alos2ProcPublic import cullOffsets
|
||||
from isceobj.Alos2Proc.Alos2ProcPublic import cullOffsetsRoipac
|
||||
from isceobj.Alos2Proc.Alos2ProcPublic import meanOffset
|
||||
from mroipac.ampcor.Ampcor import Ampcor
|
||||
|
||||
##########################################
|
||||
#2. match using ampcor
|
||||
##########################################
|
||||
ampcor = Ampcor(name='insarapp_slcs_ampcor')
|
||||
ampcor.configure()
|
||||
|
||||
#mSLC = isceobj.createSlcImage()
|
||||
mSLC = isceobj.createImage()
|
||||
mSLC.load(image1+'.xml')
|
||||
mSLC.setFilename(image1)
|
||||
#mSLC.extraFilename = image1 + '.vrt'
|
||||
mSLC.setAccessMode('read')
|
||||
mSLC.createImage()
|
||||
|
||||
#sSLC = isceobj.createSlcImage()
|
||||
sSLC = isceobj.createImage()
|
||||
sSLC.load(image2+'.xml')
|
||||
sSLC.setFilename(image2)
|
||||
#sSLC.extraFilename = image2 + '.vrt'
|
||||
sSLC.setAccessMode('read')
|
||||
sSLC.createImage()
|
||||
|
||||
if mSLC.dataType.upper() == 'CFLOAT':
|
||||
ampcor.setImageDataType1('complex')
|
||||
ampcor.setImageDataType2('complex')
|
||||
elif mSLC.dataType.upper() == 'FLOAT':
|
||||
ampcor.setImageDataType1('real')
|
||||
ampcor.setImageDataType2('real')
|
||||
else:
|
||||
raise Exception('file type not supported yet.')
|
||||
|
||||
ampcor.setMasterSlcImage(mSLC)
|
||||
ampcor.setSlaveSlcImage(sSLC)
|
||||
|
||||
#MATCH REGION
|
||||
#compute an offset at image center to use
|
||||
rgoff = -(swath2.startingRange - swath1.startingRange) / swath1.rangePixelSize
|
||||
azoff = -((swath2.sensingStart - swath1.sensingStart).total_seconds()) / swath1.azimuthLineInterval
|
||||
rgoff = int(rgoff)
|
||||
azoff = int(azoff)
|
||||
#it seems that we cannot use 0, haven't look into the problem
|
||||
if rgoff == 0:
|
||||
rgoff = 1
|
||||
if azoff == 0:
|
||||
azoff = 1
|
||||
firstSample = 1
|
||||
if rgoff < 0:
|
||||
firstSample = int(35 - rgoff)
|
||||
firstLine = 1
|
||||
if azoff < 0:
|
||||
firstLine = int(35 - azoff)
|
||||
ampcor.setAcrossGrossOffset(rgoff)
|
||||
ampcor.setDownGrossOffset(azoff)
|
||||
ampcor.setFirstSampleAcross(firstSample)
|
||||
ampcor.setLastSampleAcross(mSLC.width)
|
||||
ampcor.setNumberLocationAcross(30)
|
||||
ampcor.setFirstSampleDown(firstLine)
|
||||
ampcor.setLastSampleDown(mSLC.length)
|
||||
ampcor.setNumberLocationDown(10)
|
||||
|
||||
#MATCH PARAMETERS
|
||||
#full-aperture mode
|
||||
if matchingMode==0:
|
||||
ampcor.setWindowSizeWidth(64)
|
||||
ampcor.setWindowSizeHeight(512)
|
||||
#note this is the half width/length of search area, number of resulting correlation samples: 32*2+1
|
||||
ampcor.setSearchWindowSizeWidth(32)
|
||||
ampcor.setSearchWindowSizeHeight(32)
|
||||
#triggering full-aperture mode matching
|
||||
ampcor.setWinsizeFilt(8)
|
||||
ampcor.setOversamplingFactorFilt(64)
|
||||
#regular mode
|
||||
else:
|
||||
ampcor.setWindowSizeWidth(64)
|
||||
ampcor.setWindowSizeHeight(64)
|
||||
ampcor.setSearchWindowSizeWidth(32)
|
||||
ampcor.setSearchWindowSizeHeight(32)
|
||||
|
||||
#REST OF THE STUFF
|
||||
ampcor.setAcrossLooks(1)
|
||||
ampcor.setDownLooks(1)
|
||||
ampcor.setOversamplingFactor(64)
|
||||
ampcor.setZoomWindowSize(16)
|
||||
#1. The following not set
|
||||
#Matching Scale for Sample/Line Directions (-) = 1. 1.
|
||||
#should add the following in Ampcor.py?
|
||||
#if not set, in this case, Ampcor.py'value is also 1. 1.
|
||||
#ampcor.setScaleFactorX(1.)
|
||||
#ampcor.setScaleFactorY(1.)
|
||||
|
||||
#MATCH THRESHOLDS AND DEBUG DATA
|
||||
#2. The following not set
|
||||
#in roi_pac the value is set to 0 1
|
||||
#in isce the value is set to 0.001 1000.0
|
||||
#SNR and Covariance Thresholds (-) = {s1} {s2}
|
||||
#should add the following in Ampcor?
|
||||
#THIS SHOULD BE THE ONLY THING THAT IS DIFFERENT FROM THAT OF ROI_PAC
|
||||
#ampcor.setThresholdSNR(0)
|
||||
#ampcor.setThresholdCov(1)
|
||||
ampcor.setDebugFlag(False)
|
||||
ampcor.setDisplayFlag(False)
|
||||
|
||||
#in summary, only two things not set which are indicated by 'The following not set' above.
|
||||
|
||||
#run ampcor
|
||||
ampcor.ampcor()
|
||||
offsets = ampcor.getOffsetField()
|
||||
#ampcorOffsetFile = 'ampcor.off'
|
||||
#writeOffset(offsets, ampcorOffsetFile)
|
||||
|
||||
#finalize image, and re-create it
|
||||
#otherwise the file pointer is still at the end of the image
|
||||
mSLC.finalizeImage()
|
||||
sSLC.finalizeImage()
|
||||
|
||||
|
||||
#############################################
|
||||
#3. cull offsets
|
||||
#############################################
|
||||
#refinedOffsets = cullOffsets(offsets)
|
||||
refinedOffsets = cullOffsetsRoipac(offsets, numThreshold=50)
|
||||
|
||||
if refinedOffsets != None:
|
||||
rangeOffset, azimuthOffset = meanOffset(refinedOffsets)
|
||||
return (rangeOffset, azimuthOffset)
|
||||
else:
|
||||
return None
|
||||
|
|
@ -0,0 +1,190 @@
|
|||
#
|
||||
# Author: Cunren Liang
|
||||
# Copyright 2015-present, NASA-JPL/Caltech
|
||||
#
|
||||
|
||||
import os
|
||||
import logging
|
||||
|
||||
import isceobj
|
||||
|
||||
logger = logging.getLogger('isce.alos2insar.runGeo2Rdr')
|
||||
|
||||
def runGeo2Rdr(self):
|
||||
'''compute range and azimuth offsets
|
||||
'''
|
||||
catalog = isceobj.Catalog.createCatalog(self._insar.procDoc.name)
|
||||
self.updateParamemetersFromUser()
|
||||
|
||||
slaveTrack = self._insar.loadTrack(master=False)
|
||||
|
||||
insarDir = 'insar'
|
||||
if not os.path.exists(insarDir):
|
||||
os.makedirs(insarDir)
|
||||
os.chdir(insarDir)
|
||||
|
||||
|
||||
hasGPU= self.useGPU and self._insar.hasGPU()
|
||||
if hasGPU:
|
||||
geo2RdrGPU(slaveTrack, self._insar.numberRangeLooks1, self._insar.numberAzimuthLooks1,
|
||||
self._insar.latitude, self._insar.longitude, self._insar.height, self._insar.rangeOffset, self._insar.azimuthOffset)
|
||||
else:
|
||||
geo2RdrCPU(slaveTrack, self._insar.numberRangeLooks1, self._insar.numberAzimuthLooks1,
|
||||
self._insar.latitude, self._insar.longitude, self._insar.height, self._insar.rangeOffset, self._insar.azimuthOffset)
|
||||
|
||||
os.chdir('../')
|
||||
|
||||
catalog.printToLog(logger, "runGeo2Rdr")
|
||||
self._insar.procDoc.addAllFromCatalog(catalog)
|
||||
|
||||
|
||||
def geo2RdrCPU(slaveTrack, numberRangeLooks, numberAzimuthLooks, latFile, lonFile, hgtFile, rangeOffsetFile, azimuthOffsetFile):
|
||||
import datetime
|
||||
from zerodop.geo2rdr import createGeo2rdr
|
||||
from isceobj.Planet.Planet import Planet
|
||||
|
||||
pointingDirection = {'right': -1, 'left' :1}
|
||||
|
||||
latImage = isceobj.createImage()
|
||||
latImage.load(latFile + '.xml')
|
||||
latImage.setAccessMode('read')
|
||||
|
||||
lonImage = isceobj.createImage()
|
||||
lonImage.load(lonFile + '.xml')
|
||||
lonImage.setAccessMode('read')
|
||||
|
||||
demImage = isceobj.createDemImage()
|
||||
demImage.load(hgtFile + '.xml')
|
||||
demImage.setAccessMode('read')
|
||||
|
||||
planet = Planet(pname='Earth')
|
||||
|
||||
topo = createGeo2rdr()
|
||||
topo.configure()
|
||||
#set parameters
|
||||
topo.slantRangePixelSpacing = numberRangeLooks * slaveTrack.rangePixelSize
|
||||
topo.prf = 1.0 / (numberAzimuthLooks*slaveTrack.azimuthLineInterval)
|
||||
topo.radarWavelength = slaveTrack.radarWavelength
|
||||
topo.orbit = slaveTrack.orbit
|
||||
topo.width = slaveTrack.numberOfSamples
|
||||
topo.length = slaveTrack.numberOfLines
|
||||
topo.demLength = demImage.length
|
||||
topo.demWidth = demImage.width
|
||||
topo.wireInputPort(name='planet', object=planet)
|
||||
topo.numberRangeLooks = 1 #
|
||||
topo.numberAzimuthLooks = 1 # must be set to be 1
|
||||
topo.lookSide = pointingDirection[slaveTrack.pointingDirection]
|
||||
topo.setSensingStart(slaveTrack.sensingStart + datetime.timedelta(seconds=(numberAzimuthLooks-1.0)/2.0*slaveTrack.azimuthLineInterval))
|
||||
topo.rangeFirstSample = slaveTrack.startingRange + (numberRangeLooks-1.0)/2.0*slaveTrack.rangePixelSize
|
||||
topo.dopplerCentroidCoeffs = [0.] # we are using zero doppler geometry
|
||||
#set files
|
||||
topo.latImage = latImage
|
||||
topo.lonImage = lonImage
|
||||
topo.demImage = demImage
|
||||
topo.rangeOffsetImageName = rangeOffsetFile
|
||||
topo.azimuthOffsetImageName = azimuthOffsetFile
|
||||
#run it
|
||||
topo.geo2rdr()
|
||||
|
||||
return
|
||||
|
||||
|
||||
def geo2RdrGPU(slaveTrack, numberRangeLooks, numberAzimuthLooks, latFile, lonFile, hgtFile, rangeOffsetFile, azimuthOffsetFile):
|
||||
'''
|
||||
currently we cannot set left/right looking.
|
||||
works for right looking, but left looking probably not supported.
|
||||
'''
|
||||
|
||||
import datetime
|
||||
from zerodop.GPUgeo2rdr.GPUgeo2rdr import PyGeo2rdr
|
||||
from isceobj.Planet.Planet import Planet
|
||||
from iscesys import DateTimeUtil as DTU
|
||||
|
||||
latImage = isceobj.createImage()
|
||||
latImage.load(latFile + '.xml')
|
||||
latImage.setAccessMode('READ')
|
||||
latImage.createImage()
|
||||
|
||||
lonImage = isceobj.createImage()
|
||||
lonImage.load(lonFile + '.xml')
|
||||
lonImage.setAccessMode('READ')
|
||||
lonImage.createImage()
|
||||
|
||||
demImage = isceobj.createImage()
|
||||
demImage.load(hgtFile + '.xml')
|
||||
demImage.setAccessMode('READ')
|
||||
demImage.createImage()
|
||||
|
||||
#####Run Geo2rdr
|
||||
planet = Planet(pname='Earth')
|
||||
grdr = PyGeo2rdr()
|
||||
|
||||
grdr.setRangePixelSpacing(numberRangeLooks * slaveTrack.rangePixelSize)
|
||||
grdr.setPRF(1.0 / (numberAzimuthLooks*slaveTrack.azimuthLineInterval))
|
||||
grdr.setRadarWavelength(slaveTrack.radarWavelength)
|
||||
|
||||
#CHECK IF THIS WORKS!!!
|
||||
grdr.createOrbit(0, len(slaveTrack.orbit.stateVectors.list))
|
||||
count = 0
|
||||
for sv in slaveTrack.orbit.stateVectors.list:
|
||||
td = DTU.seconds_since_midnight(sv.getTime())
|
||||
pos = sv.getPosition()
|
||||
vel = sv.getVelocity()
|
||||
|
||||
grdr.setOrbitVector(count, td, pos[0], pos[1], pos[2], vel[0], vel[1], vel[2])
|
||||
count += 1
|
||||
|
||||
grdr.setOrbitMethod(0)
|
||||
grdr.setWidth(slaveTrack.numberOfSamples)
|
||||
grdr.setLength(slaveTrack.numberOfLines)
|
||||
grdr.setSensingStart(DTU.seconds_since_midnight(slaveTrack.sensingStart + datetime.timedelta(seconds=(numberAzimuthLooks-1.0)/2.0*slaveTrack.azimuthLineInterval)))
|
||||
grdr.setRangeFirstSample(slaveTrack.startingRange + (numberRangeLooks-1.0)/2.0*slaveTrack.rangePixelSize)
|
||||
grdr.setNumberRangeLooks(1)
|
||||
grdr.setNumberAzimuthLooks(1)
|
||||
grdr.setEllipsoidMajorSemiAxis(planet.ellipsoid.a)
|
||||
grdr.setEllipsoidEccentricitySquared(planet.ellipsoid.e2)
|
||||
|
||||
|
||||
grdr.createPoly(0, 0., 1.)
|
||||
grdr.setPolyCoeff(0, 0.)
|
||||
|
||||
grdr.setDemLength(demImage.getLength())
|
||||
grdr.setDemWidth(demImage.getWidth())
|
||||
grdr.setBistaticFlag(0)
|
||||
|
||||
rangeOffsetImage = isceobj.createImage()
|
||||
rangeOffsetImage.setFilename(rangeOffsetFile)
|
||||
rangeOffsetImage.setAccessMode('write')
|
||||
rangeOffsetImage.setDataType('FLOAT')
|
||||
rangeOffsetImage.setCaster('write', 'DOUBLE')
|
||||
rangeOffsetImage.setWidth(demImage.width)
|
||||
rangeOffsetImage.createImage()
|
||||
|
||||
azimuthOffsetImage = isceobj.createImage()
|
||||
azimuthOffsetImage.setFilename(azimuthOffsetFile)
|
||||
azimuthOffsetImage.setAccessMode('write')
|
||||
azimuthOffsetImage.setDataType('FLOAT')
|
||||
azimuthOffsetImage.setCaster('write', 'DOUBLE')
|
||||
azimuthOffsetImage.setWidth(demImage.width)
|
||||
azimuthOffsetImage.createImage()
|
||||
|
||||
grdr.setLatAccessor(latImage.getImagePointer())
|
||||
grdr.setLonAccessor(lonImage.getImagePointer())
|
||||
grdr.setHgtAccessor(demImage.getImagePointer())
|
||||
grdr.setAzAccessor(0)
|
||||
grdr.setRgAccessor(0)
|
||||
grdr.setAzOffAccessor(azimuthOffsetImage.getImagePointer())
|
||||
grdr.setRgOffAccessor(rangeOffsetImage.getImagePointer())
|
||||
|
||||
grdr.geo2rdr()
|
||||
|
||||
rangeOffsetImage.finalizeImage()
|
||||
rangeOffsetImage.renderHdr()
|
||||
|
||||
azimuthOffsetImage.finalizeImage()
|
||||
azimuthOffsetImage.renderHdr()
|
||||
latImage.finalizeImage()
|
||||
lonImage.finalizeImage()
|
||||
demImage.finalizeImage()
|
||||
|
||||
return
|
||||
|
|
@ -0,0 +1,124 @@
|
|||
#
|
||||
# Author: Cunren Liang
|
||||
# Copyright 2015-present, NASA-JPL/Caltech
|
||||
#
|
||||
|
||||
import os
|
||||
import logging
|
||||
import numpy as np
|
||||
|
||||
import isceobj
|
||||
from isceobj.Alos2Proc.Alos2ProcPublic import getBboxGeo
|
||||
|
||||
logger = logging.getLogger('isce.alos2insar.runGeocode')
|
||||
|
||||
def runGeocode(self):
|
||||
'''geocode final products
|
||||
'''
|
||||
catalog = isceobj.Catalog.createCatalog(self._insar.procDoc.name)
|
||||
self.updateParamemetersFromUser()
|
||||
|
||||
masterTrack = self._insar.loadTrack(master=True)
|
||||
#slaveTrack = self._insar.loadTrack(master=False)
|
||||
|
||||
demFile = os.path.abspath(self._insar.demGeo)
|
||||
|
||||
insarDir = 'insar'
|
||||
if not os.path.exists(insarDir):
|
||||
os.makedirs(insarDir)
|
||||
os.chdir(insarDir)
|
||||
|
||||
#compute bounding box for geocoding
|
||||
if self.bbox == None:
|
||||
bbox = getBboxGeo(masterTrack)
|
||||
else:
|
||||
bbox = self.bbox
|
||||
catalog.addItem('geocode bounding box', bbox, 'runGeocode')
|
||||
|
||||
if self.geocodeList == None:
|
||||
geocodeList = [self._insar.unwrappedInterferogram,
|
||||
self._insar.unwrappedMaskedInterferogram,
|
||||
self._insar.multilookCoherence,
|
||||
self._insar.multilookLos]
|
||||
if self.doIon:
|
||||
geocodeList.append(self._insar.multilookIon)
|
||||
else:
|
||||
geocodeList = self.geocodeList
|
||||
|
||||
numberRangeLooks = self._insar.numberRangeLooks1 * self._insar.numberRangeLooks2
|
||||
numberAzimuthLooks = self._insar.numberAzimuthLooks1 * self._insar.numberAzimuthLooks2
|
||||
|
||||
for inputFile in geocodeList:
|
||||
if self.geocodeInterpMethod == None:
|
||||
img = isceobj.createImage()
|
||||
img.load(inputFile + '.xml')
|
||||
if img.dataType.upper() == 'CFLOAT':
|
||||
interpMethod = 'sinc'
|
||||
else:
|
||||
interpMethod = 'bilinear'
|
||||
else:
|
||||
interpMethod = self.geocodeInterpMethod.lower()
|
||||
|
||||
geocode(masterTrack, demFile, inputFile, bbox, numberRangeLooks, numberAzimuthLooks, interpMethod, 0, 0)
|
||||
|
||||
|
||||
os.chdir('../')
|
||||
|
||||
catalog.printToLog(logger, "runGeocode")
|
||||
self._insar.procDoc.addAllFromCatalog(catalog)
|
||||
|
||||
|
||||
def geocode(track, demFile, inputFile, bbox, numberRangeLooks, numberAzimuthLooks, interpMethod, topShift, leftShift, addMultilookOffset=True):
|
||||
import datetime
|
||||
from zerodop.geozero import createGeozero
|
||||
from isceobj.Planet.Planet import Planet
|
||||
|
||||
pointingDirection = {'right': -1, 'left' :1}
|
||||
|
||||
demImage = isceobj.createDemImage()
|
||||
demImage.load(demFile + '.xml')
|
||||
demImage.setAccessMode('read')
|
||||
|
||||
inImage = isceobj.createImage()
|
||||
inImage.load(inputFile + '.xml')
|
||||
inImage.setAccessMode('read')
|
||||
|
||||
planet = Planet(pname='Earth')
|
||||
|
||||
topo = createGeozero()
|
||||
topo.configure()
|
||||
topo.slantRangePixelSpacing = numberRangeLooks * track.rangePixelSize
|
||||
topo.prf = 1.0 / (numberAzimuthLooks*track.azimuthLineInterval)
|
||||
topo.radarWavelength = track.radarWavelength
|
||||
topo.orbit = track.orbit
|
||||
topo.width = inImage.width
|
||||
topo.length = inImage.length
|
||||
topo.wireInputPort(name='dem', object=demImage)
|
||||
topo.wireInputPort(name='planet', object=planet)
|
||||
topo.wireInputPort(name='tobegeocoded', object=inImage)
|
||||
topo.numberRangeLooks = 1
|
||||
topo.numberAzimuthLooks = 1
|
||||
topo.lookSide = pointingDirection[track.pointingDirection]
|
||||
sensingStart = track.sensingStart + datetime.timedelta(seconds=topShift*track.azimuthLineInterval)
|
||||
rangeFirstSample = track.startingRange + leftShift * track.rangePixelSize
|
||||
if addMultilookOffset:
|
||||
sensingStart += datetime.timedelta(seconds=(numberAzimuthLooks-1.0)/2.0*track.azimuthLineInterval)
|
||||
rangeFirstSample += (numberRangeLooks-1.0)/2.0*track.rangePixelSize
|
||||
topo.setSensingStart(sensingStart)
|
||||
topo.rangeFirstSample = rangeFirstSample
|
||||
topo.method=interpMethod
|
||||
topo.demCropFilename = 'crop.dem'
|
||||
#looks like this does not work
|
||||
#topo.geoFilename = outputName
|
||||
topo.dopplerCentroidCoeffs = [0.]
|
||||
#snwe list <class 'list'>
|
||||
topo.snwe = bbox
|
||||
|
||||
topo.geocode()
|
||||
|
||||
print('South: ', topo.minimumGeoLatitude)
|
||||
print('North: ', topo.maximumGeoLatitude)
|
||||
print('West: ', topo.minimumGeoLongitude)
|
||||
print('East: ', topo.maximumGeoLongitude)
|
||||
|
||||
return
|
||||
|
|
@ -0,0 +1,64 @@
|
|||
#
|
||||
# Author: Cunren Liang
|
||||
# Copyright 2015-present, NASA-JPL/Caltech
|
||||
#
|
||||
|
||||
import os
|
||||
import logging
|
||||
import numpy as np
|
||||
|
||||
import isceobj
|
||||
from isceobj.Alos2Proc.runGeocode import geocode
|
||||
from isceobj.Alos2Proc.Alos2ProcPublic import getBboxGeo
|
||||
|
||||
logger = logging.getLogger('isce.alos2insar.runGeocodeOffset')
|
||||
|
||||
def runGeocodeOffset(self):
|
||||
'''geocode offset fied
|
||||
'''
|
||||
if not self.doDenseOffset:
|
||||
return
|
||||
if not ((self._insar.modeCombination == 0) or (self._insar.modeCombination == 1)):
|
||||
return
|
||||
|
||||
catalog = isceobj.Catalog.createCatalog(self._insar.procDoc.name)
|
||||
self.updateParamemetersFromUser()
|
||||
|
||||
#use original track object to determine bbox
|
||||
if self.bbox == None:
|
||||
masterTrack = self._insar.loadTrack(master=True)
|
||||
bbox = getBboxGeo(masterTrack)
|
||||
else:
|
||||
bbox = self.bbox
|
||||
catalog.addItem('geocode bounding box', bbox, 'runGeocodeOffset')
|
||||
|
||||
demFile = os.path.abspath(self._insar.demGeo)
|
||||
|
||||
denseOffsetDir = 'dense_offset'
|
||||
if not os.path.exists(denseOffsetDir):
|
||||
os.makedirs(denseOffsetDir)
|
||||
os.chdir(denseOffsetDir)
|
||||
|
||||
masterTrack = self._insar.loadProduct(self._insar.masterTrackParameter)
|
||||
#slaveTrack = self._insar.loadProduct(self._insar.slaveTrackParameter)
|
||||
|
||||
#########################################################################################
|
||||
#compute bounding box for geocoding
|
||||
#if self.bbox == None:
|
||||
# bbox = getBboxGeo(masterTrack)
|
||||
#else:
|
||||
# bbox = self.bbox
|
||||
#catalog.addItem('geocode bounding box', bbox, 'runGeocodeOffset')
|
||||
|
||||
geocodeList = [self._insar.denseOffset, self._insar.denseOffsetSnr]
|
||||
if self.doOffsetFiltering:
|
||||
geocodeList.append(self._insar.denseOffsetFilt)
|
||||
|
||||
for inputFile in geocodeList:
|
||||
interpMethod = 'nearest'
|
||||
geocode(masterTrack, demFile, inputFile, bbox, self.offsetSkipWidth, self.offsetSkipHeight, interpMethod, self._insar.offsetImageTopoffset, self._insar.offsetImageLeftoffset, addMultilookOffset=False)
|
||||
#########################################################################################
|
||||
|
||||
os.chdir('../')
|
||||
catalog.printToLog(logger, "runGeocodeOffset")
|
||||
self._insar.procDoc.addAllFromCatalog(catalog)
|
||||
|
|
@ -0,0 +1,599 @@
|
|||
#
|
||||
# Author: Cunren Liang
|
||||
# Copyright 2015-present, NASA-JPL/Caltech
|
||||
#
|
||||
|
||||
import os
|
||||
import logging
|
||||
import numpy as np
|
||||
import numpy.matlib
|
||||
|
||||
import isceobj
|
||||
|
||||
logger = logging.getLogger('isce.alos2insar.runIonFilt')
|
||||
|
||||
def runIonFilt(self):
|
||||
'''compute and filter ionospheric phase
|
||||
'''
|
||||
catalog = isceobj.Catalog.createCatalog(self._insar.procDoc.name)
|
||||
self.updateParamemetersFromUser()
|
||||
|
||||
if not self.doIon:
|
||||
catalog.printToLog(logger, "runIonFilt")
|
||||
self._insar.procDoc.addAllFromCatalog(catalog)
|
||||
return
|
||||
|
||||
masterTrack = self._insar.loadTrack(master=True)
|
||||
slaveTrack = self._insar.loadTrack(master=False)
|
||||
|
||||
from isceobj.Alos2Proc.runIonSubband import defineIonDir
|
||||
ionDir = defineIonDir()
|
||||
subbandPrefix = ['lower', 'upper']
|
||||
|
||||
ionCalDir = os.path.join(ionDir['ion'], ionDir['ionCal'])
|
||||
if not os.path.exists(ionCalDir):
|
||||
os.makedirs(ionCalDir)
|
||||
os.chdir(ionCalDir)
|
||||
|
||||
|
||||
############################################################
|
||||
# STEP 1. compute ionospheric phase
|
||||
############################################################
|
||||
from isceobj.Constants import SPEED_OF_LIGHT
|
||||
from isceobj.Alos2Proc.Alos2ProcPublic import create_xml
|
||||
|
||||
###################################
|
||||
#SET PARAMETERS HERE
|
||||
#THESE SHOULD BE GOOD ENOUGH, NO NEED TO SET IN setup(self)
|
||||
corThresholdAdj = 0.85
|
||||
###################################
|
||||
|
||||
print('\ncomputing ionosphere')
|
||||
#get files
|
||||
ml2 = '_{}rlks_{}alks'.format(self._insar.numberRangeLooks1*self._insar.numberRangeLooksIon,
|
||||
self._insar.numberAzimuthLooks1*self._insar.numberAzimuthLooksIon)
|
||||
|
||||
lowerUnwfile = subbandPrefix[0]+ml2+'.unw'
|
||||
upperUnwfile = subbandPrefix[1]+ml2+'.unw'
|
||||
corfile = 'diff'+ml2+'.cor'
|
||||
|
||||
#use image size from lower unwrapped interferogram
|
||||
img = isceobj.createImage()
|
||||
img.load(lowerUnwfile + '.xml')
|
||||
width = img.width
|
||||
length = img.length
|
||||
|
||||
lowerUnw = (np.fromfile(lowerUnwfile, dtype=np.float32).reshape(length*2, width))[1:length*2:2, :]
|
||||
upperUnw = (np.fromfile(upperUnwfile, dtype=np.float32).reshape(length*2, width))[1:length*2:2, :]
|
||||
cor = (np.fromfile(corfile, dtype=np.float32).reshape(length*2, width))[1:length*2:2, :]
|
||||
#amp = (np.fromfile(corfile, dtype=np.float32).reshape(length*2, width))[0:length*2:2, :]
|
||||
|
||||
#masked out user-specified areas
|
||||
if self.maskedAreasIon != None:
|
||||
maskedAreas = reformatMaskedAreas(self.maskedAreasIon, length, width)
|
||||
for area in maskedAreas:
|
||||
lowerUnw[area[0]:area[1], area[2]:area[3]] = 0
|
||||
upperUnw[area[0]:area[1], area[2]:area[3]] = 0
|
||||
cor[area[0]:area[1], area[2]:area[3]] = 0
|
||||
|
||||
#compute ionosphere
|
||||
fl = SPEED_OF_LIGHT / self._insar.subbandRadarWavelength[0]
|
||||
fu = SPEED_OF_LIGHT / self._insar.subbandRadarWavelength[1]
|
||||
adjFlag = 1
|
||||
ionos = computeIonosphere(lowerUnw, upperUnw, cor, fl, fu, adjFlag, corThresholdAdj, 0)
|
||||
|
||||
#dump ionosphere
|
||||
ionfile = 'ion'+ml2+'.ion'
|
||||
# ion = np.zeros((length*2, width), dtype=np.float32)
|
||||
# ion[0:length*2:2, :] = amp
|
||||
# ion[1:length*2:2, :] = ionos
|
||||
# ion.astype(np.float32).tofile(ionfile)
|
||||
# img.filename = ionfile
|
||||
# img.extraFilename = ionfile + '.vrt'
|
||||
# img.renderHdr()
|
||||
|
||||
ionos.astype(np.float32).tofile(ionfile)
|
||||
create_xml(ionfile, width, length, 'float')
|
||||
|
||||
|
||||
############################################################
|
||||
# STEP 2. filter ionospheric phase
|
||||
############################################################
|
||||
|
||||
#################################################
|
||||
#SET PARAMETERS HERE
|
||||
#if applying polynomial fitting
|
||||
#False: no fitting, True: with fitting
|
||||
fit = self.fitIon
|
||||
#gaussian filtering window size
|
||||
size_max = self.filteringWinsizeMaxIon
|
||||
size_min = self.filteringWinsizeMinIon
|
||||
|
||||
#THESE SHOULD BE GOOD ENOUGH, NO NEED TO SET IN setup(self)
|
||||
corThresholdIon = 0.85
|
||||
#################################################
|
||||
|
||||
print('\nfiltering ionosphere')
|
||||
ionfile = 'ion'+ml2+'.ion'
|
||||
corfile = 'diff'+ml2+'.cor'
|
||||
ionfiltfile = 'filt_ion'+ml2+'.ion'
|
||||
|
||||
img = isceobj.createImage()
|
||||
img.load(ionfile + '.xml')
|
||||
width = img.width
|
||||
length = img.length
|
||||
#ion = (np.fromfile(ionfile, dtype=np.float32).reshape(length*2, width))[1:length*2:2, :]
|
||||
ion = np.fromfile(ionfile, dtype=np.float32).reshape(length, width)
|
||||
cor = (np.fromfile(corfile, dtype=np.float32).reshape(length*2, width))[1:length*2:2, :]
|
||||
#amp = (np.fromfile(ionfile, dtype=np.float32).reshape(length*2, width))[0:length*2:2, :]
|
||||
|
||||
#masked out user-specified areas
|
||||
if self.maskedAreasIon != None:
|
||||
maskedAreas = reformatMaskedAreas(self.maskedAreasIon, length, width)
|
||||
for area in maskedAreas:
|
||||
ion[area[0]:area[1], area[2]:area[3]] = 0
|
||||
cor[area[0]:area[1], area[2]:area[3]] = 0
|
||||
|
||||
#remove possible wired values in coherence
|
||||
cor[np.nonzero(cor<0)] = 0.0
|
||||
cor[np.nonzero(cor>1)] = 0.0
|
||||
|
||||
# #applying water body mask here
|
||||
# waterBodyFile = 'wbd'+ml2+'.wbd'
|
||||
# if os.path.isfile(waterBodyFile):
|
||||
# print('applying water body mask to coherence used to compute ionospheric phase')
|
||||
# wbd = np.fromfile(waterBodyFile, dtype=np.int8).reshape(length, width)
|
||||
# cor[np.nonzero(wbd!=0)] = 0.00001
|
||||
|
||||
if fit:
|
||||
ion_fit = weight_fitting(ion, cor, width, length, 1, 1, 1, 1, 2, corThresholdIon)
|
||||
ion -= ion_fit * (ion!=0)
|
||||
|
||||
#minimize the effect of low coherence pixels
|
||||
#cor[np.nonzero( (cor<0.85)*(cor!=0) )] = 0.00001
|
||||
#filt = adaptive_gaussian(ion, cor, size_max, size_min)
|
||||
#cor**14 should be a good weight to use. 22-APR-2018
|
||||
filt = adaptive_gaussian(ion, cor**14, size_max, size_min)
|
||||
|
||||
if fit:
|
||||
filt += ion_fit * (filt!=0)
|
||||
|
||||
# ion = np.zeros((length*2, width), dtype=np.float32)
|
||||
# ion[0:length*2:2, :] = amp
|
||||
# ion[1:length*2:2, :] = filt
|
||||
# ion.astype(np.float32).tofile(ionfiltfile)
|
||||
# img.filename = ionfiltfile
|
||||
# img.extraFilename = ionfiltfile + '.vrt'
|
||||
# img.renderHdr()
|
||||
|
||||
filt.astype(np.float32).tofile(ionfiltfile)
|
||||
create_xml(ionfiltfile, width, length, 'float')
|
||||
|
||||
|
||||
############################################################
|
||||
# STEP 3. resample ionospheric phase
|
||||
############################################################
|
||||
from contrib.alos2proc_f.alos2proc_f import rect
|
||||
from isceobj.Alos2Proc.Alos2ProcPublic import create_xml
|
||||
from scipy.interpolate import interp1d
|
||||
import shutil
|
||||
|
||||
#################################################
|
||||
#SET PARAMETERS HERE
|
||||
#interpolation method
|
||||
interpolationMethod = 1
|
||||
#################################################
|
||||
|
||||
print('\ninterpolate ionosphere')
|
||||
|
||||
ml3 = '_{}rlks_{}alks'.format(self._insar.numberRangeLooks1*self._insar.numberRangeLooks2,
|
||||
self._insar.numberAzimuthLooks1*self._insar.numberAzimuthLooks2)
|
||||
|
||||
ionfiltfile = 'filt_ion'+ml2+'.ion'
|
||||
#ionrectfile = 'filt_ion'+ml3+'.ion'
|
||||
ionrectfile = self._insar.multilookIon
|
||||
|
||||
img = isceobj.createImage()
|
||||
img.load(ionfiltfile + '.xml')
|
||||
width2 = img.width
|
||||
length2 = img.length
|
||||
|
||||
img = isceobj.createImage()
|
||||
img.load(os.path.join('../../', ionDir['insar'], self._insar.multilookDifferentialInterferogram) + '.xml')
|
||||
width3 = img.width
|
||||
length3 = img.length
|
||||
|
||||
#number of range looks output
|
||||
nrlo = self._insar.numberRangeLooks1*self._insar.numberRangeLooks2
|
||||
#number of range looks input
|
||||
nrli = self._insar.numberRangeLooks1*self._insar.numberRangeLooksIon
|
||||
#number of azimuth looks output
|
||||
nalo = self._insar.numberAzimuthLooks1*self._insar.numberAzimuthLooks2
|
||||
#number of azimuth looks input
|
||||
nali = self._insar.numberAzimuthLooks1*self._insar.numberAzimuthLooksIon
|
||||
|
||||
if (self._insar.numberRangeLooks2 != self._insar.numberRangeLooksIon) or \
|
||||
(self._insar.numberAzimuthLooks2 != self._insar.numberAzimuthLooksIon):
|
||||
#this should be faster using fortran
|
||||
if interpolationMethod == 0:
|
||||
rect(ionfiltfile, ionrectfile,
|
||||
width2,length2,
|
||||
width3,length3,
|
||||
nrlo/nrli, 0.0,
|
||||
0.0, nalo/nali,
|
||||
(nrlo-nrli)/(2.0*nrli),
|
||||
(nalo-nali)/(2.0*nali),
|
||||
'REAL','Bilinear')
|
||||
#finer, but slower method
|
||||
else:
|
||||
ionfilt = np.fromfile(ionfiltfile, dtype=np.float32).reshape(length2, width2)
|
||||
index2 = np.linspace(0, width2-1, num=width2, endpoint=True)
|
||||
index3 = np.linspace(0, width3-1, num=width3, endpoint=True) * nrlo/nrli + (nrlo-nrli)/(2.0*nrli)
|
||||
ionrect = np.zeros((length3, width3), dtype=np.float32)
|
||||
for i in range(length2):
|
||||
f = interp1d(index2, ionfilt[i,:], kind='cubic', fill_value="extrapolate")
|
||||
ionrect[i, :] = f(index3)
|
||||
|
||||
index2 = np.linspace(0, length2-1, num=length2, endpoint=True)
|
||||
index3 = np.linspace(0, length3-1, num=length3, endpoint=True) * nalo/nali + (nalo-nali)/(2.0*nali)
|
||||
for j in range(width3):
|
||||
f = interp1d(index2, ionrect[0:length2, j], kind='cubic', fill_value="extrapolate")
|
||||
ionrect[:, j] = f(index3)
|
||||
ionrect.astype(np.float32).tofile(ionrectfile)
|
||||
del ionrect
|
||||
create_xml(ionrectfile, width3, length3, 'float')
|
||||
|
||||
os.rename(ionrectfile, os.path.join('../../insar', ionrectfile))
|
||||
os.rename(ionrectfile+'.vrt', os.path.join('../../insar', ionrectfile)+'.vrt')
|
||||
os.rename(ionrectfile+'.xml', os.path.join('../../insar', ionrectfile)+'.xml')
|
||||
os.chdir('../../insar')
|
||||
else:
|
||||
shutil.copyfile(ionfiltfile, os.path.join('../../insar', ionrectfile))
|
||||
os.chdir('../../insar')
|
||||
create_xml(ionrectfile, width3, length3, 'float')
|
||||
#now we are in 'insar'
|
||||
|
||||
|
||||
############################################################
|
||||
# STEP 4. correct interferogram
|
||||
############################################################
|
||||
from isceobj.Alos2Proc.Alos2ProcPublic import renameFile
|
||||
from isceobj.Alos2Proc.Alos2ProcPublic import runCmd
|
||||
|
||||
if self.applyIon:
|
||||
print('\ncorrect interferogram')
|
||||
if os.path.isfile(self._insar.multilookDifferentialInterferogramOriginal):
|
||||
print('original interferogram: {} is already here, do not rename: {}'.format(self._insar.multilookDifferentialInterferogramOriginal, self._insar.multilookDifferentialInterferogram))
|
||||
else:
|
||||
print('renaming {} to {}'.format(self._insar.multilookDifferentialInterferogram, self._insar.multilookDifferentialInterferogramOriginal))
|
||||
renameFile(self._insar.multilookDifferentialInterferogram, self._insar.multilookDifferentialInterferogramOriginal)
|
||||
|
||||
cmd = "imageMath.py -e='a*exp(-1.0*J*b)' --a={} --b={} -s BIP -t cfloat -o {}".format(
|
||||
self._insar.multilookDifferentialInterferogramOriginal,
|
||||
self._insar.multilookIon,
|
||||
self._insar.multilookDifferentialInterferogram)
|
||||
runCmd(cmd)
|
||||
else:
|
||||
print('\nionospheric phase estimation finished, but correction of interfeorgram not requested')
|
||||
|
||||
os.chdir('../')
|
||||
|
||||
catalog.printToLog(logger, "runIonFilt")
|
||||
self._insar.procDoc.addAllFromCatalog(catalog)
|
||||
|
||||
|
||||
|
||||
def computeIonosphere(lowerUnw, upperUnw, cor, fl, fu, adjFlag, corThresholdAdj, dispersive):
|
||||
'''
|
||||
This routine computes ionosphere and remove the relative phase unwrapping errors
|
||||
|
||||
lowerUnw: lower band unwrapped interferogram
|
||||
upperUnw: upper band unwrapped interferogram
|
||||
cor: coherence
|
||||
fl: lower band center frequency
|
||||
fu: upper band center frequency
|
||||
adjFlag: method for removing relative phase unwrapping errors
|
||||
0: mean value
|
||||
1: polynomial
|
||||
corThresholdAdj: coherence threshold of samples used in removing relative phase unwrapping errors
|
||||
dispersive: compute dispersive or non-dispersive
|
||||
0: dispersive
|
||||
1: non-dispersive
|
||||
'''
|
||||
|
||||
#use image size from lower unwrapped interferogram
|
||||
(length, width)=lowerUnw.shape
|
||||
|
||||
##########################################################################################
|
||||
# ADJUST PHASE USING MEAN VALUE
|
||||
# #ajust phase of upper band to remove relative phase unwrapping errors
|
||||
# flag = (lowerUnw!=0)*(cor>=ionParam.corThresholdAdj)
|
||||
# index = np.nonzero(flag!=0)
|
||||
# mv = np.mean((lowerUnw - upperUnw)[index], dtype=np.float64)
|
||||
# print('mean value of phase difference: {}'.format(mv))
|
||||
# flag2 = (lowerUnw!=0)
|
||||
# index2 = np.nonzero(flag2)
|
||||
# #phase for adjustment
|
||||
# unwd = ((lowerUnw - upperUnw)[index2] - mv) / (2.0*np.pi)
|
||||
# unw_adj = np.around(unwd) * (2.0*np.pi)
|
||||
# #ajust phase of upper band
|
||||
# upperUnw[index2] += unw_adj
|
||||
# unw_diff = lowerUnw - upperUnw
|
||||
# print('after adjustment:')
|
||||
# print('max phase difference: {}'.format(np.amax(unw_diff)))
|
||||
# print('min phase difference: {}'.format(np.amin(unw_diff)))
|
||||
##########################################################################################
|
||||
#adjust phase using mean value
|
||||
if adjFlag == 0:
|
||||
flag = (lowerUnw!=0)*(cor>=corThresholdAdj)
|
||||
index = np.nonzero(flag!=0)
|
||||
mv = np.mean((lowerUnw - upperUnw)[index], dtype=np.float64)
|
||||
print('mean value of phase difference: {}'.format(mv))
|
||||
diff = mv
|
||||
#adjust phase using a surface
|
||||
else:
|
||||
diff = weight_fitting(lowerUnw - upperUnw, cor, width, length, 1, 1, 1, 1, 2, corThresholdAdj)
|
||||
|
||||
flag2 = (lowerUnw!=0)
|
||||
index2 = np.nonzero(flag2)
|
||||
#phase for adjustment
|
||||
unwd = ((lowerUnw - upperUnw) - diff)[index2] / (2.0*np.pi)
|
||||
unw_adj = np.around(unwd) * (2.0*np.pi)
|
||||
#ajust phase of upper band
|
||||
upperUnw[index2] += unw_adj
|
||||
|
||||
unw_diff = (lowerUnw - upperUnw)[index2]
|
||||
print('after adjustment:')
|
||||
print('max phase difference: {}'.format(np.amax(unw_diff)))
|
||||
print('min phase difference: {}'.format(np.amin(unw_diff)))
|
||||
print('max-min: {}'.format(np.amax(unw_diff) - np.amin(unw_diff) ))
|
||||
|
||||
#ionosphere
|
||||
#fl = SPEED_OF_LIGHT / ionParam.radarWavelengthLower
|
||||
#fu = SPEED_OF_LIGHT / ionParam.radarWavelengthUpper
|
||||
f0 = (fl + fu) / 2.0
|
||||
|
||||
#dispersive
|
||||
if dispersive == 0:
|
||||
ionos = fl * fu * (lowerUnw * fu - upperUnw * fl) / f0 / (fu**2 - fl**2)
|
||||
#non-dispersive phase
|
||||
else:
|
||||
ionos = f0 * (upperUnw*fu - lowerUnw * fl) / (fu**2 - fl**2)
|
||||
|
||||
return ionos
|
||||
|
||||
|
||||
def fit_surface(x, y, z, wgt, order):
|
||||
# x: x coordinate, a column vector
|
||||
# y: y coordinate, a column vector
|
||||
# z: z coordinate, a column vector
|
||||
# wgt: weight of the data points, a column vector
|
||||
|
||||
|
||||
#number of data points
|
||||
m = x.shape[0]
|
||||
l = np.ones((m,1), dtype=np.float64)
|
||||
|
||||
# #create polynomial
|
||||
# if order == 1:
|
||||
# #order of estimated coefficents: 1, x, y
|
||||
# a1 = np.concatenate((l, x, y), axis=1)
|
||||
# elif order == 2:
|
||||
# #order of estimated coefficents: 1, x, y, x*y, x**2, y**2
|
||||
# a1 = np.concatenate((l, x, y, x*y, x**2, y**2), axis=1)
|
||||
# elif order == 3:
|
||||
# #order of estimated coefficents: 1, x, y, x*y, x**2, y**2, x**2*y, y**2*x, x**3, y**3
|
||||
# a1 = np.concatenate((l, x, y, x*y, x**2, y**2, x**2*y, y**2*x, x**3, y**3), axis=1)
|
||||
# else:
|
||||
# raise Exception('order not supported yet\n')
|
||||
|
||||
if order < 1:
|
||||
raise Exception('order must be larger than 1.\n')
|
||||
|
||||
#create polynomial
|
||||
a1 = l;
|
||||
for i in range(1, order+1):
|
||||
for j in range(i+1):
|
||||
a1 = np.concatenate((a1, x**(i-j)*y**(j)), axis=1)
|
||||
|
||||
#number of variable to be estimated
|
||||
n = a1.shape[1]
|
||||
|
||||
#do the least squares
|
||||
a = a1 * np.matlib.repmat(np.sqrt(wgt), 1, n)
|
||||
b = z * np.sqrt(wgt)
|
||||
c = np.linalg.lstsq(a, b, rcond=-1)[0]
|
||||
|
||||
#type: <class 'numpy.ndarray'>
|
||||
return c
|
||||
|
||||
|
||||
def cal_surface(x, y, c, order):
|
||||
#x: x coordinate, a row vector
|
||||
#y: y coordinate, a column vector
|
||||
#c: coefficients of polynomial from fit_surface
|
||||
#order: order of polynomial
|
||||
|
||||
if order < 1:
|
||||
raise Exception('order must be larger than 1.\n')
|
||||
|
||||
#number of lines
|
||||
length = y.shape[0]
|
||||
#number of columns, if row vector, only one element in the shape tuple
|
||||
#width = x.shape[1]
|
||||
width = x.shape[0]
|
||||
|
||||
x = np.matlib.repmat(x, length, 1)
|
||||
y = np.matlib.repmat(y, 1, width)
|
||||
z = c[0] * np.ones((length,width), dtype=np.float64)
|
||||
|
||||
index = 0
|
||||
for i in range(1, order+1):
|
||||
for j in range(i+1):
|
||||
index += 1
|
||||
z += c[index] * x**(i-j)*y**(j)
|
||||
|
||||
return z
|
||||
|
||||
|
||||
def weight_fitting(ionos, cor, width, length, nrli, nali, nrlo, nalo, order, coth):
|
||||
'''
|
||||
ionos: input ionospheric phase
|
||||
cor: coherence of the interferogram
|
||||
width: file width
|
||||
length: file length
|
||||
nrli: number of range looks of the input interferograms
|
||||
nali: number of azimuth looks of the input interferograms
|
||||
nrlo: number of range looks of the output ionosphere phase
|
||||
nalo: number of azimuth looks of the ioutput ionosphere phase
|
||||
order: the order of the polynomial for fitting ionosphere phase estimates
|
||||
coth: coherence threshhold for ionosphere phase estimation
|
||||
'''
|
||||
|
||||
from isceobj.Alos2Proc.Alos2ProcPublic import create_multi_index2
|
||||
|
||||
lengthi = int(length/nali)
|
||||
widthi = int(width/nrli)
|
||||
lengtho = int(length/nalo)
|
||||
widtho = int(width/nrlo)
|
||||
|
||||
#calculate output index
|
||||
rgindex = create_multi_index2(widtho, nrli, nrlo)
|
||||
azindex = create_multi_index2(lengtho, nali, nalo)
|
||||
|
||||
#convert coherence to weight
|
||||
cor = cor**2/(1.009-cor**2)
|
||||
|
||||
#look for data to use
|
||||
flag = (cor>coth)*(ionos!=0)
|
||||
point_index = np.nonzero(flag)
|
||||
m = point_index[0].shape[0]
|
||||
|
||||
#calculate input index matrix
|
||||
x0=np.matlib.repmat(np.arange(widthi), lengthi, 1)
|
||||
y0=np.matlib.repmat(np.arange(lengthi).reshape(lengthi, 1), 1, widthi)
|
||||
|
||||
x = x0[point_index].reshape(m, 1)
|
||||
y = y0[point_index].reshape(m, 1)
|
||||
z = ionos[point_index].reshape(m, 1)
|
||||
w = cor[point_index].reshape(m, 1)
|
||||
|
||||
#convert to higher precision type before use
|
||||
x=np.asfarray(x,np.float64)
|
||||
y=np.asfarray(y,np.float64)
|
||||
z=np.asfarray(z,np.float64)
|
||||
w=np.asfarray(w,np.float64)
|
||||
coeff = fit_surface(x, y, z, w, order)
|
||||
|
||||
#convert to higher precision type before use
|
||||
rgindex=np.asfarray(rgindex,np.float64)
|
||||
azindex=np.asfarray(azindex,np.float64)
|
||||
phase_fit = cal_surface(rgindex, azindex.reshape(lengtho, 1), coeff, order)
|
||||
|
||||
#format: widtho, lengtho, single band float32
|
||||
return phase_fit
|
||||
|
||||
|
||||
def gaussian(size, sigma, scale = 1.0):
|
||||
|
||||
if size % 2 != 1:
|
||||
raise Exception('size must be odd')
|
||||
hsize = (size - 1) / 2
|
||||
x = np.arange(-hsize, hsize + 1) * scale
|
||||
f = np.exp(-x**2/(2.0*sigma**2)) / (sigma * np.sqrt(2.0*np.pi))
|
||||
f2d=np.matlib.repmat(f, size, 1) * np.matlib.repmat(f.reshape(size, 1), 1, size)
|
||||
|
||||
return f2d/np.sum(f2d)
|
||||
|
||||
|
||||
def adaptive_gaussian(ionos, wgt, size_max, size_min):
|
||||
'''
|
||||
This program performs Gaussian filtering with adaptive window size.
|
||||
ionos: ionosphere
|
||||
wgt: weight
|
||||
size_max: maximum window size
|
||||
size_min: minimum window size
|
||||
'''
|
||||
import scipy.signal as ss
|
||||
|
||||
length = (ionos.shape)[0]
|
||||
width = (ionos.shape)[1]
|
||||
flag = (ionos!=0) * (wgt!=0)
|
||||
ionos *= flag
|
||||
wgt *= flag
|
||||
|
||||
size_num = 100
|
||||
size = np.linspace(size_min, size_max, num=size_num, endpoint=True)
|
||||
std = np.zeros((length, width, size_num))
|
||||
flt = np.zeros((length, width, size_num))
|
||||
out = np.zeros((length, width, 1))
|
||||
|
||||
#calculate filterd image and standard deviation
|
||||
#sigma of window size: size_max
|
||||
sigma = size_max / 2.0
|
||||
for i in range(size_num):
|
||||
size2 = np.int(np.around(size[i]))
|
||||
if size2 % 2 == 0:
|
||||
size2 += 1
|
||||
if (i+1) % 10 == 0:
|
||||
print('min win: %4d, max win: %4d, current win: %4d'%(np.int(np.around(size_min)), np.int(np.around(size_max)), size2))
|
||||
g2d = gaussian(size2, sigma*size2/size_max, scale=1.0)
|
||||
scale = ss.fftconvolve(wgt, g2d, mode='same')
|
||||
flt[:, :, i] = ss.fftconvolve(ionos*wgt, g2d, mode='same') / (scale + (scale==0))
|
||||
#variance of resulting filtered sample
|
||||
scale = scale**2
|
||||
var = ss.fftconvolve(wgt, g2d**2, mode='same') / (scale + (scale==0))
|
||||
#in case there is a large area without data where scale is very small, which leads to wired values in variance
|
||||
var[np.nonzero(var<0)] = 0
|
||||
std[:, :, i] = np.sqrt(var)
|
||||
|
||||
std_mv = np.mean(std[np.nonzero(std!=0)], dtype=np.float64)
|
||||
diff_max = np.amax(np.absolute(std - std_mv)) + std_mv + 1
|
||||
std[np.nonzero(std==0)] = diff_max
|
||||
|
||||
index = np.nonzero(np.ones((length, width))) + ((np.argmin(np.absolute(std - std_mv), axis=2)).reshape(length*width), )
|
||||
out = flt[index]
|
||||
out = out.reshape((length, width))
|
||||
|
||||
#remove artifacts due to varying wgt
|
||||
size_smt = size_min
|
||||
if size_smt % 2 == 0:
|
||||
size_smt += 1
|
||||
g2d = gaussian(size_smt, size_smt/2.0, scale=1.0)
|
||||
scale = ss.fftconvolve((out!=0), g2d, mode='same')
|
||||
out2 = ss.fftconvolve(out, g2d, mode='same') / (scale + (scale==0))
|
||||
|
||||
return out2
|
||||
|
||||
|
||||
def reformatMaskedAreas(maskedAreas, length, width):
|
||||
'''
|
||||
reformat masked areas coordinates that are ready to use
|
||||
'maskedAreas' is a 2-D list. Each element in the 2-D list is a four-element list: [firstLine,
|
||||
lastLine, firstColumn, lastColumn], with line/column numbers starting with 1. If one of the
|
||||
four elements is specified with -1, the program will use firstLine/lastLine/firstColumn/
|
||||
lastColumn instead.
|
||||
|
||||
output is a 2-D list containing the corresponding python-list/array-format indexes.
|
||||
'''
|
||||
numberOfAreas = len(maskedAreas)
|
||||
maskedAreasReformated = [[0, length, 0, width] for i in range(numberOfAreas)]
|
||||
|
||||
for i in range(numberOfAreas):
|
||||
if maskedAreas[i][0] != -1:
|
||||
maskedAreasReformated[i][0] = maskedAreas[i][0] - 1
|
||||
if maskedAreas[i][1] != -1:
|
||||
maskedAreasReformated[i][1] = maskedAreas[i][1]
|
||||
if maskedAreas[i][2] != -1:
|
||||
maskedAreasReformated[i][2] = maskedAreas[i][2] - 1
|
||||
if maskedAreas[i][3] != -1:
|
||||
maskedAreasReformated[i][3] = maskedAreas[i][3]
|
||||
if (not (0 <= maskedAreasReformated[i][0] <= length-1)) or \
|
||||
(not (1 <= maskedAreasReformated[i][1] <= length)) or \
|
||||
(not (0 <= maskedAreasReformated[i][2] <= width-1)) or \
|
||||
(not (1 <= maskedAreasReformated[i][3] <= width)) or \
|
||||
(not (maskedAreasReformated[i][1]-maskedAreasReformated[i][0]>=1)) or \
|
||||
(not (maskedAreasReformated[i][3]-maskedAreasReformated[i][2]>=1)):
|
||||
raise Exception('area {} masked out in ionospheric phase estimation not correct'.format(i+1))
|
||||
|
||||
return maskedAreasReformated
|
||||
|
|
@ -0,0 +1,457 @@
|
|||
#
|
||||
# Author: Cunren Liang
|
||||
# Copyright 2015-present, NASA-JPL/Caltech
|
||||
#
|
||||
|
||||
import os
|
||||
import logging
|
||||
|
||||
import isceobj
|
||||
from isceobj.Constants import SPEED_OF_LIGHT
|
||||
|
||||
logger = logging.getLogger('isce.alos2insar.runIonSubband')
|
||||
|
||||
def runIonSubband(self):
|
||||
'''create subband interferograms
|
||||
'''
|
||||
catalog = isceobj.Catalog.createCatalog(self._insar.procDoc.name)
|
||||
self.updateParamemetersFromUser()
|
||||
|
||||
if not self.doIon:
|
||||
catalog.printToLog(logger, "runIonSubband")
|
||||
self._insar.procDoc.addAllFromCatalog(catalog)
|
||||
return
|
||||
|
||||
masterTrack = self._insar.loadTrack(master=True)
|
||||
slaveTrack = self._insar.loadTrack(master=False)
|
||||
|
||||
#using 1/3, 1/3, 1/3 band split
|
||||
radarWavelength = masterTrack.radarWavelength
|
||||
rangeBandwidth = masterTrack.frames[0].swaths[0].rangeBandwidth
|
||||
rangeSamplingRate = masterTrack.frames[0].swaths[0].rangeSamplingRate
|
||||
radarWavelengthLower = SPEED_OF_LIGHT/(SPEED_OF_LIGHT / radarWavelength - rangeBandwidth / 3.0)
|
||||
radarWavelengthUpper = SPEED_OF_LIGHT/(SPEED_OF_LIGHT / radarWavelength + rangeBandwidth / 3.0)
|
||||
subbandRadarWavelength = [radarWavelengthLower, radarWavelengthUpper]
|
||||
subbandBandWidth = [rangeBandwidth / 3.0 / rangeSamplingRate, rangeBandwidth / 3.0 / rangeSamplingRate]
|
||||
subbandFrequencyCenter = [-rangeBandwidth / 3.0 / rangeSamplingRate, rangeBandwidth / 3.0 / rangeSamplingRate]
|
||||
|
||||
subbandPrefix = ['lower', 'upper']
|
||||
|
||||
'''
|
||||
ionDir = {
|
||||
ionDir['swathMosaic'] : 'mosaic',
|
||||
ionDir['insar'] : 'insar',
|
||||
ionDir['ion'] : 'ion',
|
||||
ionDir['subband'] : ['lower', 'upper'],
|
||||
ionDir['ionCal'] : 'ion_cal'
|
||||
}
|
||||
'''
|
||||
#define upper level directory names
|
||||
ionDir = defineIonDir()
|
||||
|
||||
|
||||
self._insar.subbandRadarWavelength = subbandRadarWavelength
|
||||
|
||||
|
||||
############################################################
|
||||
# STEP 1. create directories
|
||||
############################################################
|
||||
#create and enter 'ion' directory
|
||||
#after finishing each step, we are in this directory
|
||||
if not os.path.exists(ionDir['ion']):
|
||||
os.makedirs(ionDir['ion'])
|
||||
os.chdir(ionDir['ion'])
|
||||
|
||||
#create insar processing directories
|
||||
for k in range(2):
|
||||
subbandDir = ionDir['subband'][k]
|
||||
for i, frameNumber in enumerate(self._insar.masterFrames):
|
||||
frameDir = 'f{}_{}'.format(i+1, frameNumber)
|
||||
for j, swathNumber in enumerate(range(self._insar.startingSwath, self._insar.endingSwath + 1)):
|
||||
swathDir = 's{}'.format(swathNumber)
|
||||
fullDir = os.path.join(subbandDir, frameDir, swathDir)
|
||||
if not os.path.exists(fullDir):
|
||||
os.makedirs(fullDir)
|
||||
|
||||
#create ionospheric phase directory
|
||||
if not os.path.exists(ionDir['ionCal']):
|
||||
os.makedirs(ionDir['ionCal'])
|
||||
|
||||
|
||||
############################################################
|
||||
# STEP 2. create subband interferograms
|
||||
############################################################
|
||||
import numpy as np
|
||||
import stdproc
|
||||
from iscesys.StdOEL.StdOELPy import create_writer
|
||||
from isceobj.Alos2Proc.Alos2ProcPublic import readOffset
|
||||
from contrib.alos2proc.alos2proc import rg_filter
|
||||
|
||||
for i, frameNumber in enumerate(self._insar.masterFrames):
|
||||
frameDir = 'f{}_{}'.format(i+1, frameNumber)
|
||||
for j, swathNumber in enumerate(range(self._insar.startingSwath, self._insar.endingSwath + 1)):
|
||||
swathDir = 's{}'.format(swathNumber)
|
||||
#filter master and slave images
|
||||
for slcx in [self._insar.masterSlc, self._insar.slaveSlc]:
|
||||
slc = os.path.join('../', frameDir, swathDir, slcx)
|
||||
slcLower = os.path.join(ionDir['subband'][0], frameDir, swathDir, slcx)
|
||||
slcUpper = os.path.join(ionDir['subband'][1], frameDir, swathDir, slcx)
|
||||
rg_filter(slc, 2,
|
||||
[slcLower, slcUpper],
|
||||
subbandBandWidth,
|
||||
subbandFrequencyCenter,
|
||||
257, 2048, 0.1, 0, 0.0)
|
||||
#resample
|
||||
for k in range(2):
|
||||
os.chdir(os.path.join(ionDir['subband'][k], frameDir, swathDir))
|
||||
#recreate xml file to remove the file path
|
||||
#can also use fixImageXml.py?
|
||||
for x in [self._insar.masterSlc, self._insar.slaveSlc]:
|
||||
img = isceobj.createSlcImage()
|
||||
img.load(x + '.xml')
|
||||
img.setFilename(x)
|
||||
img.extraFilename = x + '.vrt'
|
||||
img.setAccessMode('READ')
|
||||
img.renderHdr()
|
||||
|
||||
#############################################
|
||||
#1. form interferogram
|
||||
#############################################
|
||||
masterSwath = masterTrack.frames[i].swaths[j]
|
||||
slaveSwath = slaveTrack.frames[i].swaths[j]
|
||||
|
||||
refinedOffsets = readOffset(os.path.join('../../../../', frameDir, swathDir, 'cull.off'))
|
||||
intWidth = int(masterSwath.numberOfSamples / self._insar.numberRangeLooks1)
|
||||
intLength = int(masterSwath.numberOfLines / self._insar.numberAzimuthLooks1)
|
||||
dopplerVsPixel = [i/slaveSwath.prf for i in slaveSwath.dopplerVsPixel]
|
||||
|
||||
#master slc
|
||||
mSLC = isceobj.createSlcImage()
|
||||
mSLC.load(self._insar.masterSlc+'.xml')
|
||||
mSLC.setAccessMode('read')
|
||||
mSLC.createImage()
|
||||
|
||||
#slave slc
|
||||
sSLC = isceobj.createSlcImage()
|
||||
sSLC.load(self._insar.slaveSlc+'.xml')
|
||||
sSLC.setAccessMode('read')
|
||||
sSLC.createImage()
|
||||
|
||||
#interferogram
|
||||
interf = isceobj.createIntImage()
|
||||
interf.setFilename(self._insar.interferogram)
|
||||
interf.setWidth(intWidth)
|
||||
interf.setAccessMode('write')
|
||||
interf.createImage()
|
||||
|
||||
#amplitdue
|
||||
amplitude = isceobj.createAmpImage()
|
||||
amplitude.setFilename(self._insar.amplitude)
|
||||
amplitude.setWidth(intWidth)
|
||||
amplitude.setAccessMode('write')
|
||||
amplitude.createImage()
|
||||
|
||||
#create a writer for resamp
|
||||
stdWriter = create_writer("log", "", True, filename="resamp.log")
|
||||
stdWriter.setFileTag("resamp", "log")
|
||||
stdWriter.setFileTag("resamp", "err")
|
||||
stdWriter.setFileTag("resamp", "out")
|
||||
|
||||
|
||||
#set up resampling program now
|
||||
#The setting has been compared with resamp_roi's setting in ROI_pac item by item.
|
||||
#The two kinds of setting are exactly the same. The number of setting items are
|
||||
#exactly the same
|
||||
objResamp = stdproc.createResamp()
|
||||
objResamp.wireInputPort(name='offsets', object=refinedOffsets)
|
||||
objResamp.stdWriter = stdWriter
|
||||
objResamp.setNumberFitCoefficients(6)
|
||||
objResamp.setNumberRangeBin1(masterSwath.numberOfSamples)
|
||||
objResamp.setNumberRangeBin2(slaveSwath.numberOfSamples)
|
||||
objResamp.setStartLine(1)
|
||||
objResamp.setNumberLines(masterSwath.numberOfLines)
|
||||
objResamp.setFirstLineOffset(1)
|
||||
objResamp.setDopplerCentroidCoefficients(dopplerVsPixel)
|
||||
objResamp.setRadarWavelength(subbandRadarWavelength[k])
|
||||
objResamp.setSlantRangePixelSpacing(slaveSwath.rangePixelSize)
|
||||
objResamp.setNumberRangeLooks(self._insar.numberRangeLooks1)
|
||||
objResamp.setNumberAzimuthLooks(self._insar.numberAzimuthLooks1)
|
||||
objResamp.setFlattenWithOffsetFitFlag(0)
|
||||
objResamp.resamp(mSLC, sSLC, interf, amplitude)
|
||||
|
||||
#finialize images
|
||||
mSLC.finalizeImage()
|
||||
sSLC.finalizeImage()
|
||||
interf.finalizeImage()
|
||||
amplitude.finalizeImage()
|
||||
stdWriter.finalize()
|
||||
|
||||
#############################################
|
||||
#2. trim amplitude
|
||||
#############################################
|
||||
#using memmap instead, which should be faster, since we only have a few pixels to change
|
||||
amp=np.memmap(self._insar.amplitude, dtype='complex64', mode='r+', shape=(intLength, intWidth))
|
||||
index = np.nonzero( (np.real(amp)==0) + (np.imag(amp)==0) )
|
||||
amp[index]=0
|
||||
|
||||
#Deletion flushes memory changes to disk before removing the object:
|
||||
del amp
|
||||
|
||||
#############################################
|
||||
#3. delete subband slcs
|
||||
#############################################
|
||||
os.remove(self._insar.masterSlc)
|
||||
os.remove(self._insar.masterSlc + '.vrt')
|
||||
os.remove(self._insar.masterSlc + '.xml')
|
||||
os.remove(self._insar.slaveSlc)
|
||||
os.remove(self._insar.slaveSlc + '.vrt')
|
||||
os.remove(self._insar.slaveSlc + '.xml')
|
||||
|
||||
os.chdir('../../../')
|
||||
|
||||
|
||||
############################################################
|
||||
# STEP 3. mosaic swaths
|
||||
############################################################
|
||||
from isceobj.Alos2Proc.runSwathMosaic import swathMosaic
|
||||
from isceobj.Alos2Proc.Alos2ProcPublic import create_xml
|
||||
|
||||
for k in range(2):
|
||||
os.chdir(ionDir['subband'][k])
|
||||
for i, frameNumber in enumerate(self._insar.masterFrames):
|
||||
frameDir = 'f{}_{}'.format(i+1, frameNumber)
|
||||
os.chdir(frameDir)
|
||||
|
||||
mosaicDir = ionDir['swathMosaic']
|
||||
if not os.path.exists(mosaicDir):
|
||||
os.makedirs(mosaicDir)
|
||||
os.chdir(mosaicDir)
|
||||
|
||||
if not (
|
||||
((self._insar.modeCombination == 21) or \
|
||||
(self._insar.modeCombination == 22) or \
|
||||
(self._insar.modeCombination == 31) or \
|
||||
(self._insar.modeCombination == 32))
|
||||
and
|
||||
(self._insar.endingSwath-self._insar.startingSwath+1 > 1)
|
||||
):
|
||||
import shutil
|
||||
swathDir = 's{}'.format(masterTrack.frames[i].swaths[0].swathNumber)
|
||||
|
||||
# if not os.path.isfile(self._insar.interferogram):
|
||||
# os.symlink(os.path.join('../', swathDir, self._insar.interferogram), self._insar.interferogram)
|
||||
# shutil.copy2(os.path.join('../', swathDir, self._insar.interferogram+'.vrt'), self._insar.interferogram+'.vrt')
|
||||
# shutil.copy2(os.path.join('../', swathDir, self._insar.interferogram+'.xml'), self._insar.interferogram+'.xml')
|
||||
# if not os.path.isfile(self._insar.amplitude):
|
||||
# os.symlink(os.path.join('../', swathDir, self._insar.amplitude), self._insar.amplitude)
|
||||
# shutil.copy2(os.path.join('../', swathDir, self._insar.amplitude+'.vrt'), self._insar.amplitude+'.vrt')
|
||||
# shutil.copy2(os.path.join('../', swathDir, self._insar.amplitude+'.xml'), self._insar.amplitude+'.xml')
|
||||
|
||||
os.rename(os.path.join('../', swathDir, self._insar.interferogram), self._insar.interferogram)
|
||||
os.rename(os.path.join('../', swathDir, self._insar.interferogram+'.vrt'), self._insar.interferogram+'.vrt')
|
||||
os.rename(os.path.join('../', swathDir, self._insar.interferogram+'.xml'), self._insar.interferogram+'.xml')
|
||||
os.rename(os.path.join('../', swathDir, self._insar.amplitude), self._insar.amplitude)
|
||||
os.rename(os.path.join('../', swathDir, self._insar.amplitude+'.vrt'), self._insar.amplitude+'.vrt')
|
||||
os.rename(os.path.join('../', swathDir, self._insar.amplitude+'.xml'), self._insar.amplitude+'.xml')
|
||||
|
||||
#no need to update frame parameters here
|
||||
os.chdir('../')
|
||||
#no need to save parameter file here
|
||||
os.chdir('../')
|
||||
|
||||
continue
|
||||
|
||||
#choose offsets
|
||||
numberOfFrames = len(masterTrack.frames)
|
||||
numberOfSwaths = len(masterTrack.frames[i].swaths)
|
||||
if self.swathOffsetMatching:
|
||||
#no need to do this as the API support 2-d list
|
||||
#rangeOffsets = (np.array(self._insar.swathRangeOffsetMatchingMaster)).reshape(numberOfFrames, numberOfSwaths)
|
||||
#azimuthOffsets = (np.array(self._insar.swathAzimuthOffsetMatchingMaster)).reshape(numberOfFrames, numberOfSwaths)
|
||||
rangeOffsets = self._insar.swathRangeOffsetMatchingMaster
|
||||
azimuthOffsets = self._insar.swathAzimuthOffsetMatchingMaster
|
||||
|
||||
else:
|
||||
#rangeOffsets = (np.array(self._insar.swathRangeOffsetGeometricalMaster)).reshape(numberOfFrames, numberOfSwaths)
|
||||
#azimuthOffsets = (np.array(self._insar.swathAzimuthOffsetGeometricalMaster)).reshape(numberOfFrames, numberOfSwaths)
|
||||
rangeOffsets = self._insar.swathRangeOffsetGeometricalMaster
|
||||
azimuthOffsets = self._insar.swathAzimuthOffsetGeometricalMaster
|
||||
|
||||
rangeOffsets = rangeOffsets[i]
|
||||
azimuthOffsets = azimuthOffsets[i]
|
||||
|
||||
#list of input files
|
||||
inputInterferograms = []
|
||||
inputAmplitudes = []
|
||||
for j, swathNumber in enumerate(range(self._insar.startingSwath, self._insar.endingSwath + 1)):
|
||||
swathDir = 's{}'.format(swathNumber)
|
||||
inputInterferograms.append(os.path.join('../', swathDir, self._insar.interferogram))
|
||||
inputAmplitudes.append(os.path.join('../', swathDir, self._insar.amplitude))
|
||||
|
||||
#note that frame parameters are updated after mosaicking, here no need to update parameters
|
||||
#mosaic amplitudes
|
||||
swathMosaic(masterTrack.frames[i], inputAmplitudes, self._insar.amplitude,
|
||||
rangeOffsets, azimuthOffsets, self._insar.numberRangeLooks1, self._insar.numberAzimuthLooks1, resamplingMethod=0)
|
||||
#mosaic interferograms
|
||||
swathMosaic(masterTrack.frames[i], inputInterferograms, self._insar.interferogram,
|
||||
rangeOffsets, azimuthOffsets, self._insar.numberRangeLooks1, self._insar.numberAzimuthLooks1, updateFrame=False, phaseCompensation=True, resamplingMethod=1)
|
||||
|
||||
create_xml(self._insar.amplitude, masterTrack.frames[i].numberOfSamples, masterTrack.frames[i].numberOfLines, 'amp')
|
||||
create_xml(self._insar.interferogram, masterTrack.frames[i].numberOfSamples, masterTrack.frames[i].numberOfLines, 'int')
|
||||
|
||||
#update slave frame parameters here, here no need to update parameters
|
||||
os.chdir('../')
|
||||
#save parameter file, here no need to save parameter file
|
||||
os.chdir('../')
|
||||
os.chdir('../')
|
||||
|
||||
|
||||
############################################################
|
||||
# STEP 4. mosaic frames
|
||||
############################################################
|
||||
from isceobj.Alos2Proc.runFrameMosaic import frameMosaic
|
||||
from isceobj.Alos2Proc.Alos2ProcPublic import create_xml
|
||||
|
||||
for k in range(2):
|
||||
os.chdir(ionDir['subband'][k])
|
||||
|
||||
mosaicDir = ionDir['insar']
|
||||
if not os.path.exists(mosaicDir):
|
||||
os.makedirs(mosaicDir)
|
||||
os.chdir(mosaicDir)
|
||||
|
||||
numberOfFrames = len(masterTrack.frames)
|
||||
if numberOfFrames == 1:
|
||||
import shutil
|
||||
frameDir = os.path.join('f1_{}/mosaic'.format(self._insar.masterFrames[0]))
|
||||
# if not os.path.isfile(self._insar.interferogram):
|
||||
# os.symlink(os.path.join('../', frameDir, self._insar.interferogram), self._insar.interferogram)
|
||||
# #shutil.copy2() can overwrite
|
||||
# shutil.copy2(os.path.join('../', frameDir, self._insar.interferogram+'.vrt'), self._insar.interferogram+'.vrt')
|
||||
# shutil.copy2(os.path.join('../', frameDir, self._insar.interferogram+'.xml'), self._insar.interferogram+'.xml')
|
||||
# if not os.path.isfile(self._insar.amplitude):
|
||||
# os.symlink(os.path.join('../', frameDir, self._insar.amplitude), self._insar.amplitude)
|
||||
# shutil.copy2(os.path.join('../', frameDir, self._insar.amplitude+'.vrt'), self._insar.amplitude+'.vrt')
|
||||
# shutil.copy2(os.path.join('../', frameDir, self._insar.amplitude+'.xml'), self._insar.amplitude+'.xml')
|
||||
|
||||
os.rename(os.path.join('../', frameDir, self._insar.interferogram), self._insar.interferogram)
|
||||
os.rename(os.path.join('../', frameDir, self._insar.interferogram+'.vrt'), self._insar.interferogram+'.vrt')
|
||||
os.rename(os.path.join('../', frameDir, self._insar.interferogram+'.xml'), self._insar.interferogram+'.xml')
|
||||
os.rename(os.path.join('../', frameDir, self._insar.amplitude), self._insar.amplitude)
|
||||
os.rename(os.path.join('../', frameDir, self._insar.amplitude+'.vrt'), self._insar.amplitude+'.vrt')
|
||||
os.rename(os.path.join('../', frameDir, self._insar.amplitude+'.xml'), self._insar.amplitude+'.xml')
|
||||
|
||||
#update track parameters, no need to update track parameters here
|
||||
|
||||
else:
|
||||
#choose offsets
|
||||
if self.frameOffsetMatching:
|
||||
rangeOffsets = self._insar.frameRangeOffsetMatchingMaster
|
||||
azimuthOffsets = self._insar.frameAzimuthOffsetMatchingMaster
|
||||
else:
|
||||
rangeOffsets = self._insar.frameRangeOffsetGeometricalMaster
|
||||
azimuthOffsets = self._insar.frameAzimuthOffsetGeometricalMaster
|
||||
|
||||
#list of input files
|
||||
inputInterferograms = []
|
||||
inputAmplitudes = []
|
||||
for i, frameNumber in enumerate(self._insar.masterFrames):
|
||||
frameDir = 'f{}_{}'.format(i+1, frameNumber)
|
||||
inputInterferograms.append(os.path.join('../', frameDir, 'mosaic', self._insar.interferogram))
|
||||
inputAmplitudes.append(os.path.join('../', frameDir, 'mosaic', self._insar.amplitude))
|
||||
|
||||
#note that track parameters are updated after mosaicking
|
||||
#mosaic amplitudes
|
||||
frameMosaic(masterTrack, inputAmplitudes, self._insar.amplitude,
|
||||
rangeOffsets, azimuthOffsets, self._insar.numberRangeLooks1, self._insar.numberAzimuthLooks1,
|
||||
updateTrack=False, phaseCompensation=False, resamplingMethod=0)
|
||||
#mosaic interferograms
|
||||
frameMosaic(masterTrack, inputInterferograms, self._insar.interferogram,
|
||||
rangeOffsets, azimuthOffsets, self._insar.numberRangeLooks1, self._insar.numberAzimuthLooks1,
|
||||
updateTrack=False, phaseCompensation=True, resamplingMethod=1)
|
||||
|
||||
create_xml(self._insar.amplitude, masterTrack.numberOfSamples, masterTrack.numberOfLines, 'amp')
|
||||
create_xml(self._insar.interferogram, masterTrack.numberOfSamples, masterTrack.numberOfLines, 'int')
|
||||
|
||||
#update slave parameters here, no need to update slave parameters here
|
||||
|
||||
os.chdir('../')
|
||||
#save parameter file, no need to save parameter file here
|
||||
os.chdir('../')
|
||||
|
||||
|
||||
############################################################
|
||||
# STEP 5. clear frame processing files
|
||||
############################################################
|
||||
import shutil
|
||||
from isceobj.Alos2Proc.Alos2ProcPublic import runCmd
|
||||
|
||||
for k in range(2):
|
||||
os.chdir(ionDir['subband'][k])
|
||||
for i, frameNumber in enumerate(self._insar.masterFrames):
|
||||
frameDir = 'f{}_{}'.format(i+1, frameNumber)
|
||||
shutil.rmtree(frameDir)
|
||||
#cmd = 'rm -rf {}'.format(frameDir)
|
||||
#runCmd(cmd)
|
||||
os.chdir('../')
|
||||
|
||||
|
||||
############################################################
|
||||
# STEP 6. create differential interferograms
|
||||
############################################################
|
||||
import numpy as np
|
||||
from isceobj.Alos2Proc.Alos2ProcPublic import runCmd
|
||||
|
||||
for k in range(2):
|
||||
os.chdir(ionDir['subband'][k])
|
||||
|
||||
insarDir = ionDir['insar']
|
||||
if not os.path.exists(insarDir):
|
||||
os.makedirs(insarDir)
|
||||
os.chdir(insarDir)
|
||||
|
||||
rangePixelSize = self._insar.numberRangeLooks1 * masterTrack.rangePixelSize
|
||||
radarWavelength = subbandRadarWavelength[k]
|
||||
rectRangeOffset = os.path.join('../../../', insarDir, self._insar.rectRangeOffset)
|
||||
|
||||
cmd = "imageMath.py -e='a*exp(-1.0*J*b*4.0*{}*{}/{}) * (b!=0)' --a={} --b={} -o {} -t cfloat".format(np.pi, rangePixelSize, radarWavelength, self._insar.interferogram, rectRangeOffset, self._insar.differentialInterferogram)
|
||||
runCmd(cmd)
|
||||
|
||||
os.chdir('../../')
|
||||
|
||||
|
||||
os.chdir('../')
|
||||
catalog.printToLog(logger, "runIonSubband")
|
||||
self._insar.procDoc.addAllFromCatalog(catalog)
|
||||
|
||||
|
||||
def defineIonDir():
|
||||
'''
|
||||
define directory names for ionospheric correction
|
||||
'''
|
||||
|
||||
ionDir = {
|
||||
#swath mosaicking directory
|
||||
'swathMosaic' : 'mosaic',
|
||||
#final insar processing directory
|
||||
'insar' : 'insar',
|
||||
#ionospheric correction directory
|
||||
'ion' : 'ion',
|
||||
#subband directory
|
||||
'subband' : ['lower', 'upper'],
|
||||
#final ionospheric phase calculation directory
|
||||
'ionCal' : 'ion_cal'
|
||||
}
|
||||
|
||||
return ionDir
|
||||
|
||||
|
||||
def defineIonFilenames():
|
||||
pass
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
|
@ -0,0 +1,213 @@
|
|||
#
|
||||
# Author: Cunren Liang
|
||||
# Copyright 2015-present, NASA-JPL/Caltech
|
||||
#
|
||||
|
||||
import os
|
||||
import logging
|
||||
import datetime
|
||||
import numpy as np
|
||||
|
||||
import isceobj
|
||||
|
||||
logger = logging.getLogger('isce.alos2insar.runIonUwrap')
|
||||
|
||||
def runIonUwrap(self):
|
||||
'''unwrap subband interferograms
|
||||
'''
|
||||
catalog = isceobj.Catalog.createCatalog(self._insar.procDoc.name)
|
||||
self.updateParamemetersFromUser()
|
||||
|
||||
if not self.doIon:
|
||||
catalog.printToLog(logger, "runIonUwrap")
|
||||
self._insar.procDoc.addAllFromCatalog(catalog)
|
||||
return
|
||||
|
||||
masterTrack = self._insar.loadTrack(master=True)
|
||||
slaveTrack = self._insar.loadTrack(master=False)
|
||||
|
||||
from isceobj.Alos2Proc.runIonSubband import defineIonDir
|
||||
ionDir = defineIonDir()
|
||||
subbandPrefix = ['lower', 'upper']
|
||||
|
||||
ionCalDir = os.path.join(ionDir['ion'], ionDir['ionCal'])
|
||||
if not os.path.exists(ionCalDir):
|
||||
os.makedirs(ionCalDir)
|
||||
os.chdir(ionCalDir)
|
||||
|
||||
|
||||
############################################################
|
||||
# STEP 1. take looks
|
||||
############################################################
|
||||
from isceobj.Alos2Proc.Alos2ProcPublic import create_xml
|
||||
from contrib.alos2proc.alos2proc import look
|
||||
|
||||
ml2 = '_{}rlks_{}alks'.format(self._insar.numberRangeLooks1*self._insar.numberRangeLooksIon,
|
||||
self._insar.numberAzimuthLooks1*self._insar.numberAzimuthLooksIon)
|
||||
|
||||
for k in range(2):
|
||||
fullbandDir = os.path.join('../../', ionDir['insar'])
|
||||
subbandDir = os.path.join('../', ionDir['subband'][k], ionDir['insar'])
|
||||
prefix = subbandPrefix[k]
|
||||
|
||||
amp = isceobj.createImage()
|
||||
amp.load(os.path.join(subbandDir, self._insar.amplitude)+'.xml')
|
||||
width = amp.width
|
||||
length = amp.length
|
||||
width2 = int(width / self._insar.numberRangeLooksIon)
|
||||
length2 = int(length / self._insar.numberAzimuthLooksIon)
|
||||
|
||||
#take looks
|
||||
look(os.path.join(subbandDir, self._insar.differentialInterferogram), prefix+ml2+'.int', width, self._insar.numberRangeLooksIon, self._insar.numberAzimuthLooksIon, 4, 0, 1)
|
||||
create_xml(prefix+ml2+'.int', width2, length2, 'int')
|
||||
look(os.path.join(subbandDir, self._insar.amplitude), prefix+ml2+'.amp', width, self._insar.numberRangeLooksIon, self._insar.numberAzimuthLooksIon, 4, 1, 1)
|
||||
create_xml(prefix+ml2+'.amp', width2, length2, 'amp')
|
||||
|
||||
# #water body
|
||||
# if k == 0:
|
||||
# wbdOutFile = os.path.join(fullbandDir, self._insar.wbdOut)
|
||||
# if os.path.isfile(wbdOutFile):
|
||||
# look(wbdOutFile, 'wbd'+ml2+'.wbd', width, self._insar.numberRangeLooksIon, self._insar.numberAzimuthLooksIon, 0, 0, 1)
|
||||
# create_xml('wbd'+ml2+'.wbd', width2, length2, 'byte')
|
||||
|
||||
|
||||
############################################################
|
||||
# STEP 2. compute coherence
|
||||
############################################################
|
||||
from isceobj.Alos2Proc.Alos2ProcPublic import cal_coherence
|
||||
|
||||
lowerbandInterferogramFile = subbandPrefix[0]+ml2+'.int'
|
||||
upperbandInterferogramFile = subbandPrefix[1]+ml2+'.int'
|
||||
lowerbandAmplitudeFile = subbandPrefix[0]+ml2+'.amp'
|
||||
upperbandAmplitudeFile = subbandPrefix[1]+ml2+'.amp'
|
||||
lowerbandCoherenceFile = subbandPrefix[0]+ml2+'.cor'
|
||||
upperbandCoherenceFile = subbandPrefix[1]+ml2+'.cor'
|
||||
coherenceFile = 'diff'+ml2+'.cor'
|
||||
|
||||
lowerint = np.fromfile(lowerbandInterferogramFile, dtype=np.complex64).reshape(length2, width2)
|
||||
upperint = np.fromfile(upperbandInterferogramFile, dtype=np.complex64).reshape(length2, width2)
|
||||
loweramp = np.fromfile(lowerbandAmplitudeFile, dtype=np.float32).reshape(length2, width2*2)
|
||||
upperamp = np.fromfile(upperbandAmplitudeFile, dtype=np.float32).reshape(length2, width2*2)
|
||||
|
||||
#compute coherence only using interferogram
|
||||
#here I use differential interferogram of lower and upper band interferograms
|
||||
#so that coherence is not affected by fringes
|
||||
cord = cal_coherence(lowerint*np.conjugate(upperint), win=3, edge=4)
|
||||
cor = np.zeros((length2*2, width2), dtype=np.float32)
|
||||
cor[0:length2*2:2, :] = np.sqrt( (np.absolute(lowerint)+np.absolute(upperint))/2.0 )
|
||||
cor[1:length2*2:2, :] = cord
|
||||
cor.astype(np.float32).tofile(coherenceFile)
|
||||
create_xml(coherenceFile, width2, length2, 'cor')
|
||||
|
||||
#create lower and upper band coherence files
|
||||
#lower
|
||||
amp1 = loweramp[:, 0:width2*2:2]
|
||||
amp2 = loweramp[:, 1:width2*2:2]
|
||||
cor[1:length2*2:2, :] = np.absolute(lowerint)/(amp1+(amp1==0))/(amp2+(amp2==0))*(amp1!=0)*(amp2!=0)
|
||||
cor.astype(np.float32).tofile(lowerbandCoherenceFile)
|
||||
create_xml(lowerbandCoherenceFile, width2, length2, 'cor')
|
||||
|
||||
#upper
|
||||
amp1 = upperamp[:, 0:width2*2:2]
|
||||
amp2 = upperamp[:, 1:width2*2:2]
|
||||
cor[1:length2*2:2, :] = np.absolute(upperint)/(amp1+(amp1==0))/(amp2+(amp2==0))*(amp1!=0)*(amp2!=0)
|
||||
cor.astype(np.float32).tofile(upperbandCoherenceFile)
|
||||
create_xml(upperbandCoherenceFile, width2, length2, 'cor')
|
||||
|
||||
|
||||
############################################################
|
||||
# STEP 3. filtering subband interferograms
|
||||
############################################################
|
||||
from contrib.alos2filter.alos2filter import psfilt1
|
||||
from isceobj.Alos2Proc.Alos2ProcPublic import runCmd
|
||||
from isceobj.Alos2Proc.Alos2ProcPublic import create_xml
|
||||
from mroipac.icu.Icu import Icu
|
||||
|
||||
if self.filterSubbandInt:
|
||||
for k in range(2):
|
||||
toBeFiltered = 'tmp.int'
|
||||
if self.removeMagnitudeBeforeFilteringSubbandInt:
|
||||
cmd = "imageMath.py -e='a/(abs(a)+(a==0))' --a={} -o {} -t cfloat -s BSQ".format(subbandPrefix[k]+ml2+'.int', toBeFiltered)
|
||||
else:
|
||||
#scale the inteferogram, otherwise its magnitude is too large for filtering
|
||||
cmd = "imageMath.py -e='a/100000.0' --a={} -o {} -t cfloat -s BSQ".format(subbandPrefix[k]+ml2+'.int', toBeFiltered)
|
||||
runCmd(cmd)
|
||||
|
||||
intImage = isceobj.createIntImage()
|
||||
intImage.load(toBeFiltered + '.xml')
|
||||
width = intImage.width
|
||||
length = intImage.length
|
||||
|
||||
windowSize = self.filterWinsizeSubbandInt
|
||||
stepSize = self.filterStepsizeSubbandInt
|
||||
psfilt1(toBeFiltered, 'filt_'+subbandPrefix[k]+ml2+'.int', width, self.filterStrengthSubbandInt, windowSize, stepSize)
|
||||
create_xml('filt_'+subbandPrefix[k]+ml2+'.int', width, length, 'int')
|
||||
|
||||
os.remove(toBeFiltered)
|
||||
os.remove(toBeFiltered + '.vrt')
|
||||
os.remove(toBeFiltered + '.xml')
|
||||
|
||||
#create phase sigma for phase unwrapping
|
||||
#recreate filtered image
|
||||
filtImage = isceobj.createIntImage()
|
||||
filtImage.load('filt_'+subbandPrefix[k]+ml2+'.int' + '.xml')
|
||||
filtImage.setAccessMode('read')
|
||||
filtImage.createImage()
|
||||
|
||||
#amplitude image
|
||||
ampImage = isceobj.createAmpImage()
|
||||
ampImage.load(subbandPrefix[k]+ml2+'.amp' + '.xml')
|
||||
ampImage.setAccessMode('read')
|
||||
ampImage.createImage()
|
||||
|
||||
#phase sigma correlation image
|
||||
phsigImage = isceobj.createImage()
|
||||
phsigImage.setFilename(subbandPrefix[k]+ml2+'.phsig')
|
||||
phsigImage.setWidth(width)
|
||||
phsigImage.dataType='FLOAT'
|
||||
phsigImage.bands = 1
|
||||
phsigImage.setImageType('cor')
|
||||
phsigImage.setAccessMode('write')
|
||||
phsigImage.createImage()
|
||||
|
||||
icu = Icu(name='insarapp_filter_icu')
|
||||
icu.configure()
|
||||
icu.unwrappingFlag = False
|
||||
icu.icu(intImage = filtImage, ampImage=ampImage, phsigImage=phsigImage)
|
||||
|
||||
phsigImage.renderHdr()
|
||||
|
||||
filtImage.finalizeImage()
|
||||
ampImage.finalizeImage()
|
||||
phsigImage.finalizeImage()
|
||||
|
||||
|
||||
############################################################
|
||||
# STEP 4. phase unwrapping
|
||||
############################################################
|
||||
from isceobj.Alos2Proc.Alos2ProcPublic import snaphuUnwrap
|
||||
|
||||
for k in range(2):
|
||||
tmid = masterTrack.sensingStart + datetime.timedelta(seconds=(self._insar.numberAzimuthLooks1-1.0)/2.0*masterTrack.azimuthLineInterval+
|
||||
masterTrack.numberOfLines/2.0*self._insar.numberAzimuthLooks1*masterTrack.azimuthLineInterval)
|
||||
|
||||
if self.filterSubbandInt:
|
||||
toBeUnwrapped = 'filt_'+subbandPrefix[k]+ml2+'.int'
|
||||
coherenceFile = subbandPrefix[k]+ml2+'.phsig'
|
||||
else:
|
||||
toBeUnwrapped = subbandPrefix[k]+ml2+'.int'
|
||||
coherenceFile = 'diff'+ml2+'.cor'
|
||||
|
||||
snaphuUnwrap(masterTrack, tmid,
|
||||
toBeUnwrapped,
|
||||
coherenceFile,
|
||||
subbandPrefix[k]+ml2+'.unw',
|
||||
self._insar.numberRangeLooks1*self._insar.numberRangeLooksIon,
|
||||
self._insar.numberAzimuthLooks1*self._insar.numberAzimuthLooksIon,
|
||||
costMode = 'SMOOTH',initMethod = 'MCF', defomax = 2, initOnly = True)
|
||||
|
||||
|
||||
os.chdir('../../')
|
||||
catalog.printToLog(logger, "runIonUwrap")
|
||||
self._insar.procDoc.addAllFromCatalog(catalog)
|
||||
|
||||
|
|
@ -0,0 +1,70 @@
|
|||
#
|
||||
# Author: Cunren Liang
|
||||
# Copyright 2015-present, NASA-JPL/Caltech
|
||||
#
|
||||
|
||||
import os
|
||||
import logging
|
||||
|
||||
import isceobj
|
||||
from isceobj.Alos2Proc.Alos2ProcPublic import create_xml
|
||||
from contrib.alos2proc.alos2proc import look
|
||||
from isceobj.Alos2Proc.Alos2ProcPublic import runCmd
|
||||
from isceobj.Alos2Proc.Alos2ProcPublic import waterBodyRadar
|
||||
|
||||
logger = logging.getLogger('isce.alos2insar.runLook')
|
||||
|
||||
def runLook(self):
|
||||
'''take looks
|
||||
'''
|
||||
catalog = isceobj.Catalog.createCatalog(self._insar.procDoc.name)
|
||||
self.updateParamemetersFromUser()
|
||||
|
||||
#masterTrack = self._insar.loadTrack(master=True)
|
||||
#slaveTrack = self._insar.loadTrack(master=False)
|
||||
wbdFile = os.path.abspath(self._insar.wbd)
|
||||
|
||||
insarDir = 'insar'
|
||||
if not os.path.exists(insarDir):
|
||||
os.makedirs(insarDir)
|
||||
os.chdir(insarDir)
|
||||
|
||||
|
||||
amp = isceobj.createImage()
|
||||
amp.load(self._insar.amplitude+'.xml')
|
||||
width = amp.width
|
||||
length = amp.length
|
||||
width2 = int(width / self._insar.numberRangeLooks2)
|
||||
length2 = int(length / self._insar.numberAzimuthLooks2)
|
||||
|
||||
if not ((self._insar.numberRangeLooks2 == 1) and (self._insar.numberAzimuthLooks2 == 1)):
|
||||
#take looks
|
||||
look(self._insar.differentialInterferogram, self._insar.multilookDifferentialInterferogram, width, self._insar.numberRangeLooks2, self._insar.numberAzimuthLooks2, 4, 0, 1)
|
||||
look(self._insar.amplitude, self._insar.multilookAmplitude, width, self._insar.numberRangeLooks2, self._insar.numberAzimuthLooks2, 4, 1, 1)
|
||||
look(self._insar.latitude, self._insar.multilookLatitude, width, self._insar.numberRangeLooks2, self._insar.numberAzimuthLooks2, 3, 0, 1)
|
||||
look(self._insar.longitude, self._insar.multilookLongitude, width, self._insar.numberRangeLooks2, self._insar.numberAzimuthLooks2, 3, 0, 1)
|
||||
look(self._insar.height, self._insar.multilookHeight, width, self._insar.numberRangeLooks2, self._insar.numberAzimuthLooks2, 3, 0, 1)
|
||||
#creat xml
|
||||
create_xml(self._insar.multilookDifferentialInterferogram, width2, length2, 'int')
|
||||
create_xml(self._insar.multilookAmplitude, width2, length2, 'amp')
|
||||
create_xml(self._insar.multilookLatitude, width2, length2, 'double')
|
||||
create_xml(self._insar.multilookLongitude, width2, length2, 'double')
|
||||
create_xml(self._insar.multilookHeight, width2, length2, 'double')
|
||||
#los has two bands, use look program in isce instead
|
||||
cmd = "looks.py -i {} -o {} -r {} -a {}".format(self._insar.los, self._insar.multilookLos, self._insar.numberRangeLooks2, self._insar.numberAzimuthLooks2)
|
||||
runCmd(cmd)
|
||||
|
||||
#water body
|
||||
#this looking operation has no problems where there is only water and land, but there is also possible no-data area
|
||||
#look(self._insar.wbdOut, self._insar.multilookWbdOut, width, self._insar.numberRangeLooks2, self._insar.numberAzimuthLooks2, 0, 0, 1)
|
||||
#create_xml(self._insar.multilookWbdOut, width2, length2, 'byte')
|
||||
#use waterBodyRadar instead to avoid the problems of no-data pixels in water body
|
||||
waterBodyRadar(self._insar.multilookLatitude, self._insar.multilookLongitude, wbdFile, self._insar.multilookWbdOut)
|
||||
|
||||
|
||||
os.chdir('../')
|
||||
|
||||
catalog.printToLog(logger, "runLook")
|
||||
self._insar.procDoc.addAllFromCatalog(catalog)
|
||||
|
||||
|
||||
|
|
@ -0,0 +1,466 @@
|
|||
#
|
||||
# Author: Cunren Liang
|
||||
# Copyright 2015-present, NASA-JPL/Caltech
|
||||
#
|
||||
|
||||
import os
|
||||
import logging
|
||||
import datetime
|
||||
import numpy as np
|
||||
|
||||
import isceobj
|
||||
from isceobj.Constants import SPEED_OF_LIGHT
|
||||
from isceobj.Alos2Proc.Alos2ProcPublic import overlapFrequency
|
||||
from contrib.alos2proc.alos2proc import rg_filter
|
||||
from contrib.alos2proc.alos2proc import resamp
|
||||
from contrib.alos2proc.alos2proc import mbf
|
||||
|
||||
logger = logging.getLogger('isce.alos2insar.runPrepareSlc')
|
||||
|
||||
def runPrepareSlc(self):
|
||||
'''Extract images.
|
||||
'''
|
||||
catalog = isceobj.Catalog.createCatalog(self._insar.procDoc.name)
|
||||
self.updateParamemetersFromUser()
|
||||
|
||||
masterTrack = self._insar.loadTrack(master=True)
|
||||
slaveTrack = self._insar.loadTrack(master=False)
|
||||
|
||||
|
||||
####################################################
|
||||
#1. crop slc
|
||||
####################################################
|
||||
#for ScanSAR-stripmap interferometry, we always crop slcs
|
||||
#for other cases, up to users
|
||||
if ((self._insar.modeCombination == 31) or (self._insar.modeCombination == 32)) or (self.cropSlc):
|
||||
for i, frameNumber in enumerate(self._insar.masterFrames):
|
||||
frameDir = 'f{}_{}'.format(i+1, frameNumber)
|
||||
os.chdir(frameDir)
|
||||
for j, swathNumber in enumerate(range(self._insar.startingSwath, self._insar.endingSwath + 1)):
|
||||
swathDir = 's{}'.format(swathNumber)
|
||||
os.chdir(swathDir)
|
||||
|
||||
print('cropping frame {}, swath {}'.format(frameNumber, swathNumber))
|
||||
|
||||
masterSwath = masterTrack.frames[i].swaths[j]
|
||||
slaveSwath = slaveTrack.frames[i].swaths[j]
|
||||
|
||||
#crop master
|
||||
cropSlc(masterTrack.orbit, masterSwath, self._insar.masterSlc, slaveTrack.orbit, slaveSwath, edge=0, useVirtualFile=self.useVirtualFile)
|
||||
#crop slave, since slave may go through resampling, we set edge=9
|
||||
#cropSlc(slaveTrack.orbit, slaveSwath, self._insar.slaveSlc, masterTrack.orbit, masterSwath, edge=9, useVirtualFile=self.useVirtualFile)
|
||||
cropSlc(slaveTrack.orbit, slaveSwath, self._insar.slaveSlc, masterTrack.orbit, masterSwath, edge=0, useVirtualFile=self.useVirtualFile)
|
||||
|
||||
os.chdir('../')
|
||||
os.chdir('../')
|
||||
|
||||
|
||||
####################################################
|
||||
#2. range-filter slc
|
||||
####################################################
|
||||
#compute filtering parameters, radarwavelength and range bandwidth should be the same across all swaths and frames
|
||||
centerfreq1 = SPEED_OF_LIGHT / masterTrack.radarWavelength
|
||||
bandwidth1 = masterTrack.frames[0].swaths[0].rangeBandwidth
|
||||
centerfreq2 = SPEED_OF_LIGHT / slaveTrack.radarWavelength
|
||||
bandwidth2 = slaveTrack.frames[0].swaths[0].rangeBandwidth
|
||||
overlapfreq = overlapFrequency(centerfreq1, bandwidth1, centerfreq2, bandwidth2)
|
||||
|
||||
if overlapfreq == None:
|
||||
raise Exception('there is no overlap bandwidth in range')
|
||||
overlapbandwidth = overlapfreq[1] - overlapfreq[0]
|
||||
if overlapbandwidth < 3e6:
|
||||
print('overlap bandwidth: {}, percentage: {}%'.format(overlapbandwidth, 100.0*overlapbandwidth/bandwidth1))
|
||||
raise Exception('there is not enough overlap bandwidth in range')
|
||||
centerfreq = (overlapfreq[1] + overlapfreq[0]) / 2.0
|
||||
|
||||
for i, frameNumber in enumerate(self._insar.masterFrames):
|
||||
frameDir = 'f{}_{}'.format(i+1, frameNumber)
|
||||
os.chdir(frameDir)
|
||||
for j, swathNumber in enumerate(range(self._insar.startingSwath, self._insar.endingSwath + 1)):
|
||||
swathDir = 's{}'.format(swathNumber)
|
||||
os.chdir(swathDir)
|
||||
|
||||
print('range filtering frame {}, swath {}'.format(frameNumber, swathNumber))
|
||||
|
||||
masterSwath = masterTrack.frames[i].swaths[j]
|
||||
slaveSwath = slaveTrack.frames[i].swaths[j]
|
||||
|
||||
# #compute filtering parameters
|
||||
# centerfreq1 = SPEED_OF_LIGHT / masterTrack.radarWavelength
|
||||
# bandwidth1 = masterSwath.rangeBandwidth
|
||||
# centerfreq2 = SPEED_OF_LIGHT / slaveTrack.radarWavelength
|
||||
# bandwidth2 = slaveSwath.rangeBandwidth
|
||||
# overlapfreq = overlapFrequency(centerfreq1, bandwidth1, centerfreq2, bandwidth2)
|
||||
|
||||
# if overlapfreq == None:
|
||||
# raise Exception('there is no overlap bandwidth in range')
|
||||
# overlapbandwidth = overlapfreq[1] - overlapfreq[0]
|
||||
# if overlapbandwidth < 3e6:
|
||||
# print('overlap bandwidth: {}, percentage: {}%'.format(overlapbandwidth, 100.0*overlapbandwidth/bandwidth1))
|
||||
# raise Exception('there is not enough overlap bandwidth in range')
|
||||
# centerfreq = (overlapfreq[1] + overlapfreq[0]) / 2.0
|
||||
|
||||
#filter master
|
||||
if abs(centerfreq1 - centerfreq) < 1.0 and (bandwidth1 - 1.0) < overlapbandwidth:
|
||||
print('no need to range filter {}'.format(self._insar.masterSlc))
|
||||
else:
|
||||
print('range filter {}'.format(self._insar.masterSlc))
|
||||
tmpSlc = 'tmp.slc'
|
||||
rg_filter(self._insar.masterSlc, 1, [tmpSlc], [overlapbandwidth / masterSwath.rangeSamplingRate],
|
||||
[(centerfreq - centerfreq1) / masterSwath.rangeSamplingRate],
|
||||
257, 2048, 0.1, 0, 0.0)
|
||||
|
||||
if os.path.isfile(self._insar.masterSlc):
|
||||
os.remove(self._insar.masterSlc)
|
||||
os.remove(self._insar.masterSlc+'.vrt')
|
||||
os.remove(self._insar.masterSlc+'.xml')
|
||||
|
||||
img = isceobj.createSlcImage()
|
||||
img.load(tmpSlc + '.xml')
|
||||
#remove original
|
||||
os.remove(tmpSlc + '.vrt')
|
||||
os.remove(tmpSlc + '.xml')
|
||||
os.rename(tmpSlc, self._insar.masterSlc)
|
||||
#creat new
|
||||
img.setFilename(self._insar.masterSlc)
|
||||
img.extraFilename = self._insar.masterSlc + '.vrt'
|
||||
img.setAccessMode('READ')
|
||||
img.renderHdr()
|
||||
|
||||
masterTrack.radarWavelength = SPEED_OF_LIGHT/centerfreq
|
||||
masterSwath.rangeBandwidth = overlapbandwidth
|
||||
|
||||
#filter slave
|
||||
if abs(centerfreq2 - centerfreq) < 1.0 and (bandwidth2 - 1.0) < overlapbandwidth:
|
||||
print('no need to range filter {}'.format(self._insar.slaveSlc))
|
||||
else:
|
||||
print('range filter {}'.format(self._insar.slaveSlc))
|
||||
tmpSlc = 'tmp.slc'
|
||||
rg_filter(self._insar.slaveSlc, 1, [tmpSlc], [overlapbandwidth / slaveSwath.rangeSamplingRate],
|
||||
[(centerfreq - centerfreq2) / slaveSwath.rangeSamplingRate],
|
||||
257, 2048, 0.1, 0, 0.0)
|
||||
|
||||
if os.path.isfile(self._insar.slaveSlc):
|
||||
os.remove(self._insar.slaveSlc)
|
||||
os.remove(self._insar.slaveSlc+'.vrt')
|
||||
os.remove(self._insar.slaveSlc+'.xml')
|
||||
|
||||
img = isceobj.createSlcImage()
|
||||
img.load(tmpSlc + '.xml')
|
||||
#remove original
|
||||
os.remove(tmpSlc + '.vrt')
|
||||
os.remove(tmpSlc + '.xml')
|
||||
os.rename(tmpSlc, self._insar.slaveSlc)
|
||||
#creat new
|
||||
img.setFilename(self._insar.slaveSlc)
|
||||
img.extraFilename = self._insar.slaveSlc + '.vrt'
|
||||
img.setAccessMode('READ')
|
||||
img.renderHdr()
|
||||
|
||||
slaveTrack.radarWavelength = SPEED_OF_LIGHT/centerfreq
|
||||
slaveSwath.rangeBandwidth = overlapbandwidth
|
||||
|
||||
os.chdir('../')
|
||||
os.chdir('../')
|
||||
|
||||
|
||||
####################################################
|
||||
#3. equalize sample size
|
||||
####################################################
|
||||
for i, frameNumber in enumerate(self._insar.masterFrames):
|
||||
frameDir = 'f{}_{}'.format(i+1, frameNumber)
|
||||
os.chdir(frameDir)
|
||||
for j, swathNumber in enumerate(range(self._insar.startingSwath, self._insar.endingSwath + 1)):
|
||||
swathDir = 's{}'.format(swathNumber)
|
||||
os.chdir(swathDir)
|
||||
|
||||
print('equalize sample size frame {}, swath {}'.format(frameNumber, swathNumber))
|
||||
|
||||
masterSwath = masterTrack.frames[i].swaths[j]
|
||||
slaveSwath = slaveTrack.frames[i].swaths[j]
|
||||
|
||||
if abs(masterSwath.rangeSamplingRate - slaveSwath.rangeSamplingRate) < 1.0 and abs(masterSwath.prf - slaveSwath.prf) < 1.0:
|
||||
print('no need to resample {}.'.format(self._insar.slaveSlc))
|
||||
else:
|
||||
outWidth = round(slaveSwath.numberOfSamples / slaveSwath.rangeSamplingRate * masterSwath.rangeSamplingRate)
|
||||
outLength = round(slaveSwath.numberOfLines / slaveSwath.prf * masterSwath.prf)
|
||||
|
||||
tmpSlc = 'tmp.slc'
|
||||
resamp(self._insar.slaveSlc, tmpSlc, 'fake', 'fake', outWidth, outLength, slaveSwath.prf, slaveSwath.dopplerVsPixel,
|
||||
rgcoef=[0.0, (1.0/masterSwath.rangeSamplingRate) / (1.0/slaveSwath.rangeSamplingRate) - 1.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0],
|
||||
azcoef=[0.0, 0.0, (1.0/masterSwath.prf) / (1.0/slaveSwath.prf) - 1.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0],
|
||||
azpos_off=0.0)
|
||||
|
||||
if os.path.isfile(self._insar.slaveSlc):
|
||||
os.remove(self._insar.slaveSlc)
|
||||
os.remove(self._insar.slaveSlc+'.vrt')
|
||||
os.remove(self._insar.slaveSlc+'.xml')
|
||||
|
||||
img = isceobj.createSlcImage()
|
||||
img.load(tmpSlc + '.xml')
|
||||
#remove original
|
||||
os.remove(tmpSlc + '.vrt')
|
||||
os.remove(tmpSlc + '.xml')
|
||||
os.rename(tmpSlc, self._insar.slaveSlc)
|
||||
#creat new
|
||||
img.setFilename(self._insar.slaveSlc)
|
||||
img.extraFilename = self._insar.slaveSlc + '.vrt'
|
||||
img.setAccessMode('READ')
|
||||
img.renderHdr()
|
||||
|
||||
#update parameters
|
||||
#update doppler and azfmrate first
|
||||
index2 = np.arange(outWidth)
|
||||
index = np.arange(outWidth) * (1.0/masterSwath.rangeSamplingRate) / (1.0/slaveSwath.rangeSamplingRate)
|
||||
dop = np.polyval(slaveSwath.dopplerVsPixel[::-1], index)
|
||||
p = np.polyfit(index2, dop, 3)
|
||||
slaveSwath.dopplerVsPixel = [p[3], p[2], p[1], p[0]]
|
||||
|
||||
azfmrate = np.polyval(slaveSwath.azimuthFmrateVsPixel[::-1], index)
|
||||
p = np.polyfit(index2, azfmrate, 3)
|
||||
slaveSwath.azimuthFmrateVsPixel = [p[3], p[2], p[1], p[0]]
|
||||
|
||||
slaveSwath.numberOfSamples = outWidth
|
||||
slaveSwath.numberOfLines = outLength
|
||||
|
||||
slaveSwath.prf = masterSwath.prf
|
||||
slaveSwath.rangeSamplingRate = masterSwath.rangeSamplingRate
|
||||
slaveSwath.rangePixelSize = masterSwath.rangePixelSize
|
||||
slaveSwath.azimuthPixelSize = masterSwath.azimuthPixelSize
|
||||
slaveSwath.azimuthLineInterval = masterSwath.azimuthLineInterval
|
||||
slaveSwath.prfFraction = masterSwath.prfFraction
|
||||
|
||||
os.chdir('../')
|
||||
os.chdir('../')
|
||||
|
||||
|
||||
####################################################
|
||||
#4. mbf
|
||||
####################################################
|
||||
for i, frameNumber in enumerate(self._insar.masterFrames):
|
||||
frameDir = 'f{}_{}'.format(i+1, frameNumber)
|
||||
os.chdir(frameDir)
|
||||
for j, swathNumber in enumerate(range(self._insar.startingSwath, self._insar.endingSwath + 1)):
|
||||
swathDir = 's{}'.format(swathNumber)
|
||||
os.chdir(swathDir)
|
||||
|
||||
print('azimuth filter frame {}, swath {}'.format(frameNumber, swathNumber))
|
||||
|
||||
masterSwath = masterTrack.frames[i].swaths[j]
|
||||
slaveSwath = slaveTrack.frames[i].swaths[j]
|
||||
|
||||
#using Piyush's code for computing range and azimuth offsets
|
||||
midRange = masterSwath.startingRange + masterSwath.rangePixelSize * masterSwath.numberOfSamples * 0.5
|
||||
midSensingStart = masterSwath.sensingStart + datetime.timedelta(seconds = masterSwath.numberOfLines * 0.5 / masterSwath.prf)
|
||||
llh = masterTrack.orbit.rdr2geo(midSensingStart, midRange)
|
||||
slvaz, slvrng = slaveTrack.orbit.geo2rdr(llh)
|
||||
###Translate to offsets
|
||||
#at this point, slave range pixel size and prf should be the same as those of master
|
||||
rgoff = ((slvrng - slaveSwath.startingRange) / masterSwath.rangePixelSize) - masterSwath.numberOfSamples * 0.5
|
||||
azoff = ((slvaz - slaveSwath.sensingStart).total_seconds() * masterSwath.prf) - masterSwath.numberOfLines * 0.5
|
||||
|
||||
#filter master
|
||||
if not ((self._insar.modeCombination == 21) and (self._insar.burstSynchronization <= self.burstSynchronizationThreshold)):
|
||||
print('no need to azimuth filter {}.'.format(self._insar.masterSlc))
|
||||
else:
|
||||
index = np.arange(masterSwath.numberOfSamples) + rgoff
|
||||
dop = np.polyval(slaveSwath.dopplerVsPixel[::-1], index)
|
||||
p = np.polyfit(index-rgoff, dop, 3)
|
||||
dopplerVsPixelSlave = [p[3], p[2], p[1], p[0]]
|
||||
|
||||
tmpSlc = 'tmp.slc'
|
||||
mbf(self._insar.masterSlc, tmpSlc, masterSwath.prf, 1.0,
|
||||
masterSwath.burstLength, masterSwath.burstCycleLength-masterSwath.burstLength,
|
||||
self._insar.burstUnsynchronizedTime * masterSwath.prf,
|
||||
(masterSwath.burstStartTime - masterSwath.sensingStart).total_seconds() * masterSwath.prf,
|
||||
masterSwath.azimuthFmrateVsPixel, masterSwath.dopplerVsPixel, dopplerVsPixelSlave)
|
||||
|
||||
if os.path.isfile(self._insar.masterSlc):
|
||||
os.remove(self._insar.masterSlc)
|
||||
os.remove(self._insar.masterSlc+'.vrt')
|
||||
os.remove(self._insar.masterSlc+'.xml')
|
||||
|
||||
img = isceobj.createSlcImage()
|
||||
img.load(tmpSlc + '.xml')
|
||||
#remove original
|
||||
os.remove(tmpSlc + '.vrt')
|
||||
os.remove(tmpSlc + '.xml')
|
||||
os.rename(tmpSlc, self._insar.masterSlc)
|
||||
#creat new
|
||||
img.setFilename(self._insar.masterSlc)
|
||||
img.extraFilename = self._insar.masterSlc + '.vrt'
|
||||
img.setAccessMode('READ')
|
||||
img.renderHdr()
|
||||
|
||||
#filter slave
|
||||
if not(
|
||||
((self._insar.modeCombination == 21) and (self._insar.burstSynchronization <= self.burstSynchronizationThreshold)) or \
|
||||
(self._insar.modeCombination == 31)
|
||||
):
|
||||
print('no need to azimuth filter {}.'.format(self._insar.slaveSlc))
|
||||
else:
|
||||
index = np.arange(slaveSwath.numberOfSamples) - rgoff
|
||||
dop = np.polyval(masterSwath.dopplerVsPixel[::-1], index)
|
||||
p = np.polyfit(index+rgoff, dop, 3)
|
||||
dopplerVsPixelMaster = [p[3], p[2], p[1], p[0]]
|
||||
|
||||
tmpSlc = 'tmp.slc'
|
||||
mbf(self._insar.slaveSlc, tmpSlc, slaveSwath.prf, 1.0,
|
||||
slaveSwath.burstLength, slaveSwath.burstCycleLength-slaveSwath.burstLength,
|
||||
-self._insar.burstUnsynchronizedTime * slaveSwath.prf,
|
||||
(slaveSwath.burstStartTime - slaveSwath.sensingStart).total_seconds() * slaveSwath.prf,
|
||||
slaveSwath.azimuthFmrateVsPixel, slaveSwath.dopplerVsPixel, dopplerVsPixelMaster)
|
||||
|
||||
if os.path.isfile(self._insar.slaveSlc):
|
||||
os.remove(self._insar.slaveSlc)
|
||||
os.remove(self._insar.slaveSlc+'.vrt')
|
||||
os.remove(self._insar.slaveSlc+'.xml')
|
||||
|
||||
img = isceobj.createSlcImage()
|
||||
img.load(tmpSlc + '.xml')
|
||||
#remove original
|
||||
os.remove(tmpSlc + '.vrt')
|
||||
os.remove(tmpSlc + '.xml')
|
||||
os.rename(tmpSlc, self._insar.slaveSlc)
|
||||
#creat new
|
||||
img.setFilename(self._insar.slaveSlc)
|
||||
img.extraFilename = self._insar.slaveSlc + '.vrt'
|
||||
img.setAccessMode('READ')
|
||||
img.renderHdr()
|
||||
|
||||
os.chdir('../')
|
||||
os.chdir('../')
|
||||
|
||||
#in case parameters changed
|
||||
self._insar.saveTrack(masterTrack, master=True)
|
||||
self._insar.saveTrack(slaveTrack, master=False)
|
||||
|
||||
catalog.printToLog(logger, "runPrepareSlc")
|
||||
self._insar.procDoc.addAllFromCatalog(catalog)
|
||||
|
||||
|
||||
def cropSlc(orbit, swath, slc, orbit2, swath2, edge=0, useVirtualFile=True):
|
||||
from isceobj.Alos2Proc.Alos2ProcPublic import find_vrt_keyword
|
||||
from isceobj.Alos2Proc.Alos2ProcPublic import create_xml
|
||||
'''
|
||||
orbit: orbit of the image to be cropped
|
||||
swath: swath of the image to be cropped
|
||||
slc: image to be cropped
|
||||
orbit2: orbit of the other image
|
||||
swath2: swath of the other image
|
||||
'''
|
||||
|
||||
#find topleft and lowerright corners
|
||||
#all indices start with 0
|
||||
corner = []
|
||||
for x in [[0, 0], [swath2.numberOfLines -1, swath2.numberOfSamples-1]]:
|
||||
line2 = x[0]
|
||||
sample2 = x[1]
|
||||
rg2 = swath2.startingRange + swath2.rangePixelSize * sample2
|
||||
az2 = swath2.sensingStart + datetime.timedelta(seconds = line2 / swath2.prf)
|
||||
llh2 = orbit2.rdr2geo(az2, rg2)
|
||||
az, rg = orbit.geo2rdr(llh2)
|
||||
line = (az - swath.sensingStart).total_seconds() * swath.prf
|
||||
sample = (rg - swath.startingRange) / swath.rangePixelSize
|
||||
corner.append([line, sample])
|
||||
|
||||
#image (to be cropped) bounds
|
||||
firstLine = 0
|
||||
lastLine = swath.numberOfLines-1
|
||||
firstSample = 0
|
||||
lastSample = swath.numberOfSamples-1
|
||||
|
||||
#the othe image bounds in image (to be cropped)
|
||||
#add edge
|
||||
#edge = 9
|
||||
firstLine2 = int(corner[0][0] - edge)
|
||||
lastLine2 = int(corner[1][0] + edge)
|
||||
firstSample2 = int(corner[0][1] - edge)
|
||||
lastSample2 = int(corner[1][1] + edge)
|
||||
|
||||
#image (to be cropped) output bounds
|
||||
firstLine3 = max(firstLine, firstLine2)
|
||||
lastLine3 = min(lastLine, lastLine2)
|
||||
firstSample3 = max(firstSample, firstSample2)
|
||||
lastSample3 = min(lastSample, lastSample2)
|
||||
numberOfSamples3 = lastSample3-firstSample3+1
|
||||
numberOfLines3 = lastLine3-firstLine3+1
|
||||
|
||||
#check if there is overlap
|
||||
if lastLine3 - firstLine3 +1 < 1000:
|
||||
raise Exception('azimuth overlap < 1000 lines, not enough area for InSAR\n')
|
||||
if lastSample3 - firstSample3 +1 < 1000:
|
||||
raise Exception('range overlap < 1000 samples, not enough area for InSAR\n')
|
||||
|
||||
#check if there is a need to crop image
|
||||
if abs(firstLine3-firstLine) < 100 and abs(lastLine3-lastLine) < 100 and \
|
||||
abs(firstSample3-firstSample) < 100 and abs(lastSample3-lastSample) < 100:
|
||||
print('no need to crop {}. nothing is done by crop.'.format(slc))
|
||||
return
|
||||
|
||||
#crop image
|
||||
if useVirtualFile:
|
||||
#vrt
|
||||
SourceFilename = find_vrt_keyword(slc+'.vrt', 'SourceFilename')
|
||||
ImageOffset = int(find_vrt_keyword(slc+'.vrt', 'ImageOffset'))
|
||||
PixelOffset = int(find_vrt_keyword(slc+'.vrt', 'PixelOffset'))
|
||||
LineOffset = int(find_vrt_keyword(slc+'.vrt', 'LineOffset'))
|
||||
|
||||
#overwrite vrt and xml
|
||||
img = isceobj.createImage()
|
||||
img.load(slc+'.xml')
|
||||
img.width = numberOfSamples3
|
||||
img.length = numberOfLines3
|
||||
img.renderHdr()
|
||||
|
||||
#overrite vrt
|
||||
with open(slc+'.vrt', 'w') as fid:
|
||||
fid.write('''<VRTDataset rasterXSize="{0}" rasterYSize="{1}">
|
||||
<VRTRasterBand band="1" dataType="CFloat32" subClass="VRTRawRasterBand">
|
||||
<SourceFilename relativeToVRT="0">{2}</SourceFilename>
|
||||
<ByteOrder>MSB</ByteOrder>
|
||||
<ImageOffset>{3}</ImageOffset>
|
||||
<PixelOffset>8</PixelOffset>
|
||||
<LineOffset>{4}</LineOffset>
|
||||
</VRTRasterBand>
|
||||
</VRTDataset>'''.format(numberOfSamples3,
|
||||
numberOfLines3,
|
||||
SourceFilename,
|
||||
ImageOffset + firstLine3*LineOffset + firstSample3*8,
|
||||
LineOffset))
|
||||
else:
|
||||
#read and crop data
|
||||
with open(slc, 'rb') as f:
|
||||
f.seek(firstLine3 * swath.numberOfSamples * np.dtype(np.complex64).itemsize, 0)
|
||||
data = np.fromfile(f, dtype=np.complex64, count=numberOfLines3 * swath.numberOfSamples)\
|
||||
.reshape(numberOfLines3,swath.numberOfSamples)
|
||||
data2 = data[:, firstSample3:lastSample3+1]
|
||||
#overwrite original
|
||||
data2.astype(np.complex64).tofile(slc)
|
||||
|
||||
#creat new vrt and xml
|
||||
os.remove(slc + '.xml')
|
||||
os.remove(slc + '.vrt')
|
||||
create_xml(slc, numberOfSamples3, numberOfLines3, 'slc')
|
||||
|
||||
#update parameters
|
||||
#update doppler and azfmrate first
|
||||
dop = np.polyval(swath.dopplerVsPixel[::-1], np.arange(swath.numberOfSamples))
|
||||
dop3 = dop[firstSample3:lastSample3+1]
|
||||
p = np.polyfit(np.arange(numberOfSamples3), dop3, 3)
|
||||
swath.dopplerVsPixel = [p[3], p[2], p[1], p[0]]
|
||||
|
||||
azfmrate = np.polyval(swath.azimuthFmrateVsPixel[::-1], np.arange(swath.numberOfSamples))
|
||||
azfmrate3 = azfmrate[firstSample3:lastSample3+1]
|
||||
p = np.polyfit(np.arange(numberOfSamples3), azfmrate3, 3)
|
||||
swath.azimuthFmrateVsPixel = [p[3], p[2], p[1], p[0]]
|
||||
|
||||
swath.numberOfSamples = numberOfSamples3
|
||||
swath.numberOfLines = numberOfLines3
|
||||
|
||||
swath.startingRange += firstSample3 * swath.rangePixelSize
|
||||
swath.sensingStart += datetime.timedelta(seconds = firstLine3 / swath.prf)
|
||||
|
||||
#no need to update frame and track, as parameters requiring changes are determined
|
||||
#in swath and frame mosaicking, which is not yet done at this point.
|
||||
|
||||
|
|
@ -0,0 +1,598 @@
|
|||
#
|
||||
# Author: Cunren Liang
|
||||
# Copyright 2015-present, NASA-JPL/Caltech
|
||||
#
|
||||
|
||||
import os
|
||||
import glob
|
||||
import logging
|
||||
import datetime
|
||||
import numpy as np
|
||||
|
||||
import isceobj
|
||||
import isceobj.Sensor.MultiMode as MultiMode
|
||||
from isceobj.Planet.Planet import Planet
|
||||
from isceobj.Alos2Proc.Alos2ProcPublic import runCmd
|
||||
from isceobj.Alos2Proc.Alos2ProcPublic import getBboxRdr
|
||||
from isceobj.Alos2Proc.Alos2ProcPublic import getBboxGeo
|
||||
|
||||
logger = logging.getLogger('isce.alos2insar.runPreprocessor')
|
||||
|
||||
def runPreprocessor(self):
|
||||
'''Extract images.
|
||||
'''
|
||||
catalog = isceobj.Catalog.createCatalog(self._insar.procDoc.name)
|
||||
|
||||
|
||||
#find files
|
||||
#actually no need to use absolute path any longer, since we are able to find file from vrt now. 27-JAN-2020, CRL.
|
||||
#denseoffset may still need absolute path when making links
|
||||
self.masterDir = os.path.abspath(self.masterDir)
|
||||
self.slaveDir = os.path.abspath(self.slaveDir)
|
||||
|
||||
ledFilesMaster = sorted(glob.glob(os.path.join(self.masterDir, 'LED-ALOS2*-*-*')))
|
||||
imgFilesMaster = sorted(glob.glob(os.path.join(self.masterDir, 'IMG-{}-ALOS2*-*-*'.format(self.masterPolarization.upper()))))
|
||||
|
||||
ledFilesSlave = sorted(glob.glob(os.path.join(self.slaveDir, 'LED-ALOS2*-*-*')))
|
||||
imgFilesSlave = sorted(glob.glob(os.path.join(self.slaveDir, 'IMG-{}-ALOS2*-*-*'.format(self.slavePolarization.upper()))))
|
||||
|
||||
firstFrameMaster = ledFilesMaster[0].split('-')[-3][-4:]
|
||||
firstFrameSlave = ledFilesSlave[0].split('-')[-3][-4:]
|
||||
firstFrameImagesMaster = sorted(glob.glob(os.path.join(self.masterDir, 'IMG-{}-ALOS2*{}-*-*'.format(self.masterPolarization.upper(), firstFrameMaster))))
|
||||
firstFrameImagesSlave = sorted(glob.glob(os.path.join(self.slaveDir, 'IMG-{}-ALOS2*{}-*-*'.format(self.slavePolarization.upper(), firstFrameSlave))))
|
||||
|
||||
|
||||
#determin operation mode
|
||||
masterMode = os.path.basename(ledFilesMaster[0]).split('-')[-1][0:3]
|
||||
slaveMode = os.path.basename(ledFilesSlave[0]).split('-')[-1][0:3]
|
||||
spotlightModes = ['SBS']
|
||||
stripmapModes = ['UBS', 'UBD', 'HBS', 'HBD', 'HBQ', 'FBS', 'FBD', 'FBQ']
|
||||
scansarNominalModes = ['WBS', 'WBD', 'WWS', 'WWD']
|
||||
scansarWideModes = ['VBS', 'VBD']
|
||||
scansarModes = ['WBS', 'WBD', 'WWS', 'WWD', 'VBS', 'VBD']
|
||||
|
||||
#usable combinations
|
||||
if (masterMode in spotlightModes) and (slaveMode in spotlightModes):
|
||||
self._insar.modeCombination = 0
|
||||
elif (masterMode in stripmapModes) and (slaveMode in stripmapModes):
|
||||
self._insar.modeCombination = 1
|
||||
elif (masterMode in scansarNominalModes) and (slaveMode in scansarNominalModes):
|
||||
self._insar.modeCombination = 21
|
||||
elif (masterMode in scansarWideModes) and (slaveMode in scansarWideModes):
|
||||
self._insar.modeCombination = 22
|
||||
elif (masterMode in scansarNominalModes) and (slaveMode in stripmapModes):
|
||||
self._insar.modeCombination = 31
|
||||
elif (masterMode in scansarWideModes) and (slaveMode in stripmapModes):
|
||||
self._insar.modeCombination = 32
|
||||
else:
|
||||
print('\n\nthis mode combination is not possible')
|
||||
print('note that for ScanSAR-stripmap, ScanSAR must be master\n\n')
|
||||
raise Exception('mode combination not supported')
|
||||
|
||||
# pixel size from real data processing. azimuth pixel size may change a bit as
|
||||
# the antenna points to a different swath and therefore uses a different PRF.
|
||||
|
||||
# MODE RANGE PIXEL SIZE (LOOKS) AZIMUTH PIXEL SIZE (LOOKS)
|
||||
# -------------------------------------------------------------------
|
||||
# SPT [SBS]
|
||||
# 1.4304222392897463 (2) 0.9351804642158579 (4)
|
||||
# SM1 [UBS,UBD]
|
||||
# 1.4304222392897463 (2) 1.8291988125114438 (2)
|
||||
# SM2 [HBS,HBD,HBQ]
|
||||
# 2.8608444785794984 (2) 3.0672373839847196 (2)
|
||||
# SM3 [FBS,FBD,FBQ]
|
||||
# 4.291266717869248 (2) 3.2462615913656667 (4)
|
||||
|
||||
# WD1 [WBS,WBD] [WWS,WWD]
|
||||
# 8.582533435738496 (1) 2.6053935830031887 (14)
|
||||
# 8.582533435738496 (1) 2.092362043327227 (14)
|
||||
# 8.582533435738496 (1) 2.8817632034495717 (14)
|
||||
# 8.582533435738496 (1) 3.054362492601842 (14)
|
||||
# 8.582533435738496 (1) 2.4582084463356977 (14)
|
||||
|
||||
# WD2 [VBS,VBD]
|
||||
# 8.582533435738496 (1) 2.9215796012950728 (14)
|
||||
# 8.582533435738496 (1) 3.088859074497863 (14)
|
||||
# 8.582533435738496 (1) 2.8792293071133073 (14)
|
||||
# 8.582533435738496 (1) 3.0592146044234854 (14)
|
||||
# 8.582533435738496 (1) 2.8818767752199137 (14)
|
||||
# 8.582533435738496 (1) 3.047038521027477 (14)
|
||||
# 8.582533435738496 (1) 2.898816222039108 (14)
|
||||
|
||||
#determine default number of looks:
|
||||
self._insar.numberRangeLooks1 = self.numberRangeLooks1
|
||||
self._insar.numberAzimuthLooks1 = self.numberAzimuthLooks1
|
||||
self._insar.numberRangeLooks2 = self.numberRangeLooks2
|
||||
self._insar.numberAzimuthLooks2 = self.numberAzimuthLooks2
|
||||
#the following two will be automatically determined by runRdrDemOffset.py
|
||||
self._insar.numberRangeLooksSim = self.numberRangeLooksSim
|
||||
self._insar.numberAzimuthLooksSim = self.numberAzimuthLooksSim
|
||||
self._insar.numberRangeLooksIon = self.numberRangeLooksIon
|
||||
self._insar.numberAzimuthLooksIon = self.numberAzimuthLooksIon
|
||||
|
||||
if self._insar.numberRangeLooks1 == None:
|
||||
if masterMode in ['SBS']:
|
||||
self._insar.numberRangeLooks1 = 2
|
||||
elif masterMode in ['UBS', 'UBD']:
|
||||
self._insar.numberRangeLooks1 = 2
|
||||
elif masterMode in ['HBS', 'HBD', 'HBQ']:
|
||||
self._insar.numberRangeLooks1 = 2
|
||||
elif masterMode in ['FBS', 'FBD', 'FBQ']:
|
||||
self._insar.numberRangeLooks1 = 2
|
||||
elif masterMode in ['WBS', 'WBD']:
|
||||
self._insar.numberRangeLooks1 = 1
|
||||
elif masterMode in ['WWS', 'WWD']:
|
||||
self._insar.numberRangeLooks1 = 2
|
||||
elif masterMode in ['VBS', 'VBD']:
|
||||
self._insar.numberRangeLooks1 = 1
|
||||
else:
|
||||
raise Exception('unknow acquisition mode')
|
||||
|
||||
if self._insar.numberAzimuthLooks1 == None:
|
||||
if masterMode in ['SBS']:
|
||||
self._insar.numberAzimuthLooks1 = 4
|
||||
elif masterMode in ['UBS', 'UBD']:
|
||||
self._insar.numberAzimuthLooks1 = 2
|
||||
elif masterMode in ['HBS', 'HBD', 'HBQ']:
|
||||
self._insar.numberAzimuthLooks1 = 2
|
||||
elif masterMode in ['FBS', 'FBD', 'FBQ']:
|
||||
self._insar.numberAzimuthLooks1 = 4
|
||||
elif masterMode in ['WBS', 'WBD']:
|
||||
self._insar.numberAzimuthLooks1 = 14
|
||||
elif masterMode in ['WWS', 'WWD']:
|
||||
self._insar.numberAzimuthLooks1 = 14
|
||||
elif masterMode in ['VBS', 'VBD']:
|
||||
self._insar.numberAzimuthLooks1 = 14
|
||||
else:
|
||||
raise Exception('unknow acquisition mode')
|
||||
|
||||
if self._insar.numberRangeLooks2 == None:
|
||||
if masterMode in spotlightModes:
|
||||
self._insar.numberRangeLooks2 = 4
|
||||
elif masterMode in stripmapModes:
|
||||
self._insar.numberRangeLooks2 = 4
|
||||
elif masterMode in scansarModes:
|
||||
self._insar.numberRangeLooks2 = 5
|
||||
else:
|
||||
raise Exception('unknow acquisition mode')
|
||||
|
||||
if self._insar.numberAzimuthLooks2 == None:
|
||||
if masterMode in spotlightModes:
|
||||
self._insar.numberAzimuthLooks2 = 4
|
||||
elif masterMode in stripmapModes:
|
||||
self._insar.numberAzimuthLooks2 = 4
|
||||
elif masterMode in scansarModes:
|
||||
self._insar.numberAzimuthLooks2 = 2
|
||||
else:
|
||||
raise Exception('unknow acquisition mode')
|
||||
|
||||
if self._insar.numberRangeLooksIon == None:
|
||||
if masterMode in spotlightModes:
|
||||
self._insar.numberRangeLooksIon = 16
|
||||
elif masterMode in stripmapModes:
|
||||
self._insar.numberRangeLooksIon = 16
|
||||
elif masterMode in scansarModes:
|
||||
self._insar.numberRangeLooksIon = 40
|
||||
else:
|
||||
raise Exception('unknow acquisition mode')
|
||||
|
||||
if self._insar.numberAzimuthLooksIon == None:
|
||||
if masterMode in spotlightModes:
|
||||
self._insar.numberAzimuthLooksIon = 16
|
||||
elif masterMode in stripmapModes:
|
||||
self._insar.numberAzimuthLooksIon = 16
|
||||
elif masterMode in scansarModes:
|
||||
self._insar.numberAzimuthLooksIon = 16
|
||||
else:
|
||||
raise Exception('unknow acquisition mode')
|
||||
|
||||
|
||||
#define processing file names
|
||||
self._insar.masterDate = os.path.basename(ledFilesMaster[0]).split('-')[2]
|
||||
self._insar.slaveDate = os.path.basename(ledFilesSlave[0]).split('-')[2]
|
||||
self._insar.setFilename(masterDate=self._insar.masterDate, slaveDate=self._insar.slaveDate, nrlks1=self._insar.numberRangeLooks1, nalks1=self._insar.numberAzimuthLooks1, nrlks2=self._insar.numberRangeLooks2, nalks2=self._insar.numberAzimuthLooks2)
|
||||
|
||||
|
||||
#find frame numbers
|
||||
if (self._insar.modeCombination == 31) or (self._insar.modeCombination == 32):
|
||||
if (self.masterFrames == None) or (self.slaveFrames == None):
|
||||
raise Exception('for ScanSAR-stripmap inteferometry, you must set master and slave frame numbers')
|
||||
#if not set, find frames automatically
|
||||
if self.masterFrames == None:
|
||||
self.masterFrames = []
|
||||
for led in ledFilesMaster:
|
||||
frameNumber = os.path.basename(led).split('-')[1][-4:]
|
||||
if frameNumber not in self.masterFrames:
|
||||
self.masterFrames.append(frameNumber)
|
||||
if self.slaveFrames == None:
|
||||
self.slaveFrames = []
|
||||
for led in ledFilesSlave:
|
||||
frameNumber = os.path.basename(led).split('-')[1][-4:]
|
||||
if frameNumber not in self.slaveFrames:
|
||||
self.slaveFrames.append(frameNumber)
|
||||
#sort frames
|
||||
self.masterFrames = sorted(self.masterFrames)
|
||||
self.slaveFrames = sorted(self.slaveFrames)
|
||||
#check number of frames
|
||||
if len(self.masterFrames) != len(self.slaveFrames):
|
||||
raise Exception('number of frames in master dir is not equal to number of frames \
|
||||
in slave dir. please set frame number manually')
|
||||
|
||||
|
||||
#find swath numbers (if not ScanSAR-ScanSAR, compute valid swaths)
|
||||
if (self._insar.modeCombination == 0) or (self._insar.modeCombination == 1):
|
||||
self.startingSwath = 1
|
||||
self.endingSwath = 1
|
||||
|
||||
if self._insar.modeCombination == 21:
|
||||
if self.startingSwath == None:
|
||||
self.startingSwath = 1
|
||||
if self.endingSwath == None:
|
||||
self.endingSwath = 5
|
||||
|
||||
if self._insar.modeCombination == 22:
|
||||
if self.startingSwath == None:
|
||||
self.startingSwath = 1
|
||||
if self.endingSwath == None:
|
||||
self.endingSwath = 7
|
||||
|
||||
#determine starting and ending swaths for ScanSAR-stripmap, user's settings are overwritten
|
||||
#use first frame to check overlap
|
||||
if (self._insar.modeCombination == 31) or (self._insar.modeCombination == 32):
|
||||
if self._insar.modeCombination == 31:
|
||||
numberOfSwaths = 5
|
||||
else:
|
||||
numberOfSwaths = 7
|
||||
overlapSubswaths = []
|
||||
for i in range(numberOfSwaths):
|
||||
overlapRatio = check_overlap(ledFilesMaster[0], firstFrameImagesMaster[i], ledFilesSlave[0], firstFrameImagesSlave[0])
|
||||
if overlapRatio > 1.0 / 4.0:
|
||||
overlapSubswaths.append(i+1)
|
||||
if overlapSubswaths == []:
|
||||
raise Exception('There is no overlap area between the ScanSAR-stripmap pair')
|
||||
self.startingSwath = int(overlapSubswaths[0])
|
||||
self.endingSwath = int(overlapSubswaths[-1])
|
||||
|
||||
#save the valid frames and swaths for future processing
|
||||
self._insar.masterFrames = self.masterFrames
|
||||
self._insar.slaveFrames = self.slaveFrames
|
||||
self._insar.startingSwath = self.startingSwath
|
||||
self._insar.endingSwath = self.endingSwath
|
||||
|
||||
|
||||
##################################################
|
||||
#1. create directories and read data
|
||||
##################################################
|
||||
self.master.configure()
|
||||
self.slave.configure()
|
||||
self.master.track.configure()
|
||||
self.slave.track.configure()
|
||||
for i, (masterFrame, slaveFrame) in enumerate(zip(self._insar.masterFrames, self._insar.slaveFrames)):
|
||||
#frame number starts with 1
|
||||
frameDir = 'f{}_{}'.format(i+1, masterFrame)
|
||||
if not os.path.exists(frameDir):
|
||||
os.makedirs(frameDir)
|
||||
os.chdir(frameDir)
|
||||
|
||||
#attach a frame to master and slave
|
||||
frameObjMaster = MultiMode.createFrame()
|
||||
frameObjSlave = MultiMode.createFrame()
|
||||
frameObjMaster.configure()
|
||||
frameObjSlave.configure()
|
||||
self.master.track.frames.append(frameObjMaster)
|
||||
self.slave.track.frames.append(frameObjSlave)
|
||||
|
||||
#swath number starts with 1
|
||||
for j in range(self._insar.startingSwath, self._insar.endingSwath+1):
|
||||
print('processing frame {} swath {}'.format(masterFrame, j))
|
||||
|
||||
swathDir = 's{}'.format(j)
|
||||
if not os.path.exists(swathDir):
|
||||
os.makedirs(swathDir)
|
||||
os.chdir(swathDir)
|
||||
|
||||
#attach a swath to master and slave
|
||||
swathObjMaster = MultiMode.createSwath()
|
||||
swathObjSlave = MultiMode.createSwath()
|
||||
swathObjMaster.configure()
|
||||
swathObjSlave.configure()
|
||||
self.master.track.frames[-1].swaths.append(swathObjMaster)
|
||||
self.slave.track.frames[-1].swaths.append(swathObjSlave)
|
||||
|
||||
#setup master
|
||||
self.master.leaderFile = sorted(glob.glob(os.path.join(self.masterDir, 'LED-ALOS2*{}-*-*'.format(masterFrame))))[0]
|
||||
if masterMode in scansarModes:
|
||||
self.master.imageFile = sorted(glob.glob(os.path.join(self.masterDir, 'IMG-{}-ALOS2*{}-*-*-F{}'.format(self.masterPolarization.upper(), masterFrame, j))))[0]
|
||||
else:
|
||||
self.master.imageFile = sorted(glob.glob(os.path.join(self.masterDir, 'IMG-{}-ALOS2*{}-*-*'.format(self.masterPolarization.upper(), masterFrame))))[0]
|
||||
self.master.outputFile = self._insar.masterSlc
|
||||
self.master.useVirtualFile = self.useVirtualFile
|
||||
#read master
|
||||
(imageFDR, imageData)=self.master.readImage()
|
||||
(leaderFDR, sceneHeaderRecord, platformPositionRecord, facilityRecord)=self.master.readLeader()
|
||||
self.master.setSwath(leaderFDR, sceneHeaderRecord, platformPositionRecord, facilityRecord, imageFDR, imageData)
|
||||
self.master.setFrame(leaderFDR, sceneHeaderRecord, platformPositionRecord, facilityRecord, imageFDR, imageData)
|
||||
self.master.setTrack(leaderFDR, sceneHeaderRecord, platformPositionRecord, facilityRecord, imageFDR, imageData)
|
||||
|
||||
#setup slave
|
||||
self.slave.leaderFile = sorted(glob.glob(os.path.join(self.slaveDir, 'LED-ALOS2*{}-*-*'.format(slaveFrame))))[0]
|
||||
if slaveMode in scansarModes:
|
||||
self.slave.imageFile = sorted(glob.glob(os.path.join(self.slaveDir, 'IMG-{}-ALOS2*{}-*-*-F{}'.format(self.slavePolarization.upper(), slaveFrame, j))))[0]
|
||||
else:
|
||||
self.slave.imageFile = sorted(glob.glob(os.path.join(self.slaveDir, 'IMG-{}-ALOS2*{}-*-*'.format(self.slavePolarization.upper(), slaveFrame))))[0]
|
||||
self.slave.outputFile = self._insar.slaveSlc
|
||||
self.slave.useVirtualFile = self.useVirtualFile
|
||||
#read slave
|
||||
(imageFDR, imageData)=self.slave.readImage()
|
||||
(leaderFDR, sceneHeaderRecord, platformPositionRecord, facilityRecord)=self.slave.readLeader()
|
||||
self.slave.setSwath(leaderFDR, sceneHeaderRecord, platformPositionRecord, facilityRecord, imageFDR, imageData)
|
||||
self.slave.setFrame(leaderFDR, sceneHeaderRecord, platformPositionRecord, facilityRecord, imageFDR, imageData)
|
||||
self.slave.setTrack(leaderFDR, sceneHeaderRecord, platformPositionRecord, facilityRecord, imageFDR, imageData)
|
||||
|
||||
os.chdir('../')
|
||||
self._insar.saveProduct(self.master.track.frames[-1], self._insar.masterFrameParameter)
|
||||
self._insar.saveProduct(self.slave.track.frames[-1], self._insar.slaveFrameParameter)
|
||||
os.chdir('../')
|
||||
self._insar.saveProduct(self.master.track, self._insar.masterTrackParameter)
|
||||
self._insar.saveProduct(self.slave.track, self._insar.slaveTrackParameter)
|
||||
|
||||
|
||||
##################################################
|
||||
#2. compute burst synchronization
|
||||
##################################################
|
||||
#burst synchronization may slowly change along a track as a result of the changing relative speed of the two flights
|
||||
#in one frame, real unsynchronized time is the same for all swaths
|
||||
unsynTime = 0
|
||||
#real synchronized time/percentage depends on the swath burst length (synTime = burstlength - abs(unsynTime))
|
||||
#synTime = 0
|
||||
synPercentage = 0
|
||||
|
||||
numberOfFrames = len(self._insar.masterFrames)
|
||||
numberOfSwaths = self._insar.endingSwath - self._insar.startingSwath + 1
|
||||
|
||||
for i, frameNumber in enumerate(self._insar.masterFrames):
|
||||
for j, swathNumber in enumerate(range(self._insar.startingSwath, self._insar.endingSwath + 1)):
|
||||
masterSwath = self.master.track.frames[i].swaths[j]
|
||||
slaveSwath = self.slave.track.frames[i].swaths[j]
|
||||
#using Piyush's code for computing range and azimuth offsets
|
||||
midRange = masterSwath.startingRange + masterSwath.rangePixelSize * masterSwath.numberOfSamples * 0.5
|
||||
midSensingStart = masterSwath.sensingStart + datetime.timedelta(seconds = masterSwath.numberOfLines * 0.5 / masterSwath.prf)
|
||||
llh = self.master.track.orbit.rdr2geo(midSensingStart, midRange)
|
||||
slvaz, slvrng = self.slave.track.orbit.geo2rdr(llh)
|
||||
###Translate to offsets
|
||||
#note that slave range pixel size and prf might be different from master, here we assume there is a virtual slave with same
|
||||
#range pixel size and prf
|
||||
rgoff = ((slvrng - slaveSwath.startingRange) / masterSwath.rangePixelSize) - masterSwath.numberOfSamples * 0.5
|
||||
azoff = ((slvaz - slaveSwath.sensingStart).total_seconds() * masterSwath.prf) - masterSwath.numberOfLines * 0.5
|
||||
|
||||
#compute burst synchronization
|
||||
#burst parameters for ScanSAR wide mode not estimed yet
|
||||
if self._insar.modeCombination == 21:
|
||||
scburstStartLine = (masterSwath.burstStartTime - masterSwath.sensingStart).total_seconds() * masterSwath.prf + azoff
|
||||
#slave burst start times corresponding to master burst start times (100% synchronization)
|
||||
scburstStartLines = np.arange(scburstStartLine - 100000*masterSwath.burstCycleLength, \
|
||||
scburstStartLine + 100000*masterSwath.burstCycleLength, \
|
||||
masterSwath.burstCycleLength)
|
||||
dscburstStartLines = -((slaveSwath.burstStartTime - slaveSwath.sensingStart).total_seconds() * slaveSwath.prf - scburstStartLines)
|
||||
#find the difference with minimum absolute value
|
||||
unsynLines = dscburstStartLines[np.argmin(np.absolute(dscburstStartLines))]
|
||||
if np.absolute(unsynLines) >= slaveSwath.burstLength:
|
||||
synLines = 0
|
||||
if unsynLines > 0:
|
||||
unsynLines = slaveSwath.burstLength
|
||||
else:
|
||||
unsynLines = -slaveSwath.burstLength
|
||||
else:
|
||||
synLines = slaveSwath.burstLength - np.absolute(unsynLines)
|
||||
|
||||
unsynTime += unsynLines / masterSwath.prf
|
||||
synPercentage += synLines / masterSwath.burstLength * 100.0
|
||||
|
||||
catalog.addItem('burst synchronization of frame {} swath {}'.format(frameNumber, swathNumber), '%.1f%%'%(synLines / masterSwath.burstLength * 100.0), 'runPreprocessor')
|
||||
|
||||
############################################################################################
|
||||
#illustration of the sign of the number of unsynchronized lines (unsynLines)
|
||||
#The convention is the same as ampcor offset, that is,
|
||||
# slaveLineNumber = masterLineNumber + unsynLines
|
||||
#
|
||||
# |-----------------------| ------------
|
||||
# | | ^
|
||||
# | | |
|
||||
# | | | unsynLines < 0
|
||||
# | | |
|
||||
# | | \ /
|
||||
# | | |-----------------------|
|
||||
# | | | |
|
||||
# | | | |
|
||||
# |-----------------------| | |
|
||||
# Master Burst | |
|
||||
# | |
|
||||
# | |
|
||||
# | |
|
||||
# | |
|
||||
# |-----------------------|
|
||||
# Slave Burst
|
||||
#
|
||||
#
|
||||
############################################################################################
|
||||
|
||||
##burst parameters for ScanSAR wide mode not estimed yet
|
||||
elif self._insar.modeCombination == 31:
|
||||
#scansar is master
|
||||
scburstStartLine = (masterSwath.burstStartTime - masterSwath.sensingStart).total_seconds() * masterSwath.prf + azoff
|
||||
#slave burst start times corresponding to master burst start times (100% synchronization)
|
||||
for k in range(-100000, 100000):
|
||||
saz_burstx = scburstStartLine + masterSwath.burstCycleLength * k
|
||||
st_burstx = slaveSwath.sensingStart + datetime.timedelta(seconds=saz_burstx / masterSwath.prf)
|
||||
if saz_burstx >= 0.0 and saz_burstx <= slaveSwath.numberOfLines -1:
|
||||
slaveSwath.burstStartTime = st_burstx
|
||||
slaveSwath.burstLength = masterSwath.burstLength
|
||||
slaveSwath.burstCycleLength = masterSwath.burstCycleLength
|
||||
slaveSwath.swathNumber = masterSwath.swathNumber
|
||||
break
|
||||
#unsynLines = 0
|
||||
#synLines = masterSwath.burstLength
|
||||
#unsynTime += unsynLines / masterSwath.prf
|
||||
#synPercentage += synLines / masterSwath.burstLength * 100.0
|
||||
catalog.addItem('burst synchronization of frame {} swath {}'.format(frameNumber, swathNumber), '%.1f%%'%(100.0), 'runPreprocessor')
|
||||
else:
|
||||
pass
|
||||
|
||||
#overwrite original frame parameter file
|
||||
if self._insar.modeCombination == 31:
|
||||
frameDir = 'f{}_{}'.format(i+1, frameNumber)
|
||||
self._insar.saveProduct(self.slave.track.frames[i], os.path.join(frameDir, self._insar.slaveFrameParameter))
|
||||
|
||||
#getting average
|
||||
if self._insar.modeCombination == 21:
|
||||
unsynTime /= numberOfFrames*numberOfSwaths
|
||||
synPercentage /= numberOfFrames*numberOfSwaths
|
||||
elif self._insar.modeCombination == 31:
|
||||
unsynTime = 0.
|
||||
synPercentage = 100.
|
||||
else:
|
||||
pass
|
||||
|
||||
#record results
|
||||
if (self._insar.modeCombination == 21) or (self._insar.modeCombination == 31):
|
||||
self._insar.burstUnsynchronizedTime = unsynTime
|
||||
self._insar.burstSynchronization = synPercentage
|
||||
catalog.addItem('burst synchronization averaged', '%.1f%%'%(synPercentage), 'runPreprocessor')
|
||||
|
||||
|
||||
##################################################
|
||||
#3. compute baseline
|
||||
##################################################
|
||||
#only compute baseline at four corners and center of the master track
|
||||
bboxRdr = getBboxRdr(self.master.track)
|
||||
|
||||
rangeMin = bboxRdr[0]
|
||||
rangeMax = bboxRdr[1]
|
||||
azimuthTimeMin = bboxRdr[2]
|
||||
azimuthTimeMax = bboxRdr[3]
|
||||
|
||||
azimuthTimeMid = azimuthTimeMin+datetime.timedelta(seconds=(azimuthTimeMax-azimuthTimeMin).total_seconds()/2.0)
|
||||
rangeMid = (rangeMin + rangeMax) / 2.0
|
||||
|
||||
points = [[azimuthTimeMin, rangeMin],
|
||||
[azimuthTimeMin, rangeMax],
|
||||
[azimuthTimeMax, rangeMin],
|
||||
[azimuthTimeMax, rangeMax],
|
||||
[azimuthTimeMid, rangeMid]]
|
||||
|
||||
Bpar = []
|
||||
Bperp = []
|
||||
#modify Piyush's code for computing baslines
|
||||
refElp = Planet(pname='Earth').ellipsoid
|
||||
for x in points:
|
||||
masterSV = self.master.track.orbit.interpolate(x[0], method='hermite')
|
||||
target = self.master.track.orbit.rdr2geo(x[0], x[1])
|
||||
|
||||
slvTime, slvrng = self.slave.track.orbit.geo2rdr(target)
|
||||
slaveSV = self.slave.track.orbit.interpolateOrbit(slvTime, method='hermite')
|
||||
|
||||
targxyz = np.array(refElp.LLH(target[0], target[1], target[2]).ecef().tolist())
|
||||
mxyz = np.array(masterSV.getPosition())
|
||||
mvel = np.array(masterSV.getVelocity())
|
||||
sxyz = np.array(slaveSV.getPosition())
|
||||
|
||||
aa = np.linalg.norm(sxyz-mxyz)
|
||||
costheta = (x[1]*x[1] + aa*aa - slvrng*slvrng)/(2.*x[1]*aa)
|
||||
|
||||
Bpar.append(aa*costheta)
|
||||
|
||||
perp = aa * np.sqrt(1 - costheta*costheta)
|
||||
direction = np.sign(np.dot( np.cross(targxyz-mxyz, sxyz-mxyz), mvel))
|
||||
Bperp.append(direction*perp)
|
||||
|
||||
catalog.addItem('parallel baseline at upperleft of master track', Bpar[0], 'runPreprocessor')
|
||||
catalog.addItem('parallel baseline at upperright of master track', Bpar[1], 'runPreprocessor')
|
||||
catalog.addItem('parallel baseline at lowerleft of master track', Bpar[2], 'runPreprocessor')
|
||||
catalog.addItem('parallel baseline at lowerright of master track', Bpar[3], 'runPreprocessor')
|
||||
catalog.addItem('parallel baseline at center of master track', Bpar[4], 'runPreprocessor')
|
||||
|
||||
catalog.addItem('perpendicular baseline at upperleft of master track', Bperp[0], 'runPreprocessor')
|
||||
catalog.addItem('perpendicular baseline at upperright of master track', Bperp[1], 'runPreprocessor')
|
||||
catalog.addItem('perpendicular baseline at lowerleft of master track', Bperp[2], 'runPreprocessor')
|
||||
catalog.addItem('perpendicular baseline at lowerright of master track', Bperp[3], 'runPreprocessor')
|
||||
catalog.addItem('perpendicular baseline at center of master track', Bperp[4], 'runPreprocessor')
|
||||
|
||||
|
||||
##################################################
|
||||
#4. compute bounding box
|
||||
##################################################
|
||||
masterBbox = getBboxGeo(self.master.track)
|
||||
slaveBbox = getBboxGeo(self.slave.track)
|
||||
|
||||
catalog.addItem('master bounding box', masterBbox, 'runPreprocessor')
|
||||
catalog.addItem('slave bounding box', slaveBbox, 'runPreprocessor')
|
||||
|
||||
|
||||
catalog.printToLog(logger, "runPreprocessor")
|
||||
self._insar.procDoc.addAllFromCatalog(catalog)
|
||||
|
||||
|
||||
|
||||
def check_overlap(ldr_m, img_m, ldr_s, img_s):
|
||||
from isceobj.Constants import SPEED_OF_LIGHT
|
||||
|
||||
rangeSamplingRateMaster, widthMaster, nearRangeMaster = read_param_for_checking_overlap(ldr_m, img_m)
|
||||
rangeSamplingRateSlave, widthSlave, nearRangeSlave = read_param_for_checking_overlap(ldr_s, img_s)
|
||||
|
||||
farRangeMaster = nearRangeMaster + (widthMaster-1) * 0.5 * SPEED_OF_LIGHT / rangeSamplingRateMaster
|
||||
farRangeSlave = nearRangeSlave + (widthSlave-1) * 0.5 * SPEED_OF_LIGHT / rangeSamplingRateSlave
|
||||
|
||||
#This should be good enough, although precise image offsets are not used.
|
||||
if farRangeMaster <= nearRangeSlave:
|
||||
overlapRatio = 0.0
|
||||
elif farRangeSlave <= nearRangeMaster:
|
||||
overlapRatio = 0.0
|
||||
else:
|
||||
# 0 1 2 3
|
||||
ranges = np.array([nearRangeMaster, farRangeMaster, nearRangeSlave, farRangeSlave])
|
||||
rangesIndex = np.argsort(ranges)
|
||||
overlapRatio = ranges[rangesIndex[2]]-ranges[rangesIndex[1]] / (farRangeMaster-nearRangeMaster)
|
||||
|
||||
return overlapRatio
|
||||
|
||||
|
||||
def read_param_for_checking_overlap(leader_file, image_file):
|
||||
from isceobj.Sensor import xmlPrefix
|
||||
import isceobj.Sensor.CEOS as CEOS
|
||||
|
||||
#read from leader file
|
||||
fsampConst = { 104: 1.047915957140240E+08,
|
||||
52: 5.239579785701190E+07,
|
||||
34: 3.493053190467460E+07,
|
||||
17: 1.746526595233730E+07 }
|
||||
|
||||
fp = open(leader_file,'rb')
|
||||
leaderFDR = CEOS.CEOSDB(xml=os.path.join(xmlPrefix,'alos2_slc/leader_file.xml'),dataFile=fp)
|
||||
leaderFDR.parse()
|
||||
fp.seek(leaderFDR.getEndOfRecordPosition())
|
||||
sceneHeaderRecord = CEOS.CEOSDB(xml=os.path.join(xmlPrefix,'alos2_slc/scene_record.xml'),dataFile=fp)
|
||||
sceneHeaderRecord.parse()
|
||||
fp.seek(sceneHeaderRecord.getEndOfRecordPosition())
|
||||
|
||||
fsamplookup = int(sceneHeaderRecord.metadata['Range sampling rate in MHz'])
|
||||
rangeSamplingRate = fsampConst[fsamplookup]
|
||||
fp.close()
|
||||
#print('{}'.format(rangeSamplingRate))
|
||||
|
||||
#read from image file
|
||||
fp = open(image_file, 'rb')
|
||||
imageFDR = CEOS.CEOSDB(xml=os.path.join(xmlPrefix,'alos2_slc/image_file.xml'), dataFile=fp)
|
||||
imageFDR.parse()
|
||||
fp.seek(imageFDR.getEndOfRecordPosition())
|
||||
imageData = CEOS.CEOSDB(xml=os.path.join(xmlPrefix,'alos2_slc/image_record.xml'), dataFile=fp)
|
||||
imageData.parseFast()
|
||||
|
||||
width = imageFDR.metadata['Number of pixels per line per SAR channel']
|
||||
near_range = imageData.metadata['Slant range to 1st data sample']
|
||||
fp.close()
|
||||
#print('{}'.format(width))
|
||||
#print('{}'.format(near_range))
|
||||
|
||||
return (rangeSamplingRate, width, near_range)
|
||||
|
||||
|
||||
|
|
@ -0,0 +1,230 @@
|
|||
#
|
||||
# Author: Cunren Liang
|
||||
# Copyright 2015-present, NASA-JPL/Caltech
|
||||
#
|
||||
|
||||
import os
|
||||
import logging
|
||||
|
||||
import isceobj
|
||||
from isceobj.Alos2Proc.Alos2ProcPublic import waterBodyRadar
|
||||
|
||||
logger = logging.getLogger('isce.alos2insar.runRdr2Geo')
|
||||
|
||||
def runRdr2Geo(self):
|
||||
'''compute lat/lon/hgt
|
||||
'''
|
||||
catalog = isceobj.Catalog.createCatalog(self._insar.procDoc.name)
|
||||
self.updateParamemetersFromUser()
|
||||
|
||||
masterTrack = self._insar.loadTrack(master=True)
|
||||
demFile = os.path.abspath(self._insar.dem)
|
||||
wbdFile = os.path.abspath(self._insar.wbd)
|
||||
|
||||
insarDir = 'insar'
|
||||
if not os.path.exists(insarDir):
|
||||
os.makedirs(insarDir)
|
||||
os.chdir(insarDir)
|
||||
|
||||
|
||||
if self.useGPU and self._insar.hasGPU():
|
||||
topoGPU(masterTrack, self._insar.numberRangeLooks1, self._insar.numberAzimuthLooks1, demFile,
|
||||
self._insar.latitude, self._insar.longitude, self._insar.height, self._insar.los)
|
||||
else:
|
||||
snwe = topoCPU(masterTrack, self._insar.numberRangeLooks1, self._insar.numberAzimuthLooks1, demFile,
|
||||
self._insar.latitude, self._insar.longitude, self._insar.height, self._insar.los)
|
||||
waterBodyRadar(self._insar.latitude, self._insar.longitude, wbdFile, self._insar.wbdOut)
|
||||
|
||||
os.chdir('../')
|
||||
|
||||
catalog.printToLog(logger, "runRdr2Geo")
|
||||
self._insar.procDoc.addAllFromCatalog(catalog)
|
||||
|
||||
|
||||
def topoCPU(masterTrack, numberRangeLooks, numberAzimuthLooks, demFile, latFile, lonFile, hgtFile, losFile):
|
||||
import datetime
|
||||
import isceobj
|
||||
from zerodop.topozero import createTopozero
|
||||
from isceobj.Planet.Planet import Planet
|
||||
|
||||
pointingDirection = {'right': -1, 'left' :1}
|
||||
|
||||
demImage = isceobj.createDemImage()
|
||||
demImage.load(demFile + '.xml')
|
||||
demImage.setAccessMode('read')
|
||||
|
||||
planet = Planet(pname='Earth')
|
||||
|
||||
topo = createTopozero()
|
||||
topo.slantRangePixelSpacing = numberRangeLooks * masterTrack.rangePixelSize
|
||||
topo.prf = 1.0 / (numberAzimuthLooks*masterTrack.azimuthLineInterval)
|
||||
topo.radarWavelength = masterTrack.radarWavelength
|
||||
topo.orbit = masterTrack.orbit
|
||||
topo.width = masterTrack.numberOfSamples
|
||||
topo.length = masterTrack.numberOfLines
|
||||
topo.wireInputPort(name='dem', object=demImage)
|
||||
topo.wireInputPort(name='planet', object=planet)
|
||||
topo.numberRangeLooks = 1 #must be set as 1
|
||||
topo.numberAzimuthLooks = 1 #must be set as 1 Cunren
|
||||
topo.lookSide = pointingDirection[masterTrack.pointingDirection]
|
||||
topo.sensingStart = masterTrack.sensingStart + datetime.timedelta(seconds=(numberAzimuthLooks-1.0)/2.0*masterTrack.azimuthLineInterval)
|
||||
topo.rangeFirstSample = masterTrack.startingRange + (numberRangeLooks-1.0)/2.0*masterTrack.rangePixelSize
|
||||
topo.demInterpolationMethod='BIQUINTIC'
|
||||
|
||||
topo.latFilename = latFile
|
||||
topo.lonFilename = lonFile
|
||||
topo.heightFilename = hgtFile
|
||||
topo.losFilename = losFile
|
||||
#topo.incFilename = incName
|
||||
#topo.maskFilename = mskName
|
||||
|
||||
topo.topo()
|
||||
|
||||
return list(topo.snwe)
|
||||
|
||||
|
||||
def topoGPU(masterTrack, numberRangeLooks, numberAzimuthLooks, demFile, latFile, lonFile, hgtFile, losFile):
|
||||
'''
|
||||
Try with GPU module.
|
||||
'''
|
||||
import datetime
|
||||
import numpy as np
|
||||
from isceobj.Planet.Planet import Planet
|
||||
from zerodop.GPUtopozero.GPUtopozero import PyTopozero
|
||||
from isceobj.Util.Poly2D import Poly2D
|
||||
from iscesys import DateTimeUtil as DTU
|
||||
|
||||
pointingDirection = {'right': -1, 'left' :1}
|
||||
|
||||
#creat poynomials
|
||||
polyDoppler = Poly2D(name='topsApp_dopplerPoly')
|
||||
polyDoppler.setWidth(masterTrack.numberOfSamples)
|
||||
polyDoppler.setLength(masterTrack.numberOfLines)
|
||||
polyDoppler.setNormRange(1.0)
|
||||
polyDoppler.setNormAzimuth(1.0)
|
||||
polyDoppler.setMeanRange(0.0)
|
||||
polyDoppler.setMeanAzimuth(0.0)
|
||||
polyDoppler.initPoly(rangeOrder=0,azimuthOrder=0, coeffs=[[0.]])
|
||||
polyDoppler.createPoly2D()
|
||||
|
||||
slantRangeImage = Poly2D()
|
||||
slantRangeImage.setWidth(masterTrack.numberOfSamples)
|
||||
slantRangeImage.setLength(masterTrack.numberOfLines)
|
||||
slantRangeImage.setNormRange(1.0)
|
||||
slantRangeImage.setNormAzimuth(1.0)
|
||||
slantRangeImage.setMeanRange(0.)
|
||||
slantRangeImage.setMeanAzimuth(0.)
|
||||
slantRangeImage.initPoly(rangeOrder=1,azimuthOrder=0,
|
||||
coeffs=[[masterTrack.startingRange + (numberRangeLooks-1.0)/2.0*masterTrack.rangePixelSize,numberRangeLooks * masterTrack.rangePixelSize]])
|
||||
slantRangeImage.createPoly2D()
|
||||
|
||||
#creat images
|
||||
latImage = isceobj.createImage()
|
||||
latImage.initImage(latFile, 'write', masterTrack.numberOfSamples, 'DOUBLE')
|
||||
latImage.createImage()
|
||||
|
||||
lonImage = isceobj.createImage()
|
||||
lonImage.initImage(lonFile, 'write', masterTrack.numberOfSamples, 'DOUBLE')
|
||||
lonImage.createImage()
|
||||
|
||||
losImage = isceobj.createImage()
|
||||
losImage.initImage(losFile, 'write', masterTrack.numberOfSamples, 'FLOAT', bands=2, scheme='BIL')
|
||||
losImage.setCaster('write', 'DOUBLE')
|
||||
losImage.createImage()
|
||||
|
||||
heightImage = isceobj.createImage()
|
||||
heightImage.initImage(hgtFile, 'write', masterTrack.numberOfSamples, 'DOUBLE')
|
||||
heightImage.createImage()
|
||||
|
||||
demImage = isceobj.createDemImage()
|
||||
demImage.load(demFile + '.xml')
|
||||
demImage.setCaster('read', 'FLOAT')
|
||||
demImage.createImage()
|
||||
|
||||
#compute a few things
|
||||
t0 = masterTrack.sensingStart + datetime.timedelta(seconds=(numberAzimuthLooks-1.0)/2.0*masterTrack.azimuthLineInterval)
|
||||
orb = masterTrack.orbit
|
||||
pegHdg = np.radians( orb.getENUHeading(t0))
|
||||
elp = Planet(pname='Earth').ellipsoid
|
||||
|
||||
#call gpu topo
|
||||
topo = PyTopozero()
|
||||
topo.set_firstlat(demImage.getFirstLatitude())
|
||||
topo.set_firstlon(demImage.getFirstLongitude())
|
||||
topo.set_deltalat(demImage.getDeltaLatitude())
|
||||
topo.set_deltalon(demImage.getDeltaLongitude())
|
||||
topo.set_major(elp.a)
|
||||
topo.set_eccentricitySquared(elp.e2)
|
||||
topo.set_rSpace(numberRangeLooks * masterTrack.rangePixelSize)
|
||||
topo.set_r0(masterTrack.startingRange + (numberRangeLooks-1.0)/2.0*masterTrack.rangePixelSize)
|
||||
topo.set_pegHdg(pegHdg)
|
||||
topo.set_prf(1.0 / (numberAzimuthLooks*masterTrack.azimuthLineInterval))
|
||||
topo.set_t0(DTU.seconds_since_midnight(t0))
|
||||
topo.set_wvl(masterTrack.radarWavelength)
|
||||
topo.set_thresh(.05)
|
||||
topo.set_demAccessor(demImage.getImagePointer())
|
||||
topo.set_dopAccessor(polyDoppler.getPointer())
|
||||
topo.set_slrngAccessor(slantRangeImage.getPointer())
|
||||
topo.set_latAccessor(latImage.getImagePointer())
|
||||
topo.set_lonAccessor(lonImage.getImagePointer())
|
||||
topo.set_losAccessor(losImage.getImagePointer())
|
||||
topo.set_heightAccessor(heightImage.getImagePointer())
|
||||
topo.set_incAccessor(0)
|
||||
topo.set_maskAccessor(0)
|
||||
topo.set_numIter(25)
|
||||
topo.set_idemWidth(demImage.getWidth())
|
||||
topo.set_idemLength(demImage.getLength())
|
||||
topo.set_ilrl(pointingDirection[masterTrack.pointingDirection])
|
||||
topo.set_extraIter(10)
|
||||
topo.set_length(masterTrack.numberOfLines)
|
||||
topo.set_width(masterTrack.numberOfSamples)
|
||||
topo.set_nRngLooks(1)
|
||||
topo.set_nAzLooks(1)
|
||||
topo.set_demMethod(5) # BIQUINTIC METHOD
|
||||
topo.set_orbitMethod(0) # HERMITE
|
||||
|
||||
# Need to simplify orbit stuff later
|
||||
nvecs = len(orb._stateVectors)
|
||||
topo.set_orbitNvecs(nvecs)
|
||||
topo.set_orbitBasis(1) # Is this ever different?
|
||||
topo.createOrbit() # Initializes the empty orbit to the right allocated size
|
||||
count = 0
|
||||
for sv in orb._stateVectors:
|
||||
td = DTU.seconds_since_midnight(sv.getTime())
|
||||
pos = sv.getPosition()
|
||||
vel = sv.getVelocity()
|
||||
topo.set_orbitVector(count,td,pos[0],pos[1],pos[2],vel[0],vel[1],vel[2])
|
||||
count += 1
|
||||
|
||||
topo.runTopo()
|
||||
|
||||
#tidy up
|
||||
latImage.addDescription('Pixel-by-pixel latitude in degrees.')
|
||||
latImage.finalizeImage()
|
||||
latImage.renderHdr()
|
||||
|
||||
lonImage.addDescription('Pixel-by-pixel longitude in degrees.')
|
||||
lonImage.finalizeImage()
|
||||
lonImage.renderHdr()
|
||||
|
||||
heightImage.addDescription('Pixel-by-pixel height in meters.')
|
||||
heightImage.finalizeImage()
|
||||
heightImage.renderHdr()
|
||||
|
||||
descr = '''Two channel Line-Of-Sight geometry image (all angles in degrees). Represents vector drawn from target to platform.
|
||||
Channel 1: Incidence angle measured from vertical at target (always +ve).
|
||||
Channel 2: Azimuth angle measured from North in Anti-clockwise direction.'''
|
||||
losImage.setImageType('bil')
|
||||
losImage.addDescription(descr)
|
||||
losImage.finalizeImage()
|
||||
losImage.renderHdr()
|
||||
|
||||
demImage.finalizeImage()
|
||||
|
||||
if slantRangeImage:
|
||||
try:
|
||||
slantRangeImage.finalizeImage()
|
||||
except:
|
||||
pass
|
||||
|
||||
|
||||
|
|
@ -0,0 +1,322 @@
|
|||
#
|
||||
# Author: Cunren Liang
|
||||
# Copyright 2015-present, NASA-JPL/Caltech
|
||||
#
|
||||
|
||||
import os
|
||||
import logging
|
||||
import numpy as np
|
||||
|
||||
import isceobj
|
||||
from mroipac.ampcor.Ampcor import Ampcor
|
||||
from isceobj.Alos2Proc.Alos2ProcPublic import runCmd
|
||||
from contrib.alos2proc.alos2proc import look
|
||||
from isceobj.Alos2Proc.Alos2ProcPublic import create_xml
|
||||
from isceobj.Alos2Proc.Alos2ProcPublic import writeOffset
|
||||
from contrib.alos2proc_f.alos2proc_f import fitoff
|
||||
|
||||
logger = logging.getLogger('isce.alos2insar.runRdrDemOffset')
|
||||
|
||||
def runRdrDemOffset(self):
|
||||
'''estimate between radar image and dem
|
||||
'''
|
||||
catalog = isceobj.Catalog.createCatalog(self._insar.procDoc.name)
|
||||
self.updateParamemetersFromUser()
|
||||
|
||||
masterTrack = self._insar.loadTrack(master=True)
|
||||
demFile = os.path.abspath(self._insar.dem)
|
||||
|
||||
insarDir = 'insar'
|
||||
if not os.path.exists(insarDir):
|
||||
os.makedirs(insarDir)
|
||||
os.chdir(insarDir)
|
||||
|
||||
rdrDemDir = 'rdr_dem_offset'
|
||||
if not os.path.exists(rdrDemDir):
|
||||
os.makedirs(rdrDemDir)
|
||||
os.chdir(rdrDemDir)
|
||||
|
||||
##################################################################################################
|
||||
#compute dem pixel size
|
||||
demImage = isceobj.createDemImage()
|
||||
demImage.load(demFile + '.xml')
|
||||
#DEM pixel size in meters (appoximate value)
|
||||
demDeltaLon = abs(demImage.getDeltaLongitude()) / 0.0002777777777777778 * 30.0
|
||||
demDeltaLat = abs(demImage.getDeltaLatitude()) / 0.0002777777777777778 * 30.0
|
||||
|
||||
#number of looks to take in range
|
||||
if self._insar.numberRangeLooksSim == None:
|
||||
if self._insar.numberRangeLooks1 * masterTrack.rangePixelSize > demDeltaLon:
|
||||
self._insar.numberRangeLooksSim = 1
|
||||
else:
|
||||
self._insar.numberRangeLooksSim = int(demDeltaLon / (self._insar.numberRangeLooks1 * masterTrack.rangePixelSize) + 0.5)
|
||||
#number of looks to take in azimuth
|
||||
if self._insar.numberAzimuthLooksSim == None:
|
||||
if self._insar.numberAzimuthLooks1 * masterTrack.azimuthPixelSize > demDeltaLat:
|
||||
self._insar.numberAzimuthLooksSim = 1
|
||||
else:
|
||||
self._insar.numberAzimuthLooksSim = int(demDeltaLat / (self._insar.numberAzimuthLooks1 * masterTrack.azimuthPixelSize) + 0.5)
|
||||
|
||||
#simulate a radar image using dem
|
||||
simulateRadar(os.path.join('../', self._insar.height), self._insar.sim, scale=3.0, offset=100.0)
|
||||
sim = isceobj.createImage()
|
||||
sim.load(self._insar.sim+'.xml')
|
||||
|
||||
#take looks
|
||||
if (self._insar.numberRangeLooksSim == 1) and (self._insar.numberAzimuthLooksSim == 1):
|
||||
simLookFile = self._insar.sim
|
||||
ampLookFile = 'amp_{}rlks_{}alks.float'.format(self._insar.numberRangeLooksSim*self._insar.numberRangeLooks1,
|
||||
self._insar.numberAzimuthLooksSim*self._insar.numberAzimuthLooks1)
|
||||
cmd = "imageMath.py -e='sqrt(a_0*a_0+a_1*a_1)' --a={} -o {} -t float".format(os.path.join('../', self._insar.amplitude), ampLookFile)
|
||||
runCmd(cmd)
|
||||
else:
|
||||
simLookFile = 'sim_{}rlks_{}alks.float'.format(self._insar.numberRangeLooksSim*self._insar.numberRangeLooks1,
|
||||
self._insar.numberAzimuthLooksSim*self._insar.numberAzimuthLooks1)
|
||||
ampLookFile = 'amp_{}rlks_{}alks.float'.format(self._insar.numberRangeLooksSim*self._insar.numberRangeLooks1,
|
||||
self._insar.numberAzimuthLooksSim*self._insar.numberAzimuthLooks1)
|
||||
ampTmpFile = 'amp_tmp.float'
|
||||
look(self._insar.sim, simLookFile, sim.width, self._insar.numberRangeLooksSim, self._insar.numberAzimuthLooksSim, 2, 0, 1)
|
||||
look(os.path.join('../', self._insar.amplitude), ampTmpFile, sim.width, self._insar.numberRangeLooksSim, self._insar.numberAzimuthLooksSim, 4, 1, 1)
|
||||
|
||||
width = int(sim.width/self._insar.numberRangeLooksSim)
|
||||
length = int(sim.length/self._insar.numberAzimuthLooksSim)
|
||||
create_xml(simLookFile, width, length, 'float')
|
||||
create_xml(ampTmpFile, width, length, 'amp')
|
||||
|
||||
cmd = "imageMath.py -e='sqrt(a_0*a_0+a_1*a_1)' --a={} -o {} -t float".format(ampTmpFile, ampLookFile)
|
||||
runCmd(cmd)
|
||||
os.remove(ampTmpFile)
|
||||
os.remove(ampTmpFile+'.vrt')
|
||||
os.remove(ampTmpFile+'.xml')
|
||||
|
||||
#initial number of offsets to use
|
||||
numberOfOffsets = 800
|
||||
#compute land ratio to further determine the number of offsets to use
|
||||
wbd=np.memmap(os.path.join('../', self._insar.wbdOut), dtype='byte', mode='r', shape=(sim.length, sim.width))
|
||||
landRatio = np.sum(wbd[0:sim.length:10, 0:sim.width:10]!=-1) / int(sim.length/10) / int(sim.width/10)
|
||||
del wbd
|
||||
if (landRatio <= 0.00125):
|
||||
print('\n\nWARNING: land area too small for estimating offsets between radar and dem')
|
||||
print('do not estimate offsets between radar and dem\n\n')
|
||||
self._insar.radarDemAffineTransform = [1.0, 0.0, 0.0, 1.0, 0.0, 0.0]
|
||||
catalog.addItem('warning message', 'land area too small for estimating offsets between radar and dem', 'runRdrDemOffset')
|
||||
|
||||
catalog.printToLog(logger, "runRdrDemOffset")
|
||||
self._insar.procDoc.addAllFromCatalog(catalog)
|
||||
|
||||
return
|
||||
|
||||
#total number of offsets to use
|
||||
numberOfOffsets /= landRatio
|
||||
#allocate number of offsets in range/azimuth according to image width/length
|
||||
width = int(sim.width/self._insar.numberRangeLooksSim)
|
||||
length = int(sim.length/self._insar.numberAzimuthLooksSim)
|
||||
#number of offsets to use in range/azimuth
|
||||
numberOfOffsetsRange = int(np.sqrt(numberOfOffsets * width / length))
|
||||
numberOfOffsetsAzimuth = int(length / width * np.sqrt(numberOfOffsets * width / length))
|
||||
|
||||
#this should be better?
|
||||
numberOfOffsetsRange = int(np.sqrt(numberOfOffsets))
|
||||
numberOfOffsetsAzimuth = int(np.sqrt(numberOfOffsets))
|
||||
|
||||
|
||||
if numberOfOffsetsRange > int(width/2):
|
||||
numberOfOffsetsRange = int(width/2)
|
||||
if numberOfOffsetsAzimuth > int(length/2):
|
||||
numberOfOffsetsAzimuth = int(length/2)
|
||||
|
||||
if numberOfOffsetsRange < 10:
|
||||
numberOfOffsetsRange = 10
|
||||
if numberOfOffsetsAzimuth < 10:
|
||||
numberOfOffsetsAzimuth = 10
|
||||
|
||||
catalog.addItem('number of range offsets', '{}'.format(numberOfOffsetsRange), 'runRdrDemOffset')
|
||||
catalog.addItem('number of azimuth offsets', '{}'.format(numberOfOffsetsAzimuth), 'runRdrDemOffset')
|
||||
|
||||
#matching
|
||||
ampcor = Ampcor(name='insarapp_slcs_ampcor')
|
||||
ampcor.configure()
|
||||
|
||||
mMag = isceobj.createImage()
|
||||
mMag.load(ampLookFile+'.xml')
|
||||
mMag.setAccessMode('read')
|
||||
mMag.createImage()
|
||||
|
||||
sMag = isceobj.createImage()
|
||||
sMag.load(simLookFile+'.xml')
|
||||
sMag.setAccessMode('read')
|
||||
sMag.createImage()
|
||||
|
||||
ampcor.setImageDataType1('real')
|
||||
ampcor.setImageDataType2('real')
|
||||
|
||||
ampcor.setMasterSlcImage(mMag)
|
||||
ampcor.setSlaveSlcImage(sMag)
|
||||
|
||||
#MATCH REGION
|
||||
rgoff = 0
|
||||
azoff = 0
|
||||
#it seems that we cannot use 0, haven't look into the problem
|
||||
if rgoff == 0:
|
||||
rgoff = 1
|
||||
if azoff == 0:
|
||||
azoff = 1
|
||||
firstSample = 1
|
||||
if rgoff < 0:
|
||||
firstSample = int(35 - rgoff)
|
||||
firstLine = 1
|
||||
if azoff < 0:
|
||||
firstLine = int(35 - azoff)
|
||||
ampcor.setAcrossGrossOffset(rgoff)
|
||||
ampcor.setDownGrossOffset(azoff)
|
||||
ampcor.setFirstSampleAcross(firstSample)
|
||||
ampcor.setLastSampleAcross(width)
|
||||
ampcor.setNumberLocationAcross(numberOfOffsetsRange)
|
||||
ampcor.setFirstSampleDown(firstLine)
|
||||
ampcor.setLastSampleDown(length)
|
||||
ampcor.setNumberLocationDown(numberOfOffsetsAzimuth)
|
||||
|
||||
#MATCH PARAMETERS
|
||||
ampcor.setWindowSizeWidth(64)
|
||||
ampcor.setWindowSizeHeight(64)
|
||||
#note this is the half width/length of search area, so number of resulting correlation samples: 8*2+1
|
||||
ampcor.setSearchWindowSizeWidth(16)
|
||||
ampcor.setSearchWindowSizeHeight(16)
|
||||
|
||||
#REST OF THE STUFF
|
||||
ampcor.setAcrossLooks(1)
|
||||
ampcor.setDownLooks(1)
|
||||
ampcor.setOversamplingFactor(64)
|
||||
ampcor.setZoomWindowSize(16)
|
||||
#1. The following not set
|
||||
#Matching Scale for Sample/Line Directions (-) = 1. 1.
|
||||
#should add the following in Ampcor.py?
|
||||
#if not set, in this case, Ampcor.py'value is also 1. 1.
|
||||
#ampcor.setScaleFactorX(1.)
|
||||
#ampcor.setScaleFactorY(1.)
|
||||
|
||||
#MATCH THRESHOLDS AND DEBUG DATA
|
||||
#2. The following not set
|
||||
#in roi_pac the value is set to 0 1
|
||||
#in isce the value is set to 0.001 1000.0
|
||||
#SNR and Covariance Thresholds (-) = {s1} {s2}
|
||||
#should add the following in Ampcor?
|
||||
#THIS SHOULD BE THE ONLY THING THAT IS DIFFERENT FROM THAT OF ROI_PAC
|
||||
#ampcor.setThresholdSNR(0)
|
||||
#ampcor.setThresholdCov(1)
|
||||
ampcor.setDebugFlag(False)
|
||||
ampcor.setDisplayFlag(False)
|
||||
|
||||
#in summary, only two things not set which are indicated by 'The following not set' above.
|
||||
|
||||
#run ampcor
|
||||
ampcor.ampcor()
|
||||
offsets = ampcor.getOffsetField()
|
||||
ampcorOffsetFile = 'ampcor.off'
|
||||
cullOffsetFile = 'cull.off'
|
||||
affineTransformFile = 'affine_transform.txt'
|
||||
writeOffset(offsets, ampcorOffsetFile)
|
||||
|
||||
#finalize image, and re-create it
|
||||
#otherwise the file pointer is still at the end of the image
|
||||
mMag.finalizeImage()
|
||||
sMag.finalizeImage()
|
||||
|
||||
# #cull offsets
|
||||
# import io
|
||||
# from contextlib import redirect_stdout
|
||||
# f = io.StringIO()
|
||||
# with redirect_stdout(f):
|
||||
# fitoff(ampcorOffsetFile, cullOffsetFile, 1.5, .5, 50)
|
||||
# s = f.getvalue()
|
||||
# #print(s)
|
||||
# with open(affineTransformFile, 'w') as f:
|
||||
# f.write(s)
|
||||
|
||||
#cull offsets
|
||||
import subprocess
|
||||
proc = subprocess.Popen(["python3", "-c", "import isce; from contrib.alos2proc_f.alos2proc_f import fitoff; fitoff('ampcor.off', 'cull.off', 1.5, .5, 50)"], stdout=subprocess.PIPE)
|
||||
out = proc.communicate()[0]
|
||||
with open(affineTransformFile, 'w') as f:
|
||||
f.write(out.decode('utf-8'))
|
||||
|
||||
#check number of offsets left
|
||||
with open(cullOffsetFile, 'r') as f:
|
||||
numCullOffsets = sum(1 for linex in f)
|
||||
if numCullOffsets < 50:
|
||||
print('\n\nWARNING: too few points left after culling, {} left'.format(numCullOffsets))
|
||||
print('do not estimate offsets between radar and dem\n\n')
|
||||
self._insar.radarDemAffineTransform = [1.0, 0.0, 0.0, 1.0, 0.0, 0.0]
|
||||
catalog.addItem('warning message', 'too few points left after culling, {} left'.format(numCullOffsets), 'runRdrDemOffset')
|
||||
|
||||
catalog.printToLog(logger, "runRdrDemOffset")
|
||||
self._insar.procDoc.addAllFromCatalog(catalog)
|
||||
|
||||
return
|
||||
|
||||
#read affine transform parameters
|
||||
with open(affineTransformFile) as f:
|
||||
lines = f.readlines()
|
||||
i = 0
|
||||
for linex in lines:
|
||||
if 'Affine Matrix ' in linex:
|
||||
m11 = float(lines[i + 2].split()[0])
|
||||
m12 = float(lines[i + 2].split()[1])
|
||||
m21 = float(lines[i + 3].split()[0])
|
||||
m22 = float(lines[i + 3].split()[1])
|
||||
t1 = float(lines[i + 7].split()[0])
|
||||
t2 = float(lines[i + 7].split()[1])
|
||||
break
|
||||
i += 1
|
||||
|
||||
self._insar.radarDemAffineTransform = [m11, m12, m21, m22, t1, t2]
|
||||
##################################################################################################
|
||||
|
||||
os.chdir('../../')
|
||||
|
||||
|
||||
catalog.printToLog(logger, "runRdrDemOffset")
|
||||
self._insar.procDoc.addAllFromCatalog(catalog)
|
||||
|
||||
|
||||
def simulateRadar(hgtfile, simfile, scale=3.0, offset=100.0):
|
||||
'''
|
||||
simulate a radar image by computing gradient of a dem image.
|
||||
'''
|
||||
import numpy as np
|
||||
import isceobj
|
||||
from isceobj.Alos2Proc.Alos2ProcPublic import create_xml
|
||||
|
||||
#set chunk length here for efficient processing
|
||||
###############################################
|
||||
chunk_length = 1000
|
||||
###############################################
|
||||
|
||||
hgt = isceobj.createImage()
|
||||
hgt.load(hgtfile+'.xml')
|
||||
|
||||
chunk_width = hgt.width
|
||||
num_chunk = int(hgt.length/chunk_length)
|
||||
chunk_length_last = hgt.length - num_chunk * chunk_length
|
||||
|
||||
simData = np.zeros((chunk_length, chunk_width), dtype=np.float32)
|
||||
|
||||
hgtfp = open(hgtfile,'rb')
|
||||
simfp = open(simfile,'wb')
|
||||
|
||||
print("simulating a radar image using topography")
|
||||
for i in range(num_chunk):
|
||||
print("processing chunk %6d of %6d" % (i+1, num_chunk), end='\r', flush=True)
|
||||
hgtData = np.fromfile(hgtfp, dtype=np.float64, count=chunk_length*chunk_width).reshape(chunk_length, chunk_width)
|
||||
simData[:, 0:chunk_width-1] = scale * np.diff(hgtData, axis=1) + offset
|
||||
simData.astype(np.float32).tofile(simfp)
|
||||
|
||||
print("processing chunk %6d of %6d" % (num_chunk, num_chunk))
|
||||
if chunk_length_last != 0:
|
||||
hgtData = np.fromfile(hgtfp, dtype=np.float64, count=chunk_length_last*chunk_width).reshape(chunk_length_last, chunk_width)
|
||||
simData[0:chunk_length_last, 0:chunk_width-1] = scale * np.diff(hgtData, axis=1) + offset
|
||||
(simData[0:chunk_length_last, :]).astype(np.float32).tofile(simfp)
|
||||
|
||||
hgtfp.close()
|
||||
simfp.close()
|
||||
create_xml(simfile, hgt.width, hgt.length, 'float')
|
||||
|
|
@ -0,0 +1,57 @@
|
|||
#
|
||||
# Author: Cunren Liang
|
||||
# Copyright 2015-present, NASA-JPL/Caltech
|
||||
#
|
||||
|
||||
import os
|
||||
import logging
|
||||
|
||||
import isceobj
|
||||
from contrib.alos2proc_f.alos2proc_f import rect_with_looks
|
||||
from isceobj.Alos2Proc.Alos2ProcPublic import create_xml
|
||||
|
||||
logger = logging.getLogger('isce.alos2insar.runRectRangeOffset')
|
||||
|
||||
def runRectRangeOffset(self):
|
||||
'''rectify range offset
|
||||
'''
|
||||
catalog = isceobj.Catalog.createCatalog(self._insar.procDoc.name)
|
||||
self.updateParamemetersFromUser()
|
||||
|
||||
masterTrack = self._insar.loadTrack(master=True)
|
||||
slaveTrack = self._insar.loadTrack(master=False)
|
||||
|
||||
insarDir = 'insar'
|
||||
if not os.path.exists(insarDir):
|
||||
os.makedirs(insarDir)
|
||||
os.chdir(insarDir)
|
||||
|
||||
|
||||
#rectify
|
||||
rgoff = isceobj.createImage()
|
||||
rgoff.load(self._insar.rangeOffset+'.xml')
|
||||
|
||||
if self._insar.radarDemAffineTransform == [1.0, 0.0, 0.0, 1.0, 0.0, 0.0]:
|
||||
if not os.path.isfile(self._insar.rectRangeOffset):
|
||||
os.symlink(self._insar.rangeOffset, self._insar.rectRangeOffset)
|
||||
create_xml(self._insar.rectRangeOffset, rgoff.width, rgoff.length, 'float')
|
||||
else:
|
||||
rect_with_looks(self._insar.rangeOffset,
|
||||
self._insar.rectRangeOffset,
|
||||
rgoff.width, rgoff.length,
|
||||
rgoff.width, rgoff.length,
|
||||
self._insar.radarDemAffineTransform[0], self._insar.radarDemAffineTransform[1],
|
||||
self._insar.radarDemAffineTransform[2], self._insar.radarDemAffineTransform[3],
|
||||
self._insar.radarDemAffineTransform[4], self._insar.radarDemAffineTransform[5],
|
||||
self._insar.numberRangeLooksSim*self._insar.numberRangeLooks1, self._insar.numberAzimuthLooksSim*self._insar.numberAzimuthLooks1,
|
||||
self._insar.numberRangeLooks1, self._insar.numberAzimuthLooks1,
|
||||
'REAL',
|
||||
'Bilinear')
|
||||
create_xml(self._insar.rectRangeOffset, rgoff.width, rgoff.length, 'float')
|
||||
|
||||
os.chdir('../')
|
||||
|
||||
catalog.printToLog(logger, "runRectRangeOffset")
|
||||
self._insar.procDoc.addAllFromCatalog(catalog)
|
||||
|
||||
|
||||
|
|
@ -0,0 +1,273 @@
|
|||
#
|
||||
# Author: Cunren Liang
|
||||
# Copyright 2015-present, NASA-JPL/Caltech
|
||||
#
|
||||
|
||||
import os
|
||||
import logging
|
||||
import numpy as np
|
||||
|
||||
import isceobj
|
||||
from isceobj.Alos2Proc.runRdr2Geo import topoCPU
|
||||
from isceobj.Alos2Proc.runRdr2Geo import topoGPU
|
||||
from isceobj.Alos2Proc.runGeo2Rdr import geo2RdrCPU
|
||||
from isceobj.Alos2Proc.runGeo2Rdr import geo2RdrGPU
|
||||
from contrib.alos2proc.alos2proc import resamp
|
||||
from isceobj.Alos2Proc.Alos2ProcPublic import create_xml
|
||||
from isceobj.Alos2Proc.Alos2ProcPublic import renameFile
|
||||
from isceobj.Alos2Proc.Alos2ProcPublic import waterBodyRadar
|
||||
from mroipac.ampcor.Ampcor import Ampcor
|
||||
from isceobj.Alos2Proc.Alos2ProcPublic import meanOffset
|
||||
from isceobj.Alos2Proc.Alos2ProcPublic import cullOffsetsRoipac
|
||||
|
||||
logger = logging.getLogger('isce.alos2insar.runSlcMatch')
|
||||
|
||||
def runSlcMatch(self):
|
||||
'''match a pair of SLCs
|
||||
'''
|
||||
if not self.doDenseOffset:
|
||||
return
|
||||
if not ((self._insar.modeCombination == 0) or (self._insar.modeCombination == 1)):
|
||||
return
|
||||
|
||||
catalog = isceobj.Catalog.createCatalog(self._insar.procDoc.name)
|
||||
self.updateParamemetersFromUser()
|
||||
|
||||
demFile = os.path.abspath(self._insar.dem)
|
||||
wbdFile = os.path.abspath(self._insar.wbd)
|
||||
|
||||
denseOffsetDir = 'dense_offset'
|
||||
if not os.path.exists(denseOffsetDir):
|
||||
os.makedirs(denseOffsetDir)
|
||||
os.chdir(denseOffsetDir)
|
||||
|
||||
masterTrack = self._insar.loadProduct(self._insar.masterTrackParameter)
|
||||
slaveTrack = self._insar.loadProduct(self._insar.slaveTrackParameter)
|
||||
|
||||
#########################################################################################
|
||||
|
||||
|
||||
##################################################
|
||||
# compute geometric offsets
|
||||
##################################################
|
||||
if self.useGPU and self._insar.hasGPU():
|
||||
topoGPU(masterTrack, 1, 1, demFile,
|
||||
'lat.rdr', 'lon.rdr', 'hgt.rdr', 'los.rdr')
|
||||
geo2RdrGPU(slaveTrack, 1, 1,
|
||||
'lat.rdr', 'lon.rdr', 'hgt.rdr', 'rg.off', 'az.off')
|
||||
else:
|
||||
topoCPU(masterTrack, 1, 1, demFile,
|
||||
'lat.rdr', 'lon.rdr', 'hgt.rdr', 'los.rdr')
|
||||
geo2RdrCPU(slaveTrack, 1, 1,
|
||||
'lat.rdr', 'lon.rdr', 'hgt.rdr', 'rg.off', 'az.off')
|
||||
|
||||
|
||||
##################################################
|
||||
# resample SLC
|
||||
##################################################
|
||||
#SlaveSlcResampled = os.path.splitext(self._insar.slaveSlc)[0]+'_resamp'+os.path.splitext(self._insar.slaveSlc)[1]
|
||||
SlaveSlcResampled = self._insar.slaveSlcCoregistered
|
||||
rangeOffsets2Frac = 0.0
|
||||
azimuthOffsets2Frac = 0.0
|
||||
resamp(self._insar.slaveSlc,
|
||||
SlaveSlcResampled,
|
||||
'rg.off',
|
||||
'az.off',
|
||||
masterTrack.numberOfSamples, masterTrack.numberOfLines,
|
||||
slaveTrack.prf,
|
||||
slaveTrack.dopplerVsPixel,
|
||||
[rangeOffsets2Frac, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0],
|
||||
[azimuthOffsets2Frac, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0])
|
||||
create_xml(SlaveSlcResampled, masterTrack.numberOfSamples, masterTrack.numberOfLines, 'slc')
|
||||
|
||||
|
||||
if self.estimateResidualOffset:
|
||||
|
||||
numberOfOffsets = 800
|
||||
rangeStep = 50
|
||||
|
||||
length = masterTrack.numberOfLines
|
||||
width = masterTrack.numberOfSamples
|
||||
waterBodyRadar('lat.rdr', 'lon.rdr', wbdFile, 'wbd.rdr')
|
||||
wbd=np.memmap('wbd.rdr', dtype=np.int8, mode='r', shape=(length, width))
|
||||
azimuthStep = int(length/width*rangeStep+0.5)
|
||||
landRatio = np.sum(wbd[0:length:azimuthStep,0:width:rangeStep]!=-1)/(int(length/azimuthStep)*int(width/rangeStep))
|
||||
del wbd
|
||||
|
||||
if (landRatio <= 0.00125):
|
||||
print('\n\nWARNING: land area too small for estimating residual slc offsets')
|
||||
print('do not estimate residual offsets\n\n')
|
||||
catalog.addItem('warning message', 'land area too small for estimating residual slc offsets', 'runSlcMatch')
|
||||
else:
|
||||
numberOfOffsets /= landRatio
|
||||
#we use equal number of offsets in range and azimuth here
|
||||
numberOfOffsetsRange = int(np.sqrt(numberOfOffsets)+0.5)
|
||||
numberOfOffsetsAzimuth = int(np.sqrt(numberOfOffsets)+0.5)
|
||||
if numberOfOffsetsRange > int(width/2):
|
||||
numberOfOffsetsRange = int(width/2)
|
||||
if numberOfOffsetsAzimuth > int(length/2):
|
||||
numberOfOffsetsAzimuth = int(length/2)
|
||||
if numberOfOffsetsRange < 10:
|
||||
numberOfOffsetsRange = 10
|
||||
if numberOfOffsetsAzimuth < 10:
|
||||
numberOfOffsetsAzimuth = 10
|
||||
|
||||
|
||||
##########################################
|
||||
#2. match using ampcor
|
||||
##########################################
|
||||
ampcor = Ampcor(name='insarapp_slcs_ampcor')
|
||||
ampcor.configure()
|
||||
|
||||
mSLC = isceobj.createSlcImage()
|
||||
mSLC.load(self._insar.masterSlc+'.xml')
|
||||
mSLC.setAccessMode('read')
|
||||
mSLC.createImage()
|
||||
|
||||
sSLC = isceobj.createSlcImage()
|
||||
sSLC.load(SlaveSlcResampled+'.xml')
|
||||
sSLC.setAccessMode('read')
|
||||
sSLC.createImage()
|
||||
|
||||
ampcor.setImageDataType1('complex')
|
||||
ampcor.setImageDataType2('complex')
|
||||
|
||||
ampcor.setMasterSlcImage(mSLC)
|
||||
ampcor.setSlaveSlcImage(sSLC)
|
||||
|
||||
#MATCH REGION
|
||||
#compute an offset at image center to use
|
||||
rgoff = 0.0
|
||||
azoff = 0.0
|
||||
#it seems that we cannot use 0, haven't look into the problem
|
||||
if rgoff == 0:
|
||||
rgoff = 1
|
||||
if azoff == 0:
|
||||
azoff = 1
|
||||
firstSample = 1
|
||||
if rgoff < 0:
|
||||
firstSample = int(35 - rgoff)
|
||||
firstLine = 1
|
||||
if azoff < 0:
|
||||
firstLine = int(35 - azoff)
|
||||
ampcor.setAcrossGrossOffset(rgoff)
|
||||
ampcor.setDownGrossOffset(azoff)
|
||||
ampcor.setFirstSampleAcross(firstSample)
|
||||
ampcor.setLastSampleAcross(mSLC.width)
|
||||
ampcor.setNumberLocationAcross(numberOfOffsetsRange)
|
||||
ampcor.setFirstSampleDown(firstLine)
|
||||
ampcor.setLastSampleDown(mSLC.length)
|
||||
ampcor.setNumberLocationDown(numberOfOffsetsAzimuth)
|
||||
|
||||
#MATCH PARAMETERS
|
||||
#full-aperture mode
|
||||
if (self._insar.modeCombination == 21) or \
|
||||
(self._insar.modeCombination == 22) or \
|
||||
(self._insar.modeCombination == 31) or \
|
||||
(self._insar.modeCombination == 32):
|
||||
ampcor.setWindowSizeWidth(64)
|
||||
ampcor.setWindowSizeHeight(512)
|
||||
#note this is the half width/length of search area, number of resulting correlation samples: 32*2+1
|
||||
ampcor.setSearchWindowSizeWidth(32)
|
||||
ampcor.setSearchWindowSizeHeight(32)
|
||||
#triggering full-aperture mode matching
|
||||
ampcor.setWinsizeFilt(8)
|
||||
ampcor.setOversamplingFactorFilt(64)
|
||||
#regular mode
|
||||
else:
|
||||
ampcor.setWindowSizeWidth(64)
|
||||
ampcor.setWindowSizeHeight(64)
|
||||
ampcor.setSearchWindowSizeWidth(16)
|
||||
ampcor.setSearchWindowSizeHeight(16)
|
||||
|
||||
#REST OF THE STUFF
|
||||
ampcor.setAcrossLooks(1)
|
||||
ampcor.setDownLooks(1)
|
||||
ampcor.setOversamplingFactor(64)
|
||||
ampcor.setZoomWindowSize(16)
|
||||
#1. The following not set
|
||||
#Matching Scale for Sample/Line Directions (-) = 1. 1.
|
||||
#should add the following in Ampcor.py?
|
||||
#if not set, in this case, Ampcor.py'value is also 1. 1.
|
||||
#ampcor.setScaleFactorX(1.)
|
||||
#ampcor.setScaleFactorY(1.)
|
||||
|
||||
#MATCH THRESHOLDS AND DEBUG DATA
|
||||
#2. The following not set
|
||||
#in roi_pac the value is set to 0 1
|
||||
#in isce the value is set to 0.001 1000.0
|
||||
#SNR and Covariance Thresholds (-) = {s1} {s2}
|
||||
#should add the following in Ampcor?
|
||||
#THIS SHOULD BE THE ONLY THING THAT IS DIFFERENT FROM THAT OF ROI_PAC
|
||||
#ampcor.setThresholdSNR(0)
|
||||
#ampcor.setThresholdCov(1)
|
||||
ampcor.setDebugFlag(False)
|
||||
ampcor.setDisplayFlag(False)
|
||||
|
||||
#in summary, only two things not set which are indicated by 'The following not set' above.
|
||||
|
||||
#run ampcor
|
||||
ampcor.ampcor()
|
||||
offsets = ampcor.getOffsetField()
|
||||
mSLC.finalizeImage()
|
||||
sSLC.finalizeImage()
|
||||
|
||||
|
||||
#3. cull offsets
|
||||
refinedOffsets = cullOffsetsRoipac(offsets, numThreshold=50)
|
||||
if refinedOffsets == None:
|
||||
print('\n\nWARNING: too few offsets left for slc residual offset estimation')
|
||||
print('do not estimate residual offsets\n\n')
|
||||
catalog.addItem('warning message', 'too few offsets left for slc residual offset estimation', 'runSlcMatch')
|
||||
else:
|
||||
rangeOffset, azimuthOffset = meanOffset(refinedOffsets)
|
||||
os.remove(SlaveSlcResampled)
|
||||
os.remove(SlaveSlcResampled+'.vrt')
|
||||
os.remove(SlaveSlcResampled+'.xml')
|
||||
|
||||
rangeOffsets2Frac = rangeOffset
|
||||
azimuthOffsets2Frac = azimuthOffset
|
||||
resamp(self._insar.slaveSlc,
|
||||
SlaveSlcResampled,
|
||||
'rg.off',
|
||||
'az.off',
|
||||
masterTrack.numberOfSamples, masterTrack.numberOfLines,
|
||||
slaveTrack.prf,
|
||||
slaveTrack.dopplerVsPixel,
|
||||
[rangeOffsets2Frac, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0],
|
||||
[azimuthOffsets2Frac, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0])
|
||||
create_xml(SlaveSlcResampled, masterTrack.numberOfSamples, masterTrack.numberOfLines, 'slc')
|
||||
|
||||
catalog.addItem('number of offsets range', numberOfOffsetsRange, 'runSlcMatch')
|
||||
catalog.addItem('number of offsets azimuth', numberOfOffsetsAzimuth, 'runSlcMatch')
|
||||
catalog.addItem('range residual offset after geometric coregistration', rangeOffset, 'runSlcMatch')
|
||||
catalog.addItem('azimuth residual offset after geometric coregistration', azimuthOffset, 'runSlcMatch')
|
||||
|
||||
|
||||
|
||||
|
||||
if self.deleteGeometryFiles:
|
||||
os.remove('lat.rdr')
|
||||
os.remove('lat.rdr.vrt')
|
||||
os.remove('lat.rdr.xml')
|
||||
os.remove('lon.rdr')
|
||||
os.remove('lon.rdr.vrt')
|
||||
os.remove('lon.rdr.xml')
|
||||
os.remove('hgt.rdr')
|
||||
os.remove('hgt.rdr.vrt')
|
||||
os.remove('hgt.rdr.xml')
|
||||
os.remove('los.rdr')
|
||||
os.remove('los.rdr.vrt')
|
||||
os.remove('los.rdr.xml')
|
||||
# if os.path.isfile('wbd.rdr'):
|
||||
# os.remove('wbd.rdr')
|
||||
# os.remove('wbd.rdr.vrt')
|
||||
# os.remove('wbd.rdr.xml')
|
||||
|
||||
#########################################################################################
|
||||
|
||||
os.chdir('../')
|
||||
catalog.printToLog(logger, "runSlcMatch")
|
||||
self._insar.procDoc.addAllFromCatalog(catalog)
|
||||
|
||||
|
||||
|
|
@ -0,0 +1,182 @@
|
|||
#
|
||||
# Author: Cunren Liang
|
||||
# Copyright 2015-present, NASA-JPL/Caltech
|
||||
#
|
||||
|
||||
import os
|
||||
import logging
|
||||
import numpy as np
|
||||
|
||||
import isceobj
|
||||
from isceobj.Alos2Proc.runFrameOffset import frameOffset
|
||||
from isceobj.Alos2Proc.runFrameMosaic import frameMosaic
|
||||
from isceobj.Alos2Proc.Alos2ProcPublic import create_xml
|
||||
|
||||
logger = logging.getLogger('isce.alos2insar.runSlcMosaic')
|
||||
|
||||
def runSlcMosaic(self):
|
||||
'''mosaic SLCs
|
||||
'''
|
||||
if not self.doDenseOffset:
|
||||
print('\ndense offset not requested, skip this and the remaining steps...')
|
||||
return
|
||||
if not ((self._insar.modeCombination == 0) or (self._insar.modeCombination == 1)):
|
||||
print('dense offset only support spotligh-spotlight and stripmap-stripmap pairs')
|
||||
return
|
||||
|
||||
catalog = isceobj.Catalog.createCatalog(self._insar.procDoc.name)
|
||||
self.updateParamemetersFromUser()
|
||||
masterTrack = self._insar.loadTrack(master=True)
|
||||
slaveTrack = self._insar.loadTrack(master=False)
|
||||
|
||||
denseOffsetDir = 'dense_offset'
|
||||
if not os.path.exists(denseOffsetDir):
|
||||
os.makedirs(denseOffsetDir)
|
||||
os.chdir(denseOffsetDir)
|
||||
|
||||
|
||||
##################################################
|
||||
# estimate master and slave frame offsets
|
||||
##################################################
|
||||
if len(masterTrack.frames) > 1:
|
||||
matchingMode=1
|
||||
|
||||
#if master offsets from matching are not already computed
|
||||
if self.frameOffsetMatching == False:
|
||||
offsetMaster = frameOffset(masterTrack, self._insar.masterSlc, self._insar.masterFrameOffset,
|
||||
crossCorrelation=True, matchingMode=matchingMode)
|
||||
offsetSlave = frameOffset(slaveTrack, self._insar.slaveSlc, self._insar.slaveFrameOffset,
|
||||
crossCorrelation=True, matchingMode=matchingMode)
|
||||
if self.frameOffsetMatching == False:
|
||||
self._insar.frameRangeOffsetMatchingMaster = offsetMaster[2]
|
||||
self._insar.frameAzimuthOffsetMatchingMaster = offsetMaster[3]
|
||||
self._insar.frameRangeOffsetMatchingSlave = offsetSlave[2]
|
||||
self._insar.frameAzimuthOffsetMatchingSlave = offsetSlave[3]
|
||||
|
||||
|
||||
##################################################
|
||||
# mosaic slc
|
||||
##################################################
|
||||
numberOfFrames = len(masterTrack.frames)
|
||||
if numberOfFrames == 1:
|
||||
import shutil
|
||||
#frameDir = os.path.join('f1_{}/mosaic'.format(self._insar.masterFrames[0]))
|
||||
frameDir = os.path.join('f1_{}/s{}'.format(self._insar.masterFrames[0], self._insar.startingSwath))
|
||||
if not os.path.isfile(self._insar.masterSlc):
|
||||
if os.path.isfile(os.path.join('../', frameDir, self._insar.masterSlc)):
|
||||
os.symlink(os.path.join('../', frameDir, self._insar.masterSlc), self._insar.masterSlc)
|
||||
#shutil.copy2() can overwrite
|
||||
shutil.copy2(os.path.join('../', frameDir, self._insar.masterSlc+'.vrt'), self._insar.masterSlc+'.vrt')
|
||||
shutil.copy2(os.path.join('../', frameDir, self._insar.masterSlc+'.xml'), self._insar.masterSlc+'.xml')
|
||||
if not os.path.isfile(self._insar.slaveSlc):
|
||||
if os.path.isfile(os.path.join('../', frameDir, self._insar.slaveSlc)):
|
||||
os.symlink(os.path.join('../', frameDir, self._insar.slaveSlc), self._insar.slaveSlc)
|
||||
shutil.copy2(os.path.join('../', frameDir, self._insar.slaveSlc+'.vrt'), self._insar.slaveSlc+'.vrt')
|
||||
shutil.copy2(os.path.join('../', frameDir, self._insar.slaveSlc+'.xml'), self._insar.slaveSlc+'.xml')
|
||||
|
||||
#update track parameters
|
||||
#########################################################
|
||||
#mosaic size
|
||||
masterTrack.numberOfSamples = masterTrack.frames[0].swaths[0].numberOfSamples
|
||||
masterTrack.numberOfLines = masterTrack.frames[0].swaths[0].numberOfLines
|
||||
#NOTE THAT WE ARE STILL USING SINGLE LOOK PARAMETERS HERE
|
||||
#range parameters
|
||||
masterTrack.startingRange = masterTrack.frames[0].swaths[0].startingRange
|
||||
masterTrack.rangeSamplingRate = masterTrack.frames[0].swaths[0].rangeSamplingRate
|
||||
masterTrack.rangePixelSize = masterTrack.frames[0].swaths[0].rangePixelSize
|
||||
#azimuth parameters
|
||||
masterTrack.sensingStart = masterTrack.frames[0].swaths[0].sensingStart
|
||||
masterTrack.prf = masterTrack.frames[0].swaths[0].prf
|
||||
masterTrack.azimuthPixelSize = masterTrack.frames[0].swaths[0].azimuthPixelSize
|
||||
masterTrack.azimuthLineInterval = masterTrack.frames[0].swaths[0].azimuthLineInterval
|
||||
|
||||
masterTrack.dopplerVsPixel = masterTrack.frames[0].swaths[0].dopplerVsPixel
|
||||
|
||||
#update track parameters, slave
|
||||
#########################################################
|
||||
#mosaic size
|
||||
slaveTrack.numberOfSamples = slaveTrack.frames[0].swaths[0].numberOfSamples
|
||||
slaveTrack.numberOfLines = slaveTrack.frames[0].swaths[0].numberOfLines
|
||||
#NOTE THAT WE ARE STILL USING SINGLE LOOK PARAMETERS HERE
|
||||
#range parameters
|
||||
slaveTrack.startingRange = slaveTrack.frames[0].swaths[0].startingRange
|
||||
slaveTrack.rangeSamplingRate = slaveTrack.frames[0].swaths[0].rangeSamplingRate
|
||||
slaveTrack.rangePixelSize = slaveTrack.frames[0].swaths[0].rangePixelSize
|
||||
#azimuth parameters
|
||||
slaveTrack.sensingStart = slaveTrack.frames[0].swaths[0].sensingStart
|
||||
slaveTrack.prf = slaveTrack.frames[0].swaths[0].prf
|
||||
slaveTrack.azimuthPixelSize = slaveTrack.frames[0].swaths[0].azimuthPixelSize
|
||||
slaveTrack.azimuthLineInterval = slaveTrack.frames[0].swaths[0].azimuthLineInterval
|
||||
|
||||
slaveTrack.dopplerVsPixel = slaveTrack.frames[0].swaths[0].dopplerVsPixel
|
||||
|
||||
else:
|
||||
#mosaic master slc
|
||||
#########################################################
|
||||
#choose offsets
|
||||
rangeOffsets = self._insar.frameRangeOffsetMatchingMaster
|
||||
azimuthOffsets = self._insar.frameAzimuthOffsetMatchingMaster
|
||||
|
||||
#list of input files
|
||||
slcs = []
|
||||
for i, frameNumber in enumerate(self._insar.masterFrames):
|
||||
frameDir = 'f{}_{}'.format(i+1, frameNumber)
|
||||
swathDir = 's{}'.format(self._insar.startingSwath)
|
||||
slcs.append(os.path.join('../', frameDir, swathDir, self._insar.masterSlc))
|
||||
|
||||
#note that track parameters are updated after mosaicking
|
||||
#parameters update is checked, it is OK.
|
||||
frameMosaic(masterTrack, slcs, self._insar.masterSlc,
|
||||
rangeOffsets, azimuthOffsets, 1, 1,
|
||||
updateTrack=True, phaseCompensation=True, resamplingMethod=2)
|
||||
create_xml(self._insar.masterSlc, masterTrack.numberOfSamples, masterTrack.numberOfLines, 'slc')
|
||||
masterTrack.dopplerVsPixel = computeTrackDoppler(masterTrack)
|
||||
|
||||
#mosaic slave slc
|
||||
#########################################################
|
||||
#choose offsets
|
||||
rangeOffsets = self._insar.frameRangeOffsetMatchingSlave
|
||||
azimuthOffsets = self._insar.frameAzimuthOffsetMatchingSlave
|
||||
|
||||
#list of input files
|
||||
slcs = []
|
||||
for i, frameNumber in enumerate(self._insar.masterFrames):
|
||||
frameDir = 'f{}_{}'.format(i+1, frameNumber)
|
||||
swathDir = 's{}'.format(self._insar.startingSwath)
|
||||
slcs.append(os.path.join('../', frameDir, swathDir, self._insar.slaveSlc))
|
||||
|
||||
#note that track parameters are updated after mosaicking
|
||||
#parameters update is checked, it is OK.
|
||||
frameMosaic(slaveTrack, slcs, self._insar.slaveSlc,
|
||||
rangeOffsets, azimuthOffsets, 1, 1,
|
||||
updateTrack=True, phaseCompensation=True, resamplingMethod=2)
|
||||
create_xml(self._insar.slaveSlc, slaveTrack.numberOfSamples, slaveTrack.numberOfLines, 'slc')
|
||||
slaveTrack.dopplerVsPixel = computeTrackDoppler(slaveTrack)
|
||||
|
||||
|
||||
#save parameter file inside denseoffset directory
|
||||
self._insar.saveProduct(masterTrack, self._insar.masterTrackParameter)
|
||||
self._insar.saveProduct(slaveTrack, self._insar.slaveTrackParameter)
|
||||
|
||||
|
||||
os.chdir('../')
|
||||
catalog.printToLog(logger, "runSlcMosaic")
|
||||
self._insar.procDoc.addAllFromCatalog(catalog)
|
||||
|
||||
|
||||
def computeTrackDoppler(track):
|
||||
'''
|
||||
compute doppler for a track
|
||||
'''
|
||||
numberOfFrames = len(track.frames)
|
||||
dop = np.zeros(track.numberOfSamples)
|
||||
for i in range(numberOfFrames):
|
||||
index = track.startingRange + np.arange(track.numberOfSamples) * track.rangePixelSize
|
||||
index = (index - track.frames[i].swaths[0].startingRange) / track.frames[i].swaths[0].rangePixelSize
|
||||
dop = dop + np.polyval(track.frames[i].swaths[0].dopplerVsPixel[::-1], index)
|
||||
|
||||
index1 = np.arange(track.numberOfSamples)
|
||||
dop1 = dop/numberOfFrames
|
||||
p = np.polyfit(index1, dop1, 3)
|
||||
|
||||
return [p[3], p[2], p[1], p[0]]
|
||||
|
|
@ -0,0 +1,275 @@
|
|||
#
|
||||
# Author: Cunren Liang
|
||||
# Copyright 2015-present, NASA-JPL/Caltech
|
||||
#
|
||||
|
||||
import os
|
||||
import glob
|
||||
import logging
|
||||
import datetime
|
||||
import numpy as np
|
||||
|
||||
import isceobj
|
||||
import mroipac
|
||||
from mroipac.ampcor.Ampcor import Ampcor
|
||||
from isceobj.Alos2Proc.Alos2ProcPublic import topo
|
||||
from isceobj.Alos2Proc.Alos2ProcPublic import geo2rdr
|
||||
from isceobj.Alos2Proc.Alos2ProcPublic import waterBodyRadar
|
||||
from isceobj.Alos2Proc.Alos2ProcPublic import reformatGeometricalOffset
|
||||
from isceobj.Alos2Proc.Alos2ProcPublic import writeOffset
|
||||
from isceobj.Alos2Proc.Alos2ProcPublic import cullOffsets
|
||||
from isceobj.Alos2Proc.Alos2ProcPublic import computeOffsetFromOrbit
|
||||
|
||||
logger = logging.getLogger('isce.alos2insar.runSlcOffset')
|
||||
|
||||
def runSlcOffset(self):
|
||||
'''estimate SLC offsets
|
||||
'''
|
||||
catalog = isceobj.Catalog.createCatalog(self._insar.procDoc.name)
|
||||
self.updateParamemetersFromUser()
|
||||
|
||||
masterTrack = self._insar.loadTrack(master=True)
|
||||
slaveTrack = self._insar.loadTrack(master=False)
|
||||
|
||||
demFile = os.path.abspath(self._insar.dem)
|
||||
wbdFile = os.path.abspath(self._insar.wbd)
|
||||
|
||||
for i, frameNumber in enumerate(self._insar.masterFrames):
|
||||
frameDir = 'f{}_{}'.format(i+1, frameNumber)
|
||||
os.chdir(frameDir)
|
||||
for j, swathNumber in enumerate(range(self._insar.startingSwath, self._insar.endingSwath + 1)):
|
||||
swathDir = 's{}'.format(swathNumber)
|
||||
os.chdir(swathDir)
|
||||
|
||||
print('estimating offset frame {}, swath {}'.format(frameNumber, swathNumber))
|
||||
|
||||
masterSwath = masterTrack.frames[i].swaths[j]
|
||||
slaveSwath = slaveTrack.frames[i].swaths[j]
|
||||
|
||||
##########################################
|
||||
#1. set number of matching points
|
||||
##########################################
|
||||
#set initinial numbers
|
||||
if (self._insar.modeCombination == 21) or (self._insar.modeCombination == 22):
|
||||
numberOfOffsetsRange = 10
|
||||
numberOfOffsetsAzimuth = 40
|
||||
else:
|
||||
numberOfOffsetsRange = 20
|
||||
numberOfOffsetsAzimuth = 20
|
||||
|
||||
#change the initial numbers using water body
|
||||
if self.useWbdForNumberOffsets and (self._insar.wbd != None):
|
||||
numberRangeLooks=100
|
||||
numberAzimuthLooks=100
|
||||
#compute land ratio using topo module
|
||||
topo(masterSwath, masterTrack, demFile, 'lat.rdr', 'lon.rdr', 'hgt.rdr', losFile='los.rdr',
|
||||
incFile=None, mskFile=None,
|
||||
numberRangeLooks=numberRangeLooks, numberAzimuthLooks=numberAzimuthLooks, multilookTimeOffset=False)
|
||||
waterBodyRadar('lat.rdr', 'lon.rdr', wbdFile, 'wbd.rdr')
|
||||
|
||||
wbdImg = isceobj.createImage()
|
||||
wbdImg.load('wbd.rdr.xml')
|
||||
width = wbdImg.width
|
||||
length = wbdImg.length
|
||||
|
||||
wbd = np.fromfile('wbd.rdr', dtype=np.byte).reshape(length, width)
|
||||
landRatio = np.sum(wbd==0) / (length*width)
|
||||
|
||||
if (landRatio <= 0.00125):
|
||||
print('\n\nWARNING: land too small for estimating slc offsets at frame {}, swath {}'.format(frameNumber, swathNumber))
|
||||
print('proceed to use geometric offsets for forming interferogram')
|
||||
print('but please consider not using this swath\n\n')
|
||||
catalog.addItem('warning message', 'land too small for estimating slc offsets at frame {}, swath {}, use geometric offsets'.format(frameNumber, swathNumber), 'runSlcOffset')
|
||||
|
||||
#compute geomtricla offsets
|
||||
geo2rdr(slaveSwath, slaveTrack, 'lat.rdr', 'lon.rdr', 'hgt.rdr', 'rg.rdr', 'az.rdr', numberRangeLooks=numberRangeLooks, numberAzimuthLooks=numberAzimuthLooks, multilookTimeOffset=False)
|
||||
reformatGeometricalOffset('rg.rdr', 'az.rdr', 'cull.off', rangeStep=numberRangeLooks, azimuthStep=numberAzimuthLooks, maximumNumberOfOffsets=2000)
|
||||
|
||||
os.remove('lat.rdr')
|
||||
os.remove('lat.rdr.vrt')
|
||||
os.remove('lat.rdr.xml')
|
||||
os.remove('lon.rdr')
|
||||
os.remove('lon.rdr.vrt')
|
||||
os.remove('lon.rdr.xml')
|
||||
os.remove('hgt.rdr')
|
||||
os.remove('hgt.rdr.vrt')
|
||||
os.remove('hgt.rdr.xml')
|
||||
os.remove('los.rdr')
|
||||
os.remove('los.rdr.vrt')
|
||||
os.remove('los.rdr.xml')
|
||||
os.remove('wbd.rdr')
|
||||
os.remove('wbd.rdr.vrt')
|
||||
os.remove('wbd.rdr.xml')
|
||||
|
||||
os.remove('rg.rdr')
|
||||
os.remove('rg.rdr.vrt')
|
||||
os.remove('rg.rdr.xml')
|
||||
os.remove('az.rdr')
|
||||
os.remove('az.rdr.vrt')
|
||||
os.remove('az.rdr.xml')
|
||||
|
||||
os.chdir('../')
|
||||
continue
|
||||
|
||||
|
||||
os.remove('lat.rdr')
|
||||
os.remove('lat.rdr.vrt')
|
||||
os.remove('lat.rdr.xml')
|
||||
os.remove('lon.rdr')
|
||||
os.remove('lon.rdr.vrt')
|
||||
os.remove('lon.rdr.xml')
|
||||
os.remove('hgt.rdr')
|
||||
os.remove('hgt.rdr.vrt')
|
||||
os.remove('hgt.rdr.xml')
|
||||
os.remove('los.rdr')
|
||||
os.remove('los.rdr.vrt')
|
||||
os.remove('los.rdr.xml')
|
||||
os.remove('wbd.rdr')
|
||||
os.remove('wbd.rdr.vrt')
|
||||
os.remove('wbd.rdr.xml')
|
||||
|
||||
#put the results on a grid with a specified interval
|
||||
interval = 0.2
|
||||
axisRatio = int(np.sqrt(landRatio)/interval)*interval + interval
|
||||
if axisRatio > 1:
|
||||
axisRatio = 1
|
||||
|
||||
numberOfOffsetsRange = int(numberOfOffsetsRange/axisRatio)
|
||||
numberOfOffsetsAzimuth = int(numberOfOffsetsAzimuth/axisRatio)
|
||||
else:
|
||||
catalog.addItem('warning message', 'no water mask used to determine number of matching points. frame {} swath {}'.format(frameNumber, swathNumber), 'runSlcOffset')
|
||||
|
||||
#user's settings
|
||||
if self.numberRangeOffsets != None:
|
||||
numberOfOffsetsRange = self.numberRangeOffsets[i][j]
|
||||
if self.numberAzimuthOffsets != None:
|
||||
numberOfOffsetsAzimuth = self.numberAzimuthOffsets[i][j]
|
||||
|
||||
catalog.addItem('number of offsets range frame {} swath {}'.format(frameNumber, swathNumber), numberOfOffsetsRange, 'runSlcOffset')
|
||||
catalog.addItem('number of offsets azimuth frame {} swath {}'.format(frameNumber, swathNumber), numberOfOffsetsAzimuth, 'runSlcOffset')
|
||||
|
||||
##########################################
|
||||
#2. match using ampcor
|
||||
##########################################
|
||||
ampcor = Ampcor(name='insarapp_slcs_ampcor')
|
||||
ampcor.configure()
|
||||
|
||||
mSLC = isceobj.createSlcImage()
|
||||
mSLC.load(self._insar.masterSlc+'.xml')
|
||||
mSLC.setAccessMode('read')
|
||||
mSLC.createImage()
|
||||
|
||||
sSLC = isceobj.createSlcImage()
|
||||
sSLC.load(self._insar.slaveSlc+'.xml')
|
||||
sSLC.setAccessMode('read')
|
||||
sSLC.createImage()
|
||||
|
||||
ampcor.setImageDataType1('complex')
|
||||
ampcor.setImageDataType2('complex')
|
||||
|
||||
ampcor.setMasterSlcImage(mSLC)
|
||||
ampcor.setSlaveSlcImage(sSLC)
|
||||
|
||||
#MATCH REGION
|
||||
#compute an offset at image center to use
|
||||
rgoff, azoff = computeOffsetFromOrbit(masterSwath, masterTrack, slaveSwath, slaveTrack,
|
||||
masterSwath.numberOfSamples * 0.5,
|
||||
masterSwath.numberOfLines * 0.5)
|
||||
#it seems that we cannot use 0, haven't look into the problem
|
||||
if rgoff == 0:
|
||||
rgoff = 1
|
||||
if azoff == 0:
|
||||
azoff = 1
|
||||
firstSample = 1
|
||||
if rgoff < 0:
|
||||
firstSample = int(35 - rgoff)
|
||||
firstLine = 1
|
||||
if azoff < 0:
|
||||
firstLine = int(35 - azoff)
|
||||
ampcor.setAcrossGrossOffset(rgoff)
|
||||
ampcor.setDownGrossOffset(azoff)
|
||||
ampcor.setFirstSampleAcross(firstSample)
|
||||
ampcor.setLastSampleAcross(mSLC.width)
|
||||
ampcor.setNumberLocationAcross(numberOfOffsetsRange)
|
||||
ampcor.setFirstSampleDown(firstLine)
|
||||
ampcor.setLastSampleDown(mSLC.length)
|
||||
ampcor.setNumberLocationDown(numberOfOffsetsAzimuth)
|
||||
|
||||
#MATCH PARAMETERS
|
||||
#full-aperture mode
|
||||
if (self._insar.modeCombination == 21) or \
|
||||
(self._insar.modeCombination == 22) or \
|
||||
(self._insar.modeCombination == 31) or \
|
||||
(self._insar.modeCombination == 32):
|
||||
ampcor.setWindowSizeWidth(64)
|
||||
ampcor.setWindowSizeHeight(512)
|
||||
#note this is the half width/length of search area, number of resulting correlation samples: 32*2+1
|
||||
ampcor.setSearchWindowSizeWidth(32)
|
||||
ampcor.setSearchWindowSizeHeight(32)
|
||||
#triggering full-aperture mode matching
|
||||
ampcor.setWinsizeFilt(8)
|
||||
ampcor.setOversamplingFactorFilt(64)
|
||||
#regular mode
|
||||
else:
|
||||
ampcor.setWindowSizeWidth(64)
|
||||
ampcor.setWindowSizeHeight(64)
|
||||
ampcor.setSearchWindowSizeWidth(32)
|
||||
ampcor.setSearchWindowSizeHeight(32)
|
||||
|
||||
#REST OF THE STUFF
|
||||
ampcor.setAcrossLooks(1)
|
||||
ampcor.setDownLooks(1)
|
||||
ampcor.setOversamplingFactor(64)
|
||||
ampcor.setZoomWindowSize(16)
|
||||
#1. The following not set
|
||||
#Matching Scale for Sample/Line Directions (-) = 1. 1.
|
||||
#should add the following in Ampcor.py?
|
||||
#if not set, in this case, Ampcor.py'value is also 1. 1.
|
||||
#ampcor.setScaleFactorX(1.)
|
||||
#ampcor.setScaleFactorY(1.)
|
||||
|
||||
#MATCH THRESHOLDS AND DEBUG DATA
|
||||
#2. The following not set
|
||||
#in roi_pac the value is set to 0 1
|
||||
#in isce the value is set to 0.001 1000.0
|
||||
#SNR and Covariance Thresholds (-) = {s1} {s2}
|
||||
#should add the following in Ampcor?
|
||||
#THIS SHOULD BE THE ONLY THING THAT IS DIFFERENT FROM THAT OF ROI_PAC
|
||||
#ampcor.setThresholdSNR(0)
|
||||
#ampcor.setThresholdCov(1)
|
||||
ampcor.setDebugFlag(False)
|
||||
ampcor.setDisplayFlag(False)
|
||||
|
||||
#in summary, only two things not set which are indicated by 'The following not set' above.
|
||||
|
||||
#run ampcor
|
||||
ampcor.ampcor()
|
||||
offsets = ampcor.getOffsetField()
|
||||
ampcorOffsetFile = 'ampcor.off'
|
||||
writeOffset(offsets, ampcorOffsetFile)
|
||||
|
||||
#finalize image, and re-create it
|
||||
#otherwise the file pointer is still at the end of the image
|
||||
mSLC.finalizeImage()
|
||||
sSLC.finalizeImage()
|
||||
|
||||
##########################################
|
||||
#3. cull offsets
|
||||
##########################################
|
||||
refinedOffsets = cullOffsets(offsets)
|
||||
if refinedOffsets == None:
|
||||
print('******************************************************************')
|
||||
print('WARNING: There are not enough offsets left, so we are forced to')
|
||||
print(' use offset without culling. frame {}, swath {}'.format(frameNumber, swathNumber))
|
||||
print('******************************************************************')
|
||||
catalog.addItem('warning message', 'not enough offsets left, use offset without culling. frame {} swath {}'.format(frameNumber, swathNumber), 'runSlcOffset')
|
||||
refinedOffsets = offsets
|
||||
|
||||
cullOffsetFile = 'cull.off'
|
||||
writeOffset(refinedOffsets, cullOffsetFile)
|
||||
|
||||
os.chdir('../')
|
||||
os.chdir('../')
|
||||
|
||||
catalog.printToLog(logger, "runSlcOffset")
|
||||
self._insar.procDoc.addAllFromCatalog(catalog)
|
||||
|
|
@ -0,0 +1,574 @@
|
|||
#
|
||||
# Author: Cunren Liang
|
||||
# Copyright 2015-present, NASA-JPL/Caltech
|
||||
#
|
||||
|
||||
import os
|
||||
import glob
|
||||
import logging
|
||||
import datetime
|
||||
import numpy as np
|
||||
|
||||
import isceobj
|
||||
from isceobj.Alos2Proc.Alos2ProcPublic import create_xml
|
||||
|
||||
logger = logging.getLogger('isce.alos2insar.runSwathMosaic')
|
||||
|
||||
def runSwathMosaic(self):
|
||||
'''mosaic subswaths
|
||||
'''
|
||||
catalog = isceobj.Catalog.createCatalog(self._insar.procDoc.name)
|
||||
self.updateParamemetersFromUser()
|
||||
|
||||
masterTrack = self._insar.loadTrack(master=True)
|
||||
slaveTrack = self._insar.loadTrack(master=False)
|
||||
|
||||
for i, frameNumber in enumerate(self._insar.masterFrames):
|
||||
frameDir = 'f{}_{}'.format(i+1, frameNumber)
|
||||
os.chdir(frameDir)
|
||||
|
||||
mosaicDir = 'mosaic'
|
||||
if not os.path.exists(mosaicDir):
|
||||
os.makedirs(mosaicDir)
|
||||
os.chdir(mosaicDir)
|
||||
|
||||
if not (
|
||||
((self._insar.modeCombination == 21) or \
|
||||
(self._insar.modeCombination == 22) or \
|
||||
(self._insar.modeCombination == 31) or \
|
||||
(self._insar.modeCombination == 32))
|
||||
and
|
||||
(self._insar.endingSwath-self._insar.startingSwath+1 > 1)
|
||||
):
|
||||
import shutil
|
||||
swathDir = 's{}'.format(masterTrack.frames[i].swaths[0].swathNumber)
|
||||
|
||||
if not os.path.isfile(self._insar.interferogram):
|
||||
os.symlink(os.path.join('../', swathDir, self._insar.interferogram), self._insar.interferogram)
|
||||
shutil.copy2(os.path.join('../', swathDir, self._insar.interferogram+'.vrt'), self._insar.interferogram+'.vrt')
|
||||
shutil.copy2(os.path.join('../', swathDir, self._insar.interferogram+'.xml'), self._insar.interferogram+'.xml')
|
||||
if not os.path.isfile(self._insar.amplitude):
|
||||
os.symlink(os.path.join('../', swathDir, self._insar.amplitude), self._insar.amplitude)
|
||||
shutil.copy2(os.path.join('../', swathDir, self._insar.amplitude+'.vrt'), self._insar.amplitude+'.vrt')
|
||||
shutil.copy2(os.path.join('../', swathDir, self._insar.amplitude+'.xml'), self._insar.amplitude+'.xml')
|
||||
|
||||
# os.rename(os.path.join('../', swathDir, self._insar.interferogram), self._insar.interferogram)
|
||||
# os.rename(os.path.join('../', swathDir, self._insar.interferogram+'.vrt'), self._insar.interferogram+'.vrt')
|
||||
# os.rename(os.path.join('../', swathDir, self._insar.interferogram+'.xml'), self._insar.interferogram+'.xml')
|
||||
# os.rename(os.path.join('../', swathDir, self._insar.amplitude), self._insar.amplitude)
|
||||
# os.rename(os.path.join('../', swathDir, self._insar.amplitude+'.vrt'), self._insar.amplitude+'.vrt')
|
||||
# os.rename(os.path.join('../', swathDir, self._insar.amplitude+'.xml'), self._insar.amplitude+'.xml')
|
||||
|
||||
#update frame parameters
|
||||
#########################################################
|
||||
frame = masterTrack.frames[i]
|
||||
infImg = isceobj.createImage()
|
||||
infImg.load(self._insar.interferogram+'.xml')
|
||||
#mosaic size
|
||||
frame.numberOfSamples = infImg.width
|
||||
frame.numberOfLines = infImg.length
|
||||
#NOTE THAT WE ARE STILL USING SINGLE LOOK PARAMETERS HERE
|
||||
#range parameters
|
||||
frame.startingRange = frame.swaths[0].startingRange
|
||||
frame.rangeSamplingRate = frame.swaths[0].rangeSamplingRate
|
||||
frame.rangePixelSize = frame.swaths[0].rangePixelSize
|
||||
#azimuth parameters
|
||||
frame.sensingStart = frame.swaths[0].sensingStart
|
||||
frame.prf = frame.swaths[0].prf
|
||||
frame.azimuthPixelSize = frame.swaths[0].azimuthPixelSize
|
||||
frame.azimuthLineInterval = frame.swaths[0].azimuthLineInterval
|
||||
|
||||
#update frame parameters, slave
|
||||
#########################################################
|
||||
frame = slaveTrack.frames[i]
|
||||
#mosaic size
|
||||
frame.numberOfSamples = int(frame.swaths[0].numberOfSamples/self._insar.numberRangeLooks1)
|
||||
frame.numberOfLines = int(frame.swaths[0].numberOfLines/self._insar.numberAzimuthLooks1)
|
||||
#NOTE THAT WE ARE STILL USING SINGLE LOOK PARAMETERS HERE
|
||||
#range parameters
|
||||
frame.startingRange = frame.swaths[0].startingRange
|
||||
frame.rangeSamplingRate = frame.swaths[0].rangeSamplingRate
|
||||
frame.rangePixelSize = frame.swaths[0].rangePixelSize
|
||||
#azimuth parameters
|
||||
frame.sensingStart = frame.swaths[0].sensingStart
|
||||
frame.prf = frame.swaths[0].prf
|
||||
frame.azimuthPixelSize = frame.swaths[0].azimuthPixelSize
|
||||
frame.azimuthLineInterval = frame.swaths[0].azimuthLineInterval
|
||||
|
||||
os.chdir('../')
|
||||
|
||||
#save parameter file
|
||||
self._insar.saveProduct(masterTrack.frames[i], self._insar.masterFrameParameter)
|
||||
self._insar.saveProduct(slaveTrack.frames[i], self._insar.slaveFrameParameter)
|
||||
|
||||
os.chdir('../')
|
||||
|
||||
continue
|
||||
|
||||
#choose offsets
|
||||
numberOfFrames = len(masterTrack.frames)
|
||||
numberOfSwaths = len(masterTrack.frames[i].swaths)
|
||||
if self.swathOffsetMatching:
|
||||
#no need to do this as the API support 2-d list
|
||||
#rangeOffsets = (np.array(self._insar.swathRangeOffsetMatchingMaster)).reshape(numberOfFrames, numberOfSwaths)
|
||||
#azimuthOffsets = (np.array(self._insar.swathAzimuthOffsetMatchingMaster)).reshape(numberOfFrames, numberOfSwaths)
|
||||
rangeOffsets = self._insar.swathRangeOffsetMatchingMaster
|
||||
azimuthOffsets = self._insar.swathAzimuthOffsetMatchingMaster
|
||||
|
||||
else:
|
||||
#rangeOffsets = (np.array(self._insar.swathRangeOffsetGeometricalMaster)).reshape(numberOfFrames, numberOfSwaths)
|
||||
#azimuthOffsets = (np.array(self._insar.swathAzimuthOffsetGeometricalMaster)).reshape(numberOfFrames, numberOfSwaths)
|
||||
rangeOffsets = self._insar.swathRangeOffsetGeometricalMaster
|
||||
azimuthOffsets = self._insar.swathAzimuthOffsetGeometricalMaster
|
||||
|
||||
rangeOffsets = rangeOffsets[i]
|
||||
azimuthOffsets = azimuthOffsets[i]
|
||||
|
||||
#list of input files
|
||||
inputInterferograms = []
|
||||
inputAmplitudes = []
|
||||
for j, swathNumber in enumerate(range(self._insar.startingSwath, self._insar.endingSwath + 1)):
|
||||
swathDir = 's{}'.format(swathNumber)
|
||||
inputInterferograms.append(os.path.join('../', swathDir, self._insar.interferogram))
|
||||
inputAmplitudes.append(os.path.join('../', swathDir, self._insar.amplitude))
|
||||
|
||||
#note that frame parameters are updated after mosaicking
|
||||
#mosaic amplitudes
|
||||
swathMosaic(masterTrack.frames[i], inputAmplitudes, self._insar.amplitude,
|
||||
rangeOffsets, azimuthOffsets, self._insar.numberRangeLooks1, self._insar.numberAzimuthLooks1, resamplingMethod=0)
|
||||
#mosaic interferograms
|
||||
swathMosaic(masterTrack.frames[i], inputInterferograms, self._insar.interferogram,
|
||||
rangeOffsets, azimuthOffsets, self._insar.numberRangeLooks1, self._insar.numberAzimuthLooks1, updateFrame=True, resamplingMethod=1)
|
||||
|
||||
create_xml(self._insar.amplitude, masterTrack.frames[i].numberOfSamples, masterTrack.frames[i].numberOfLines, 'amp')
|
||||
create_xml(self._insar.interferogram, masterTrack.frames[i].numberOfSamples, masterTrack.frames[i].numberOfLines, 'int')
|
||||
|
||||
#update slave frame parameters here
|
||||
#no matching for slave, always use geometry
|
||||
rangeOffsets = self._insar.swathRangeOffsetGeometricalSlave
|
||||
azimuthOffsets = self._insar.swathAzimuthOffsetGeometricalSlave
|
||||
rangeOffsets = rangeOffsets[i]
|
||||
azimuthOffsets = azimuthOffsets[i]
|
||||
swathMosaicParameters(slaveTrack.frames[i], rangeOffsets, azimuthOffsets, self._insar.numberRangeLooks1, self._insar.numberAzimuthLooks1)
|
||||
|
||||
os.chdir('../')
|
||||
|
||||
#save parameter file
|
||||
self._insar.saveProduct(masterTrack.frames[i], self._insar.masterFrameParameter)
|
||||
self._insar.saveProduct(slaveTrack.frames[i], self._insar.slaveFrameParameter)
|
||||
|
||||
os.chdir('../')
|
||||
|
||||
catalog.printToLog(logger, "runSwathMosaic")
|
||||
self._insar.procDoc.addAllFromCatalog(catalog)
|
||||
|
||||
|
||||
def swathMosaic(frame, inputFiles, outputfile, rangeOffsets, azimuthOffsets, numberOfRangeLooks, numberOfAzimuthLooks, updateFrame=False, phaseCompensation=False, pcRangeLooks=1, pcAzimuthLooks=4, filt=False, resamplingMethod=0):
|
||||
'''
|
||||
mosaic swaths
|
||||
|
||||
frame: frame
|
||||
inputFiles: input file list
|
||||
output file: output mosaic file
|
||||
rangeOffsets: range offsets
|
||||
azimuthOffsets: azimuth offsets
|
||||
numberOfRangeLooks: number of range looks of the input files
|
||||
numberOfAzimuthLooks: number of azimuth looks of the input files
|
||||
phaseCompensation: whether do phase compensation for each swath
|
||||
pcRangeLooks: number of range looks to take when compute swath phase difference
|
||||
pcAzimuthLooks: number of azimuth looks to take when compute swath phase difference
|
||||
filt: whether do filtering when compute swath phase difference
|
||||
resamplingMethod: 0: amp resampling. 1: int resampling.
|
||||
'''
|
||||
from contrib.alos2proc_f.alos2proc_f import rect_with_looks
|
||||
from contrib.alos2proc.alos2proc import mosaicsubswath
|
||||
from isceobj.Alos2Proc.Alos2ProcPublic import multilook
|
||||
from isceobj.Alos2Proc.Alos2ProcPublic import cal_coherence_1
|
||||
from isceobj.Alos2Proc.Alos2ProcPublic import filterInterferogram
|
||||
|
||||
numberOfSwaths = len(frame.swaths)
|
||||
swaths = frame.swaths
|
||||
|
||||
rangeScale = []
|
||||
azimuthScale = []
|
||||
rectWidth = []
|
||||
rectLength = []
|
||||
for i in range(numberOfSwaths):
|
||||
rangeScale.append(swaths[0].rangePixelSize / swaths[i].rangePixelSize)
|
||||
azimuthScale.append(swaths[0].azimuthLineInterval / swaths[i].azimuthLineInterval)
|
||||
if i == 0:
|
||||
rectWidth.append( int(swaths[i].numberOfSamples / numberOfRangeLooks) )
|
||||
rectLength.append( int(swaths[i].numberOfLines / numberOfAzimuthLooks) )
|
||||
else:
|
||||
rectWidth.append( int(1.0 / rangeScale[i] * int(swaths[i].numberOfSamples / numberOfRangeLooks)) )
|
||||
rectLength.append( int(1.0 / azimuthScale[i] * int(swaths[i].numberOfLines / numberOfAzimuthLooks)) )
|
||||
|
||||
#convert original offset to offset for images with looks
|
||||
#use list instead of np.array to make it consistent with the rest of the code
|
||||
rangeOffsets1 = [i/numberOfRangeLooks for i in rangeOffsets]
|
||||
azimuthOffsets1 = [i/numberOfAzimuthLooks for i in azimuthOffsets]
|
||||
|
||||
#get offset relative to the first frame
|
||||
rangeOffsets2 = [0.0]
|
||||
azimuthOffsets2 = [0.0]
|
||||
for i in range(1, numberOfSwaths):
|
||||
rangeOffsets2.append(0.0)
|
||||
azimuthOffsets2.append(0.0)
|
||||
for j in range(1, i+1):
|
||||
rangeOffsets2[i] += rangeOffsets1[j]
|
||||
azimuthOffsets2[i] += azimuthOffsets1[j]
|
||||
|
||||
#resample each swath
|
||||
rinfs = []
|
||||
for i, inf in enumerate(inputFiles):
|
||||
rinfs.append("{}_{}{}".format(os.path.splitext(os.path.basename(inf))[0], i, os.path.splitext(os.path.basename(inf))[1]))
|
||||
#do not resample first swath
|
||||
if i == 0:
|
||||
if os.path.isfile(rinfs[i]):
|
||||
os.remove(rinfs[i])
|
||||
os.symlink(inf, rinfs[i])
|
||||
else:
|
||||
infImg = isceobj.createImage()
|
||||
infImg.load(inf+'.xml')
|
||||
rangeOffsets2Frac = rangeOffsets2[i] - int(rangeOffsets2[i])
|
||||
azimuthOffsets2Frac = azimuthOffsets2[i] - int(azimuthOffsets2[i])
|
||||
|
||||
|
||||
if resamplingMethod == 0:
|
||||
rect_with_looks(inf,
|
||||
rinfs[i],
|
||||
infImg.width, infImg.length,
|
||||
rectWidth[i], rectLength[i],
|
||||
rangeScale[i], 0.0,
|
||||
0.0,azimuthScale[i],
|
||||
rangeOffsets2Frac * rangeScale[i], azimuthOffsets2Frac * azimuthScale[i],
|
||||
1,1,
|
||||
1,1,
|
||||
'COMPLEX',
|
||||
'Bilinear')
|
||||
elif resamplingMethod == 1:
|
||||
#decompose amplitude and phase
|
||||
phaseFile = 'phase'
|
||||
amplitudeFile = 'amplitude'
|
||||
data = np.fromfile(inf, dtype=np.complex64).reshape(infImg.length, infImg.width)
|
||||
phase = np.exp(np.complex64(1j) * np.angle(data))
|
||||
phase[np.nonzero(data==0)] = 0
|
||||
phase.astype(np.complex64).tofile(phaseFile)
|
||||
amplitude = np.absolute(data)
|
||||
amplitude.astype(np.float32).tofile(amplitudeFile)
|
||||
|
||||
#resampling
|
||||
phaseRectFile = 'phaseRect'
|
||||
amplitudeRectFile = 'amplitudeRect'
|
||||
rect_with_looks(phaseFile,
|
||||
phaseRectFile,
|
||||
infImg.width, infImg.length,
|
||||
rectWidth[i], rectLength[i],
|
||||
rangeScale[i], 0.0,
|
||||
0.0,azimuthScale[i],
|
||||
rangeOffsets2Frac * rangeScale[i], azimuthOffsets2Frac * azimuthScale[i],
|
||||
1,1,
|
||||
1,1,
|
||||
'COMPLEX',
|
||||
'Sinc')
|
||||
rect_with_looks(amplitudeFile,
|
||||
amplitudeRectFile,
|
||||
infImg.width, infImg.length,
|
||||
rectWidth[i], rectLength[i],
|
||||
rangeScale[i], 0.0,
|
||||
0.0,azimuthScale[i],
|
||||
rangeOffsets2Frac * rangeScale[i], azimuthOffsets2Frac * azimuthScale[i],
|
||||
1,1,
|
||||
1,1,
|
||||
'REAL',
|
||||
'Bilinear')
|
||||
|
||||
#recombine amplitude and phase
|
||||
phase = np.fromfile(phaseRectFile, dtype=np.complex64).reshape(rectLength[i], rectWidth[i])
|
||||
amplitude = np.fromfile(amplitudeRectFile, dtype=np.float32).reshape(rectLength[i], rectWidth[i])
|
||||
(phase*amplitude).astype(np.complex64).tofile(rinfs[i])
|
||||
|
||||
#tidy up
|
||||
os.remove(phaseFile)
|
||||
os.remove(amplitudeFile)
|
||||
os.remove(phaseRectFile)
|
||||
os.remove(amplitudeRectFile)
|
||||
|
||||
|
||||
#determine output width and length
|
||||
#actually no need to calculate in range direction
|
||||
xs = []
|
||||
xe = []
|
||||
ys = []
|
||||
ye = []
|
||||
for i in range(numberOfSwaths):
|
||||
if i == 0:
|
||||
xs.append(0)
|
||||
xe.append(rectWidth[i] - 1)
|
||||
ys.append(0)
|
||||
ye.append(rectLength[i] - 1)
|
||||
else:
|
||||
xs.append(0 - int(rangeOffsets2[i]))
|
||||
xe.append(rectWidth[i] - 1 - int(rangeOffsets2[i]))
|
||||
ys.append(0 - int(azimuthOffsets2[i]))
|
||||
ye.append(rectLength[i] - 1 - int(azimuthOffsets2[i]))
|
||||
|
||||
(xmin, xminIndex) = min((v,i) for i,v in enumerate(xs))
|
||||
(xmax, xmaxIndex) = max((v,i) for i,v in enumerate(xe))
|
||||
(ymin, yminIndex) = min((v,i) for i,v in enumerate(ys))
|
||||
(ymax, ymaxIndex) = max((v,i) for i,v in enumerate(ye))
|
||||
|
||||
outWidth = xmax - xmin + 1
|
||||
outLength = ymax - ymin + 1
|
||||
|
||||
#prepare offset for mosaicing
|
||||
rangeOffsets3 = []
|
||||
azimuthOffsets3 = []
|
||||
for i in range(numberOfSwaths):
|
||||
azimuthOffsets3.append(int(azimuthOffsets2[i]) - int(azimuthOffsets2[yminIndex]))
|
||||
if i != 0:
|
||||
rangeOffsets3.append(int(rangeOffsets2[i]) - int(rangeOffsets2[i-1]))
|
||||
else:
|
||||
rangeOffsets3.append(0)
|
||||
|
||||
|
||||
delta = int(30 / numberOfRangeLooks)
|
||||
|
||||
#compute compensation phase for each swath
|
||||
diffMean2 = [0.0 for i in range(numberOfSwaths)]
|
||||
if phaseCompensation:
|
||||
#compute swath phase offset
|
||||
diffMean = [0.0]
|
||||
for i in range(1, numberOfSwaths):
|
||||
#all indexes start with zero, all the computed start/end sample/line indexes are included.
|
||||
|
||||
#no need to add edge here, as we are going to find first/last nonzero sample/lines later
|
||||
#edge = delta
|
||||
edge = 0
|
||||
|
||||
#image i-1
|
||||
startSample1 = edge + 0 - int(rangeOffsets2[i]) + int(rangeOffsets2[i-1])
|
||||
endSample1 = -edge + rectWidth[i-1]-1
|
||||
startLine1 = edge + max(0 - int(azimuthOffsets2[i]) + int(azimuthOffsets2[i-1]), 0)
|
||||
endLine1 = -edge + min(rectLength[i]-1 - int(azimuthOffsets2[i]) + int(azimuthOffsets2[i-1]), rectLength[i-1]-1)
|
||||
data1 = readImage(rinfs[i-1], rectWidth[i-1], rectLength[i-1], startSample1, endSample1, startLine1, endLine1)
|
||||
|
||||
#image i
|
||||
startSample2 = edge + 0
|
||||
endSample2 = -edge + rectWidth[i-1]-1 - int(rangeOffsets2[i-1]) + int(rangeOffsets2[i])
|
||||
startLine2 = edge + max(0 - int(azimuthOffsets2[i-1]) + int(azimuthOffsets2[i]), 0)
|
||||
endLine2 = -edge + min(rectLength[i-1]-1 - int(azimuthOffsets2[i-1]) + int(azimuthOffsets2[i]), rectLength[i]-1)
|
||||
data2 = readImage(rinfs[i], rectWidth[i], rectLength[i], startSample2, endSample2, startLine2, endLine2)
|
||||
|
||||
#remove edge due to incomplete covolution in resampling
|
||||
edge = 9
|
||||
(startLine0, endLine0, startSample0, endSample0) = findNonzero( np.logical_and((data1!=0), (data2!=0)) )
|
||||
data1 = data1[startLine0+edge:endLine0+1-edge, startSample0+edge:endSample0+1-edge]
|
||||
data2 = data2[startLine0+edge:endLine0+1-edge, startSample0+edge:endSample0+1-edge]
|
||||
|
||||
#take looks
|
||||
data1 = multilook(data1, pcAzimuthLooks, pcRangeLooks)
|
||||
data2 = multilook(data2, pcAzimuthLooks, pcRangeLooks)
|
||||
|
||||
#filter
|
||||
if filt:
|
||||
data1 /= (np.absolute(data1)+(data1==0))
|
||||
data2 /= (np.absolute(data2)+(data2==0))
|
||||
data1 = filterInterferogram(data1, 3.0, 64, 1)
|
||||
data2 = filterInterferogram(data2, 3.0, 64, 1)
|
||||
|
||||
|
||||
#get difference
|
||||
corth = 0.87
|
||||
if filt:
|
||||
corth = 0.90
|
||||
diffMean0 = 0.0
|
||||
for k in range(5):
|
||||
dataDiff = data1 * np.conj(data2)
|
||||
cor = cal_coherence_1(dataDiff, win=3)
|
||||
index = np.nonzero(np.logical_and(cor>corth, dataDiff!=0))
|
||||
if index[0].size < 100:
|
||||
diffMean0 = 0.0
|
||||
print('\n\nWARNING: too few high coherence pixels for swath phase difference estimation between swath {} and {}'.format(i-1, i))
|
||||
print(' : first swath swath number: 0\n\n')
|
||||
break
|
||||
angle = np.mean(np.angle(dataDiff[index]), dtype=np.float64)
|
||||
diffMean0 += angle
|
||||
data2 *= np.exp(np.complex64(1j) * angle)
|
||||
print('phase offset: %15.12f rad after loop: %3d'%(diffMean0, k))
|
||||
|
||||
DEBUG=False
|
||||
if DEBUG and (k==0):
|
||||
from isceobj.Alos2Proc.Alos2ProcPublic import create_xml
|
||||
(lengthxx, widthxx)=dataDiff.shape
|
||||
filtnamePrefix = 'subswath{}_subswath{}_loop{}'.format(frame.swaths[i-1].swathNumber, frame.swaths[i].swathNumber, k)
|
||||
cor.astype(np.float32).tofile(filtnamePrefix+'.cor')
|
||||
create_xml(filtnamePrefix+'.cor', widthxx, lengthxx, 'float')
|
||||
dataDiff.astype(np.complex64).tofile(filtnamePrefix+'.int')
|
||||
create_xml(filtnamePrefix+'.int', widthxx, lengthxx, 'int')
|
||||
|
||||
diffMean.append(diffMean0)
|
||||
print('phase offset: subswath{} - subswath{}: {}'.format(frame.swaths[i-1].swathNumber, frame.swaths[i].swathNumber, diffMean0))
|
||||
|
||||
for i in range(1, numberOfSwaths):
|
||||
for j in range(1, i+1):
|
||||
diffMean2[i] += diffMean[j]
|
||||
|
||||
|
||||
#mosaic swaths
|
||||
diffflag = 1
|
||||
oflag = [0 for i in range(numberOfSwaths)]
|
||||
mosaicsubswath(outputfile, outWidth, outLength, delta, diffflag, numberOfSwaths,
|
||||
rinfs, rectWidth, rangeOffsets3, azimuthOffsets3, diffMean2, oflag)
|
||||
#remove tmp files
|
||||
for x in rinfs:
|
||||
os.remove(x)
|
||||
|
||||
|
||||
#update frame parameters
|
||||
if updateFrame:
|
||||
#mosaic size
|
||||
frame.numberOfSamples = outWidth
|
||||
frame.numberOfLines = outLength
|
||||
#NOTE THAT WE ARE STILL USING SINGLE LOOK PARAMETERS HERE
|
||||
#range parameters
|
||||
frame.startingRange = frame.swaths[0].startingRange
|
||||
frame.rangeSamplingRate = frame.swaths[0].rangeSamplingRate
|
||||
frame.rangePixelSize = frame.swaths[0].rangePixelSize
|
||||
#azimuth parameters
|
||||
azimuthTimeOffset = - max([int(x) for x in azimuthOffsets2]) * numberOfAzimuthLooks * frame.swaths[0].azimuthLineInterval
|
||||
frame.sensingStart = frame.swaths[0].sensingStart + datetime.timedelta(seconds = azimuthTimeOffset)
|
||||
frame.prf = frame.swaths[0].prf
|
||||
frame.azimuthPixelSize = frame.swaths[0].azimuthPixelSize
|
||||
frame.azimuthLineInterval = frame.swaths[0].azimuthLineInterval
|
||||
|
||||
|
||||
def swathMosaicParameters(frame, rangeOffsets, azimuthOffsets, numberOfRangeLooks, numberOfAzimuthLooks):
|
||||
'''
|
||||
mosaic swaths (this is simplified version of swathMosaic to update parameters only)
|
||||
|
||||
frame: frame
|
||||
rangeOffsets: range offsets
|
||||
azimuthOffsets: azimuth offsets
|
||||
numberOfRangeLooks: number of range looks of the input files
|
||||
numberOfAzimuthLooks: number of azimuth looks of the input files
|
||||
'''
|
||||
|
||||
numberOfSwaths = len(frame.swaths)
|
||||
swaths = frame.swaths
|
||||
|
||||
rangeScale = []
|
||||
azimuthScale = []
|
||||
rectWidth = []
|
||||
rectLength = []
|
||||
for i in range(numberOfSwaths):
|
||||
rangeScale.append(swaths[0].rangePixelSize / swaths[i].rangePixelSize)
|
||||
azimuthScale.append(swaths[0].azimuthLineInterval / swaths[i].azimuthLineInterval)
|
||||
if i == 0:
|
||||
rectWidth.append( int(swaths[i].numberOfSamples / numberOfRangeLooks) )
|
||||
rectLength.append( int(swaths[i].numberOfLines / numberOfAzimuthLooks) )
|
||||
else:
|
||||
rectWidth.append( int(1.0 / rangeScale[i] * int(swaths[i].numberOfSamples / numberOfRangeLooks)) )
|
||||
rectLength.append( int(1.0 / azimuthScale[i] * int(swaths[i].numberOfLines / numberOfAzimuthLooks)) )
|
||||
|
||||
#convert original offset to offset for images with looks
|
||||
#use list instead of np.array to make it consistent with the rest of the code
|
||||
rangeOffsets1 = [i/numberOfRangeLooks for i in rangeOffsets]
|
||||
azimuthOffsets1 = [i/numberOfAzimuthLooks for i in azimuthOffsets]
|
||||
|
||||
#get offset relative to the first frame
|
||||
rangeOffsets2 = [0.0]
|
||||
azimuthOffsets2 = [0.0]
|
||||
for i in range(1, numberOfSwaths):
|
||||
rangeOffsets2.append(0.0)
|
||||
azimuthOffsets2.append(0.0)
|
||||
for j in range(1, i+1):
|
||||
rangeOffsets2[i] += rangeOffsets1[j]
|
||||
azimuthOffsets2[i] += azimuthOffsets1[j]
|
||||
|
||||
#determine output width and length
|
||||
#actually no need to calculate in range direction
|
||||
xs = []
|
||||
xe = []
|
||||
ys = []
|
||||
ye = []
|
||||
for i in range(numberOfSwaths):
|
||||
if i == 0:
|
||||
xs.append(0)
|
||||
xe.append(rectWidth[i] - 1)
|
||||
ys.append(0)
|
||||
ye.append(rectLength[i] - 1)
|
||||
else:
|
||||
xs.append(0 - int(rangeOffsets2[i]))
|
||||
xe.append(rectWidth[i] - 1 - int(rangeOffsets2[i]))
|
||||
ys.append(0 - int(azimuthOffsets2[i]))
|
||||
ye.append(rectLength[i] - 1 - int(azimuthOffsets2[i]))
|
||||
|
||||
(xmin, xminIndex) = min((v,i) for i,v in enumerate(xs))
|
||||
(xmax, xmaxIndex) = max((v,i) for i,v in enumerate(xe))
|
||||
(ymin, yminIndex) = min((v,i) for i,v in enumerate(ys))
|
||||
(ymax, ymaxIndex) = max((v,i) for i,v in enumerate(ye))
|
||||
|
||||
outWidth = xmax - xmin + 1
|
||||
outLength = ymax - ymin + 1
|
||||
|
||||
#update frame parameters
|
||||
#mosaic size
|
||||
frame.numberOfSamples = outWidth
|
||||
frame.numberOfLines = outLength
|
||||
#NOTE THAT WE ARE STILL USING SINGLE LOOK PARAMETERS HERE
|
||||
#range parameters
|
||||
frame.startingRange = frame.swaths[0].startingRange
|
||||
frame.rangeSamplingRate = frame.swaths[0].rangeSamplingRate
|
||||
frame.rangePixelSize = frame.swaths[0].rangePixelSize
|
||||
#azimuth parameters
|
||||
azimuthTimeOffset = - max([int(x) for x in azimuthOffsets2]) * numberOfAzimuthLooks * frame.swaths[0].azimuthLineInterval
|
||||
frame.sensingStart = frame.swaths[0].sensingStart + datetime.timedelta(seconds = azimuthTimeOffset)
|
||||
frame.prf = frame.swaths[0].prf
|
||||
frame.azimuthPixelSize = frame.swaths[0].azimuthPixelSize
|
||||
frame.azimuthLineInterval = frame.swaths[0].azimuthLineInterval
|
||||
|
||||
|
||||
def readImage(inputfile, numberOfSamples, numberOfLines, startSample, endSample, startLine, endLine):
|
||||
'''
|
||||
read a chunk of image
|
||||
the indexes (startSample, endSample, startLine, endLine) are included and start with zero
|
||||
|
||||
memmap is not used, because it is much slower
|
||||
'''
|
||||
data = np.zeros((endLine-startLine+1, endSample-startSample+1), dtype=np.complex64)
|
||||
with open(inputfile,'rb') as fp:
|
||||
#for i in range(endLine-startLine+1):
|
||||
for i in range(startLine, endLine+1):
|
||||
fp.seek((i*numberOfSamples+startSample)*8, 0)
|
||||
data[i-startLine] = np.fromfile(fp, dtype=np.complex64, count=endSample-startSample+1)
|
||||
return data
|
||||
|
||||
|
||||
def findNonzero_v1(data):
|
||||
'''
|
||||
find the first/last non-zero line/sample
|
||||
all indexes start from zero
|
||||
'''
|
||||
indexes = np.nonzero(data)
|
||||
|
||||
#first line last line first sample last sample
|
||||
return (indexes[0][0], indexes[0][-1], indexes[1][0], indexes[1][-1])
|
||||
|
||||
|
||||
def findNonzero(data, lineRatio=0.5, sampleRatio=0.5):
|
||||
'''
|
||||
find the first/last non-zero line/sample
|
||||
all indexes start from zero
|
||||
'''
|
||||
import numpy as np
|
||||
|
||||
(length, width)=data.shape
|
||||
|
||||
lineIndex = (np.nonzero(np.sum((data!=0), axis=1) > width*lineRatio))[0]
|
||||
sampleIndex = (np.nonzero(np.sum((data!=0), axis=0) > length*sampleRatio))[0]
|
||||
|
||||
#first line last line first sample last sample
|
||||
return (lineIndex[0], lineIndex[-1], sampleIndex[0], sampleIndex[-1])
|
||||
|
||||
|
||||
|
|
@ -0,0 +1,390 @@
|
|||
#
|
||||
# Author: Cunren Liang
|
||||
# Copyright 2015-present, NASA-JPL/Caltech
|
||||
#
|
||||
|
||||
import os
|
||||
import glob
|
||||
import logging
|
||||
import datetime
|
||||
import numpy as np
|
||||
|
||||
import isceobj
|
||||
from isceobj.Alos2Proc.Alos2ProcPublic import multilook
|
||||
|
||||
|
||||
logger = logging.getLogger('isce.alos2insar.runSwathOffset')
|
||||
|
||||
def runSwathOffset(self):
|
||||
'''estimate swath offsets.
|
||||
'''
|
||||
catalog = isceobj.Catalog.createCatalog(self._insar.procDoc.name)
|
||||
self.updateParamemetersFromUser()
|
||||
|
||||
masterTrack = self._insar.loadTrack(master=True)
|
||||
slaveTrack = self._insar.loadTrack(master=False)
|
||||
|
||||
for i, frameNumber in enumerate(self._insar.masterFrames):
|
||||
frameDir = 'f{}_{}'.format(i+1, frameNumber)
|
||||
os.chdir(frameDir)
|
||||
|
||||
mosaicDir = 'mosaic'
|
||||
if not os.path.exists(mosaicDir):
|
||||
os.makedirs(mosaicDir)
|
||||
os.chdir(mosaicDir)
|
||||
|
||||
if not (
|
||||
((self._insar.modeCombination == 21) or \
|
||||
(self._insar.modeCombination == 22) or \
|
||||
(self._insar.modeCombination == 31) or \
|
||||
(self._insar.modeCombination == 32))
|
||||
and
|
||||
(self._insar.endingSwath-self._insar.startingSwath+1 > 1)
|
||||
):
|
||||
|
||||
os.chdir('../../')
|
||||
|
||||
continue
|
||||
|
||||
#compute swath offset
|
||||
offsetMaster = swathOffset(masterTrack.frames[i], self._insar.masterSlc, self._insar.masterSwathOffset,
|
||||
crossCorrelation=self.swathOffsetMatching, numberOfAzimuthLooks=10)
|
||||
#only use geometrical offset for slave
|
||||
offsetSlave = swathOffset(slaveTrack.frames[i], self._insar.slaveSlc, self._insar.slaveSwathOffset,
|
||||
crossCorrelation=False, numberOfAzimuthLooks=10)
|
||||
|
||||
#initialization
|
||||
if i == 0:
|
||||
self._insar.swathRangeOffsetGeometricalMaster = []
|
||||
self._insar.swathAzimuthOffsetGeometricalMaster = []
|
||||
self._insar.swathRangeOffsetGeometricalSlave = []
|
||||
self._insar.swathAzimuthOffsetGeometricalSlave = []
|
||||
if self.swathOffsetMatching:
|
||||
self._insar.swathRangeOffsetMatchingMaster = []
|
||||
self._insar.swathAzimuthOffsetMatchingMaster = []
|
||||
#self._insar.swathRangeOffsetMatchingSlave = []
|
||||
#self._insar.swathAzimuthOffsetMatchingSlave = []
|
||||
|
||||
#append list directly, as the API support 2-d list
|
||||
self._insar.swathRangeOffsetGeometricalMaster.append(offsetMaster[0])
|
||||
self._insar.swathAzimuthOffsetGeometricalMaster.append(offsetMaster[1])
|
||||
self._insar.swathRangeOffsetGeometricalSlave.append(offsetSlave[0])
|
||||
self._insar.swathAzimuthOffsetGeometricalSlave.append(offsetSlave[1])
|
||||
if self.swathOffsetMatching:
|
||||
self._insar.swathRangeOffsetMatchingMaster.append(offsetMaster[2])
|
||||
self._insar.swathAzimuthOffsetMatchingMaster.append(offsetMaster[3])
|
||||
#self._insar.swathRangeOffsetMatchingSlave.append(offsetSlave[2])
|
||||
#self._insar.swathAzimuthOffsetMatchingSlave.append(offsetSlave[3])
|
||||
|
||||
os.chdir('../../')
|
||||
|
||||
catalog.printToLog(logger, "runSwathOffset")
|
||||
self._insar.procDoc.addAllFromCatalog(catalog)
|
||||
|
||||
|
||||
def swathOffset(frame, image, outputfile, crossCorrelation=True, numberOfAzimuthLooks=10):
|
||||
'''
|
||||
compute swath offset
|
||||
frame: frame object
|
||||
image: image for doing matching
|
||||
outputfile: output txt file for saving swath offset
|
||||
crossCorrelation: whether do matching
|
||||
numberOfAzimuthLooks: number of looks to take in azimuth before matching
|
||||
'''
|
||||
|
||||
rangeOffsetGeometrical = []
|
||||
azimuthOffsetGeometrical = []
|
||||
rangeOffsetMatching = []
|
||||
azimuthOffsetMatching = []
|
||||
|
||||
for j in range(len(frame.swaths)):
|
||||
frameNumber = frame.frameNumber
|
||||
swathNumber = frame.swaths[j].swathNumber
|
||||
swathDir = 's{}'.format(swathNumber)
|
||||
|
||||
print('estimate offset frame {}, swath {}'.format(frameNumber, swathNumber))
|
||||
|
||||
if j == 0:
|
||||
rangeOffsetGeometrical.append(0.0)
|
||||
azimuthOffsetGeometrical.append(0.0)
|
||||
rangeOffsetMatching.append(0.0)
|
||||
azimuthOffsetMatching.append(0.0)
|
||||
swathDirLast = swathDir
|
||||
continue
|
||||
|
||||
image1 = os.path.join('../', swathDirLast, image)
|
||||
image2 = os.path.join('../', swathDir, image)
|
||||
swath0 = frame.swaths[0]
|
||||
swath1 = frame.swaths[j-1]
|
||||
swath2 = frame.swaths[j]
|
||||
|
||||
rangeScale1 = swath0.rangePixelSize / swath1.rangePixelSize
|
||||
azimuthScale1 = swath0.azimuthLineInterval / swath1.azimuthLineInterval
|
||||
rangeScale2 = swath0.rangePixelSize / swath2.rangePixelSize
|
||||
azimuthScale2 = swath0.azimuthLineInterval / swath2.azimuthLineInterval
|
||||
|
||||
#offset from geometry
|
||||
offsetGeometrical = computeSwathOffset(swath1, swath2, rangeScale1, azimuthScale1)
|
||||
rangeOffsetGeometrical.append(offsetGeometrical[0])
|
||||
azimuthOffsetGeometrical.append(offsetGeometrical[1])
|
||||
|
||||
#offset from cross-correlation
|
||||
if crossCorrelation:
|
||||
offsetMatching = estimateSwathOffset(swath1, swath2, image1, image2, rangeScale1,
|
||||
azimuthScale1, rangeScale2, azimuthScale2, numberOfAzimuthLooks)
|
||||
if offsetMatching != None:
|
||||
rangeOffsetMatching.append(offsetMatching[0])
|
||||
azimuthOffsetMatching.append(offsetMatching[1])
|
||||
else:
|
||||
print('******************************************************************')
|
||||
print('WARNING: bad matching offset, we are forced to use')
|
||||
print(' geometrical offset for swath mosaicking')
|
||||
print('******************************************************************')
|
||||
rangeOffsetMatching.append(offsetGeometrical[0])
|
||||
azimuthOffsetMatching.append(offsetGeometrical[1])
|
||||
|
||||
swathDirLast = swathDir
|
||||
|
||||
|
||||
if crossCorrelation:
|
||||
offsetComp = "\n\ncomparision of offsets:\n\n"
|
||||
offsetComp += "offset type i geometrical match difference\n"
|
||||
offsetComp += "+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++\n"
|
||||
for i, (offset1, offset2) in enumerate(zip(rangeOffsetGeometrical, rangeOffsetMatching)):
|
||||
offsetComp += "range offset {:2d} {:13.3f} {:13.3f} {:13.3f}\n".format(i, offset1, offset2, offset1 - offset2)
|
||||
for i, (offset1, offset2) in enumerate(zip(azimuthOffsetGeometrical, azimuthOffsetMatching)):
|
||||
offsetComp += "azimuth offset {:2d} {:13.3f} {:13.3f} {:13.3f}\n".format(i, offset1, offset2, offset1 - offset2)
|
||||
|
||||
#write and report offsets
|
||||
with open(outputfile, 'w') as f:
|
||||
f.write(offsetComp)
|
||||
print("{}".format(offsetComp))
|
||||
|
||||
|
||||
if crossCorrelation:
|
||||
return (rangeOffsetGeometrical, azimuthOffsetGeometrical, rangeOffsetMatching, azimuthOffsetMatching)
|
||||
else:
|
||||
return (rangeOffsetGeometrical, azimuthOffsetGeometrical)
|
||||
|
||||
|
||||
def computeSwathOffset(swath1, swath2, rangeScale1=1, azimuthScale1=1):
|
||||
|
||||
rangeOffset = -(swath2.startingRange - swath1.startingRange) / swath1.rangePixelSize
|
||||
azimuthOffset = -((swath2.sensingStart - swath1.sensingStart).total_seconds()) / swath1.azimuthLineInterval
|
||||
|
||||
rangeOffset /= rangeScale1
|
||||
azimuthOffset /= azimuthScale1
|
||||
|
||||
return (rangeOffset, azimuthOffset)
|
||||
|
||||
|
||||
def estimateSwathOffset(swath1, swath2, image1, image2, rangeScale1=1, azimuthScale1=1, rangeScale2=1, azimuthScale2=1, numberOfAzimuthLooks=10):
|
||||
'''
|
||||
estimate offset of two adjacent swaths using matching
|
||||
'''
|
||||
from osgeo import gdal
|
||||
import isceobj
|
||||
from contrib.alos2proc_f.alos2proc_f import rect_with_looks
|
||||
from isceobj.Alos2Proc.Alos2ProcPublic import create_xml
|
||||
from isceobj.Alos2Proc.Alos2ProcPublic import cullOffsets
|
||||
from isceobj.Alos2Proc.Alos2ProcPublic import meanOffset
|
||||
from mroipac.ampcor.Ampcor import Ampcor
|
||||
|
||||
|
||||
#processing image 1
|
||||
rangeOff1 = int((swath2.startingRange - swath1.startingRange) / swath1.rangePixelSize)
|
||||
if rangeOff1 < 0:
|
||||
rangeOff1 = 0
|
||||
numberOfSamples1 = swath1.numberOfSamples - rangeOff1
|
||||
|
||||
numberOfSamplesRect1 = int(numberOfSamples1/rangeScale1)
|
||||
numberOfLinesRect1 = int(swath1.numberOfLines/azimuthScale1)
|
||||
|
||||
numberOfSamplesLook1 = int(numberOfSamplesRect1/1)
|
||||
numberOfLinesLook1 = int(numberOfLinesRect1/numberOfAzimuthLooks)
|
||||
|
||||
#get magnitude image whether complex or not
|
||||
#ReadAsArray: https://pcjericks.github.io/py-gdalogr-cookbook/raster_layers.html
|
||||
ds = gdal.Open(image1 + '.vrt', gdal.GA_ReadOnly)
|
||||
data = ds.ReadAsArray(rangeOff1, 0, numberOfSamples1, swath1.numberOfLines)
|
||||
ds = None
|
||||
(np.absolute(data)).astype(np.float32).tofile('image1.float')
|
||||
|
||||
#rectify
|
||||
if rangeScale1 == 1 and azimuthScale1 == 1:
|
||||
os.rename('image1.float', 'image1_rect.float')
|
||||
else:
|
||||
rect_with_looks('image1.float',
|
||||
'image1_rect.float',
|
||||
numberOfSamples1, swath1.numberOfLines,
|
||||
numberOfSamplesRect1, numberOfLinesRect1,
|
||||
rangeScale1, 0.0,
|
||||
0.0,azimuthScale1,
|
||||
0.0,0.0,
|
||||
1,1,
|
||||
1,1,
|
||||
'REAL',
|
||||
'Bilinear')
|
||||
os.remove('image1.float')
|
||||
|
||||
#take looks
|
||||
if numberOfAzimuthLooks == 1:
|
||||
os.rename('image1_rect.float', 'image1_look.float')
|
||||
else:
|
||||
data1 = np.fromfile('image1_rect.float', dtype=np.float32).reshape(numberOfLinesRect1, numberOfSamplesRect1)
|
||||
data1 = np.sqrt(multilook(data1**2, numberOfAzimuthLooks, 1))
|
||||
data1.astype(np.float32).tofile('image1_look.float')
|
||||
os.remove('image1_rect.float')
|
||||
create_xml('image1_look.float', numberOfSamplesLook1, numberOfLinesLook1, 'float')
|
||||
|
||||
|
||||
#processing image 2
|
||||
rangeOff2 = 0
|
||||
numberOfSamples2 = int((swath1.startingRange + swath1.rangePixelSize * (swath1.numberOfSamples - 1) - swath2.startingRange) / swath2.rangePixelSize) + 1
|
||||
if numberOfSamples2 > swath2.numberOfSamples:
|
||||
numberOfSamples2 = swath2.numberOfSamples
|
||||
|
||||
numberOfSamplesRect2 = int(numberOfSamples2/rangeScale2)
|
||||
numberOfLinesRect2 = int(swath2.numberOfLines/azimuthScale2)
|
||||
|
||||
numberOfSamplesLook2 = int(numberOfSamplesRect2/1)
|
||||
numberOfLinesLook2 = int(numberOfLinesRect2/numberOfAzimuthLooks)
|
||||
|
||||
#get magnitude image whether complex or not
|
||||
ds = gdal.Open(image2 + '.vrt', gdal.GA_ReadOnly)
|
||||
data = ds.ReadAsArray(rangeOff2, 0, numberOfSamples2, swath2.numberOfLines)
|
||||
ds = None
|
||||
(np.absolute(data)).astype(np.float32).tofile('image2.float')
|
||||
|
||||
#rectify
|
||||
if rangeScale2 == 1 and azimuthScale2 == 1:
|
||||
os.rename('image2.float', 'image2_rect.float')
|
||||
else:
|
||||
rect_with_looks('image2.float',
|
||||
'image2_rect.float',
|
||||
numberOfSamples2, swath2.numberOfLines,
|
||||
numberOfSamplesRect2, numberOfLinesRect2,
|
||||
rangeScale2, 0.0,
|
||||
0.0,azimuthScale2,
|
||||
0.0,0.0,
|
||||
1,1,
|
||||
1,1,
|
||||
'REAL',
|
||||
'Bilinear')
|
||||
os.remove('image2.float')
|
||||
|
||||
#take looks
|
||||
if numberOfAzimuthLooks == 1:
|
||||
os.rename('image2_rect.float', 'image2_look.float')
|
||||
else:
|
||||
data2 = np.fromfile('image2_rect.float', dtype=np.float32).reshape(numberOfLinesRect2, numberOfSamplesRect2)
|
||||
data2 = np.sqrt(multilook(data2**2, numberOfAzimuthLooks, 1))
|
||||
data2.astype(np.float32).tofile('image2_look.float')
|
||||
os.remove('image2_rect.float')
|
||||
create_xml('image2_look.float', numberOfSamplesLook2, numberOfLinesLook2, 'float')
|
||||
|
||||
|
||||
#matching
|
||||
ampcor = Ampcor(name='insarapp_slcs_ampcor')
|
||||
ampcor.configure()
|
||||
|
||||
mMag = isceobj.createImage()
|
||||
mMag.load('image1_look.float.xml')
|
||||
mMag.setAccessMode('read')
|
||||
mMag.createImage()
|
||||
|
||||
sMag = isceobj.createImage()
|
||||
sMag.load('image2_look.float.xml')
|
||||
sMag.setAccessMode('read')
|
||||
sMag.createImage()
|
||||
|
||||
ampcor.setImageDataType1('real')
|
||||
ampcor.setImageDataType2('real')
|
||||
|
||||
ampcor.setMasterSlcImage(mMag)
|
||||
ampcor.setSlaveSlcImage(sMag)
|
||||
|
||||
#MATCH REGION
|
||||
rgoff = 0
|
||||
azoff = int((swath1.sensingStart - swath2.sensingStart).total_seconds() / swath1.azimuthLineInterval / azimuthScale1 / numberOfAzimuthLooks)
|
||||
#it seems that we cannot use 0, haven't look into the problem
|
||||
if rgoff == 0:
|
||||
rgoff = 1
|
||||
if azoff == 0:
|
||||
azoff = 1
|
||||
firstSample = 1
|
||||
if rgoff < 0:
|
||||
firstSample = int(35 - rgoff)
|
||||
firstLine = 1
|
||||
if azoff < 0:
|
||||
firstLine = int(35 - azoff)
|
||||
ampcor.setAcrossGrossOffset(rgoff)
|
||||
ampcor.setDownGrossOffset(azoff)
|
||||
ampcor.setFirstSampleAcross(firstSample)
|
||||
ampcor.setLastSampleAcross(numberOfSamplesLook1)
|
||||
ampcor.setNumberLocationAcross(20)
|
||||
ampcor.setFirstSampleDown(firstLine)
|
||||
ampcor.setLastSampleDown(numberOfLinesLook1)
|
||||
ampcor.setNumberLocationDown(100)
|
||||
|
||||
#MATCH PARAMETERS
|
||||
ampcor.setWindowSizeWidth(32)
|
||||
ampcor.setWindowSizeHeight(32)
|
||||
#note this is the half width/length of search area, so number of resulting correlation samples: 8*2+1
|
||||
ampcor.setSearchWindowSizeWidth(8)
|
||||
ampcor.setSearchWindowSizeHeight(8)
|
||||
|
||||
#REST OF THE STUFF
|
||||
ampcor.setAcrossLooks(1)
|
||||
ampcor.setDownLooks(1)
|
||||
ampcor.setOversamplingFactor(64)
|
||||
ampcor.setZoomWindowSize(16)
|
||||
#1. The following not set
|
||||
#Matching Scale for Sample/Line Directions (-) = 1. 1.
|
||||
#should add the following in Ampcor.py?
|
||||
#if not set, in this case, Ampcor.py'value is also 1. 1.
|
||||
#ampcor.setScaleFactorX(1.)
|
||||
#ampcor.setScaleFactorY(1.)
|
||||
|
||||
#MATCH THRESHOLDS AND DEBUG DATA
|
||||
#2. The following not set
|
||||
#in roi_pac the value is set to 0 1
|
||||
#in isce the value is set to 0.001 1000.0
|
||||
#SNR and Covariance Thresholds (-) = {s1} {s2}
|
||||
#should add the following in Ampcor?
|
||||
#THIS SHOULD BE THE ONLY THING THAT IS DIFFERENT FROM THAT OF ROI_PAC
|
||||
#ampcor.setThresholdSNR(0)
|
||||
#ampcor.setThresholdCov(1)
|
||||
ampcor.setDebugFlag(False)
|
||||
ampcor.setDisplayFlag(False)
|
||||
|
||||
#in summary, only two things not set which are indicated by 'The following not set' above.
|
||||
|
||||
#run ampcor
|
||||
ampcor.ampcor()
|
||||
offsets = ampcor.getOffsetField()
|
||||
refinedOffsets = cullOffsets(offsets)
|
||||
|
||||
#finalize image, and re-create it
|
||||
#otherwise the file pointer is still at the end of the image
|
||||
mMag.finalizeImage()
|
||||
sMag.finalizeImage()
|
||||
|
||||
os.remove('image1_look.float')
|
||||
os.remove('image1_look.float.vrt')
|
||||
os.remove('image1_look.float.xml')
|
||||
os.remove('image2_look.float')
|
||||
os.remove('image2_look.float.vrt')
|
||||
os.remove('image2_look.float.xml')
|
||||
|
||||
if refinedOffsets != None:
|
||||
rangeOffset, azimuthOffset = meanOffset(refinedOffsets)
|
||||
rangeOffset -= rangeOff1/rangeScale1
|
||||
azimuthOffset *= numberOfAzimuthLooks
|
||||
return (rangeOffset, azimuthOffset)
|
||||
else:
|
||||
return None
|
||||
|
||||
|
||||
|
||||
|
||||
|
|
@ -0,0 +1,91 @@
|
|||
#
|
||||
# Author: Cunren Liang
|
||||
# Copyright 2015-present, NASA-JPL/Caltech
|
||||
#
|
||||
|
||||
import os
|
||||
import shutil
|
||||
import logging
|
||||
import datetime
|
||||
import numpy as np
|
||||
|
||||
import isceobj
|
||||
from isceobj.Alos2Proc.Alos2ProcPublic import snaphuUnwrap
|
||||
from isceobj.Alos2Proc.Alos2ProcPublic import snaphuUnwrapOriginal
|
||||
from isceobj.Alos2Proc.Alos2ProcPublic import runCmd
|
||||
|
||||
logger = logging.getLogger('isce.alos2insar.runUnwrapSnaphu')
|
||||
|
||||
def runUnwrapSnaphu(self):
|
||||
'''unwrap filtered interferogram
|
||||
'''
|
||||
catalog = isceobj.Catalog.createCatalog(self._insar.procDoc.name)
|
||||
self.updateParamemetersFromUser()
|
||||
|
||||
masterTrack = self._insar.loadTrack(master=True)
|
||||
#slaveTrack = self._insar.loadTrack(master=False)
|
||||
|
||||
insarDir = 'insar'
|
||||
if not os.path.exists(insarDir):
|
||||
os.makedirs(insarDir)
|
||||
os.chdir(insarDir)
|
||||
|
||||
|
||||
############################################################
|
||||
# STEP 1. unwrap interferogram
|
||||
############################################################
|
||||
if shutil.which('snaphu') != None:
|
||||
print('\noriginal snaphu program found')
|
||||
print('unwrap {} using original snaphu, rather than that in ISCE'.format(self._insar.filteredInterferogram))
|
||||
snaphuUnwrapOriginal(self._insar.filteredInterferogram,
|
||||
self._insar.multilookPhsig,
|
||||
self._insar.multilookAmplitude,
|
||||
self._insar.unwrappedInterferogram,
|
||||
costMode = 's',
|
||||
initMethod = 'mcf')
|
||||
else:
|
||||
tmid = masterTrack.sensingStart + datetime.timedelta(seconds=(self._insar.numberAzimuthLooks1-1.0)/2.0*masterTrack.azimuthLineInterval+
|
||||
masterTrack.numberOfLines/2.0*self._insar.numberAzimuthLooks1*masterTrack.azimuthLineInterval)
|
||||
snaphuUnwrap(masterTrack, tmid,
|
||||
self._insar.filteredInterferogram,
|
||||
self._insar.multilookPhsig,
|
||||
self._insar.unwrappedInterferogram,
|
||||
self._insar.numberRangeLooks1*self._insar.numberRangeLooks2,
|
||||
self._insar.numberAzimuthLooks1*self._insar.numberAzimuthLooks2,
|
||||
costMode = 'SMOOTH',initMethod = 'MCF', defomax = 2, initOnly = True)
|
||||
|
||||
|
||||
############################################################
|
||||
# STEP 2. mask using connected components
|
||||
############################################################
|
||||
cmd = "imageMath.py -e='a_0*(b>0);a_1*(b>0)' --a={} --b={} -s BIL -t float -o={}".format(self._insar.unwrappedInterferogram, self._insar.unwrappedInterferogram+'.conncomp', self._insar.unwrappedMaskedInterferogram)
|
||||
runCmd(cmd)
|
||||
|
||||
|
||||
############################################################
|
||||
# STEP 3. mask using water body
|
||||
############################################################
|
||||
|
||||
if self.waterBodyMaskStartingStep=='unwrap':
|
||||
wbdImage = isceobj.createImage()
|
||||
wbdImage.load(self._insar.multilookWbdOut+'.xml')
|
||||
width = wbdImage.width
|
||||
length = wbdImage.length
|
||||
if not os.path.exists(self._insar.multilookWbdOut):
|
||||
catalog.addItem('warning message', 'requested masking interferogram with water body, but water body does not exist', 'runUnwrapSnaphu')
|
||||
else:
|
||||
wbd = np.fromfile(self._insar.multilookWbdOut, dtype=np.int8).reshape(length, width)
|
||||
unw=np.memmap(self._insar.unwrappedInterferogram, dtype='float32', mode='r+', shape=(length*2, width))
|
||||
(unw[0:length*2:2, :])[np.nonzero(wbd==-1)]=0
|
||||
(unw[1:length*2:2, :])[np.nonzero(wbd==-1)]=0
|
||||
del unw
|
||||
unw=np.memmap(self._insar.unwrappedMaskedInterferogram, dtype='float32', mode='r+', shape=(length*2, width))
|
||||
(unw[0:length*2:2, :])[np.nonzero(wbd==-1)]=0
|
||||
(unw[1:length*2:2, :])[np.nonzero(wbd==-1)]=0
|
||||
del unw, wbd
|
||||
|
||||
os.chdir('../')
|
||||
|
||||
catalog.printToLog(logger, "runUnwrapSnaphu")
|
||||
self._insar.procDoc.addAllFromCatalog(catalog)
|
||||
|
||||
File diff suppressed because it is too large
Load Diff
File diff suppressed because it is too large
Load Diff
File diff suppressed because it is too large
Load Diff
File diff suppressed because it is too large
Load Diff
|
|
@ -0,0 +1,19 @@
|
|||
InstallSameDir(
|
||||
__init__.py
|
||||
Factories.py
|
||||
Alos2burstProc.py
|
||||
runPreprocessor.py
|
||||
runExtractBurst.py
|
||||
runCoregGeom.py
|
||||
runCoregCc.py
|
||||
runCoregSd.py
|
||||
runSwathOffset.py
|
||||
runSwathMosaic.py
|
||||
runFrameOffset.py
|
||||
runFrameMosaic.py
|
||||
runIonSubband.py
|
||||
runLookSd.py
|
||||
runFiltSd.py
|
||||
runUnwrapSnaphuSd.py
|
||||
runGeocodeSd.py
|
||||
)
|
||||
|
|
@ -0,0 +1,114 @@
|
|||
#
|
||||
# Author: Piyush Agram
|
||||
# Copyright 2016
|
||||
#
|
||||
|
||||
# Path to the _RunWrapper factories
|
||||
_PATH = "isceobj.Alos2burstProc."
|
||||
|
||||
## A factory to make _RunWrapper factories
|
||||
def _factory(name, other_name=None, path=_PATH):
|
||||
"""create_run_wrapper = _factory(name)
|
||||
name is the module and class function name
|
||||
"""
|
||||
other_name = other_name or name
|
||||
module = __import__(
|
||||
path+name, fromlist=[""]
|
||||
)
|
||||
cls = getattr(module, other_name)
|
||||
def creater(other, *args, **kwargs):
|
||||
"""_RunWrapper for object calling %s"""
|
||||
return _RunWrapper(other, cls)
|
||||
return creater
|
||||
|
||||
## Put in "_" to prevernt import on "from Factorties import *"
|
||||
class _RunWrapper(object):
|
||||
"""_RunWrapper(other, func)(*args, **kwargs)
|
||||
|
||||
executes:
|
||||
|
||||
func(other, *args, **kwargs)
|
||||
|
||||
(like a method)
|
||||
"""
|
||||
def __init__(self, other, func):
|
||||
self.method = func
|
||||
self.other = other
|
||||
return None
|
||||
|
||||
def __call__(self, *args, **kwargs):
|
||||
return self.method(self.other, *args, **kwargs)
|
||||
|
||||
pass
|
||||
|
||||
def createUnwrapper(other, do_unwrap = None, unwrapperName = None,
|
||||
unwrap = None):
|
||||
if not do_unwrap and not unwrap:
|
||||
#if not defined create an empty method that does nothing
|
||||
def runUnwrap(self):
|
||||
return None
|
||||
elif unwrapperName.lower() == 'snaphu':
|
||||
from .runUnwrapSnaphu import runUnwrap
|
||||
elif unwrapperName.lower() == 'snaphu_mcf':
|
||||
from .runUnwrapSnaphu import runUnwrapMcf as runUnwrap
|
||||
elif unwrapperName.lower() == 'downsample_snaphu':
|
||||
from .run_downsample_unwrapper import runUnwrap
|
||||
elif unwrapperName.lower() == 'icu':
|
||||
from .runUnwrapIcu import runUnwrap
|
||||
elif unwrapperName.lower() == 'grass':
|
||||
from .runUnwrapGrass import runUnwrap
|
||||
return _RunWrapper(other, runUnwrap)
|
||||
|
||||
def createUnwrap2Stage(other, do_unwrap_2stage = None, unwrapperName = None):
|
||||
if (not do_unwrap_2stage) or (unwrapperName.lower() == 'icu') or (unwrapperName.lower() == 'grass'):
|
||||
#if not defined create an empty method that does nothing
|
||||
def runUnwrap2Stage(*arg, **kwargs):
|
||||
return None
|
||||
else:
|
||||
try:
|
||||
import pulp
|
||||
from .runUnwrap2Stage import runUnwrap2Stage
|
||||
except ImportError:
|
||||
raise Exception('Please install PuLP Linear Programming API to run 2stage unwrap')
|
||||
return _RunWrapper(other, runUnwrap2Stage)
|
||||
|
||||
|
||||
createPreprocessor = _factory("runPreprocessor")
|
||||
createExtractBurst = _factory("runExtractBurst")
|
||||
createDownloadDem = _factory("runDownloadDem", path = "isceobj.Alos2Proc.")
|
||||
createCoregGeom = _factory("runCoregGeom")
|
||||
createCoregCc = _factory("runCoregCc")
|
||||
createCoregSd = _factory("runCoregSd")
|
||||
createSwathOffset = _factory("runSwathOffset")
|
||||
createSwathMosaic = _factory("runSwathMosaic")
|
||||
createFrameOffset = _factory("runFrameOffset")
|
||||
createFrameMosaic = _factory("runFrameMosaic")
|
||||
createRdr2Geo = _factory("runRdr2Geo", path = "isceobj.Alos2Proc.")
|
||||
createGeo2Rdr = _factory("runGeo2Rdr", path = "isceobj.Alos2Proc.")
|
||||
createRdrDemOffset = _factory("runRdrDemOffset", path = "isceobj.Alos2Proc.")
|
||||
createRectRangeOffset = _factory("runRectRangeOffset", path = "isceobj.Alos2Proc.")
|
||||
createDiffInterferogram = _factory("runDiffInterferogram", path = "isceobj.Alos2Proc.")
|
||||
createLook = _factory("runLook", path = "isceobj.Alos2Proc.")
|
||||
createCoherence = _factory("runCoherence", path = "isceobj.Alos2Proc.")
|
||||
createIonSubband = _factory("runIonSubband")
|
||||
createIonUwrap = _factory("runIonUwrap", path = "isceobj.Alos2Proc.")
|
||||
createIonFilt = _factory("runIonFilt", path = "isceobj.Alos2Proc.")
|
||||
createFilt = _factory("runFilt", path = "isceobj.Alos2Proc.")
|
||||
createUnwrapSnaphu = _factory("runUnwrapSnaphu", path = "isceobj.Alos2Proc.")
|
||||
createGeocode = _factory("runGeocode", path = "isceobj.Alos2Proc.")
|
||||
|
||||
createLookSd = _factory("runLookSd")
|
||||
createFiltSd = _factory("runFiltSd")
|
||||
createUnwrapSnaphuSd = _factory("runUnwrapSnaphuSd")
|
||||
createGeocodeSd = _factory("runGeocodeSd")
|
||||
|
||||
|
||||
# steps imported from: Alos2Proc
|
||||
# ##############################################################
|
||||
# there is only problem with (at start of script):
|
||||
# logger = logging.getLogger('isce.alos2insar.runDownloadDem')
|
||||
# but it looks like OK.
|
||||
|
||||
|
||||
|
||||
|
||||
|
|
@ -0,0 +1,45 @@
|
|||
#! /usr/bin/env python
|
||||
|
||||
#~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
|
||||
# Copyright 2012 California Institute of Technology. ALL RIGHTS RESERVED.
|
||||
#
|
||||
# Licensed under the Apache License, Version 2.0 (the "License");
|
||||
# you may not use this file except in compliance with the License.
|
||||
# You may obtain a copy of the License at
|
||||
#
|
||||
# http://www.apache.org/licenses/LICENSE-2.0
|
||||
#
|
||||
# Unless required by applicable law or agreed to in writing, software
|
||||
# distributed under the License is distributed on an "AS IS" BASIS,
|
||||
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||
# See the License for the specific language governing permissions and
|
||||
# limitations under the License.
|
||||
#
|
||||
# United States Government Sponsorship acknowledged. This software is subject to
|
||||
# U.S. export control laws and regulations and has been classified as 'EAR99 NLR'
|
||||
# (No [Export] License Required except when exporting to an embargoed country,
|
||||
# end user, or in support of a prohibited end use). By downloading this software,
|
||||
# the user agrees to comply with all applicable U.S. export laws and regulations.
|
||||
# The user has the responsibility to obtain export licenses, or other export
|
||||
# authority as may be required before exporting this software to any 'EAR99'
|
||||
# embargoed foreign country or citizen of those countries.
|
||||
#
|
||||
# Author: Eric Gurrola
|
||||
#~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
#!/usr/bin/env python
|
||||
import os
|
||||
|
||||
Import('envisceobj')
|
||||
package = envisceobj['PACKAGE']
|
||||
project = 'Alos2burstProc'
|
||||
|
||||
install = os.path.join(envisceobj['PRJ_SCONS_INSTALL'],package,project)
|
||||
|
||||
listFiles = ['__init__.py', 'Factories.py', 'Alos2burstProc.py', 'runPreprocessor.py', 'runExtractBurst.py', 'runCoregGeom.py', 'runCoregCc.py', 'runCoregSd.py', 'runSwathOffset.py', 'runSwathMosaic.py', 'runFrameOffset.py', 'runFrameMosaic.py', 'runIonSubband.py', 'runLookSd.py', 'runFiltSd.py', 'runUnwrapSnaphuSd.py', 'runGeocodeSd.py']
|
||||
envisceobj.Install(install,listFiles)
|
||||
envisceobj.Alias('install',install)
|
||||
|
|
@ -0,0 +1,22 @@
|
|||
#
|
||||
# Author: Piyush Agram
|
||||
# Copyright 2016
|
||||
#
|
||||
|
||||
from .Alos2burstProc import *
|
||||
from .Factories import *
|
||||
|
||||
def getFactoriesInfo():
|
||||
return {'Alos2burstProc':
|
||||
{'args':
|
||||
{
|
||||
'procDoc':{'value':None,'type':'Catalog','optional':True}
|
||||
},
|
||||
'factory':'createAlos2burstProc'
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
def createAlos2burstProc(name=None, procDoc= None):
|
||||
from .Alos2burstProc import Alos2burstProc
|
||||
return Alos2burstProc(name = name,procDoc = procDoc)
|
||||
|
|
@ -0,0 +1,13 @@
|
|||
order of Doppler and azimuth FM rate polynomials
|
||||
##############################################################
|
||||
while Doppler and azimuth FM rate polynomials support 3rd order, try to use smaller order,
|
||||
because (range sample number)^3 can be very large. There may be float point error that is too
|
||||
large?
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
|
@ -0,0 +1,306 @@
|
|||
#
|
||||
# Author: Cunren Liang
|
||||
# Copyright 2015-present, NASA-JPL/Caltech
|
||||
#
|
||||
|
||||
import os
|
||||
import copy
|
||||
import shutil
|
||||
import logging
|
||||
import numpy as np
|
||||
|
||||
import isceobj
|
||||
from mroipac.ampcor.Ampcor import Ampcor
|
||||
from isceobj.Alos2Proc.Alos2ProcPublic import cullOffsetsRoipac
|
||||
from isceobj.Alos2Proc.Alos2ProcPublic import meanOffset
|
||||
from isceobj.Alos2Proc.Alos2ProcPublic import resampleBursts
|
||||
from isceobj.Alos2Proc.Alos2ProcPublic import mosaicBurstAmplitude
|
||||
from isceobj.Alos2Proc.Alos2ProcPublic import mosaicBurstInterferogram
|
||||
from isceobj.Alos2Proc.Alos2ProcPublic import create_xml
|
||||
|
||||
logger = logging.getLogger('isce.alos2burstinsar.runCoregCc')
|
||||
|
||||
def runCoregCc(self):
|
||||
'''coregister bursts by cross correlation
|
||||
'''
|
||||
catalog = isceobj.Catalog.createCatalog(self._insar.procDoc.name)
|
||||
self.updateParamemetersFromUser()
|
||||
|
||||
masterTrack = self._insar.loadTrack(master=True)
|
||||
slaveTrack = self._insar.loadTrack(master=False)
|
||||
|
||||
#demFile = os.path.abspath(self._insar.dem)
|
||||
#wbdFile = os.path.abspath(self._insar.wbd)
|
||||
###############################################################################
|
||||
self._insar.rangeResidualOffsetCc = [[] for i in range(len(masterTrack.frames))]
|
||||
self._insar.azimuthResidualOffsetCc = [[] for i in range(len(masterTrack.frames))]
|
||||
for i, frameNumber in enumerate(self._insar.masterFrames):
|
||||
frameDir = 'f{}_{}'.format(i+1, frameNumber)
|
||||
os.chdir(frameDir)
|
||||
for j, swathNumber in enumerate(range(self._insar.startingSwath, self._insar.endingSwath + 1)):
|
||||
swathDir = 's{}'.format(swathNumber)
|
||||
os.chdir(swathDir)
|
||||
|
||||
print('processing frame {}, swath {}'.format(frameNumber, swathNumber))
|
||||
|
||||
masterSwath = masterTrack.frames[i].swaths[j]
|
||||
slaveSwath = slaveTrack.frames[i].swaths[j]
|
||||
|
||||
##################################################
|
||||
# estimate cross-correlation offsets
|
||||
##################################################
|
||||
#compute number of offsets to use
|
||||
wbdImg = isceobj.createImage()
|
||||
wbdImg.load(self._insar.wbdOut+'.xml')
|
||||
width = wbdImg.width
|
||||
length = wbdImg.length
|
||||
|
||||
#initial number of offsets to use
|
||||
numberOfOffsets = 800
|
||||
|
||||
#compute land ratio to further determine the number of offsets to use
|
||||
if self.useWbdForNumberOffsets:
|
||||
wbd=np.memmap(self._insar.wbdOut, dtype='byte', mode='r', shape=(length, width))
|
||||
landRatio = np.sum(wbd==0) / length / width
|
||||
del wbd
|
||||
if (landRatio <= 0.00125):
|
||||
print('\n\nWARNING: land area too small for estimating offsets between master and slave magnitudes at frame {}, swath {}'.format(frameNumber, swathNumber))
|
||||
print('set offsets to zero\n\n')
|
||||
self._insar.rangeResidualOffsetCc[i].append(0.0)
|
||||
self._insar.azimuthResidualOffsetCc[i].append(0.0)
|
||||
catalog.addItem('warning message', 'land area too small for estimating offsets between master and slave magnitudes at frame {}, swath {}'.format(frameNumber, swathNumber), 'runCoregCc')
|
||||
continue
|
||||
#total number of offsets to use
|
||||
numberOfOffsets /= landRatio
|
||||
|
||||
#allocate number of offsets in range/azimuth according to image width/length
|
||||
#number of offsets to use in range/azimuth
|
||||
numberOfOffsetsRange = int(np.sqrt(numberOfOffsets * width / length))
|
||||
numberOfOffsetsAzimuth = int(length / width * np.sqrt(numberOfOffsets * width / length))
|
||||
|
||||
#this should be better?
|
||||
numberOfOffsetsRange = int(np.sqrt(numberOfOffsets))
|
||||
numberOfOffsetsAzimuth = int(np.sqrt(numberOfOffsets))
|
||||
|
||||
if numberOfOffsetsRange > int(width/2):
|
||||
numberOfOffsetsRange = int(width/2)
|
||||
if numberOfOffsetsAzimuth > int(length/2):
|
||||
numberOfOffsetsAzimuth = int(length/2)
|
||||
|
||||
if numberOfOffsetsRange < 10:
|
||||
numberOfOffsetsRange = 10
|
||||
if numberOfOffsetsAzimuth < 10:
|
||||
numberOfOffsetsAzimuth = 10
|
||||
|
||||
#user's settings
|
||||
if self.numberRangeOffsets != None:
|
||||
numberOfOffsetsRange = self.numberRangeOffsets[i][j]
|
||||
if self.numberAzimuthOffsets != None:
|
||||
numberOfOffsetsAzimuth = self.numberAzimuthOffsets[i][j]
|
||||
|
||||
catalog.addItem('number of range offsets at frame {}, swath {}'.format(frameNumber, swathNumber), '{}'.format(numberOfOffsetsRange), 'runCoregCc')
|
||||
catalog.addItem('number of azimuth offsets at frame {}, swath {}'.format(frameNumber, swathNumber), '{}'.format(numberOfOffsetsAzimuth), 'runCoregCc')
|
||||
|
||||
#need to cp to current directory to make it (gdal) work
|
||||
if not os.path.isfile(self._insar.masterMagnitude):
|
||||
os.symlink(os.path.join(self._insar.masterBurstPrefix, self._insar.masterMagnitude), self._insar.masterMagnitude)
|
||||
#shutil.copy2() can overwrite
|
||||
shutil.copy2(os.path.join(self._insar.masterBurstPrefix, self._insar.masterMagnitude+'.vrt'), self._insar.masterMagnitude+'.vrt')
|
||||
shutil.copy2(os.path.join(self._insar.masterBurstPrefix, self._insar.masterMagnitude+'.xml'), self._insar.masterMagnitude+'.xml')
|
||||
|
||||
if not os.path.isfile(self._insar.slaveMagnitude):
|
||||
os.symlink(os.path.join(self._insar.slaveBurstPrefix + '_1_coreg_geom', self._insar.slaveMagnitude), self._insar.slaveMagnitude)
|
||||
#shutil.copy2() can overwrite
|
||||
shutil.copy2(os.path.join(self._insar.slaveBurstPrefix + '_1_coreg_geom', self._insar.slaveMagnitude+'.vrt'), self._insar.slaveMagnitude+'.vrt')
|
||||
shutil.copy2(os.path.join(self._insar.slaveBurstPrefix + '_1_coreg_geom', self._insar.slaveMagnitude+'.xml'), self._insar.slaveMagnitude+'.xml')
|
||||
|
||||
#matching
|
||||
ampcor = Ampcor(name='insarapp_slcs_ampcor')
|
||||
ampcor.configure()
|
||||
|
||||
mMag = isceobj.createImage()
|
||||
mMag.load(self._insar.masterMagnitude+'.xml')
|
||||
mMag.setAccessMode('read')
|
||||
mMag.createImage()
|
||||
|
||||
sMag = isceobj.createImage()
|
||||
sMag.load(self._insar.slaveMagnitude+'.xml')
|
||||
sMag.setAccessMode('read')
|
||||
sMag.createImage()
|
||||
|
||||
ampcor.setImageDataType1('real')
|
||||
ampcor.setImageDataType2('real')
|
||||
|
||||
ampcor.setMasterSlcImage(mMag)
|
||||
ampcor.setSlaveSlcImage(sMag)
|
||||
|
||||
#MATCH REGION
|
||||
rgoff = 0
|
||||
azoff = 0
|
||||
#it seems that we cannot use 0, haven't look into the problem
|
||||
if rgoff == 0:
|
||||
rgoff = 1
|
||||
if azoff == 0:
|
||||
azoff = 1
|
||||
firstSample = 1
|
||||
if rgoff < 0:
|
||||
firstSample = int(35 - rgoff)
|
||||
firstLine = 1
|
||||
if azoff < 0:
|
||||
firstLine = int(35 - azoff)
|
||||
ampcor.setAcrossGrossOffset(rgoff)
|
||||
ampcor.setDownGrossOffset(azoff)
|
||||
ampcor.setFirstSampleAcross(firstSample)
|
||||
ampcor.setLastSampleAcross(mMag.width)
|
||||
ampcor.setNumberLocationAcross(numberOfOffsetsRange)
|
||||
ampcor.setFirstSampleDown(firstLine)
|
||||
ampcor.setLastSampleDown(mMag.length)
|
||||
ampcor.setNumberLocationDown(numberOfOffsetsAzimuth)
|
||||
|
||||
#MATCH PARAMETERS
|
||||
ampcor.setWindowSizeWidth(64)
|
||||
ampcor.setWindowSizeHeight(64)
|
||||
#note this is the half width/length of search area, so number of resulting correlation samples: 8*2+1
|
||||
ampcor.setSearchWindowSizeWidth(8)
|
||||
ampcor.setSearchWindowSizeHeight(8)
|
||||
|
||||
#REST OF THE STUFF
|
||||
ampcor.setAcrossLooks(1)
|
||||
ampcor.setDownLooks(1)
|
||||
ampcor.setOversamplingFactor(64)
|
||||
ampcor.setZoomWindowSize(16)
|
||||
#1. The following not set
|
||||
#Matching Scale for Sample/Line Directions (-) = 1. 1.
|
||||
#should add the following in Ampcor.py?
|
||||
#if not set, in this case, Ampcor.py'value is also 1. 1.
|
||||
#ampcor.setScaleFactorX(1.)
|
||||
#ampcor.setScaleFactorY(1.)
|
||||
|
||||
#MATCH THRESHOLDS AND DEBUG DATA
|
||||
#2. The following not set
|
||||
#in roi_pac the value is set to 0 1
|
||||
#in isce the value is set to 0.001 1000.0
|
||||
#SNR and Covariance Thresholds (-) = {s1} {s2}
|
||||
#should add the following in Ampcor?
|
||||
#THIS SHOULD BE THE ONLY THING THAT IS DIFFERENT FROM THAT OF ROI_PAC
|
||||
#ampcor.setThresholdSNR(0)
|
||||
#ampcor.setThresholdCov(1)
|
||||
ampcor.setDebugFlag(False)
|
||||
ampcor.setDisplayFlag(False)
|
||||
|
||||
#in summary, only two things not set which are indicated by 'The following not set' above.
|
||||
|
||||
#run ampcor
|
||||
ampcor.ampcor()
|
||||
offsets = ampcor.getOffsetField()
|
||||
refinedOffsets = cullOffsetsRoipac(offsets, numThreshold=50)
|
||||
|
||||
#finalize image, and re-create it
|
||||
#otherwise the file pointer is still at the end of the image
|
||||
mMag.finalizeImage()
|
||||
sMag.finalizeImage()
|
||||
|
||||
#clear up
|
||||
os.remove(self._insar.masterMagnitude)
|
||||
os.remove(self._insar.masterMagnitude+'.vrt')
|
||||
os.remove(self._insar.masterMagnitude+'.xml')
|
||||
os.remove(self._insar.slaveMagnitude)
|
||||
os.remove(self._insar.slaveMagnitude+'.vrt')
|
||||
os.remove(self._insar.slaveMagnitude+'.xml')
|
||||
|
||||
#compute average offsets to use in resampling
|
||||
if refinedOffsets == None:
|
||||
rangeOffset = 0
|
||||
azimuthOffset = 0
|
||||
self._insar.rangeResidualOffsetCc[i].append(rangeOffset)
|
||||
self._insar.azimuthResidualOffsetCc[i].append(azimuthOffset)
|
||||
print('\n\nWARNING: too few offsets left in matching master and slave magnitudes at frame {}, swath {}'.format(frameNumber, swathNumber))
|
||||
print('set offsets to zero\n\n')
|
||||
catalog.addItem('warning message', 'too few offsets left in matching master and slave magnitudes at frame {}, swath {}'.format(frameNumber, swathNumber), 'runCoregCc')
|
||||
else:
|
||||
rangeOffset, azimuthOffset = meanOffset(refinedOffsets)
|
||||
#for range offset, need to compute from a polynomial
|
||||
#see components/isceobj/Location/Offset.py and components/isceobj/Util/Library/python/Poly2D.py for definations
|
||||
(azimuthPoly, rangePoly) = refinedOffsets.getFitPolynomials(rangeOrder=2,azimuthOrder=2)
|
||||
#make a deep copy, otherwise it also changes original coefficient list of rangePoly, which affects following rangePoly(*, *) computation
|
||||
polyCoeff = copy.deepcopy(rangePoly.getCoeffs())
|
||||
rgIndex = (np.arange(width)-rangePoly.getMeanRange())/rangePoly.getNormRange()
|
||||
azIndex = (np.arange(length)-rangePoly.getMeanAzimuth())/rangePoly.getNormAzimuth()
|
||||
rangeOffset = polyCoeff[0][0] + polyCoeff[0][1]*rgIndex[None,:] + polyCoeff[0][2]*rgIndex[None,:]**2 + \
|
||||
(polyCoeff[1][0] + polyCoeff[1][1]*rgIndex[None,:]) * azIndex[:, None] + \
|
||||
polyCoeff[2][0] * azIndex[:, None]**2
|
||||
polyCoeff.append([rangePoly.getMeanRange(), rangePoly.getNormRange(), rangePoly.getMeanAzimuth(), rangePoly.getNormAzimuth()])
|
||||
self._insar.rangeResidualOffsetCc[i].append(polyCoeff)
|
||||
self._insar.azimuthResidualOffsetCc[i].append(azimuthOffset)
|
||||
|
||||
catalog.addItem('range residual offset at {} {} at frame {}, swath {}'.format(0, 0, frameNumber, swathNumber),
|
||||
'{}'.format(rangePoly(0, 0)), 'runCoregCc')
|
||||
catalog.addItem('range residual offset at {} {} at frame {}, swath {}'.format(0, width-1, frameNumber, swathNumber),
|
||||
'{}'.format(rangePoly(0, width-1)), 'runCoregCc')
|
||||
catalog.addItem('range residual offset at {} {} at frame {}, swath {}'.format(length-1, 0, frameNumber, swathNumber),
|
||||
'{}'.format(rangePoly(length-1, 0)), 'runCoregCc')
|
||||
catalog.addItem('range residual offset at {} {} at frame {}, swath {}'.format(length-1,width-1, frameNumber, swathNumber),
|
||||
'{}'.format(rangePoly(length-1,width-1)), 'runCoregCc')
|
||||
catalog.addItem('azimuth residual offset at frame {}, swath {}'.format(frameNumber, swathNumber),
|
||||
'{}'.format(azimuthOffset), 'runCoregCc')
|
||||
|
||||
DEBUG=False
|
||||
if DEBUG:
|
||||
print('+++++++++++++++++++++++++++++')
|
||||
print(rangeOffset[0,0], rangePoly(0, 0))
|
||||
print(rangeOffset[0,width-1], rangePoly(0, width-1))
|
||||
print(rangeOffset[length-1,0], rangePoly(length-1, 0))
|
||||
print(rangeOffset[length-1,width-1], rangePoly(length-1,width-1))
|
||||
print(rangeOffset[int((length-1)/2),int((width-1)/2)], rangePoly(int((length-1)/2),int((width-1)/2)))
|
||||
print('+++++++++++++++++++++++++++++')
|
||||
|
||||
|
||||
##################################################
|
||||
# resample bursts
|
||||
##################################################
|
||||
slaveBurstResampledDir = self._insar.slaveBurstPrefix + '_2_coreg_cc'
|
||||
#interferogramDir = self._insar.masterBurstPrefix + '-' + self._insar.slaveBurstPrefix + '_coreg_geom'
|
||||
interferogramDir = 'burst_interf_2_coreg_cc'
|
||||
interferogramPrefix = self._insar.masterBurstPrefix + '-' + self._insar.slaveBurstPrefix
|
||||
resampleBursts(masterSwath, slaveSwath,
|
||||
self._insar.masterBurstPrefix, self._insar.slaveBurstPrefix, slaveBurstResampledDir, interferogramDir,
|
||||
self._insar.masterBurstPrefix, self._insar.slaveBurstPrefix, self._insar.slaveBurstPrefix, interferogramPrefix,
|
||||
self._insar.rangeOffset, self._insar.azimuthOffset, rangeOffsetResidual=rangeOffset, azimuthOffsetResidual=azimuthOffset)
|
||||
|
||||
|
||||
##################################################
|
||||
# mosaic burst amplitudes and interferograms
|
||||
##################################################
|
||||
os.chdir(slaveBurstResampledDir)
|
||||
mosaicBurstAmplitude(masterSwath, self._insar.slaveBurstPrefix, self._insar.slaveMagnitude, numberOfLooksThreshold=4)
|
||||
os.chdir('../')
|
||||
|
||||
os.chdir(interferogramDir)
|
||||
mosaicBurstInterferogram(masterSwath, interferogramPrefix, self._insar.interferogram, numberOfLooksThreshold=4)
|
||||
os.chdir('../')
|
||||
|
||||
|
||||
##################################################
|
||||
# final amplitude and interferogram
|
||||
##################################################
|
||||
amp = np.zeros((masterSwath.numberOfLines, 2*masterSwath.numberOfSamples), dtype=np.float32)
|
||||
amp[0:, 1:masterSwath.numberOfSamples*2:2] = np.fromfile(os.path.join(slaveBurstResampledDir, self._insar.slaveMagnitude), \
|
||||
dtype=np.float32).reshape(masterSwath.numberOfLines, masterSwath.numberOfSamples)
|
||||
amp[0:, 0:masterSwath.numberOfSamples*2:2] = np.fromfile(os.path.join(self._insar.masterBurstPrefix, self._insar.masterMagnitude), \
|
||||
dtype=np.float32).reshape(masterSwath.numberOfLines, masterSwath.numberOfSamples)
|
||||
amp.astype(np.float32).tofile(self._insar.amplitude)
|
||||
create_xml(self._insar.amplitude, masterSwath.numberOfSamples, masterSwath.numberOfLines, 'amp')
|
||||
|
||||
os.rename(os.path.join(interferogramDir, self._insar.interferogram), self._insar.interferogram)
|
||||
os.rename(os.path.join(interferogramDir, self._insar.interferogram+'.vrt'), self._insar.interferogram+'.vrt')
|
||||
os.rename(os.path.join(interferogramDir, self._insar.interferogram+'.xml'), self._insar.interferogram+'.xml')
|
||||
|
||||
os.chdir('../')
|
||||
os.chdir('../')
|
||||
|
||||
###############################################################################
|
||||
catalog.printToLog(logger, "runCoregCc")
|
||||
self._insar.procDoc.addAllFromCatalog(catalog)
|
||||
|
||||
|
||||
|
||||
|
|
@ -0,0 +1,142 @@
|
|||
#
|
||||
# Author: Cunren Liang
|
||||
# Copyright 2015-present, NASA-JPL/Caltech
|
||||
#
|
||||
|
||||
import os
|
||||
import logging
|
||||
|
||||
import isceobj
|
||||
from isceobj.Alos2Proc.runRdr2Geo import topoCPU
|
||||
from isceobj.Alos2Proc.runRdr2Geo import topoGPU
|
||||
from isceobj.Alos2Proc.runGeo2Rdr import geo2RdrCPU
|
||||
from isceobj.Alos2Proc.runGeo2Rdr import geo2RdrGPU
|
||||
from isceobj.Alos2Proc.Alos2ProcPublic import waterBodyRadar
|
||||
from isceobj.Alos2Proc.Alos2ProcPublic import resampleBursts
|
||||
from isceobj.Alos2Proc.Alos2ProcPublic import mosaicBurstAmplitude
|
||||
from isceobj.Alos2Proc.Alos2ProcPublic import mosaicBurstInterferogram
|
||||
|
||||
logger = logging.getLogger('isce.alos2burstinsar.runCoregGeom')
|
||||
|
||||
def runCoregGeom(self):
|
||||
'''compute geometric offset
|
||||
'''
|
||||
catalog = isceobj.Catalog.createCatalog(self._insar.procDoc.name)
|
||||
self.updateParamemetersFromUser()
|
||||
|
||||
masterTrack = self._insar.loadTrack(master=True)
|
||||
slaveTrack = self._insar.loadTrack(master=False)
|
||||
|
||||
demFile = os.path.abspath(self._insar.dem)
|
||||
wbdFile = os.path.abspath(self._insar.wbd)
|
||||
###############################################################################
|
||||
|
||||
for i, frameNumber in enumerate(self._insar.masterFrames):
|
||||
frameDir = 'f{}_{}'.format(i+1, frameNumber)
|
||||
os.chdir(frameDir)
|
||||
for j, swathNumber in enumerate(range(self._insar.startingSwath, self._insar.endingSwath + 1)):
|
||||
swathDir = 's{}'.format(swathNumber)
|
||||
os.chdir(swathDir)
|
||||
|
||||
print('processing frame {}, swath {}'.format(frameNumber, swathNumber))
|
||||
|
||||
masterSwath = masterTrack.frames[i].swaths[j]
|
||||
slaveSwath = slaveTrack.frames[i].swaths[j]
|
||||
|
||||
|
||||
##################################################
|
||||
# compute geometric offsets
|
||||
##################################################
|
||||
#set up track parameters just for computing offsets
|
||||
#ALL track parameters are listed here
|
||||
#master
|
||||
#masterTrack.passDirection =
|
||||
#masterTrack.pointingDirection =
|
||||
#masterTrack.operationMode =
|
||||
#masterTrack.radarWavelength =
|
||||
masterTrack.numberOfSamples = masterSwath.numberOfSamples
|
||||
masterTrack.numberOfLines = masterSwath.numberOfLines
|
||||
masterTrack.startingRange = masterSwath.startingRange
|
||||
#masterTrack.rangeSamplingRate =
|
||||
masterTrack.rangePixelSize = masterSwath.rangePixelSize
|
||||
masterTrack.sensingStart = masterSwath.sensingStart
|
||||
#masterTrack.prf =
|
||||
#masterTrack.azimuthPixelSize =
|
||||
masterTrack.azimuthLineInterval = masterSwath.azimuthLineInterval
|
||||
#masterTrack.dopplerVsPixel =
|
||||
#masterTrack.frames =
|
||||
#masterTrack.orbit =
|
||||
|
||||
#slave
|
||||
slaveTrack.numberOfSamples = slaveSwath.numberOfSamples
|
||||
slaveTrack.numberOfLines = slaveSwath.numberOfLines
|
||||
slaveTrack.startingRange = slaveSwath.startingRange
|
||||
slaveTrack.rangePixelSize = slaveSwath.rangePixelSize
|
||||
slaveTrack.sensingStart = slaveSwath.sensingStart
|
||||
slaveTrack.azimuthLineInterval = slaveSwath.azimuthLineInterval
|
||||
|
||||
if self.useGPU and self._insar.hasGPU():
|
||||
topoGPU(masterTrack, 1, 1, demFile,
|
||||
self._insar.latitude, self._insar.longitude, self._insar.height, self._insar.los)
|
||||
geo2RdrGPU(slaveTrack, 1, 1,
|
||||
self._insar.latitude, self._insar.longitude, self._insar.height, self._insar.rangeOffset, self._insar.azimuthOffset)
|
||||
else:
|
||||
topoCPU(masterTrack, 1, 1, demFile,
|
||||
self._insar.latitude, self._insar.longitude, self._insar.height, self._insar.los)
|
||||
geo2RdrCPU(slaveTrack, 1, 1,
|
||||
self._insar.latitude, self._insar.longitude, self._insar.height, self._insar.rangeOffset, self._insar.azimuthOffset)
|
||||
|
||||
waterBodyRadar(self._insar.latitude, self._insar.longitude, wbdFile, self._insar.wbdOut)
|
||||
|
||||
#clear up, leaving only range/azimuth offsets
|
||||
os.remove(self._insar.latitude)
|
||||
os.remove(self._insar.latitude+'.vrt')
|
||||
os.remove(self._insar.latitude+'.xml')
|
||||
os.remove(self._insar.longitude)
|
||||
os.remove(self._insar.longitude+'.vrt')
|
||||
os.remove(self._insar.longitude+'.xml')
|
||||
os.remove(self._insar.height)
|
||||
os.remove(self._insar.height+'.vrt')
|
||||
os.remove(self._insar.height+'.xml')
|
||||
os.remove(self._insar.los)
|
||||
os.remove(self._insar.los+'.vrt')
|
||||
os.remove(self._insar.los+'.xml')
|
||||
|
||||
|
||||
##################################################
|
||||
# resample bursts
|
||||
##################################################
|
||||
slaveBurstResampledDir = self._insar.slaveBurstPrefix + '_1_coreg_geom'
|
||||
#interferogramDir = self._insar.masterBurstPrefix + '-' + self._insar.slaveBurstPrefix + '_coreg_geom'
|
||||
interferogramDir = 'burst_interf_1_coreg_geom'
|
||||
interferogramPrefix = self._insar.masterBurstPrefix + '-' + self._insar.slaveBurstPrefix
|
||||
resampleBursts(masterSwath, slaveSwath,
|
||||
self._insar.masterBurstPrefix, self._insar.slaveBurstPrefix, slaveBurstResampledDir, interferogramDir,
|
||||
self._insar.masterBurstPrefix, self._insar.slaveBurstPrefix, self._insar.slaveBurstPrefix, interferogramPrefix,
|
||||
self._insar.rangeOffset, self._insar.azimuthOffset, rangeOffsetResidual=0, azimuthOffsetResidual=0)
|
||||
|
||||
|
||||
##################################################
|
||||
# mosaic burst amplitudes and interferograms
|
||||
##################################################
|
||||
os.chdir(slaveBurstResampledDir)
|
||||
mosaicBurstAmplitude(masterSwath, self._insar.slaveBurstPrefix, self._insar.slaveMagnitude, numberOfLooksThreshold=4)
|
||||
os.chdir('../')
|
||||
|
||||
#the interferogram is not good enough, do not mosaic
|
||||
mosaic=False
|
||||
if mosaic:
|
||||
os.chdir(interferogramDir)
|
||||
mosaicBurstInterferogram(masterSwath, interferogramPrefix, self._insar.interferogram, numberOfLooksThreshold=4)
|
||||
os.chdir('../')
|
||||
|
||||
|
||||
os.chdir('../')
|
||||
os.chdir('../')
|
||||
|
||||
###############################################################################
|
||||
catalog.printToLog(logger, "runCoregGeom")
|
||||
self._insar.procDoc.addAllFromCatalog(catalog)
|
||||
|
||||
|
||||
|
||||
|
|
@ -0,0 +1,236 @@
|
|||
#
|
||||
# Author: Cunren Liang
|
||||
# Copyright 2015-present, NASA-JPL/Caltech
|
||||
#
|
||||
|
||||
import os
|
||||
import logging
|
||||
import numpy as np
|
||||
|
||||
import isceobj
|
||||
from isceobj.Alos2Proc.Alos2ProcPublic import resampleBursts
|
||||
from isceobj.Alos2Proc.Alos2ProcPublic import mosaicBurstAmplitude
|
||||
from isceobj.Alos2Proc.Alos2ProcPublic import mosaicBurstInterferogram
|
||||
|
||||
logger = logging.getLogger('isce.alos2burstinsar.runCoregSd')
|
||||
|
||||
def runCoregSd(self):
|
||||
'''coregister bursts by spectral diversity
|
||||
'''
|
||||
catalog = isceobj.Catalog.createCatalog(self._insar.procDoc.name)
|
||||
self.updateParamemetersFromUser()
|
||||
|
||||
masterTrack = self._insar.loadTrack(master=True)
|
||||
slaveTrack = self._insar.loadTrack(master=False)
|
||||
|
||||
#demFile = os.path.abspath(self._insar.dem)
|
||||
#wbdFile = os.path.abspath(self._insar.wbd)
|
||||
###############################################################################
|
||||
#self._insar.rangeResidualOffsetSd = [[] for i in range(len(masterTrack.frames))]
|
||||
self._insar.azimuthResidualOffsetSd = [[] for i in range(len(masterTrack.frames))]
|
||||
for i, frameNumber in enumerate(self._insar.masterFrames):
|
||||
frameDir = 'f{}_{}'.format(i+1, frameNumber)
|
||||
os.chdir(frameDir)
|
||||
for j, swathNumber in enumerate(range(self._insar.startingSwath, self._insar.endingSwath + 1)):
|
||||
swathDir = 's{}'.format(swathNumber)
|
||||
os.chdir(swathDir)
|
||||
|
||||
print('processing frame {}, swath {}'.format(frameNumber, swathNumber))
|
||||
|
||||
masterSwath = masterTrack.frames[i].swaths[j]
|
||||
slaveSwath = slaveTrack.frames[i].swaths[j]
|
||||
|
||||
##################################################
|
||||
# spectral diversity or mai
|
||||
##################################################
|
||||
sdDir = 'spectral_diversity'
|
||||
if not os.path.exists(sdDir):
|
||||
os.makedirs(sdDir)
|
||||
os.chdir(sdDir)
|
||||
|
||||
interferogramDir = 'burst_interf_2_coreg_cc'
|
||||
interferogramPrefix = self._insar.masterBurstPrefix + '-' + self._insar.slaveBurstPrefix
|
||||
offsetSd = spectralDiversity(masterSwath, os.path.join('../', interferogramDir), interferogramPrefix, self._insar.interferogramSd,
|
||||
numberLooksScanSAR=4, numberRangeLooks=28, numberAzimuthLooks=8, coherenceThreshold=0.85,
|
||||
keep=True, filt=True, filtWinSizeRange=5, filtWinSizeAzimuth=5)
|
||||
#here use the number of looks for sd as filtWinSizeRange and filtWinSizeAzimuth to get the best filtering result?
|
||||
|
||||
os.chdir('../')
|
||||
|
||||
self._insar.azimuthResidualOffsetSd[i].append(offsetSd)
|
||||
catalog.addItem('azimuth residual offset at frame {}, swath {}'.format(frameNumber, swathNumber), '{}'.format(offsetSd), 'runCoregSd')
|
||||
|
||||
|
||||
#this small residual azimuth offset has small impact, it's not worth the time to resample slave bursts again.
|
||||
formInterferogram=False
|
||||
if formInterferogram:
|
||||
##################################################
|
||||
# resample bursts
|
||||
##################################################
|
||||
slaveBurstResampledDir = self._insar.slaveBurstPrefix + '_3_coreg_sd'
|
||||
#interferogramDir = self._insar.masterBurstPrefix + '-' + self._insar.slaveBurstPrefix + '_coreg_geom'
|
||||
interferogramDir = 'burst_interf_3_coreg_sd'
|
||||
interferogramPrefix = self._insar.masterBurstPrefix + '-' + self._insar.slaveBurstPrefix
|
||||
resampleBursts(masterSwath, slaveSwath,
|
||||
self._insar.masterBurstPrefix, self._insar.slaveBurstPrefix, slaveBurstResampledDir, interferogramDir,
|
||||
self._insar.masterBurstPrefix, self._insar.slaveBurstPrefix, self._insar.slaveBurstPrefix, interferogramPrefix,
|
||||
self._insar.rangeOffset, self._insar.azimuthOffset, rangeOffsetResidual=self._insar.rangeResidualOffsetCc[i][j], azimuthOffsetResidual=self._insar.azimuthResidualOffsetCc[i][j]+offsetSd)
|
||||
|
||||
|
||||
##################################################
|
||||
# mosaic burst amplitudes and interferograms
|
||||
##################################################
|
||||
os.chdir(slaveBurstResampledDir)
|
||||
mosaicBurstAmplitude(masterSwath, self._insar.slaveBurstPrefix, self._insar.slaveMagnitude, numberOfLooksThreshold=4)
|
||||
os.chdir('../')
|
||||
|
||||
os.chdir(interferogramDir)
|
||||
mosaicBurstInterferogram(masterSwath, interferogramPrefix, self._insar.interferogram, numberOfLooksThreshold=4)
|
||||
os.chdir('../')
|
||||
|
||||
|
||||
os.chdir('../')
|
||||
os.chdir('../')
|
||||
|
||||
###############################################################################
|
||||
catalog.printToLog(logger, "runCoregSd")
|
||||
self._insar.procDoc.addAllFromCatalog(catalog)
|
||||
|
||||
|
||||
def spectralDiversity(masterSwath, interferogramDir, interferogramPrefix, outputList, numberLooksScanSAR=None, numberRangeLooks=20, numberAzimuthLooks=10, coherenceThreshold=0.85, keep=False, filt=False, filtWinSizeRange=5, filtWinSizeAzimuth=5):
|
||||
'''
|
||||
numberLooksScanSAR: number of looks of the ScanSAR system
|
||||
numberRangeLooks: number of range looks to take
|
||||
numberAzimuthLooks: number of azimuth looks to take
|
||||
keep: whether keep intermediate files
|
||||
'''
|
||||
import os
|
||||
import numpy as np
|
||||
from isceobj.Alos2Proc.Alos2ProcPublic import create_multi_index
|
||||
from isceobj.Alos2Proc.Alos2ProcPublic import create_xml
|
||||
from isceobj.Alos2Proc.Alos2ProcPublic import multilook
|
||||
from isceobj.Alos2Proc.Alos2ProcPublic import cal_coherence_1
|
||||
|
||||
width = masterSwath.numberOfSamples
|
||||
length = masterSwath.numberOfLines
|
||||
lengthBurst = masterSwath.burstSlcNumberOfLines
|
||||
nBurst = masterSwath.numberOfBursts
|
||||
azsi = masterSwath.azimuthLineInterval
|
||||
tc = masterSwath.burstCycleLength / masterSwath.prf
|
||||
|
||||
bursts = [os.path.join(interferogramDir, interferogramPrefix+'_%02d.int'%(i+1)) for i in range(masterSwath.numberOfBursts)]
|
||||
|
||||
####################################################
|
||||
#input parameters
|
||||
rgl = numberRangeLooks
|
||||
azl = numberAzimuthLooks
|
||||
cor_th = coherenceThreshold
|
||||
nls0 = lengthBurst / (masterSwath.burstSlcFirstLineOffsets[nBurst-1] / (nBurst-1.0))
|
||||
print('number of looks of the ScanSAR system: {}'.format(nls0))
|
||||
if numberLooksScanSAR != None:
|
||||
nls = numberLooksScanSAR
|
||||
else:
|
||||
nls = int(nls0)
|
||||
print('number of looks to be used: {}'.format(nls))
|
||||
####################################################
|
||||
|
||||
#read burst interferograms
|
||||
inf = np.zeros((length, width, nls), dtype=np.complex64)
|
||||
cnt = np.zeros((length, width), dtype=np.int8)
|
||||
for i in range(nBurst):
|
||||
if (i+1)%5 == 0 or (i+1) == nBurst:
|
||||
print('reading burst %02d' % (i+1))
|
||||
|
||||
burst = np.fromfile(bursts[i], dtype=np.complex64).reshape(lengthBurst, width)
|
||||
|
||||
#subset for the burst
|
||||
cntBurst = cnt[0+masterSwath.burstSlcFirstLineOffsets[i]:lengthBurst+masterSwath.burstSlcFirstLineOffsets[i], :]
|
||||
infBurst = inf[0+masterSwath.burstSlcFirstLineOffsets[i]:lengthBurst+masterSwath.burstSlcFirstLineOffsets[i], :, :]
|
||||
|
||||
#set number of non-zero pixels
|
||||
cntBurst[np.nonzero(burst)] += 1
|
||||
|
||||
#get index
|
||||
index1 = np.nonzero(np.logical_and(burst!=0, cntBurst<=nls))
|
||||
index2 = index1 + (cntBurst[index1]-1,)
|
||||
|
||||
#set values
|
||||
infBurst[index2] = burst[index1]
|
||||
|
||||
#number of looks for each sample
|
||||
if keep:
|
||||
nlFile = 'number_of_looks.nl'
|
||||
cnt.astype(np.int8).tofile(nlFile)
|
||||
create_xml(nlFile, width, length, 'byte')
|
||||
|
||||
if filt:
|
||||
import scipy.signal as ss
|
||||
filterKernel = np.ones((filtWinSizeAzimuth,filtWinSizeRange), dtype=np.float64)
|
||||
for i in range(nls):
|
||||
print('filtering look {}'.format(i+1))
|
||||
flag = (inf[:,:,i]!=0)
|
||||
#scale = ss.fftconvolve(flag, filterKernel, mode='same')
|
||||
#inf[:,:,i] = flag*ss.fftconvolve(inf[:,:,i], filterKernel, mode='same') / (scale + (scale==0))
|
||||
#this should be faster?
|
||||
scale = ss.convolve2d(flag, filterKernel, mode='same')
|
||||
inf[:,:,i] = flag*ss.convolve2d(inf[:,:,i], filterKernel, mode='same') / (scale + (scale==0))
|
||||
|
||||
#width and length after multilooking
|
||||
widthm = int(width/rgl)
|
||||
lengthm = int(length/azl)
|
||||
#use the convention that ka > 0
|
||||
ka = -np.polyval(masterSwath.azimuthFmrateVsPixel[::-1], create_multi_index(width, rgl))
|
||||
|
||||
#get spectral diversity inteferogram
|
||||
offset_sd=[]
|
||||
for i in range(1, nls):
|
||||
print('ouput spectral diversity inteferogram %d' % i)
|
||||
#original spectral diversity inteferogram
|
||||
sd = inf[:,:,0] * np.conj(inf[:,:,i])
|
||||
|
||||
#replace original amplitude with its square root
|
||||
index = np.nonzero(sd!=0)
|
||||
sd[index] /= np.sqrt(np.absolute(sd[index]))
|
||||
|
||||
sdFile = outputList[i-1]
|
||||
sd.astype(np.complex64).tofile(sdFile)
|
||||
create_xml(sdFile, width, length, 'int')
|
||||
|
||||
#multi look
|
||||
sdm = multilook(sd, azl, rgl)
|
||||
cor = cal_coherence_1(sdm)
|
||||
|
||||
#convert phase to offset
|
||||
offset = np.angle(sdm)/(2.0 * np.pi * ka * tc * i)[None,:] / azsi
|
||||
|
||||
#compute offset using good samples
|
||||
point_index = np.nonzero(np.logical_and(cor>=cor_th, np.angle(sdm)!=0))
|
||||
npoint = round(np.size(point_index)/2)
|
||||
if npoint < 20:
|
||||
print('WARNING: too few good samples for spectral diversity at look {}: {}'.format(i, npoint))
|
||||
offset_sd.append(0)
|
||||
else:
|
||||
offset_sd.append( np.sum(offset[point_index]*cor[point_index])/np.sum(cor[point_index]) )
|
||||
|
||||
if keep:
|
||||
sdmFile = 'sd_%d_%drlks_%dalks.int' % (i, rgl, azl)
|
||||
sdm.astype(np.complex64).tofile(sdmFile)
|
||||
create_xml(sdmFile, widthm, lengthm, 'int')
|
||||
corFile = 'sd_%d_%drlks_%dalks.cor' % (i, rgl, azl)
|
||||
cor.astype(np.float32).tofile(corFile)
|
||||
create_xml(corFile, widthm, lengthm, 'float')
|
||||
offsetFile = 'sd_%d_%drlks_%dalks.off' % (i, rgl, azl)
|
||||
offset.astype(np.float32).tofile(offsetFile)
|
||||
create_xml(offsetFile, widthm, lengthm, 'float')
|
||||
|
||||
offset_mean = np.sum(np.array(offset_sd) * np.arange(1, nls)) / np.sum(np.arange(1, nls))
|
||||
|
||||
return offset_mean
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
|
@ -0,0 +1,136 @@
|
|||
#
|
||||
# Author: Cunren Liang
|
||||
# Copyright 2015-present, NASA-JPL/Caltech
|
||||
#
|
||||
|
||||
import os
|
||||
import glob
|
||||
import logging
|
||||
import datetime
|
||||
#import subprocess
|
||||
import numpy as np
|
||||
|
||||
import isceobj
|
||||
from isceobj.Alos2Proc.Alos2ProcPublic import create_xml
|
||||
from isceobj.Alos2Proc.Alos2ProcPublic import mosaicBurstAmplitude
|
||||
from contrib.alos2proc.alos2proc import extract_burst
|
||||
|
||||
logger = logging.getLogger('isce.alos2burstinsar.runExtractBurst')
|
||||
|
||||
def runExtractBurst(self):
|
||||
'''extract bursts.
|
||||
'''
|
||||
catalog = isceobj.Catalog.createCatalog(self._insar.procDoc.name)
|
||||
self.updateParamemetersFromUser()
|
||||
|
||||
masterTrack = self._insar.loadTrack(master=True)
|
||||
slaveTrack = self._insar.loadTrack(master=False)
|
||||
|
||||
#demFile = os.path.abspath(self._insar.dem)
|
||||
#wbdFile = os.path.abspath(self._insar.wbd)
|
||||
###############################################################################
|
||||
for i, frameNumber in enumerate(self._insar.masterFrames):
|
||||
frameDir = 'f{}_{}'.format(i+1, frameNumber)
|
||||
os.chdir(frameDir)
|
||||
for j, swathNumber in enumerate(range(self._insar.startingSwath, self._insar.endingSwath + 1)):
|
||||
swathDir = 's{}'.format(swathNumber)
|
||||
os.chdir(swathDir)
|
||||
|
||||
print('extracting bursts frame {}, swath {}'.format(frameNumber, swathNumber))
|
||||
|
||||
az_ratio1 = 20.0
|
||||
for k in range(2):
|
||||
if k==0:
|
||||
#master
|
||||
swath = masterTrack.frames[i].swaths[j]
|
||||
unsynLines = self._insar.burstUnsynchronizedTime * swath.prf
|
||||
extractDir = self._insar.masterBurstPrefix
|
||||
burstPrefix = self._insar.masterBurstPrefix
|
||||
fullApertureSlc = self._insar.masterSlc
|
||||
magnitude = self._insar.masterMagnitude
|
||||
else:
|
||||
#slave
|
||||
swath = slaveTrack.frames[i].swaths[j]
|
||||
unsynLines = -self._insar.burstUnsynchronizedTime * swath.prf
|
||||
extractDir = self._insar.slaveBurstPrefix
|
||||
burstPrefix = self._insar.slaveBurstPrefix
|
||||
fullApertureSlc = self._insar.slaveSlc
|
||||
magnitude = self._insar.slaveMagnitude
|
||||
|
||||
#UPDATE SWATH PARAMETERS 1
|
||||
#########################################################################################
|
||||
if self._insar.burstSynchronization <= self.burstSynchronizationThreshold:
|
||||
swath.burstLength -= abs(unsynLines)
|
||||
if unsynLines < 0:
|
||||
swath.burstStartTime += datetime.timedelta(seconds=abs(unsynLines)/swath.prf)
|
||||
#########################################################################################
|
||||
|
||||
#extract burst
|
||||
if not os.path.exists(extractDir):
|
||||
os.makedirs(extractDir)
|
||||
os.chdir(extractDir)
|
||||
if os.path.isfile(os.path.join('../', fullApertureSlc)):
|
||||
os.rename(os.path.join('../', fullApertureSlc), fullApertureSlc)
|
||||
os.rename(os.path.join('../', fullApertureSlc+'.vrt'), fullApertureSlc+'.vrt')
|
||||
os.rename(os.path.join('../', fullApertureSlc+'.xml'), fullApertureSlc+'.xml')
|
||||
|
||||
extract_burst(fullApertureSlc, burstPrefix, swath.prf, swath.prfFraction, swath.burstLength, swath.burstCycleLength-swath.burstLength, \
|
||||
(swath.burstStartTime - swath.sensingStart).total_seconds() * swath.prf, swath.azimuthFmrateVsPixel, swath.dopplerVsPixel, az_ratio1, 0.0)
|
||||
|
||||
#read output parameters
|
||||
with open('extract_burst.txt', 'r') as f:
|
||||
lines = f.readlines()
|
||||
offsetFromFirstBurst = []
|
||||
for linex in lines:
|
||||
if 'total number of bursts extracted' in linex:
|
||||
numberOfBursts = int(linex.split(':')[1])
|
||||
if 'output burst length' in linex:
|
||||
burstSlcNumberOfLines = int(linex.split(':')[1])
|
||||
if 'line number of first line of first output burst in original SLC (1.0/prf)' in linex:
|
||||
fb_ln = float(linex.split(':')[1])
|
||||
if 'bsl of first output burst' in linex:
|
||||
bsl_firstburst = float(linex.split(':')[1])
|
||||
if 'offset from first burst' in linex:
|
||||
offsetFromFirstBurst.append(int(linex.split(',')[0].split(':')[1]))
|
||||
|
||||
#time of first line of first burst raw
|
||||
firstBurstRawStartTime = swath.sensingStart + datetime.timedelta(seconds=bsl_firstburst/swath.prf)
|
||||
|
||||
#time of first line of first burst slc
|
||||
#original time is at the upper edge of first line, we change it to center of first line.
|
||||
sensingStart = swath.sensingStart + datetime.timedelta(seconds=fb_ln/swath.prf+(az_ratio1-1.0)/2.0/swath.prf)
|
||||
numberOfLines = offsetFromFirstBurst[numberOfBursts-1] + burstSlcNumberOfLines
|
||||
|
||||
for ii in range(numberOfBursts):
|
||||
burstFile = burstPrefix + '_%02d.slc'%(ii+1)
|
||||
create_xml(burstFile, swath.numberOfSamples, burstSlcNumberOfLines, 'slc')
|
||||
|
||||
#UPDATE SWATH PARAMETERS 2
|
||||
#########################################################################################
|
||||
swath.numberOfLines = numberOfLines
|
||||
#this is also the time of the first line of the first burst slc
|
||||
swath.sensingStart = sensingStart
|
||||
swath.azimuthPixelSize = az_ratio1 * swath.azimuthPixelSize
|
||||
swath.azimuthLineInterval = az_ratio1 * swath.azimuthLineInterval
|
||||
|
||||
swath.numberOfBursts = numberOfBursts
|
||||
swath.firstBurstRawStartTime = firstBurstRawStartTime
|
||||
swath.firstBurstSlcStartTime = sensingStart
|
||||
swath.burstSlcFirstLineOffsets = offsetFromFirstBurst
|
||||
swath.burstSlcNumberOfSamples = swath.numberOfSamples
|
||||
swath.burstSlcNumberOfLines = burstSlcNumberOfLines
|
||||
#########################################################################################
|
||||
|
||||
#create a magnitude image
|
||||
mosaicBurstAmplitude(swath, burstPrefix, magnitude, numberOfLooksThreshold=4)
|
||||
|
||||
os.chdir('../')
|
||||
os.chdir('../')
|
||||
self._insar.saveProduct(masterTrack.frames[i], self._insar.masterFrameParameter)
|
||||
self._insar.saveProduct(slaveTrack.frames[i], self._insar.slaveFrameParameter)
|
||||
os.chdir('../')
|
||||
|
||||
###############################################################################
|
||||
catalog.printToLog(logger, "runExtractBurst")
|
||||
self._insar.procDoc.addAllFromCatalog(catalog)
|
||||
|
||||
|
|
@ -0,0 +1,94 @@
|
|||
#
|
||||
# Author: Cunren Liang
|
||||
# Copyright 2015-present, NASA-JPL/Caltech
|
||||
#
|
||||
|
||||
import os
|
||||
import shutil
|
||||
import logging
|
||||
import numpy as np
|
||||
|
||||
import isceobj
|
||||
from mroipac.filter.Filter import Filter
|
||||
from mroipac.icu.Icu import Icu
|
||||
from isceobj.Alos2Proc.Alos2ProcPublic import runCmd
|
||||
from isceobj.Alos2Proc.Alos2ProcPublic import renameFile
|
||||
from isceobj.Alos2Proc.Alos2ProcPublic import create_xml
|
||||
from contrib.alos2filter.alos2filter import psfilt1
|
||||
from isceobj.Alos2Proc.Alos2ProcPublic import cal_coherence
|
||||
|
||||
logger = logging.getLogger('isce.alos2burstinsar.runFiltSd')
|
||||
|
||||
def runFiltSd(self):
|
||||
'''filter interferogram
|
||||
'''
|
||||
catalog = isceobj.Catalog.createCatalog(self._insar.procDoc.name)
|
||||
self.updateParamemetersFromUser()
|
||||
|
||||
#masterTrack = self._insar.loadTrack(master=True)
|
||||
#slaveTrack = self._insar.loadTrack(master=False)
|
||||
|
||||
sdDir = 'sd'
|
||||
if not os.path.exists(sdDir):
|
||||
os.makedirs(sdDir)
|
||||
os.chdir(sdDir)
|
||||
|
||||
sd = isceobj.createImage()
|
||||
sd.load(self._insar.multilookInterferogramSd[0]+'.xml')
|
||||
width = sd.width
|
||||
length = sd.length
|
||||
|
||||
############################################################
|
||||
# STEP 1. filter interferogram
|
||||
############################################################
|
||||
for sdInterferogram, sdInterferogramFilt, sdCoherence in zip(self._insar.multilookInterferogramSd, self._insar.filteredInterferogramSd, self._insar.multilookCoherenceSd):
|
||||
print('filter interferogram: {}'.format(sdInterferogram))
|
||||
#remove mangnitude
|
||||
data = np.fromfile(sdInterferogram, dtype=np.complex64).reshape(length, width)
|
||||
index = np.nonzero(data!=0)
|
||||
data[index] /= np.absolute(data[index])
|
||||
data.astype(np.complex64).tofile('tmp.int')
|
||||
|
||||
#filter
|
||||
windowSize = self.filterWinsizeSd
|
||||
stepSize = self.filterStepsizeSd
|
||||
psfilt1('tmp.int', sdInterferogramFilt, width, self.filterStrengthSd, windowSize, stepSize)
|
||||
create_xml(sdInterferogramFilt, width, length, 'int')
|
||||
os.remove('tmp.int')
|
||||
|
||||
#restore magnitude
|
||||
data = np.fromfile(sdInterferogram, dtype=np.complex64).reshape(length, width)
|
||||
dataFilt = np.fromfile(sdInterferogramFilt, dtype=np.complex64).reshape(length, width)
|
||||
index = np.nonzero(dataFilt!=0)
|
||||
dataFilt[index] = dataFilt[index] / np.absolute(dataFilt[index]) * np.absolute(data[index])
|
||||
dataFilt.astype(np.complex64).tofile(sdInterferogramFilt)
|
||||
|
||||
# #create a coherence using an interferogram with most sparse fringes
|
||||
# if sdInterferogramFilt == self._insar.filteredInterferogramSd[0]:
|
||||
# print('create coherence using: {}'.format(sdInterferogramFilt))
|
||||
# cor = cal_coherence(dataFilt, win=3, edge=2)
|
||||
# cor.astype(np.float32).tofile(self._insar.multilookCoherenceSd)
|
||||
# create_xml(self._insar.multilookCoherenceSd, width, length, 'float')
|
||||
|
||||
cor = cal_coherence(dataFilt, win=3, edge=2)
|
||||
cor.astype(np.float32).tofile(sdCoherence)
|
||||
create_xml(sdCoherence, width, length, 'float')
|
||||
|
||||
|
||||
############################################################
|
||||
# STEP 3. mask filtered interferogram using water body
|
||||
############################################################
|
||||
if self.waterBodyMaskStartingStepSd=='filt':
|
||||
print('mask filtered interferogram using: {}'.format(self._insar.multilookWbdOutSd))
|
||||
wbd = np.fromfile(self._insar.multilookWbdOutSd, dtype=np.int8).reshape(length, width)
|
||||
cor=np.memmap(self._insar.multilookCoherenceSd, dtype='float32', mode='r+', shape=(length, width))
|
||||
cor[np.nonzero(wbd==-1)]=0
|
||||
for sdInterferogramFilt in self._insar.filteredInterferogramSd:
|
||||
filt=np.memmap(sdInterferogramFilt, dtype='complex64', mode='r+', shape=(length, width))
|
||||
filt[np.nonzero(wbd==-1)]=0
|
||||
|
||||
os.chdir('../')
|
||||
|
||||
catalog.printToLog(logger, "runFiltSd")
|
||||
self._insar.procDoc.addAllFromCatalog(catalog)
|
||||
|
||||
|
|
@ -0,0 +1,172 @@
|
|||
#
|
||||
# Author: Cunren Liang
|
||||
# Copyright 2015-present, NASA-JPL/Caltech
|
||||
#
|
||||
|
||||
import os
|
||||
import logging
|
||||
|
||||
import isceobj
|
||||
from isceobj.Alos2Proc.runFrameMosaic import frameMosaic
|
||||
from isceobj.Alos2Proc.runFrameMosaic import frameMosaicParameters
|
||||
from isceobj.Alos2Proc.Alos2ProcPublic import create_xml
|
||||
|
||||
logger = logging.getLogger('isce.alos2burstinsar.runFrameMosaic')
|
||||
|
||||
def runFrameMosaic(self):
|
||||
'''mosaic frames
|
||||
'''
|
||||
catalog = isceobj.Catalog.createCatalog(self._insar.procDoc.name)
|
||||
self.updateParamemetersFromUser()
|
||||
|
||||
masterTrack = self._insar.loadTrack(master=True)
|
||||
slaveTrack = self._insar.loadTrack(master=False)
|
||||
|
||||
mosaicDir = 'insar'
|
||||
if not os.path.exists(mosaicDir):
|
||||
os.makedirs(mosaicDir)
|
||||
os.chdir(mosaicDir)
|
||||
|
||||
numberOfFrames = len(masterTrack.frames)
|
||||
if numberOfFrames == 1:
|
||||
import shutil
|
||||
frameDir = os.path.join('f1_{}/mosaic'.format(self._insar.masterFrames[0]))
|
||||
if not os.path.isfile(self._insar.interferogram):
|
||||
os.symlink(os.path.join('../', frameDir, self._insar.interferogram), self._insar.interferogram)
|
||||
#shutil.copy2() can overwrite
|
||||
shutil.copy2(os.path.join('../', frameDir, self._insar.interferogram+'.vrt'), self._insar.interferogram+'.vrt')
|
||||
shutil.copy2(os.path.join('../', frameDir, self._insar.interferogram+'.xml'), self._insar.interferogram+'.xml')
|
||||
if not os.path.isfile(self._insar.amplitude):
|
||||
os.symlink(os.path.join('../', frameDir, self._insar.amplitude), self._insar.amplitude)
|
||||
shutil.copy2(os.path.join('../', frameDir, self._insar.amplitude+'.vrt'), self._insar.amplitude+'.vrt')
|
||||
shutil.copy2(os.path.join('../', frameDir, self._insar.amplitude+'.xml'), self._insar.amplitude+'.xml')
|
||||
|
||||
# os.rename(os.path.join('../', frameDir, self._insar.interferogram), self._insar.interferogram)
|
||||
# os.rename(os.path.join('../', frameDir, self._insar.interferogram+'.vrt'), self._insar.interferogram+'.vrt')
|
||||
# os.rename(os.path.join('../', frameDir, self._insar.interferogram+'.xml'), self._insar.interferogram+'.xml')
|
||||
# os.rename(os.path.join('../', frameDir, self._insar.amplitude), self._insar.amplitude)
|
||||
# os.rename(os.path.join('../', frameDir, self._insar.amplitude+'.vrt'), self._insar.amplitude+'.vrt')
|
||||
# os.rename(os.path.join('../', frameDir, self._insar.amplitude+'.xml'), self._insar.amplitude+'.xml')
|
||||
|
||||
#update track parameters
|
||||
#########################################################
|
||||
#mosaic size
|
||||
masterTrack.numberOfSamples = masterTrack.frames[0].numberOfSamples
|
||||
masterTrack.numberOfLines = masterTrack.frames[0].numberOfLines
|
||||
#NOTE THAT WE ARE STILL USING SINGLE LOOK PARAMETERS HERE
|
||||
#range parameters
|
||||
masterTrack.startingRange = masterTrack.frames[0].startingRange
|
||||
masterTrack.rangeSamplingRate = masterTrack.frames[0].rangeSamplingRate
|
||||
masterTrack.rangePixelSize = masterTrack.frames[0].rangePixelSize
|
||||
#azimuth parameters
|
||||
masterTrack.sensingStart = masterTrack.frames[0].sensingStart
|
||||
masterTrack.prf = masterTrack.frames[0].prf
|
||||
masterTrack.azimuthPixelSize = masterTrack.frames[0].azimuthPixelSize
|
||||
masterTrack.azimuthLineInterval = masterTrack.frames[0].azimuthLineInterval
|
||||
|
||||
#update track parameters, slave
|
||||
#########################################################
|
||||
#mosaic size
|
||||
slaveTrack.numberOfSamples = slaveTrack.frames[0].numberOfSamples
|
||||
slaveTrack.numberOfLines = slaveTrack.frames[0].numberOfLines
|
||||
#NOTE THAT WE ARE STILL USING SINGLE LOOK PARAMETERS HERE
|
||||
#range parameters
|
||||
slaveTrack.startingRange = slaveTrack.frames[0].startingRange
|
||||
slaveTrack.rangeSamplingRate = slaveTrack.frames[0].rangeSamplingRate
|
||||
slaveTrack.rangePixelSize = slaveTrack.frames[0].rangePixelSize
|
||||
#azimuth parameters
|
||||
slaveTrack.sensingStart = slaveTrack.frames[0].sensingStart
|
||||
slaveTrack.prf = slaveTrack.frames[0].prf
|
||||
slaveTrack.azimuthPixelSize = slaveTrack.frames[0].azimuthPixelSize
|
||||
slaveTrack.azimuthLineInterval = slaveTrack.frames[0].azimuthLineInterval
|
||||
|
||||
else:
|
||||
#choose offsets
|
||||
if self.frameOffsetMatching:
|
||||
rangeOffsets = self._insar.frameRangeOffsetMatchingMaster
|
||||
azimuthOffsets = self._insar.frameAzimuthOffsetMatchingMaster
|
||||
else:
|
||||
rangeOffsets = self._insar.frameRangeOffsetGeometricalMaster
|
||||
azimuthOffsets = self._insar.frameAzimuthOffsetGeometricalMaster
|
||||
|
||||
#list of input files
|
||||
inputInterferograms = []
|
||||
inputAmplitudes = []
|
||||
for i, frameNumber in enumerate(self._insar.masterFrames):
|
||||
frameDir = 'f{}_{}'.format(i+1, frameNumber)
|
||||
inputInterferograms.append(os.path.join('../', frameDir, 'mosaic', self._insar.interferogram))
|
||||
inputAmplitudes.append(os.path.join('../', frameDir, 'mosaic', self._insar.amplitude))
|
||||
|
||||
#note that track parameters are updated after mosaicking
|
||||
#mosaic amplitudes
|
||||
frameMosaic(masterTrack, inputAmplitudes, self._insar.amplitude,
|
||||
rangeOffsets, azimuthOffsets, self._insar.numberRangeLooks1, self._insar.numberAzimuthLooks1,
|
||||
updateTrack=False, phaseCompensation=False, resamplingMethod=0)
|
||||
#mosaic interferograms
|
||||
frameMosaic(masterTrack, inputInterferograms, self._insar.interferogram,
|
||||
rangeOffsets, azimuthOffsets, self._insar.numberRangeLooks1, self._insar.numberAzimuthLooks1,
|
||||
updateTrack=True, phaseCompensation=True, resamplingMethod=1)
|
||||
|
||||
create_xml(self._insar.amplitude, masterTrack.numberOfSamples, masterTrack.numberOfLines, 'amp')
|
||||
create_xml(self._insar.interferogram, masterTrack.numberOfSamples, masterTrack.numberOfLines, 'int')
|
||||
|
||||
#update slave parameters here
|
||||
#do not match for slave, always use geometrical
|
||||
rangeOffsets = self._insar.frameRangeOffsetGeometricalSlave
|
||||
azimuthOffsets = self._insar.frameAzimuthOffsetGeometricalSlave
|
||||
frameMosaicParameters(slaveTrack, rangeOffsets, azimuthOffsets, self._insar.numberRangeLooks1, self._insar.numberAzimuthLooks1)
|
||||
|
||||
os.chdir('../')
|
||||
#save parameter file
|
||||
self._insar.saveProduct(masterTrack, self._insar.masterTrackParameter)
|
||||
self._insar.saveProduct(slaveTrack, self._insar.slaveTrackParameter)
|
||||
|
||||
|
||||
|
||||
#mosaic spectral diversity inteferograms
|
||||
mosaicDir = 'sd'
|
||||
if not os.path.exists(mosaicDir):
|
||||
os.makedirs(mosaicDir)
|
||||
os.chdir(mosaicDir)
|
||||
|
||||
numberOfFrames = len(masterTrack.frames)
|
||||
if numberOfFrames == 1:
|
||||
import shutil
|
||||
frameDir = os.path.join('f1_{}/mosaic'.format(self._insar.masterFrames[0]))
|
||||
for sdFile in self._insar.interferogramSd:
|
||||
if not os.path.isfile(sdFile):
|
||||
os.symlink(os.path.join('../', frameDir, sdFile), sdFile)
|
||||
shutil.copy2(os.path.join('../', frameDir, sdFile+'.vrt'), sdFile+'.vrt')
|
||||
shutil.copy2(os.path.join('../', frameDir, sdFile+'.xml'), sdFile+'.xml')
|
||||
else:
|
||||
#choose offsets
|
||||
if self.frameOffsetMatching:
|
||||
rangeOffsets = self._insar.frameRangeOffsetMatchingMaster
|
||||
azimuthOffsets = self._insar.frameAzimuthOffsetMatchingMaster
|
||||
else:
|
||||
rangeOffsets = self._insar.frameRangeOffsetGeometricalMaster
|
||||
azimuthOffsets = self._insar.frameAzimuthOffsetGeometricalMaster
|
||||
|
||||
#list of input files
|
||||
inputSd = [[], [], []]
|
||||
for i, frameNumber in enumerate(self._insar.masterFrames):
|
||||
frameDir = 'f{}_{}'.format(i+1, frameNumber)
|
||||
for k, sdFile in enumerate(self._insar.interferogramSd):
|
||||
inputSd[k].append(os.path.join('../', frameDir, 'mosaic', sdFile))
|
||||
|
||||
#mosaic spectral diversity interferograms
|
||||
for inputSdList, outputSdFile in zip(inputSd, self._insar.interferogramSd):
|
||||
frameMosaic(masterTrack, inputSdList, outputSdFile,
|
||||
rangeOffsets, azimuthOffsets, self._insar.numberRangeLooks1, self._insar.numberAzimuthLooks1,
|
||||
updateTrack=False, phaseCompensation=True, resamplingMethod=1)
|
||||
|
||||
for sdFile in self._insar.interferogramSd:
|
||||
create_xml(sdFile, masterTrack.numberOfSamples, masterTrack.numberOfLines, 'int')
|
||||
|
||||
os.chdir('../')
|
||||
|
||||
|
||||
catalog.printToLog(logger, "runFrameMosaic")
|
||||
self._insar.procDoc.addAllFromCatalog(catalog)
|
||||
|
||||
|
||||
|
|
@ -0,0 +1,55 @@
|
|||
#
|
||||
# Author: Cunren Liang
|
||||
# Copyright 2015-present, NASA-JPL/Caltech
|
||||
#
|
||||
|
||||
import os
|
||||
import logging
|
||||
|
||||
import isceobj
|
||||
from isceobj.Alos2Proc.runFrameOffset import frameOffset
|
||||
|
||||
logger = logging.getLogger('isce.alos2burstinsar.runFrameOffset')
|
||||
|
||||
def runFrameOffset(self):
|
||||
'''estimate frame offsets.
|
||||
'''
|
||||
catalog = isceobj.Catalog.createCatalog(self._insar.procDoc.name)
|
||||
self.updateParamemetersFromUser()
|
||||
|
||||
masterTrack = self._insar.loadTrack(master=True)
|
||||
slaveTrack = self._insar.loadTrack(master=False)
|
||||
|
||||
mosaicDir = 'insar'
|
||||
if not os.path.exists(mosaicDir):
|
||||
os.makedirs(mosaicDir)
|
||||
os.chdir(mosaicDir)
|
||||
|
||||
if len(masterTrack.frames) > 1:
|
||||
#here we use master amplitude image mosaicked from extracted bursts.
|
||||
matchingMode=1
|
||||
|
||||
#compute swath offset
|
||||
offsetMaster = frameOffset(masterTrack, os.path.join(self._insar.masterBurstPrefix, self._insar.masterMagnitude), self._insar.masterFrameOffset,
|
||||
crossCorrelation=self.frameOffsetMatching, matchingMode=matchingMode)
|
||||
#only use geometrical offset for slave
|
||||
offsetSlave = frameOffset(slaveTrack, os.path.join(self._insar.slaveBurstPrefix, self._insar.slaveMagnitude), self._insar.slaveFrameOffset,
|
||||
crossCorrelation=False, matchingMode=matchingMode)
|
||||
|
||||
self._insar.frameRangeOffsetGeometricalMaster = offsetMaster[0]
|
||||
self._insar.frameAzimuthOffsetGeometricalMaster = offsetMaster[1]
|
||||
self._insar.frameRangeOffsetGeometricalSlave = offsetSlave[0]
|
||||
self._insar.frameAzimuthOffsetGeometricalSlave = offsetSlave[1]
|
||||
if self.frameOffsetMatching:
|
||||
self._insar.frameRangeOffsetMatchingMaster = offsetMaster[2]
|
||||
self._insar.frameAzimuthOffsetMatchingMaster = offsetMaster[3]
|
||||
#self._insar.frameRangeOffsetMatchingSlave = offsetSlave[2]
|
||||
#self._insar.frameAzimuthOffsetMatchingSlave = offsetSlave[3]
|
||||
|
||||
|
||||
os.chdir('../')
|
||||
|
||||
catalog.printToLog(logger, "runFrameOffset")
|
||||
self._insar.procDoc.addAllFromCatalog(catalog)
|
||||
|
||||
|
||||
|
|
@ -0,0 +1,64 @@
|
|||
#
|
||||
# Author: Cunren Liang
|
||||
# Copyright 2015-present, NASA-JPL/Caltech
|
||||
#
|
||||
|
||||
import os
|
||||
import logging
|
||||
import numpy as np
|
||||
|
||||
import isceobj
|
||||
from isceobj.Alos2Proc.runGeocode import geocode
|
||||
from isceobj.Alos2Proc.Alos2ProcPublic import getBboxGeo
|
||||
|
||||
logger = logging.getLogger('isce.alos2insar.runGeocodeSd')
|
||||
|
||||
def runGeocodeSd(self):
|
||||
'''geocode final products
|
||||
'''
|
||||
catalog = isceobj.Catalog.createCatalog(self._insar.procDoc.name)
|
||||
self.updateParamemetersFromUser()
|
||||
|
||||
masterTrack = self._insar.loadTrack(master=True)
|
||||
#slaveTrack = self._insar.loadTrack(master=False)
|
||||
|
||||
demFile = os.path.abspath(self._insar.demGeo)
|
||||
|
||||
sdDir = 'sd'
|
||||
if not os.path.exists(sdDir):
|
||||
os.makedirs(sdDir)
|
||||
os.chdir(sdDir)
|
||||
|
||||
if self.geocodeListSd == None:
|
||||
geocodeList = self._insar.multilookCoherenceSd + self._insar.azimuthDeformationSd + self._insar.maskedAzimuthDeformationSd
|
||||
else:
|
||||
geocodeList = self.geocodeListSd
|
||||
|
||||
if self.bbox == None:
|
||||
bbox = getBboxGeo(masterTrack)
|
||||
else:
|
||||
bbox = self.bbox
|
||||
catalog.addItem('geocode bounding box', bbox, 'runGeocodeSd')
|
||||
|
||||
numberRangeLooks = self._insar.numberRangeLooks1 * self._insar.numberRangeLooksSd
|
||||
numberAzimuthLooks = self._insar.numberAzimuthLooks1 * self._insar.numberAzimuthLooksSd
|
||||
|
||||
for inputFile in geocodeList:
|
||||
if self.geocodeInterpMethodSd == None:
|
||||
img = isceobj.createImage()
|
||||
img.load(inputFile + '.xml')
|
||||
if img.dataType.upper() == 'CFLOAT':
|
||||
interpMethod = 'sinc'
|
||||
else:
|
||||
interpMethod = 'bilinear'
|
||||
else:
|
||||
interpMethod = self.geocodeInterpMethodSd.lower()
|
||||
|
||||
geocode(masterTrack, demFile, inputFile, bbox, numberRangeLooks, numberAzimuthLooks, interpMethod, 0, 0)
|
||||
|
||||
|
||||
os.chdir('../')
|
||||
|
||||
catalog.printToLog(logger, "runGeocodeSd")
|
||||
self._insar.procDoc.addAllFromCatalog(catalog)
|
||||
|
||||
|
|
@ -0,0 +1,425 @@
|
|||
#
|
||||
# Author: Cunren Liang
|
||||
# Copyright 2015-present, NASA-JPL/Caltech
|
||||
#
|
||||
|
||||
import os
|
||||
import shutil
|
||||
import logging
|
||||
|
||||
import isceobj
|
||||
from isceobj.Constants import SPEED_OF_LIGHT
|
||||
|
||||
logger = logging.getLogger('isce.alos2burstinsar.runIonSubband')
|
||||
|
||||
def runIonSubband(self):
|
||||
'''create subband interferograms
|
||||
'''
|
||||
catalog = isceobj.Catalog.createCatalog(self._insar.procDoc.name)
|
||||
self.updateParamemetersFromUser()
|
||||
|
||||
if not self.doIon:
|
||||
catalog.printToLog(logger, "runIonSubband")
|
||||
self._insar.procDoc.addAllFromCatalog(catalog)
|
||||
return
|
||||
|
||||
masterTrack = self._insar.loadTrack(master=True)
|
||||
slaveTrack = self._insar.loadTrack(master=False)
|
||||
|
||||
#using 1/3, 1/3, 1/3 band split
|
||||
radarWavelength = masterTrack.radarWavelength
|
||||
rangeBandwidth = masterTrack.frames[0].swaths[0].rangeBandwidth
|
||||
rangeSamplingRate = masterTrack.frames[0].swaths[0].rangeSamplingRate
|
||||
radarWavelengthLower = SPEED_OF_LIGHT/(SPEED_OF_LIGHT / radarWavelength - rangeBandwidth / 3.0)
|
||||
radarWavelengthUpper = SPEED_OF_LIGHT/(SPEED_OF_LIGHT / radarWavelength + rangeBandwidth / 3.0)
|
||||
subbandRadarWavelength = [radarWavelengthLower, radarWavelengthUpper]
|
||||
subbandBandWidth = [rangeBandwidth / 3.0 / rangeSamplingRate, rangeBandwidth / 3.0 / rangeSamplingRate]
|
||||
subbandFrequencyCenter = [-rangeBandwidth / 3.0 / rangeSamplingRate, rangeBandwidth / 3.0 / rangeSamplingRate]
|
||||
|
||||
subbandPrefix = ['lower', 'upper']
|
||||
|
||||
'''
|
||||
ionDir = {
|
||||
ionDir['swathMosaic'] : 'mosaic',
|
||||
ionDir['insar'] : 'insar',
|
||||
ionDir['ion'] : 'ion',
|
||||
ionDir['subband'] : ['lower', 'upper'],
|
||||
ionDir['ionCal'] : 'ion_cal'
|
||||
}
|
||||
'''
|
||||
#define upper level directory names
|
||||
ionDir = defineIonDir()
|
||||
|
||||
|
||||
self._insar.subbandRadarWavelength = subbandRadarWavelength
|
||||
|
||||
|
||||
############################################################
|
||||
# STEP 1. create directories
|
||||
############################################################
|
||||
#create and enter 'ion' directory
|
||||
#after finishing each step, we are in this directory
|
||||
if not os.path.exists(ionDir['ion']):
|
||||
os.makedirs(ionDir['ion'])
|
||||
os.chdir(ionDir['ion'])
|
||||
|
||||
#create insar processing directories
|
||||
for k in range(2):
|
||||
subbandDir = ionDir['subband'][k]
|
||||
for i, frameNumber in enumerate(self._insar.masterFrames):
|
||||
frameDir = 'f{}_{}'.format(i+1, frameNumber)
|
||||
for j, swathNumber in enumerate(range(self._insar.startingSwath, self._insar.endingSwath + 1)):
|
||||
swathDir = 's{}'.format(swathNumber)
|
||||
fullDir = os.path.join(subbandDir, frameDir, swathDir)
|
||||
if not os.path.exists(fullDir):
|
||||
os.makedirs(fullDir)
|
||||
|
||||
#create ionospheric phase directory
|
||||
if not os.path.exists(ionDir['ionCal']):
|
||||
os.makedirs(ionDir['ionCal'])
|
||||
|
||||
|
||||
############################################################
|
||||
# STEP 2. create subband interferograms
|
||||
############################################################
|
||||
import shutil
|
||||
import numpy as np
|
||||
from contrib.alos2proc.alos2proc import rg_filter
|
||||
from isceobj.Alos2Proc.Alos2ProcPublic import resampleBursts
|
||||
from isceobj.Alos2Proc.Alos2ProcPublic import mosaicBurstAmplitude
|
||||
from isceobj.Alos2Proc.Alos2ProcPublic import mosaicBurstInterferogram
|
||||
from isceobj.Alos2Proc.Alos2ProcPublic import create_xml
|
||||
|
||||
for i, frameNumber in enumerate(self._insar.masterFrames):
|
||||
frameDir = 'f{}_{}'.format(i+1, frameNumber)
|
||||
for j, swathNumber in enumerate(range(self._insar.startingSwath, self._insar.endingSwath + 1)):
|
||||
swathDir = 's{}'.format(swathNumber)
|
||||
#filter master and slave images
|
||||
for burstPrefix, swath in zip([self._insar.masterBurstPrefix, self._insar.slaveBurstPrefix],
|
||||
[masterTrack.frames[i].swaths[j], slaveTrack.frames[i].swaths[j]]):
|
||||
slcDir = os.path.join('../', frameDir, swathDir, burstPrefix)
|
||||
slcLowerDir = os.path.join(ionDir['subband'][0], frameDir, swathDir, burstPrefix)
|
||||
slcUpperDir = os.path.join(ionDir['subband'][1], frameDir, swathDir, burstPrefix)
|
||||
if not os.path.exists(slcLowerDir):
|
||||
os.makedirs(slcLowerDir)
|
||||
if not os.path.exists(slcUpperDir):
|
||||
os.makedirs(slcUpperDir)
|
||||
for k in range(swath.numberOfBursts):
|
||||
print('processing burst: %02d'%(k+1))
|
||||
slc = os.path.join(slcDir, burstPrefix+'_%02d.slc'%(k+1))
|
||||
slcLower = os.path.join(slcLowerDir, burstPrefix+'_%02d.slc'%(k+1))
|
||||
slcUpper = os.path.join(slcUpperDir, burstPrefix+'_%02d.slc'%(k+1))
|
||||
rg_filter(slc, 2,
|
||||
[slcLower, slcUpper],
|
||||
subbandBandWidth,
|
||||
subbandFrequencyCenter,
|
||||
257, 2048, 0.1, 0, 0.0)
|
||||
#resample
|
||||
for l in range(2):
|
||||
os.chdir(os.path.join(ionDir['subband'][l], frameDir, swathDir))
|
||||
#recreate xml file to remove the file path
|
||||
#can also use fixImageXml.py?
|
||||
for burstPrefix, swath in zip([self._insar.masterBurstPrefix, self._insar.slaveBurstPrefix],
|
||||
[masterTrack.frames[i].swaths[j], slaveTrack.frames[i].swaths[j]]):
|
||||
os.chdir(burstPrefix)
|
||||
for k in range(swath.numberOfBursts):
|
||||
slc = burstPrefix+'_%02d.slc'%(k+1)
|
||||
img = isceobj.createSlcImage()
|
||||
img.load(slc + '.xml')
|
||||
img.setFilename(slc)
|
||||
img.extraFilename = slc + '.vrt'
|
||||
img.setAccessMode('READ')
|
||||
img.renderHdr()
|
||||
os.chdir('../')
|
||||
|
||||
#############################################
|
||||
#1. form interferogram
|
||||
#############################################
|
||||
masterSwath = masterTrack.frames[i].swaths[j]
|
||||
slaveSwath = slaveTrack.frames[i].swaths[j]
|
||||
|
||||
#set up resampling parameters
|
||||
width = masterSwath.numberOfSamples
|
||||
length = masterSwath.numberOfLines
|
||||
polyCoeff = self._insar.rangeResidualOffsetCc[i][j]
|
||||
rgIndex = (np.arange(width)-polyCoeff[-1][0])/polyCoeff[-1][1]
|
||||
azIndex = (np.arange(length)-polyCoeff[-1][2])/polyCoeff[-1][3]
|
||||
rangeOffset = polyCoeff[0][0] + polyCoeff[0][1]*rgIndex[None,:] + polyCoeff[0][2]*rgIndex[None,:]**2 + \
|
||||
(polyCoeff[1][0] + polyCoeff[1][1]*rgIndex[None,:]) * azIndex[:, None] + \
|
||||
polyCoeff[2][0] * azIndex[:, None]**2
|
||||
azimuthOffset = self._insar.azimuthResidualOffsetCc[i][j]
|
||||
|
||||
slaveBurstResampledDir = self._insar.slaveBurstPrefix + '_2_coreg_cc'
|
||||
interferogramDir = 'burst_interf_2_coreg_cc'
|
||||
interferogramPrefix = self._insar.masterBurstPrefix + '-' + self._insar.slaveBurstPrefix
|
||||
resampleBursts(masterSwath, slaveSwath,
|
||||
self._insar.masterBurstPrefix, self._insar.slaveBurstPrefix, slaveBurstResampledDir, interferogramDir,
|
||||
self._insar.masterBurstPrefix, self._insar.slaveBurstPrefix, self._insar.slaveBurstPrefix, interferogramPrefix,
|
||||
os.path.join('../../../../{}/{}'.format(frameDir, swathDir), self._insar.rangeOffset),
|
||||
os.path.join('../../../../{}/{}'.format(frameDir, swathDir), self._insar.azimuthOffset),
|
||||
rangeOffsetResidual=rangeOffset, azimuthOffsetResidual=azimuthOffset)
|
||||
|
||||
os.chdir(self._insar.masterBurstPrefix)
|
||||
mosaicBurstAmplitude(masterSwath, self._insar.masterBurstPrefix, self._insar.masterMagnitude, numberOfLooksThreshold=4)
|
||||
os.chdir('../')
|
||||
|
||||
os.chdir(slaveBurstResampledDir)
|
||||
mosaicBurstAmplitude(masterSwath, self._insar.slaveBurstPrefix, self._insar.slaveMagnitude, numberOfLooksThreshold=4)
|
||||
os.chdir('../')
|
||||
|
||||
os.chdir(interferogramDir)
|
||||
mosaicBurstInterferogram(masterSwath, interferogramPrefix, self._insar.interferogram, numberOfLooksThreshold=4)
|
||||
os.chdir('../')
|
||||
|
||||
|
||||
amp = np.zeros((masterSwath.numberOfLines, 2*masterSwath.numberOfSamples), dtype=np.float32)
|
||||
amp[0:, 1:masterSwath.numberOfSamples*2:2] = np.fromfile(os.path.join(slaveBurstResampledDir, self._insar.slaveMagnitude), \
|
||||
dtype=np.float32).reshape(masterSwath.numberOfLines, masterSwath.numberOfSamples)
|
||||
amp[0:, 0:masterSwath.numberOfSamples*2:2] = np.fromfile(os.path.join(self._insar.masterBurstPrefix, self._insar.masterMagnitude), \
|
||||
dtype=np.float32).reshape(masterSwath.numberOfLines, masterSwath.numberOfSamples)
|
||||
amp.astype(np.float32).tofile(self._insar.amplitude)
|
||||
create_xml(self._insar.amplitude, masterSwath.numberOfSamples, masterSwath.numberOfLines, 'amp')
|
||||
|
||||
os.rename(os.path.join(interferogramDir, self._insar.interferogram), self._insar.interferogram)
|
||||
os.rename(os.path.join(interferogramDir, self._insar.interferogram+'.vrt'), self._insar.interferogram+'.vrt')
|
||||
os.rename(os.path.join(interferogramDir, self._insar.interferogram+'.xml'), self._insar.interferogram+'.xml')
|
||||
|
||||
#############################################
|
||||
#2. delete subband slcs
|
||||
#############################################
|
||||
shutil.rmtree(self._insar.masterBurstPrefix)
|
||||
shutil.rmtree(self._insar.slaveBurstPrefix)
|
||||
shutil.rmtree(slaveBurstResampledDir)
|
||||
shutil.rmtree(interferogramDir)
|
||||
|
||||
os.chdir('../../../')
|
||||
|
||||
|
||||
############################################################
|
||||
# STEP 3. mosaic swaths
|
||||
############################################################
|
||||
from isceobj.Alos2Proc.runSwathMosaic import swathMosaic
|
||||
from isceobj.Alos2Proc.Alos2ProcPublic import create_xml
|
||||
|
||||
for k in range(2):
|
||||
os.chdir(ionDir['subband'][k])
|
||||
for i, frameNumber in enumerate(self._insar.masterFrames):
|
||||
frameDir = 'f{}_{}'.format(i+1, frameNumber)
|
||||
os.chdir(frameDir)
|
||||
|
||||
mosaicDir = 'mosaic'
|
||||
if not os.path.exists(mosaicDir):
|
||||
os.makedirs(mosaicDir)
|
||||
os.chdir(mosaicDir)
|
||||
|
||||
if self._insar.endingSwath-self._insar.startingSwath+1 == 1:
|
||||
import shutil
|
||||
swathDir = 's{}'.format(masterTrack.frames[i].swaths[0].swathNumber)
|
||||
|
||||
# if not os.path.isfile(self._insar.interferogram):
|
||||
# os.symlink(os.path.join('../', swathDir, self._insar.interferogram), self._insar.interferogram)
|
||||
# shutil.copy2(os.path.join('../', swathDir, self._insar.interferogram+'.vrt'), self._insar.interferogram+'.vrt')
|
||||
# shutil.copy2(os.path.join('../', swathDir, self._insar.interferogram+'.xml'), self._insar.interferogram+'.xml')
|
||||
# if not os.path.isfile(self._insar.amplitude):
|
||||
# os.symlink(os.path.join('../', swathDir, self._insar.amplitude), self._insar.amplitude)
|
||||
# shutil.copy2(os.path.join('../', swathDir, self._insar.amplitude+'.vrt'), self._insar.amplitude+'.vrt')
|
||||
# shutil.copy2(os.path.join('../', swathDir, self._insar.amplitude+'.xml'), self._insar.amplitude+'.xml')
|
||||
|
||||
os.rename(os.path.join('../', swathDir, self._insar.interferogram), self._insar.interferogram)
|
||||
os.rename(os.path.join('../', swathDir, self._insar.interferogram+'.vrt'), self._insar.interferogram+'.vrt')
|
||||
os.rename(os.path.join('../', swathDir, self._insar.interferogram+'.xml'), self._insar.interferogram+'.xml')
|
||||
os.rename(os.path.join('../', swathDir, self._insar.amplitude), self._insar.amplitude)
|
||||
os.rename(os.path.join('../', swathDir, self._insar.amplitude+'.vrt'), self._insar.amplitude+'.vrt')
|
||||
os.rename(os.path.join('../', swathDir, self._insar.amplitude+'.xml'), self._insar.amplitude+'.xml')
|
||||
|
||||
os.chdir('../')
|
||||
os.chdir('../')
|
||||
continue
|
||||
|
||||
#choose offsets
|
||||
numberOfFrames = len(masterTrack.frames)
|
||||
numberOfSwaths = len(masterTrack.frames[i].swaths)
|
||||
if self.swathOffsetMatching:
|
||||
#no need to do this as the API support 2-d list
|
||||
#rangeOffsets = (np.array(self._insar.swathRangeOffsetMatchingMaster)).reshape(numberOfFrames, numberOfSwaths)
|
||||
#azimuthOffsets = (np.array(self._insar.swathAzimuthOffsetMatchingMaster)).reshape(numberOfFrames, numberOfSwaths)
|
||||
rangeOffsets = self._insar.swathRangeOffsetMatchingMaster
|
||||
azimuthOffsets = self._insar.swathAzimuthOffsetMatchingMaster
|
||||
|
||||
else:
|
||||
#rangeOffsets = (np.array(self._insar.swathRangeOffsetGeometricalMaster)).reshape(numberOfFrames, numberOfSwaths)
|
||||
#azimuthOffsets = (np.array(self._insar.swathAzimuthOffsetGeometricalMaster)).reshape(numberOfFrames, numberOfSwaths)
|
||||
rangeOffsets = self._insar.swathRangeOffsetGeometricalMaster
|
||||
azimuthOffsets = self._insar.swathAzimuthOffsetGeometricalMaster
|
||||
|
||||
rangeOffsets = rangeOffsets[i]
|
||||
azimuthOffsets = azimuthOffsets[i]
|
||||
|
||||
#list of input files
|
||||
inputInterferograms = []
|
||||
inputAmplitudes = []
|
||||
for j, swathNumber in enumerate(range(self._insar.startingSwath, self._insar.endingSwath + 1)):
|
||||
swathDir = 's{}'.format(swathNumber)
|
||||
inputInterferograms.append(os.path.join('../', swathDir, self._insar.interferogram))
|
||||
inputAmplitudes.append(os.path.join('../', swathDir, self._insar.amplitude))
|
||||
|
||||
#note that frame parameters are updated after mosaicking
|
||||
#mosaic amplitudes
|
||||
swathMosaic(masterTrack.frames[i], inputAmplitudes, self._insar.amplitude,
|
||||
rangeOffsets, azimuthOffsets, self._insar.numberRangeLooks1, self._insar.numberAzimuthLooks1, resamplingMethod=0)
|
||||
#mosaic interferograms
|
||||
swathMosaic(masterTrack.frames[i], inputInterferograms, self._insar.interferogram,
|
||||
rangeOffsets, azimuthOffsets, self._insar.numberRangeLooks1, self._insar.numberAzimuthLooks1, updateFrame=False, phaseCompensation=True, resamplingMethod=1)
|
||||
|
||||
create_xml(self._insar.amplitude, masterTrack.frames[i].numberOfSamples, masterTrack.frames[i].numberOfLines, 'amp')
|
||||
create_xml(self._insar.interferogram, masterTrack.frames[i].numberOfSamples, masterTrack.frames[i].numberOfLines, 'int')
|
||||
|
||||
os.chdir('../')
|
||||
os.chdir('../')
|
||||
os.chdir('../')
|
||||
|
||||
|
||||
############################################################
|
||||
# STEP 4. mosaic frames
|
||||
############################################################
|
||||
from isceobj.Alos2Proc.runFrameMosaic import frameMosaic
|
||||
from isceobj.Alos2Proc.Alos2ProcPublic import create_xml
|
||||
|
||||
for k in range(2):
|
||||
os.chdir(ionDir['subband'][k])
|
||||
|
||||
mosaicDir = 'insar'
|
||||
if not os.path.exists(mosaicDir):
|
||||
os.makedirs(mosaicDir)
|
||||
os.chdir(mosaicDir)
|
||||
|
||||
numberOfFrames = len(masterTrack.frames)
|
||||
if numberOfFrames == 1:
|
||||
import shutil
|
||||
frameDir = os.path.join('f1_{}/mosaic'.format(self._insar.masterFrames[0]))
|
||||
# if not os.path.isfile(self._insar.interferogram):
|
||||
# os.symlink(os.path.join('../', frameDir, self._insar.interferogram), self._insar.interferogram)
|
||||
# #shutil.copy2() can overwrite
|
||||
# shutil.copy2(os.path.join('../', frameDir, self._insar.interferogram+'.vrt'), self._insar.interferogram+'.vrt')
|
||||
# shutil.copy2(os.path.join('../', frameDir, self._insar.interferogram+'.xml'), self._insar.interferogram+'.xml')
|
||||
# if not os.path.isfile(self._insar.amplitude):
|
||||
# os.symlink(os.path.join('../', frameDir, self._insar.amplitude), self._insar.amplitude)
|
||||
# shutil.copy2(os.path.join('../', frameDir, self._insar.amplitude+'.vrt'), self._insar.amplitude+'.vrt')
|
||||
# shutil.copy2(os.path.join('../', frameDir, self._insar.amplitude+'.xml'), self._insar.amplitude+'.xml')
|
||||
|
||||
os.rename(os.path.join('../', frameDir, self._insar.interferogram), self._insar.interferogram)
|
||||
os.rename(os.path.join('../', frameDir, self._insar.interferogram+'.vrt'), self._insar.interferogram+'.vrt')
|
||||
os.rename(os.path.join('../', frameDir, self._insar.interferogram+'.xml'), self._insar.interferogram+'.xml')
|
||||
os.rename(os.path.join('../', frameDir, self._insar.amplitude), self._insar.amplitude)
|
||||
os.rename(os.path.join('../', frameDir, self._insar.amplitude+'.vrt'), self._insar.amplitude+'.vrt')
|
||||
os.rename(os.path.join('../', frameDir, self._insar.amplitude+'.xml'), self._insar.amplitude+'.xml')
|
||||
|
||||
else:
|
||||
#choose offsets
|
||||
if self.frameOffsetMatching:
|
||||
rangeOffsets = self._insar.frameRangeOffsetMatchingMaster
|
||||
azimuthOffsets = self._insar.frameAzimuthOffsetMatchingMaster
|
||||
else:
|
||||
rangeOffsets = self._insar.frameRangeOffsetGeometricalMaster
|
||||
azimuthOffsets = self._insar.frameAzimuthOffsetGeometricalMaster
|
||||
|
||||
#list of input files
|
||||
inputInterferograms = []
|
||||
inputAmplitudes = []
|
||||
for i, frameNumber in enumerate(self._insar.masterFrames):
|
||||
frameDir = 'f{}_{}'.format(i+1, frameNumber)
|
||||
inputInterferograms.append(os.path.join('../', frameDir, 'mosaic', self._insar.interferogram))
|
||||
inputAmplitudes.append(os.path.join('../', frameDir, 'mosaic', self._insar.amplitude))
|
||||
|
||||
#note that track parameters are updated after mosaicking
|
||||
#mosaic amplitudes
|
||||
frameMosaic(masterTrack, inputAmplitudes, self._insar.amplitude,
|
||||
rangeOffsets, azimuthOffsets, self._insar.numberRangeLooks1, self._insar.numberAzimuthLooks1,
|
||||
updateTrack=False, phaseCompensation=False, resamplingMethod=0)
|
||||
#mosaic interferograms
|
||||
frameMosaic(masterTrack, inputInterferograms, self._insar.interferogram,
|
||||
rangeOffsets, azimuthOffsets, self._insar.numberRangeLooks1, self._insar.numberAzimuthLooks1,
|
||||
updateTrack=False, phaseCompensation=True, resamplingMethod=1)
|
||||
|
||||
create_xml(self._insar.amplitude, masterTrack.numberOfSamples, masterTrack.numberOfLines, 'amp')
|
||||
create_xml(self._insar.interferogram, masterTrack.numberOfSamples, masterTrack.numberOfLines, 'int')
|
||||
|
||||
os.chdir('../')
|
||||
os.chdir('../')
|
||||
|
||||
|
||||
############################################################
|
||||
# STEP 5. clear frame processing files
|
||||
############################################################
|
||||
import shutil
|
||||
from isceobj.Alos2Proc.Alos2ProcPublic import runCmd
|
||||
|
||||
for k in range(2):
|
||||
os.chdir(ionDir['subband'][k])
|
||||
for i, frameNumber in enumerate(self._insar.masterFrames):
|
||||
frameDir = 'f{}_{}'.format(i+1, frameNumber)
|
||||
shutil.rmtree(frameDir)
|
||||
#cmd = 'rm -rf {}'.format(frameDir)
|
||||
#runCmd(cmd)
|
||||
os.chdir('../')
|
||||
|
||||
|
||||
############################################################
|
||||
# STEP 6. create differential interferograms
|
||||
############################################################
|
||||
import numpy as np
|
||||
from isceobj.Alos2Proc.Alos2ProcPublic import runCmd
|
||||
|
||||
for k in range(2):
|
||||
os.chdir(ionDir['subband'][k])
|
||||
|
||||
insarDir = ionDir['insar']
|
||||
if not os.path.exists(insarDir):
|
||||
os.makedirs(insarDir)
|
||||
os.chdir(insarDir)
|
||||
|
||||
rangePixelSize = self._insar.numberRangeLooks1 * masterTrack.rangePixelSize
|
||||
radarWavelength = subbandRadarWavelength[k]
|
||||
rectRangeOffset = os.path.join('../../../', insarDir, self._insar.rectRangeOffset)
|
||||
|
||||
cmd = "imageMath.py -e='a*exp(-1.0*J*b*4.0*{}*{}/{}) * (b!=0)' --a={} --b={} -o {} -t cfloat".format(np.pi, rangePixelSize, radarWavelength, self._insar.interferogram, rectRangeOffset, self._insar.differentialInterferogram)
|
||||
runCmd(cmd)
|
||||
|
||||
os.chdir('../../')
|
||||
|
||||
|
||||
os.chdir('../')
|
||||
catalog.printToLog(logger, "runIonSubband")
|
||||
self._insar.procDoc.addAllFromCatalog(catalog)
|
||||
|
||||
|
||||
def defineIonDir():
|
||||
'''
|
||||
define directory names for ionospheric correction
|
||||
'''
|
||||
|
||||
ionDir = {
|
||||
#swath mosaicking directory
|
||||
'swathMosaic' : 'mosaic',
|
||||
#final insar processing directory
|
||||
'insar' : 'insar',
|
||||
#ionospheric correction directory
|
||||
'ion' : 'ion',
|
||||
#subband directory
|
||||
'subband' : ['lower', 'upper'],
|
||||
#final ionospheric phase calculation directory
|
||||
'ionCal' : 'ion_cal'
|
||||
}
|
||||
|
||||
return ionDir
|
||||
|
||||
|
||||
def defineIonFilenames():
|
||||
pass
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
|
@ -0,0 +1,57 @@
|
|||
#
|
||||
# Author: Cunren Liang
|
||||
# Copyright 2015-present, NASA-JPL/Caltech
|
||||
#
|
||||
|
||||
import os
|
||||
import logging
|
||||
|
||||
import isceobj
|
||||
from isceobj.Alos2Proc.Alos2ProcPublic import create_xml
|
||||
from contrib.alos2proc.alos2proc import look
|
||||
from isceobj.Alos2Proc.Alos2ProcPublic import waterBodyRadar
|
||||
|
||||
logger = logging.getLogger('isce.alos2burstinsar.runLookSd')
|
||||
|
||||
def runLookSd(self):
|
||||
'''take looks
|
||||
'''
|
||||
catalog = isceobj.Catalog.createCatalog(self._insar.procDoc.name)
|
||||
self.updateParamemetersFromUser()
|
||||
|
||||
#masterTrack = self._insar.loadTrack(master=True)
|
||||
#slaveTrack = self._insar.loadTrack(master=False)
|
||||
wbdFile = os.path.abspath(self._insar.wbd)
|
||||
|
||||
sdDir = 'sd'
|
||||
if not os.path.exists(sdDir):
|
||||
os.makedirs(sdDir)
|
||||
os.chdir(sdDir)
|
||||
|
||||
sd = isceobj.createImage()
|
||||
sd.load(self._insar.interferogramSd[0]+'.xml')
|
||||
width = sd.width
|
||||
length = sd.length
|
||||
width2 = int(width / self._insar.numberRangeLooksSd)
|
||||
length2 = int(length / self._insar.numberAzimuthLooksSd)
|
||||
|
||||
if not ((self._insar.numberRangeLooksSd == 1) and (self._insar.numberAzimuthLooksSd == 1)):
|
||||
#take looks
|
||||
for sd, sdMultilook in zip(self._insar.interferogramSd, self._insar.multilookInterferogramSd):
|
||||
look(sd, sdMultilook, width, self._insar.numberRangeLooksSd, self._insar.numberAzimuthLooksSd, 4, 0, 1)
|
||||
create_xml(sdMultilook, width2, length2, 'int')
|
||||
look(os.path.join('../insar', self._insar.latitude), self._insar.multilookLatitudeSd, width,
|
||||
self._insar.numberRangeLooksSd, self._insar.numberAzimuthLooksSd, 3, 0, 1)
|
||||
look(os.path.join('../insar', self._insar.longitude), self._insar.multilookLongitudeSd, width,
|
||||
self._insar.numberRangeLooksSd, self._insar.numberAzimuthLooksSd, 3, 0, 1)
|
||||
create_xml(self._insar.multilookLatitudeSd, width2, length2, 'double')
|
||||
create_xml(self._insar.multilookLongitudeSd, width2, length2, 'double')
|
||||
#water body
|
||||
waterBodyRadar(self._insar.multilookLatitudeSd, self._insar.multilookLongitudeSd, wbdFile, self._insar.multilookWbdOutSd)
|
||||
|
||||
os.chdir('../')
|
||||
|
||||
catalog.printToLog(logger, "runLookSd")
|
||||
self._insar.procDoc.addAllFromCatalog(catalog)
|
||||
|
||||
|
||||
|
|
@ -0,0 +1,521 @@
|
|||
#
|
||||
# Author: Cunren Liang
|
||||
# Copyright 2015-present, NASA-JPL/Caltech
|
||||
#
|
||||
|
||||
import os
|
||||
import glob
|
||||
import logging
|
||||
import datetime
|
||||
import numpy as np
|
||||
|
||||
import isceobj
|
||||
import isceobj.Sensor.MultiMode as MultiMode
|
||||
from isceobj.Planet.Planet import Planet
|
||||
from isceobj.Alos2Proc.Alos2ProcPublic import runCmd
|
||||
from isceobj.Alos2Proc.Alos2ProcPublic import getBboxRdr
|
||||
from isceobj.Alos2Proc.Alos2ProcPublic import getBboxGeo
|
||||
|
||||
logger = logging.getLogger('isce.alos2burstinsar.runPreprocessor')
|
||||
|
||||
def runPreprocessor(self):
|
||||
'''Extract images.
|
||||
'''
|
||||
catalog = isceobj.Catalog.createCatalog(self._insar.procDoc.name)
|
||||
|
||||
|
||||
#find files
|
||||
#actually no need to use absolute path any longer, since we are able to find file from vrt now. 27-JAN-2020, CRL.
|
||||
#denseoffset may still need absolute path when making links
|
||||
self.masterDir = os.path.abspath(self.masterDir)
|
||||
self.slaveDir = os.path.abspath(self.slaveDir)
|
||||
|
||||
ledFilesMaster = sorted(glob.glob(os.path.join(self.masterDir, 'LED-ALOS2*-*-*')))
|
||||
imgFilesMaster = sorted(glob.glob(os.path.join(self.masterDir, 'IMG-{}-ALOS2*-*-*'.format(self.masterPolarization.upper()))))
|
||||
|
||||
ledFilesSlave = sorted(glob.glob(os.path.join(self.slaveDir, 'LED-ALOS2*-*-*')))
|
||||
imgFilesSlave = sorted(glob.glob(os.path.join(self.slaveDir, 'IMG-{}-ALOS2*-*-*'.format(self.slavePolarization.upper()))))
|
||||
|
||||
firstFrameMaster = ledFilesMaster[0].split('-')[-3][-4:]
|
||||
firstFrameSlave = ledFilesSlave[0].split('-')[-3][-4:]
|
||||
firstFrameImagesMaster = sorted(glob.glob(os.path.join(self.masterDir, 'IMG-{}-ALOS2*{}-*-*'.format(self.masterPolarization.upper(), firstFrameMaster))))
|
||||
firstFrameImagesSlave = sorted(glob.glob(os.path.join(self.slaveDir, 'IMG-{}-ALOS2*{}-*-*'.format(self.slavePolarization.upper(), firstFrameSlave))))
|
||||
|
||||
|
||||
#determin operation mode
|
||||
masterMode = os.path.basename(ledFilesMaster[0]).split('-')[-1][0:3]
|
||||
slaveMode = os.path.basename(ledFilesSlave[0]).split('-')[-1][0:3]
|
||||
spotlightModes = ['SBS']
|
||||
stripmapModes = ['UBS', 'UBD', 'HBS', 'HBD', 'HBQ', 'FBS', 'FBD', 'FBQ']
|
||||
scansarNominalModes = ['WBS', 'WBD', 'WWS', 'WWD']
|
||||
scansarWideModes = ['VBS', 'VBD']
|
||||
scansarModes = ['WBS', 'WBD', 'WWS', 'WWD', 'VBS', 'VBD']
|
||||
|
||||
#usable combinations
|
||||
if (masterMode in spotlightModes) and (slaveMode in spotlightModes):
|
||||
self._insar.modeCombination = 0
|
||||
elif (masterMode in stripmapModes) and (slaveMode in stripmapModes):
|
||||
self._insar.modeCombination = 1
|
||||
elif (masterMode in scansarNominalModes) and (slaveMode in scansarNominalModes):
|
||||
self._insar.modeCombination = 21
|
||||
elif (masterMode in scansarWideModes) and (slaveMode in scansarWideModes):
|
||||
self._insar.modeCombination = 22
|
||||
elif (masterMode in scansarNominalModes) and (slaveMode in stripmapModes):
|
||||
self._insar.modeCombination = 31
|
||||
elif (masterMode in scansarWideModes) and (slaveMode in stripmapModes):
|
||||
self._insar.modeCombination = 32
|
||||
else:
|
||||
print('\n\nthis mode combination is not possible')
|
||||
print('note that for ScanSAR-stripmap, ScanSAR must be master\n\n')
|
||||
raise Exception('mode combination not supported')
|
||||
|
||||
|
||||
if self._insar.modeCombination != 21:
|
||||
print('\n\nburst processing only support {}\n\n'.format(scansarNominalModes))
|
||||
raise Exception('mode combination not supported')
|
||||
|
||||
|
||||
#determine default number of looks:
|
||||
self._insar.numberRangeLooks1 = self.numberRangeLooks1
|
||||
self._insar.numberAzimuthLooks1 = self.numberAzimuthLooks1
|
||||
self._insar.numberRangeLooks2 = self.numberRangeLooks2
|
||||
self._insar.numberAzimuthLooks2 = self.numberAzimuthLooks2
|
||||
#the following two will be automatically determined by runRdrDemOffset.py
|
||||
self._insar.numberRangeLooksSim = self.numberRangeLooksSim
|
||||
self._insar.numberAzimuthLooksSim = self.numberAzimuthLooksSim
|
||||
self._insar.numberRangeLooksIon = self.numberRangeLooksIon
|
||||
self._insar.numberAzimuthLooksIon = self.numberAzimuthLooksIon
|
||||
self._insar.numberRangeLooksSd = self.numberRangeLooksSd
|
||||
self._insar.numberAzimuthLooksSd = self.numberAzimuthLooksSd
|
||||
|
||||
#force number of looks 1 to 1
|
||||
self.numberRangeLooks1 = 1
|
||||
self.numberAzimuthLooks1 = 1
|
||||
self._insar.numberRangeLooks1 = 1
|
||||
self._insar.numberAzimuthLooks1 = 1
|
||||
if self._insar.numberRangeLooks2 == None:
|
||||
self._insar.numberRangeLooks2 = 7
|
||||
if self._insar.numberAzimuthLooks2 == None:
|
||||
self._insar.numberAzimuthLooks2 = 2
|
||||
if self._insar.numberRangeLooksIon == None:
|
||||
self._insar.numberRangeLooksIon = 42
|
||||
if self._insar.numberAzimuthLooksIon == None:
|
||||
self._insar.numberAzimuthLooksIon = 12
|
||||
if self._insar.numberRangeLooksSd == None:
|
||||
self._insar.numberRangeLooksSd = 14
|
||||
if self._insar.numberAzimuthLooksSd == None:
|
||||
self._insar.numberAzimuthLooksSd = 4
|
||||
|
||||
#define processing file names
|
||||
self._insar.masterDate = os.path.basename(ledFilesMaster[0]).split('-')[2]
|
||||
self._insar.slaveDate = os.path.basename(ledFilesSlave[0]).split('-')[2]
|
||||
self._insar.setFilename(masterDate=self._insar.masterDate, slaveDate=self._insar.slaveDate,
|
||||
nrlks1=self._insar.numberRangeLooks1, nalks1=self._insar.numberAzimuthLooks1,
|
||||
nrlks2=self._insar.numberRangeLooks2, nalks2=self._insar.numberAzimuthLooks2)
|
||||
self._insar.setFilenameSd(masterDate=self._insar.masterDate, slaveDate=self._insar.slaveDate,
|
||||
nrlks1=self._insar.numberRangeLooks1, nalks1=self._insar.numberAzimuthLooks1,
|
||||
nrlks_sd=self._insar.numberRangeLooksSd, nalks_sd=self._insar.numberAzimuthLooksSd, nsd=3)
|
||||
|
||||
#find frame numbers
|
||||
if (self._insar.modeCombination == 31) or (self._insar.modeCombination == 32):
|
||||
if (self.masterFrames == None) or (self.slaveFrames == None):
|
||||
raise Exception('for ScanSAR-stripmap inteferometry, you must set master and slave frame numbers')
|
||||
#if not set, find frames automatically
|
||||
if self.masterFrames == None:
|
||||
self.masterFrames = []
|
||||
for led in ledFilesMaster:
|
||||
frameNumber = os.path.basename(led).split('-')[1][-4:]
|
||||
if frameNumber not in self.masterFrames:
|
||||
self.masterFrames.append(frameNumber)
|
||||
if self.slaveFrames == None:
|
||||
self.slaveFrames = []
|
||||
for led in ledFilesSlave:
|
||||
frameNumber = os.path.basename(led).split('-')[1][-4:]
|
||||
if frameNumber not in self.slaveFrames:
|
||||
self.slaveFrames.append(frameNumber)
|
||||
#sort frames
|
||||
self.masterFrames = sorted(self.masterFrames)
|
||||
self.slaveFrames = sorted(self.slaveFrames)
|
||||
#check number of frames
|
||||
if len(self.masterFrames) != len(self.slaveFrames):
|
||||
raise Exception('number of frames in master dir is not equal to number of frames \
|
||||
in slave dir. please set frame number manually')
|
||||
|
||||
|
||||
#find swath numbers (if not ScanSAR-ScanSAR, compute valid swaths)
|
||||
if (self._insar.modeCombination == 0) or (self._insar.modeCombination == 1):
|
||||
self.startingSwath = 1
|
||||
self.endingSwath = 1
|
||||
|
||||
if self._insar.modeCombination == 21:
|
||||
if self.startingSwath == None:
|
||||
self.startingSwath = 1
|
||||
if self.endingSwath == None:
|
||||
self.endingSwath = 5
|
||||
|
||||
if self._insar.modeCombination == 22:
|
||||
if self.startingSwath == None:
|
||||
self.startingSwath = 1
|
||||
if self.endingSwath == None:
|
||||
self.endingSwath = 7
|
||||
|
||||
#determine starting and ending swaths for ScanSAR-stripmap, user's settings are overwritten
|
||||
#use first frame to check overlap
|
||||
if (self._insar.modeCombination == 31) or (self._insar.modeCombination == 32):
|
||||
if self._insar.modeCombination == 31:
|
||||
numberOfSwaths = 5
|
||||
else:
|
||||
numberOfSwaths = 7
|
||||
overlapSubswaths = []
|
||||
for i in range(numberOfSwaths):
|
||||
overlapRatio = check_overlap(ledFilesMaster[0], firstFrameImagesMaster[i], ledFilesSlave[0], firstFrameImagesSlave[0])
|
||||
if overlapRatio > 1.0 / 4.0:
|
||||
overlapSubswaths.append(i+1)
|
||||
if overlapSubswaths == []:
|
||||
raise Exception('There is no overlap area between the ScanSAR-stripmap pair')
|
||||
self.startingSwath = int(overlapSubswaths[0])
|
||||
self.endingSwath = int(overlapSubswaths[-1])
|
||||
|
||||
#save the valid frames and swaths for future processing
|
||||
self._insar.masterFrames = self.masterFrames
|
||||
self._insar.slaveFrames = self.slaveFrames
|
||||
self._insar.startingSwath = self.startingSwath
|
||||
self._insar.endingSwath = self.endingSwath
|
||||
|
||||
|
||||
##################################################
|
||||
#1. create directories and read data
|
||||
##################################################
|
||||
self.master.configure()
|
||||
self.slave.configure()
|
||||
self.master.track.configure()
|
||||
self.slave.track.configure()
|
||||
for i, (masterFrame, slaveFrame) in enumerate(zip(self._insar.masterFrames, self._insar.slaveFrames)):
|
||||
#frame number starts with 1
|
||||
frameDir = 'f{}_{}'.format(i+1, masterFrame)
|
||||
if not os.path.exists(frameDir):
|
||||
os.makedirs(frameDir)
|
||||
os.chdir(frameDir)
|
||||
|
||||
#attach a frame to master and slave
|
||||
frameObjMaster = MultiMode.createFrame()
|
||||
frameObjSlave = MultiMode.createFrame()
|
||||
frameObjMaster.configure()
|
||||
frameObjSlave.configure()
|
||||
self.master.track.frames.append(frameObjMaster)
|
||||
self.slave.track.frames.append(frameObjSlave)
|
||||
|
||||
#swath number starts with 1
|
||||
for j in range(self._insar.startingSwath, self._insar.endingSwath+1):
|
||||
print('processing frame {} swath {}'.format(masterFrame, j))
|
||||
|
||||
swathDir = 's{}'.format(j)
|
||||
if not os.path.exists(swathDir):
|
||||
os.makedirs(swathDir)
|
||||
os.chdir(swathDir)
|
||||
|
||||
#attach a swath to master and slave
|
||||
swathObjMaster = MultiMode.createSwath()
|
||||
swathObjSlave = MultiMode.createSwath()
|
||||
swathObjMaster.configure()
|
||||
swathObjSlave.configure()
|
||||
self.master.track.frames[-1].swaths.append(swathObjMaster)
|
||||
self.slave.track.frames[-1].swaths.append(swathObjSlave)
|
||||
|
||||
#setup master
|
||||
self.master.leaderFile = sorted(glob.glob(os.path.join(self.masterDir, 'LED-ALOS2*{}-*-*'.format(masterFrame))))[0]
|
||||
if masterMode in scansarModes:
|
||||
self.master.imageFile = sorted(glob.glob(os.path.join(self.masterDir, 'IMG-{}-ALOS2*{}-*-*-F{}'.format(self.masterPolarization.upper(), masterFrame, j))))[0]
|
||||
else:
|
||||
self.master.imageFile = sorted(glob.glob(os.path.join(self.masterDir, 'IMG-{}-ALOS2*{}-*-*'.format(self.masterPolarization.upper(), masterFrame))))[0]
|
||||
self.master.outputFile = self._insar.masterSlc
|
||||
self.master.useVirtualFile = self.useVirtualFile
|
||||
#read master
|
||||
(imageFDR, imageData)=self.master.readImage()
|
||||
(leaderFDR, sceneHeaderRecord, platformPositionRecord, facilityRecord)=self.master.readLeader()
|
||||
self.master.setSwath(leaderFDR, sceneHeaderRecord, platformPositionRecord, facilityRecord, imageFDR, imageData)
|
||||
self.master.setFrame(leaderFDR, sceneHeaderRecord, platformPositionRecord, facilityRecord, imageFDR, imageData)
|
||||
self.master.setTrack(leaderFDR, sceneHeaderRecord, platformPositionRecord, facilityRecord, imageFDR, imageData)
|
||||
|
||||
#setup slave
|
||||
self.slave.leaderFile = sorted(glob.glob(os.path.join(self.slaveDir, 'LED-ALOS2*{}-*-*'.format(slaveFrame))))[0]
|
||||
if slaveMode in scansarModes:
|
||||
self.slave.imageFile = sorted(glob.glob(os.path.join(self.slaveDir, 'IMG-{}-ALOS2*{}-*-*-F{}'.format(self.slavePolarization.upper(), slaveFrame, j))))[0]
|
||||
else:
|
||||
self.slave.imageFile = sorted(glob.glob(os.path.join(self.slaveDir, 'IMG-{}-ALOS2*{}-*-*'.format(self.slavePolarization.upper(), slaveFrame))))[0]
|
||||
self.slave.outputFile = self._insar.slaveSlc
|
||||
self.slave.useVirtualFile = self.useVirtualFile
|
||||
#read slave
|
||||
(imageFDR, imageData)=self.slave.readImage()
|
||||
(leaderFDR, sceneHeaderRecord, platformPositionRecord, facilityRecord)=self.slave.readLeader()
|
||||
self.slave.setSwath(leaderFDR, sceneHeaderRecord, platformPositionRecord, facilityRecord, imageFDR, imageData)
|
||||
self.slave.setFrame(leaderFDR, sceneHeaderRecord, platformPositionRecord, facilityRecord, imageFDR, imageData)
|
||||
self.slave.setTrack(leaderFDR, sceneHeaderRecord, platformPositionRecord, facilityRecord, imageFDR, imageData)
|
||||
|
||||
os.chdir('../')
|
||||
self._insar.saveProduct(self.master.track.frames[-1], self._insar.masterFrameParameter)
|
||||
self._insar.saveProduct(self.slave.track.frames[-1], self._insar.slaveFrameParameter)
|
||||
os.chdir('../')
|
||||
self._insar.saveProduct(self.master.track, self._insar.masterTrackParameter)
|
||||
self._insar.saveProduct(self.slave.track, self._insar.slaveTrackParameter)
|
||||
|
||||
|
||||
##################################################
|
||||
#2. compute burst synchronization
|
||||
##################################################
|
||||
#burst synchronization may slowly change along a track as a result of the changing relative speed of the two flights
|
||||
#in one frame, real unsynchronized time is the same for all swaths
|
||||
unsynTime = 0
|
||||
#real synchronized time/percentage depends on the swath burst length (synTime = burstlength - abs(unsynTime))
|
||||
#synTime = 0
|
||||
synPercentage = 0
|
||||
|
||||
numberOfFrames = len(self._insar.masterFrames)
|
||||
numberOfSwaths = self._insar.endingSwath - self._insar.startingSwath + 1
|
||||
|
||||
for i, frameNumber in enumerate(self._insar.masterFrames):
|
||||
for j, swathNumber in enumerate(range(self._insar.startingSwath, self._insar.endingSwath + 1)):
|
||||
masterSwath = self.master.track.frames[i].swaths[j]
|
||||
slaveSwath = self.slave.track.frames[i].swaths[j]
|
||||
#using Piyush's code for computing range and azimuth offsets
|
||||
midRange = masterSwath.startingRange + masterSwath.rangePixelSize * masterSwath.numberOfSamples * 0.5
|
||||
midSensingStart = masterSwath.sensingStart + datetime.timedelta(seconds = masterSwath.numberOfLines * 0.5 / masterSwath.prf)
|
||||
llh = self.master.track.orbit.rdr2geo(midSensingStart, midRange)
|
||||
slvaz, slvrng = self.slave.track.orbit.geo2rdr(llh)
|
||||
###Translate to offsets
|
||||
#note that slave range pixel size and prf might be different from master, here we assume there is a virtual slave with same
|
||||
#range pixel size and prf
|
||||
rgoff = ((slvrng - slaveSwath.startingRange) / masterSwath.rangePixelSize) - masterSwath.numberOfSamples * 0.5
|
||||
azoff = ((slvaz - slaveSwath.sensingStart).total_seconds() * masterSwath.prf) - masterSwath.numberOfLines * 0.5
|
||||
|
||||
#compute burst synchronization
|
||||
#burst parameters for ScanSAR wide mode not estimed yet
|
||||
if self._insar.modeCombination == 21:
|
||||
scburstStartLine = (masterSwath.burstStartTime - masterSwath.sensingStart).total_seconds() * masterSwath.prf + azoff
|
||||
#slave burst start times corresponding to master burst start times (100% synchronization)
|
||||
scburstStartLines = np.arange(scburstStartLine - 100000*masterSwath.burstCycleLength, \
|
||||
scburstStartLine + 100000*masterSwath.burstCycleLength, \
|
||||
masterSwath.burstCycleLength)
|
||||
dscburstStartLines = -((slaveSwath.burstStartTime - slaveSwath.sensingStart).total_seconds() * slaveSwath.prf - scburstStartLines)
|
||||
#find the difference with minimum absolute value
|
||||
unsynLines = dscburstStartLines[np.argmin(np.absolute(dscburstStartLines))]
|
||||
if np.absolute(unsynLines) >= slaveSwath.burstLength:
|
||||
synLines = 0
|
||||
if unsynLines > 0:
|
||||
unsynLines = slaveSwath.burstLength
|
||||
else:
|
||||
unsynLines = -slaveSwath.burstLength
|
||||
else:
|
||||
synLines = slaveSwath.burstLength - np.absolute(unsynLines)
|
||||
|
||||
unsynTime += unsynLines / masterSwath.prf
|
||||
synPercentage += synLines / masterSwath.burstLength * 100.0
|
||||
|
||||
catalog.addItem('burst synchronization of frame {} swath {}'.format(frameNumber, swathNumber), '%.1f%%'%(synLines / masterSwath.burstLength * 100.0), 'runPreprocessor')
|
||||
|
||||
############################################################################################
|
||||
#illustration of the sign of the number of unsynchronized lines (unsynLines)
|
||||
#The convention is the same as ampcor offset, that is,
|
||||
# slaveLineNumber = masterLineNumber + unsynLines
|
||||
#
|
||||
# |-----------------------| ------------
|
||||
# | | ^
|
||||
# | | |
|
||||
# | | | unsynLines < 0
|
||||
# | | |
|
||||
# | | \ /
|
||||
# | | |-----------------------|
|
||||
# | | | |
|
||||
# | | | |
|
||||
# |-----------------------| | |
|
||||
# Master Burst | |
|
||||
# | |
|
||||
# | |
|
||||
# | |
|
||||
# | |
|
||||
# |-----------------------|
|
||||
# Slave Burst
|
||||
#
|
||||
#
|
||||
############################################################################################
|
||||
|
||||
##burst parameters for ScanSAR wide mode not estimed yet
|
||||
elif self._insar.modeCombination == 31:
|
||||
#scansar is master
|
||||
scburstStartLine = (masterSwath.burstStartTime - masterSwath.sensingStart).total_seconds() * masterSwath.prf + azoff
|
||||
#slave burst start times corresponding to master burst start times (100% synchronization)
|
||||
for k in range(-100000, 100000):
|
||||
saz_burstx = scburstStartLine + masterSwath.burstCycleLength * k
|
||||
st_burstx = slaveSwath.sensingStart + datetime.timedelta(seconds=saz_burstx / masterSwath.prf)
|
||||
if saz_burstx >= 0.0 and saz_burstx <= slaveSwath.numberOfLines -1:
|
||||
slaveSwath.burstStartTime = st_burstx
|
||||
slaveSwath.burstLength = masterSwath.burstLength
|
||||
slaveSwath.burstCycleLength = masterSwath.burstCycleLength
|
||||
slaveSwath.swathNumber = masterSwath.swathNumber
|
||||
break
|
||||
#unsynLines = 0
|
||||
#synLines = masterSwath.burstLength
|
||||
#unsynTime += unsynLines / masterSwath.prf
|
||||
#synPercentage += synLines / masterSwath.burstLength * 100.0
|
||||
catalog.addItem('burst synchronization of frame {} swath {}'.format(frameNumber, swathNumber), '%.1f%%'%(100.0), 'runPreprocessor')
|
||||
else:
|
||||
pass
|
||||
|
||||
#overwrite original frame parameter file
|
||||
if self._insar.modeCombination == 31:
|
||||
frameDir = 'f{}_{}'.format(i+1, frameNumber)
|
||||
self._insar.saveProduct(self.slave.track.frames[i], os.path.join(frameDir, self._insar.slaveFrameParameter))
|
||||
|
||||
#getting average
|
||||
if self._insar.modeCombination == 21:
|
||||
unsynTime /= numberOfFrames*numberOfSwaths
|
||||
synPercentage /= numberOfFrames*numberOfSwaths
|
||||
elif self._insar.modeCombination == 31:
|
||||
unsynTime = 0.
|
||||
synPercentage = 100.
|
||||
else:
|
||||
pass
|
||||
|
||||
#record results
|
||||
if (self._insar.modeCombination == 21) or (self._insar.modeCombination == 31):
|
||||
self._insar.burstUnsynchronizedTime = unsynTime
|
||||
self._insar.burstSynchronization = synPercentage
|
||||
catalog.addItem('burst synchronization averaged', '%.1f%%'%(synPercentage), 'runPreprocessor')
|
||||
|
||||
|
||||
##################################################
|
||||
#3. compute baseline
|
||||
##################################################
|
||||
#only compute baseline at four corners and center of the master track
|
||||
bboxRdr = getBboxRdr(self.master.track)
|
||||
|
||||
rangeMin = bboxRdr[0]
|
||||
rangeMax = bboxRdr[1]
|
||||
azimuthTimeMin = bboxRdr[2]
|
||||
azimuthTimeMax = bboxRdr[3]
|
||||
|
||||
azimuthTimeMid = azimuthTimeMin+datetime.timedelta(seconds=(azimuthTimeMax-azimuthTimeMin).total_seconds()/2.0)
|
||||
rangeMid = (rangeMin + rangeMax) / 2.0
|
||||
|
||||
points = [[azimuthTimeMin, rangeMin],
|
||||
[azimuthTimeMin, rangeMax],
|
||||
[azimuthTimeMax, rangeMin],
|
||||
[azimuthTimeMax, rangeMax],
|
||||
[azimuthTimeMid, rangeMid]]
|
||||
|
||||
Bpar = []
|
||||
Bperp = []
|
||||
#modify Piyush's code for computing baslines
|
||||
refElp = Planet(pname='Earth').ellipsoid
|
||||
for x in points:
|
||||
masterSV = self.master.track.orbit.interpolate(x[0], method='hermite')
|
||||
target = self.master.track.orbit.rdr2geo(x[0], x[1])
|
||||
|
||||
slvTime, slvrng = self.slave.track.orbit.geo2rdr(target)
|
||||
slaveSV = self.slave.track.orbit.interpolateOrbit(slvTime, method='hermite')
|
||||
|
||||
targxyz = np.array(refElp.LLH(target[0], target[1], target[2]).ecef().tolist())
|
||||
mxyz = np.array(masterSV.getPosition())
|
||||
mvel = np.array(masterSV.getVelocity())
|
||||
sxyz = np.array(slaveSV.getPosition())
|
||||
|
||||
aa = np.linalg.norm(sxyz-mxyz)
|
||||
costheta = (x[1]*x[1] + aa*aa - slvrng*slvrng)/(2.*x[1]*aa)
|
||||
|
||||
Bpar.append(aa*costheta)
|
||||
|
||||
perp = aa * np.sqrt(1 - costheta*costheta)
|
||||
direction = np.sign(np.dot( np.cross(targxyz-mxyz, sxyz-mxyz), mvel))
|
||||
Bperp.append(direction*perp)
|
||||
|
||||
catalog.addItem('parallel baseline at upperleft of master track', Bpar[0], 'runPreprocessor')
|
||||
catalog.addItem('parallel baseline at upperright of master track', Bpar[1], 'runPreprocessor')
|
||||
catalog.addItem('parallel baseline at lowerleft of master track', Bpar[2], 'runPreprocessor')
|
||||
catalog.addItem('parallel baseline at lowerright of master track', Bpar[3], 'runPreprocessor')
|
||||
catalog.addItem('parallel baseline at center of master track', Bpar[4], 'runPreprocessor')
|
||||
|
||||
catalog.addItem('perpendicular baseline at upperleft of master track', Bperp[0], 'runPreprocessor')
|
||||
catalog.addItem('perpendicular baseline at upperright of master track', Bperp[1], 'runPreprocessor')
|
||||
catalog.addItem('perpendicular baseline at lowerleft of master track', Bperp[2], 'runPreprocessor')
|
||||
catalog.addItem('perpendicular baseline at lowerright of master track', Bperp[3], 'runPreprocessor')
|
||||
catalog.addItem('perpendicular baseline at center of master track', Bperp[4], 'runPreprocessor')
|
||||
|
||||
|
||||
##################################################
|
||||
#4. compute bounding box
|
||||
##################################################
|
||||
masterBbox = getBboxGeo(self.master.track)
|
||||
slaveBbox = getBboxGeo(self.slave.track)
|
||||
|
||||
catalog.addItem('master bounding box', masterBbox, 'runPreprocessor')
|
||||
catalog.addItem('slave bounding box', slaveBbox, 'runPreprocessor')
|
||||
|
||||
|
||||
catalog.printToLog(logger, "runPreprocessor")
|
||||
self._insar.procDoc.addAllFromCatalog(catalog)
|
||||
|
||||
|
||||
|
||||
def check_overlap(ldr_m, img_m, ldr_s, img_s):
|
||||
from isceobj.Constants import SPEED_OF_LIGHT
|
||||
|
||||
rangeSamplingRateMaster, widthMaster, nearRangeMaster = read_param_for_checking_overlap(ldr_m, img_m)
|
||||
rangeSamplingRateSlave, widthSlave, nearRangeSlave = read_param_for_checking_overlap(ldr_s, img_s)
|
||||
|
||||
farRangeMaster = nearRangeMaster + (widthMaster-1) * 0.5 * SPEED_OF_LIGHT / rangeSamplingRateMaster
|
||||
farRangeSlave = nearRangeSlave + (widthSlave-1) * 0.5 * SPEED_OF_LIGHT / rangeSamplingRateSlave
|
||||
|
||||
#This should be good enough, although precise image offsets are not used.
|
||||
if farRangeMaster <= nearRangeSlave:
|
||||
overlapRatio = 0.0
|
||||
elif farRangeSlave <= nearRangeMaster:
|
||||
overlapRatio = 0.0
|
||||
else:
|
||||
# 0 1 2 3
|
||||
ranges = np.array([nearRangeMaster, farRangeMaster, nearRangeSlave, farRangeSlave])
|
||||
rangesIndex = np.argsort(ranges)
|
||||
overlapRatio = ranges[rangesIndex[2]]-ranges[rangesIndex[1]] / (farRangeMaster-nearRangeMaster)
|
||||
|
||||
return overlapRatio
|
||||
|
||||
|
||||
def read_param_for_checking_overlap(leader_file, image_file):
|
||||
from isceobj.Sensor import xmlPrefix
|
||||
import isceobj.Sensor.CEOS as CEOS
|
||||
|
||||
#read from leader file
|
||||
fsampConst = { 104: 1.047915957140240E+08,
|
||||
52: 5.239579785701190E+07,
|
||||
34: 3.493053190467460E+07,
|
||||
17: 1.746526595233730E+07 }
|
||||
|
||||
fp = open(leader_file,'rb')
|
||||
leaderFDR = CEOS.CEOSDB(xml=os.path.join(xmlPrefix,'alos2_slc/leader_file.xml'),dataFile=fp)
|
||||
leaderFDR.parse()
|
||||
fp.seek(leaderFDR.getEndOfRecordPosition())
|
||||
sceneHeaderRecord = CEOS.CEOSDB(xml=os.path.join(xmlPrefix,'alos2_slc/scene_record.xml'),dataFile=fp)
|
||||
sceneHeaderRecord.parse()
|
||||
fp.seek(sceneHeaderRecord.getEndOfRecordPosition())
|
||||
|
||||
fsamplookup = int(sceneHeaderRecord.metadata['Range sampling rate in MHz'])
|
||||
rangeSamplingRate = fsampConst[fsamplookup]
|
||||
fp.close()
|
||||
#print('{}'.format(rangeSamplingRate))
|
||||
|
||||
#read from image file
|
||||
fp = open(image_file, 'rb')
|
||||
imageFDR = CEOS.CEOSDB(xml=os.path.join(xmlPrefix,'alos2_slc/image_file.xml'), dataFile=fp)
|
||||
imageFDR.parse()
|
||||
fp.seek(imageFDR.getEndOfRecordPosition())
|
||||
imageData = CEOS.CEOSDB(xml=os.path.join(xmlPrefix,'alos2_slc/image_record.xml'), dataFile=fp)
|
||||
imageData.parseFast()
|
||||
|
||||
width = imageFDR.metadata['Number of pixels per line per SAR channel']
|
||||
near_range = imageData.metadata['Slant range to 1st data sample']
|
||||
fp.close()
|
||||
#print('{}'.format(width))
|
||||
#print('{}'.format(near_range))
|
||||
|
||||
return (rangeSamplingRate, width, near_range)
|
||||
|
||||
|
||||
|
|
@ -0,0 +1,221 @@
|
|||
#
|
||||
# Author: Cunren Liang
|
||||
# Copyright 2015-present, NASA-JPL/Caltech
|
||||
#
|
||||
|
||||
import os
|
||||
import logging
|
||||
|
||||
import isceobj
|
||||
from isceobj.Alos2Proc.runSwathMosaic import swathMosaic
|
||||
from isceobj.Alos2Proc.runSwathMosaic import swathMosaicParameters
|
||||
from isceobj.Alos2Proc.Alos2ProcPublic import create_xml
|
||||
|
||||
logger = logging.getLogger('isce.alos2burstinsar.runSwathMosaic')
|
||||
|
||||
def runSwathMosaic(self):
|
||||
'''mosaic subswaths
|
||||
'''
|
||||
catalog = isceobj.Catalog.createCatalog(self._insar.procDoc.name)
|
||||
self.updateParamemetersFromUser()
|
||||
|
||||
masterTrack = self._insar.loadTrack(master=True)
|
||||
slaveTrack = self._insar.loadTrack(master=False)
|
||||
|
||||
|
||||
for i, frameNumber in enumerate(self._insar.masterFrames):
|
||||
frameDir = 'f{}_{}'.format(i+1, frameNumber)
|
||||
os.chdir(frameDir)
|
||||
|
||||
mosaicDir = 'mosaic'
|
||||
if not os.path.exists(mosaicDir):
|
||||
os.makedirs(mosaicDir)
|
||||
os.chdir(mosaicDir)
|
||||
|
||||
if self._insar.endingSwath-self._insar.startingSwath+1 == 1:
|
||||
import shutil
|
||||
swathDir = 's{}'.format(masterTrack.frames[i].swaths[0].swathNumber)
|
||||
|
||||
if not os.path.isfile(self._insar.interferogram):
|
||||
os.symlink(os.path.join('../', swathDir, self._insar.interferogram), self._insar.interferogram)
|
||||
shutil.copy2(os.path.join('../', swathDir, self._insar.interferogram+'.vrt'), self._insar.interferogram+'.vrt')
|
||||
shutil.copy2(os.path.join('../', swathDir, self._insar.interferogram+'.xml'), self._insar.interferogram+'.xml')
|
||||
if not os.path.isfile(self._insar.amplitude):
|
||||
os.symlink(os.path.join('../', swathDir, self._insar.amplitude), self._insar.amplitude)
|
||||
shutil.copy2(os.path.join('../', swathDir, self._insar.amplitude+'.vrt'), self._insar.amplitude+'.vrt')
|
||||
shutil.copy2(os.path.join('../', swathDir, self._insar.amplitude+'.xml'), self._insar.amplitude+'.xml')
|
||||
|
||||
# os.rename(os.path.join('../', swathDir, self._insar.interferogram), self._insar.interferogram)
|
||||
# os.rename(os.path.join('../', swathDir, self._insar.interferogram+'.vrt'), self._insar.interferogram+'.vrt')
|
||||
# os.rename(os.path.join('../', swathDir, self._insar.interferogram+'.xml'), self._insar.interferogram+'.xml')
|
||||
# os.rename(os.path.join('../', swathDir, self._insar.amplitude), self._insar.amplitude)
|
||||
# os.rename(os.path.join('../', swathDir, self._insar.amplitude+'.vrt'), self._insar.amplitude+'.vrt')
|
||||
# os.rename(os.path.join('../', swathDir, self._insar.amplitude+'.xml'), self._insar.amplitude+'.xml')
|
||||
|
||||
#update frame parameters
|
||||
#########################################################
|
||||
frame = masterTrack.frames[i]
|
||||
infImg = isceobj.createImage()
|
||||
infImg.load(self._insar.interferogram+'.xml')
|
||||
#mosaic size
|
||||
frame.numberOfSamples = infImg.width
|
||||
frame.numberOfLines = infImg.length
|
||||
#NOTE THAT WE ARE STILL USING SINGLE LOOK PARAMETERS HERE
|
||||
#range parameters
|
||||
frame.startingRange = frame.swaths[0].startingRange
|
||||
frame.rangeSamplingRate = frame.swaths[0].rangeSamplingRate
|
||||
frame.rangePixelSize = frame.swaths[0].rangePixelSize
|
||||
#azimuth parameters
|
||||
frame.sensingStart = frame.swaths[0].sensingStart
|
||||
frame.prf = frame.swaths[0].prf
|
||||
frame.azimuthPixelSize = frame.swaths[0].azimuthPixelSize
|
||||
frame.azimuthLineInterval = frame.swaths[0].azimuthLineInterval
|
||||
|
||||
#update frame parameters, slave
|
||||
#########################################################
|
||||
frame = slaveTrack.frames[i]
|
||||
#mosaic size
|
||||
frame.numberOfSamples = int(frame.swaths[0].numberOfSamples/self._insar.numberRangeLooks1)
|
||||
frame.numberOfLines = int(frame.swaths[0].numberOfLines/self._insar.numberAzimuthLooks1)
|
||||
#NOTE THAT WE ARE STILL USING SINGLE LOOK PARAMETERS HERE
|
||||
#range parameters
|
||||
frame.startingRange = frame.swaths[0].startingRange
|
||||
frame.rangeSamplingRate = frame.swaths[0].rangeSamplingRate
|
||||
frame.rangePixelSize = frame.swaths[0].rangePixelSize
|
||||
#azimuth parameters
|
||||
frame.sensingStart = frame.swaths[0].sensingStart
|
||||
frame.prf = frame.swaths[0].prf
|
||||
frame.azimuthPixelSize = frame.swaths[0].azimuthPixelSize
|
||||
frame.azimuthLineInterval = frame.swaths[0].azimuthLineInterval
|
||||
|
||||
os.chdir('../')
|
||||
|
||||
#save parameter file
|
||||
self._insar.saveProduct(masterTrack.frames[i], self._insar.masterFrameParameter)
|
||||
self._insar.saveProduct(slaveTrack.frames[i], self._insar.slaveFrameParameter)
|
||||
|
||||
os.chdir('../')
|
||||
|
||||
continue
|
||||
|
||||
#choose offsets
|
||||
numberOfFrames = len(masterTrack.frames)
|
||||
numberOfSwaths = len(masterTrack.frames[i].swaths)
|
||||
if self.swathOffsetMatching:
|
||||
#no need to do this as the API support 2-d list
|
||||
#rangeOffsets = (np.array(self._insar.swathRangeOffsetMatchingMaster)).reshape(numberOfFrames, numberOfSwaths)
|
||||
#azimuthOffsets = (np.array(self._insar.swathAzimuthOffsetMatchingMaster)).reshape(numberOfFrames, numberOfSwaths)
|
||||
rangeOffsets = self._insar.swathRangeOffsetMatchingMaster
|
||||
azimuthOffsets = self._insar.swathAzimuthOffsetMatchingMaster
|
||||
|
||||
else:
|
||||
#rangeOffsets = (np.array(self._insar.swathRangeOffsetGeometricalMaster)).reshape(numberOfFrames, numberOfSwaths)
|
||||
#azimuthOffsets = (np.array(self._insar.swathAzimuthOffsetGeometricalMaster)).reshape(numberOfFrames, numberOfSwaths)
|
||||
rangeOffsets = self._insar.swathRangeOffsetGeometricalMaster
|
||||
azimuthOffsets = self._insar.swathAzimuthOffsetGeometricalMaster
|
||||
|
||||
rangeOffsets = rangeOffsets[i]
|
||||
azimuthOffsets = azimuthOffsets[i]
|
||||
|
||||
#list of input files
|
||||
inputInterferograms = []
|
||||
inputAmplitudes = []
|
||||
for j, swathNumber in enumerate(range(self._insar.startingSwath, self._insar.endingSwath + 1)):
|
||||
swathDir = 's{}'.format(swathNumber)
|
||||
inputInterferograms.append(os.path.join('../', swathDir, self._insar.interferogram))
|
||||
inputAmplitudes.append(os.path.join('../', swathDir, self._insar.amplitude))
|
||||
|
||||
#note that frame parameters are updated after mosaicking
|
||||
#mosaic amplitudes
|
||||
swathMosaic(masterTrack.frames[i], inputAmplitudes, self._insar.amplitude,
|
||||
rangeOffsets, azimuthOffsets, self._insar.numberRangeLooks1, self._insar.numberAzimuthLooks1, resamplingMethod=0)
|
||||
#mosaic interferograms
|
||||
swathMosaic(masterTrack.frames[i], inputInterferograms, self._insar.interferogram,
|
||||
rangeOffsets, azimuthOffsets, self._insar.numberRangeLooks1, self._insar.numberAzimuthLooks1, updateFrame=True, resamplingMethod=1)
|
||||
|
||||
create_xml(self._insar.amplitude, masterTrack.frames[i].numberOfSamples, masterTrack.frames[i].numberOfLines, 'amp')
|
||||
create_xml(self._insar.interferogram, masterTrack.frames[i].numberOfSamples, masterTrack.frames[i].numberOfLines, 'int')
|
||||
|
||||
#update slave frame parameters here
|
||||
#no matching for slave, always use geometry
|
||||
rangeOffsets = self._insar.swathRangeOffsetGeometricalSlave
|
||||
azimuthOffsets = self._insar.swathAzimuthOffsetGeometricalSlave
|
||||
rangeOffsets = rangeOffsets[i]
|
||||
azimuthOffsets = azimuthOffsets[i]
|
||||
swathMosaicParameters(slaveTrack.frames[i], rangeOffsets, azimuthOffsets, self._insar.numberRangeLooks1, self._insar.numberAzimuthLooks1)
|
||||
|
||||
os.chdir('../')
|
||||
|
||||
#save parameter file
|
||||
self._insar.saveProduct(masterTrack.frames[i], self._insar.masterFrameParameter)
|
||||
self._insar.saveProduct(slaveTrack.frames[i], self._insar.slaveFrameParameter)
|
||||
|
||||
os.chdir('../')
|
||||
|
||||
|
||||
#mosaic spectral diversity interferograms
|
||||
for i, frameNumber in enumerate(self._insar.masterFrames):
|
||||
frameDir = 'f{}_{}'.format(i+1, frameNumber)
|
||||
os.chdir(frameDir)
|
||||
|
||||
mosaicDir = 'mosaic'
|
||||
if not os.path.exists(mosaicDir):
|
||||
os.makedirs(mosaicDir)
|
||||
os.chdir(mosaicDir)
|
||||
|
||||
if self._insar.endingSwath-self._insar.startingSwath+1 == 1:
|
||||
import shutil
|
||||
swathDir = 's{}'.format(masterTrack.frames[i].swaths[0].swathNumber)
|
||||
|
||||
for sdFile in self._insar.interferogramSd:
|
||||
if not os.path.isfile(sdFile):
|
||||
os.symlink(os.path.join('../', swathDir, 'spectral_diversity', sdFile), sdFile)
|
||||
shutil.copy2(os.path.join('../', swathDir, 'spectral_diversity', sdFile+'.vrt'), sdFile+'.vrt')
|
||||
shutil.copy2(os.path.join('../', swathDir, 'spectral_diversity', sdFile+'.xml'), sdFile+'.xml')
|
||||
|
||||
os.chdir('../')
|
||||
os.chdir('../')
|
||||
continue
|
||||
|
||||
#choose offsets
|
||||
numberOfFrames = len(masterTrack.frames)
|
||||
numberOfSwaths = len(masterTrack.frames[i].swaths)
|
||||
if self.swathOffsetMatching:
|
||||
#no need to do this as the API support 2-d list
|
||||
#rangeOffsets = (np.array(self._insar.swathRangeOffsetMatchingMaster)).reshape(numberOfFrames, numberOfSwaths)
|
||||
#azimuthOffsets = (np.array(self._insar.swathAzimuthOffsetMatchingMaster)).reshape(numberOfFrames, numberOfSwaths)
|
||||
rangeOffsets = self._insar.swathRangeOffsetMatchingMaster
|
||||
azimuthOffsets = self._insar.swathAzimuthOffsetMatchingMaster
|
||||
|
||||
else:
|
||||
#rangeOffsets = (np.array(self._insar.swathRangeOffsetGeometricalMaster)).reshape(numberOfFrames, numberOfSwaths)
|
||||
#azimuthOffsets = (np.array(self._insar.swathAzimuthOffsetGeometricalMaster)).reshape(numberOfFrames, numberOfSwaths)
|
||||
rangeOffsets = self._insar.swathRangeOffsetGeometricalMaster
|
||||
azimuthOffsets = self._insar.swathAzimuthOffsetGeometricalMaster
|
||||
|
||||
rangeOffsets = rangeOffsets[i]
|
||||
azimuthOffsets = azimuthOffsets[i]
|
||||
|
||||
#list of input files
|
||||
inputSd = [[], [], []]
|
||||
for j, swathNumber in enumerate(range(self._insar.startingSwath, self._insar.endingSwath + 1)):
|
||||
swathDir = 's{}'.format(swathNumber)
|
||||
for k, sdFile in enumerate(self._insar.interferogramSd):
|
||||
inputSd[k].append(os.path.join('../', swathDir, 'spectral_diversity', sdFile))
|
||||
|
||||
#mosaic spectral diversity interferograms
|
||||
for inputSdList, outputSdFile in zip(inputSd, self._insar.interferogramSd):
|
||||
swathMosaic(masterTrack.frames[i], inputSdList, outputSdFile,
|
||||
rangeOffsets, azimuthOffsets, self._insar.numberRangeLooks1, self._insar.numberAzimuthLooks1, updateFrame=False, phaseCompensation=True, pcRangeLooks=5, pcAzimuthLooks=5, filt=True, resamplingMethod=1)
|
||||
|
||||
for sdFile in self._insar.interferogramSd:
|
||||
create_xml(sdFile, masterTrack.frames[i].numberOfSamples, masterTrack.frames[i].numberOfLines, 'int')
|
||||
|
||||
os.chdir('../')
|
||||
os.chdir('../')
|
||||
|
||||
|
||||
catalog.printToLog(logger, "runSwathMosaic")
|
||||
self._insar.procDoc.addAllFromCatalog(catalog)
|
||||
|
||||
|
||||
|
|
@ -0,0 +1,73 @@
|
|||
#
|
||||
# Author: Cunren Liang
|
||||
# Copyright 2015-present, NASA-JPL/Caltech
|
||||
#
|
||||
|
||||
import os
|
||||
import logging
|
||||
|
||||
import isceobj
|
||||
from isceobj.Alos2Proc.runSwathOffset import swathOffset
|
||||
|
||||
logger = logging.getLogger('isce.alos2burstinsar.runSwathOffset')
|
||||
|
||||
def runSwathOffset(self):
|
||||
'''estimate swath offsets.
|
||||
'''
|
||||
catalog = isceobj.Catalog.createCatalog(self._insar.procDoc.name)
|
||||
self.updateParamemetersFromUser()
|
||||
|
||||
masterTrack = self._insar.loadTrack(master=True)
|
||||
slaveTrack = self._insar.loadTrack(master=False)
|
||||
|
||||
|
||||
|
||||
for i, frameNumber in enumerate(self._insar.masterFrames):
|
||||
frameDir = 'f{}_{}'.format(i+1, frameNumber)
|
||||
os.chdir(frameDir)
|
||||
|
||||
mosaicDir = 'mosaic'
|
||||
if not os.path.exists(mosaicDir):
|
||||
os.makedirs(mosaicDir)
|
||||
os.chdir(mosaicDir)
|
||||
|
||||
if self._insar.endingSwath-self._insar.startingSwath+1 == 1:
|
||||
os.chdir('../../')
|
||||
continue
|
||||
|
||||
#compute swath offset
|
||||
offsetMaster = swathOffset(masterTrack.frames[i], os.path.join(self._insar.masterBurstPrefix, self._insar.masterMagnitude), self._insar.masterSwathOffset,
|
||||
crossCorrelation=self.swathOffsetMatching, numberOfAzimuthLooks=1)
|
||||
#only use geometrical offset for slave
|
||||
offsetSlave = swathOffset(slaveTrack.frames[i], os.path.join(self._insar.slaveBurstPrefix, self._insar.slaveMagnitude), self._insar.slaveSwathOffset,
|
||||
crossCorrelation=False, numberOfAzimuthLooks=1)
|
||||
|
||||
#initialization
|
||||
if i == 0:
|
||||
self._insar.swathRangeOffsetGeometricalMaster = []
|
||||
self._insar.swathAzimuthOffsetGeometricalMaster = []
|
||||
self._insar.swathRangeOffsetGeometricalSlave = []
|
||||
self._insar.swathAzimuthOffsetGeometricalSlave = []
|
||||
if self.swathOffsetMatching:
|
||||
self._insar.swathRangeOffsetMatchingMaster = []
|
||||
self._insar.swathAzimuthOffsetMatchingMaster = []
|
||||
#self._insar.swathRangeOffsetMatchingSlave = []
|
||||
#self._insar.swathAzimuthOffsetMatchingSlave = []
|
||||
|
||||
#append list directly, as the API support 2-d list
|
||||
self._insar.swathRangeOffsetGeometricalMaster.append(offsetMaster[0])
|
||||
self._insar.swathAzimuthOffsetGeometricalMaster.append(offsetMaster[1])
|
||||
self._insar.swathRangeOffsetGeometricalSlave.append(offsetSlave[0])
|
||||
self._insar.swathAzimuthOffsetGeometricalSlave.append(offsetSlave[1])
|
||||
if self.swathOffsetMatching:
|
||||
self._insar.swathRangeOffsetMatchingMaster.append(offsetMaster[2])
|
||||
self._insar.swathAzimuthOffsetMatchingMaster.append(offsetMaster[3])
|
||||
#self._insar.swathRangeOffsetMatchingSlave.append(offsetSlave[2])
|
||||
#self._insar.swathAzimuthOffsetMatchingSlave.append(offsetSlave[3])
|
||||
|
||||
os.chdir('../../')
|
||||
|
||||
catalog.printToLog(logger, "runSwathOffset")
|
||||
self._insar.procDoc.addAllFromCatalog(catalog)
|
||||
|
||||
|
||||
|
|
@ -0,0 +1,199 @@
|
|||
#
|
||||
# Author: Cunren Liang
|
||||
# Copyright 2015-present, NASA-JPL/Caltech
|
||||
#
|
||||
|
||||
import os
|
||||
import shutil
|
||||
import logging
|
||||
import datetime
|
||||
import numpy as np
|
||||
|
||||
import isceobj
|
||||
from isceobj.Alos2Proc.Alos2ProcPublic import snaphuUnwrap
|
||||
from isceobj.Alos2Proc.Alos2ProcPublic import snaphuUnwrapOriginal
|
||||
from isceobj.Alos2Proc.Alos2ProcPublic import runCmd
|
||||
from contrib.alos2proc.alos2proc import look
|
||||
from isceobj.Alos2Proc.Alos2ProcPublic import create_xml
|
||||
|
||||
logger = logging.getLogger('isce.alos2burstinsar.runUnwrapSnaphuSd')
|
||||
|
||||
def runUnwrapSnaphuSd(self):
|
||||
'''unwrap filtered interferogram
|
||||
'''
|
||||
catalog = isceobj.Catalog.createCatalog(self._insar.procDoc.name)
|
||||
self.updateParamemetersFromUser()
|
||||
|
||||
masterTrack = self._insar.loadTrack(master=True)
|
||||
#slaveTrack = self._insar.loadTrack(master=False)
|
||||
|
||||
sdDir = 'sd'
|
||||
if not os.path.exists(sdDir):
|
||||
os.makedirs(sdDir)
|
||||
os.chdir(sdDir)
|
||||
|
||||
|
||||
############################################################
|
||||
# STEP 1. unwrap interferogram
|
||||
############################################################
|
||||
nsd = len(self._insar.filteredInterferogramSd)
|
||||
img = isceobj.createImage()
|
||||
img.load(self._insar.filteredInterferogramSd[0]+'.xml')
|
||||
width = img.width
|
||||
length = img.length
|
||||
|
||||
if shutil.which('snaphu') != None:
|
||||
print('\noriginal snaphu program found, use it for unwrapping interferograms')
|
||||
useOriginalSnaphu = True
|
||||
#create an amplitude for use
|
||||
# amplitude = os.path.join('../insar', self._insar.amplitude)
|
||||
# amplitudeMultilook = 'tmp.amp'
|
||||
# img = isceobj.createImage()
|
||||
# img.load(amplitude+'.xml')
|
||||
# look(amplitude, amplitudeMultilook, img.width, self._insar.numberRangeLooksSd, self._insar.numberAzimuthLooksSd, 4, 1, 1)
|
||||
else:
|
||||
useOriginalSnaphu = False
|
||||
|
||||
for sdCoherence, sdInterferogramFilt, sdInterferogramUnwrap in zip(self._insar.multilookCoherenceSd, self._insar.filteredInterferogramSd, self._insar.unwrappedInterferogramSd):
|
||||
if useOriginalSnaphu:
|
||||
amplitudeMultilook = 'tmp.amp'
|
||||
cmd = "imageMath.py -e='sqrt(abs(a));sqrt(abs(a))' --a={} -o {} -t float -s BSQ".format(sdInterferogramFilt, amplitudeMultilook)
|
||||
runCmd(cmd)
|
||||
snaphuUnwrapOriginal(sdInterferogramFilt,
|
||||
sdCoherence,
|
||||
amplitudeMultilook,
|
||||
sdInterferogramUnwrap,
|
||||
costMode = 's',
|
||||
initMethod = 'mcf')
|
||||
os.remove(amplitudeMultilook)
|
||||
os.remove(amplitudeMultilook+'.vrt')
|
||||
os.remove(amplitudeMultilook+'.xml')
|
||||
else:
|
||||
tmid = masterTrack.sensingStart + datetime.timedelta(seconds=(self._insar.numberAzimuthLooks1-1.0)/2.0*masterTrack.azimuthLineInterval+
|
||||
masterTrack.numberOfLines/2.0*self._insar.numberAzimuthLooks1*masterTrack.azimuthLineInterval)
|
||||
snaphuUnwrap(masterTrack, tmid,
|
||||
sdInterferogramFilt,
|
||||
sdCoherence,
|
||||
sdInterferogramUnwrap,
|
||||
self._insar.numberRangeLooks1*self._insar.numberRangeLooksSd,
|
||||
self._insar.numberAzimuthLooks1*self._insar.numberAzimuthLooksSd,
|
||||
costMode = 'SMOOTH',initMethod = 'MCF', defomax = 2, initOnly = True)
|
||||
|
||||
#if useOriginalSnaphu:
|
||||
# os.remove(amplitudeMultilook)
|
||||
|
||||
|
||||
############################################################
|
||||
# STEP 2. mask using connected components
|
||||
############################################################
|
||||
for sdInterferogramUnwrap, sdInterferogramUnwrapMasked in zip(self._insar.unwrappedInterferogramSd, self._insar.unwrappedMaskedInterferogramSd):
|
||||
cmd = "imageMath.py -e='a_0*(b>0);a_1*(b>0)' --a={} --b={} -s BIL -t float -o={}".format(sdInterferogramUnwrap, sdInterferogramUnwrap+'.conncomp', sdInterferogramUnwrapMasked)
|
||||
runCmd(cmd)
|
||||
|
||||
|
||||
############################################################
|
||||
# STEP 3. mask using water body
|
||||
############################################################
|
||||
if self.waterBodyMaskStartingStepSd=='unwrap':
|
||||
wbd = np.fromfile(self._insar.multilookWbdOutSd, dtype=np.int8).reshape(length, width)
|
||||
|
||||
for sdInterferogramUnwrap, sdInterferogramUnwrapMasked in zip(self._insar.unwrappedInterferogramSd, self._insar.unwrappedMaskedInterferogramSd):
|
||||
unw=np.memmap(sdInterferogramUnwrap, dtype='float32', mode='r+', shape=(length*2, width))
|
||||
(unw[0:length*2:2, :])[np.nonzero(wbd==-1)] = 0
|
||||
(unw[1:length*2:2, :])[np.nonzero(wbd==-1)] = 0
|
||||
unw=np.memmap(sdInterferogramUnwrapMasked, dtype='float32', mode='r+', shape=(length*2, width))
|
||||
(unw[0:length*2:2, :])[np.nonzero(wbd==-1)] = 0
|
||||
(unw[1:length*2:2, :])[np.nonzero(wbd==-1)] = 0
|
||||
|
||||
|
||||
############################################################
|
||||
# STEP 4. convert to azimuth deformation
|
||||
############################################################
|
||||
#burst cycle in s
|
||||
burstCycleLength = masterTrack.frames[0].swaths[0].burstCycleLength / masterTrack.frames[0].swaths[0].prf
|
||||
|
||||
#compute azimuth fmrate
|
||||
#stack all azimuth fmrates
|
||||
index = np.array([], dtype=np.float64)
|
||||
ka = np.array([], dtype=np.float64)
|
||||
for frame in masterTrack.frames:
|
||||
for swath in frame.swaths:
|
||||
startingRangeMultilook = masterTrack.frames[0].swaths[0].startingRange + \
|
||||
(self._insar.numberRangeLooks1*self._insar.numberRangeLooksSd-1.0)/2.0*masterTrack.frames[0].swaths[0].rangePixelSize
|
||||
rangePixelSizeMultilook = self._insar.numberRangeLooks1 * self._insar.numberRangeLooksSd * masterTrack.frames[0].swaths[0].rangePixelSize
|
||||
index0 = (swath.startingRange + np.arange(swath.numberOfSamples) * swath.rangePixelSize - startingRangeMultilook) / rangePixelSizeMultilook
|
||||
ka0 = np.polyval(swath.azimuthFmrateVsPixel[::-1], np.arange(swath.numberOfSamples))
|
||||
index = np.concatenate((index, index0))
|
||||
ka = np.concatenate((ka, ka0))
|
||||
p = np.polyfit(index, ka, 3)
|
||||
#new ka
|
||||
ka = np.polyval(p, np.arange(width))
|
||||
|
||||
#compute radar beam footprint velocity at middle track
|
||||
tmid = masterTrack.sensingStart + datetime.timedelta(seconds=(self._insar.numberAzimuthLooks1-1.0)/2.0*masterTrack.azimuthLineInterval+
|
||||
masterTrack.numberOfLines/2.0*self._insar.numberAzimuthLooks1*masterTrack.azimuthLineInterval)
|
||||
svmid = masterTrack.orbit.interpolateOrbit(tmid, method='hermite')
|
||||
#earth radius in meters
|
||||
r = 6371 * 1000.0
|
||||
#radar footprint velocity
|
||||
veln = np.linalg.norm(svmid.getVelocity()) * r / np.linalg.norm(svmid.getPosition())
|
||||
print('radar beam footprint velocity at middle track: %8.2f m/s'%veln)
|
||||
|
||||
#phase to defo factor
|
||||
factor = -1.0* veln / (2.0 * np.pi * ka * burstCycleLength)
|
||||
|
||||
#process unwrapped without mask
|
||||
sdunw_out = np.zeros((length*2, width))
|
||||
flag = np.zeros((length, width))
|
||||
wgt = np.zeros((length, width))
|
||||
for i in range(nsd):
|
||||
sdunw = np.fromfile(self._insar.unwrappedInterferogramSd[i], dtype=np.float32).reshape(length*2, width)
|
||||
sdunw[1:length*2:2, :] *= factor[None, :] / (i+1.0)
|
||||
sdunw.astype(np.float32).tofile(self._insar.azimuthDeformationSd[i])
|
||||
create_xml(self._insar.azimuthDeformationSd[i], width, length, 'rmg')
|
||||
flag += (sdunw[1:length*2:2, :]!=0)
|
||||
#since the interferogram is filtered, we only use this light weight
|
||||
wgt0 = (i+1)**2
|
||||
wgt += wgt0 * (sdunw[1:length*2:2, :]!=0)
|
||||
sdunw_out[0:length*2:2, :] += (sdunw[0:length*2:2, :])**2
|
||||
sdunw_out[1:length*2:2, :] += wgt0 * sdunw[1:length*2:2, :]
|
||||
#output weighting average
|
||||
index = np.nonzero(flag!=0)
|
||||
(sdunw_out[0:length*2:2, :])[index] = np.sqrt((sdunw_out[0:length*2:2, :])[index] / flag[index])
|
||||
(sdunw_out[1:length*2:2, :])[index] = (sdunw_out[1:length*2:2, :])[index] / wgt[index]
|
||||
if not self.unionSd:
|
||||
(sdunw_out[0:length*2:2, :])[np.nonzero(flag<nsd)] = 0
|
||||
(sdunw_out[1:length*2:2, :])[np.nonzero(flag<nsd)] = 0
|
||||
sdunw_out.astype(np.float32).tofile(self._insar.azimuthDeformationSd[-1])
|
||||
create_xml(self._insar.azimuthDeformationSd[-1], width, length, 'rmg')
|
||||
|
||||
#process unwrapped with mask
|
||||
sdunw_out = np.zeros((length*2, width))
|
||||
flag = np.zeros((length, width))
|
||||
wgt = np.zeros((length, width))
|
||||
for i in range(nsd):
|
||||
sdunw = np.fromfile(self._insar.unwrappedMaskedInterferogramSd[i], dtype=np.float32).reshape(length*2, width)
|
||||
sdunw[1:length*2:2, :] *= factor[None, :] / (i+1.0)
|
||||
sdunw.astype(np.float32).tofile(self._insar.maskedAzimuthDeformationSd[i])
|
||||
create_xml(self._insar.maskedAzimuthDeformationSd[i], width, length, 'rmg')
|
||||
flag += (sdunw[1:length*2:2, :]!=0)
|
||||
#since the interferogram is filtered, we only use this light weight
|
||||
wgt0 = (i+1)**2
|
||||
wgt += wgt0 * (sdunw[1:length*2:2, :]!=0)
|
||||
sdunw_out[0:length*2:2, :] += (sdunw[0:length*2:2, :])**2
|
||||
sdunw_out[1:length*2:2, :] += wgt0 * sdunw[1:length*2:2, :]
|
||||
#output weighting average
|
||||
index = np.nonzero(flag!=0)
|
||||
(sdunw_out[0:length*2:2, :])[index] = np.sqrt((sdunw_out[0:length*2:2, :])[index] / flag[index])
|
||||
(sdunw_out[1:length*2:2, :])[index] = (sdunw_out[1:length*2:2, :])[index] / wgt[index]
|
||||
if not self.unionSd:
|
||||
(sdunw_out[0:length*2:2, :])[np.nonzero(flag<nsd)] = 0
|
||||
(sdunw_out[1:length*2:2, :])[np.nonzero(flag<nsd)] = 0
|
||||
sdunw_out.astype(np.float32).tofile(self._insar.maskedAzimuthDeformationSd[-1])
|
||||
create_xml(self._insar.maskedAzimuthDeformationSd[-1], width, length, 'rmg')
|
||||
|
||||
os.chdir('../')
|
||||
|
||||
catalog.printToLog(logger, "runUnwrapSnaphuSd")
|
||||
self._insar.procDoc.addAllFromCatalog(catalog)
|
||||
|
||||
|
|
@ -1,6 +1,8 @@
|
|||
add_subdirectory(Util)
|
||||
add_subdirectory(Sensor)
|
||||
|
||||
add_subdirectory(Alos2Proc)
|
||||
add_subdirectory(Alos2burstProc)
|
||||
add_subdirectory(Attitude)
|
||||
add_subdirectory(Catalog)
|
||||
add_subdirectory(Constants)
|
||||
|
|
|
|||
|
|
@ -71,3 +71,5 @@ SConscript('StripmapProc/SConscript')
|
|||
SConscript('TopsProc/SConscript')
|
||||
SConscript('RtcProc/SConscript')
|
||||
SConscript('ScansarProc/SConscript')
|
||||
SConscript('Alos2Proc/SConscript')
|
||||
SConscript('Alos2burstProc/SConscript')
|
||||
|
|
|
|||
|
|
@ -1,6 +1,7 @@
|
|||
add_subdirectory(db)
|
||||
add_subdirectory(TOPS)
|
||||
add_subdirectory(ScanSAR)
|
||||
add_subdirectory(MultiMode)
|
||||
|
||||
set(installfiles
|
||||
alos
|
||||
|
|
|
|||
|
|
@ -0,0 +1,831 @@
|
|||
#!/usr/bin/env python3
|
||||
|
||||
#Author: Cunren Liang, 2015-
|
||||
|
||||
import os
|
||||
import datetime
|
||||
import isceobj.Sensor.CEOS as CEOS
|
||||
import logging
|
||||
from isceobj.Orbit.Orbit import StateVector,Orbit
|
||||
from isceobj.Planet.AstronomicalHandbook import Const
|
||||
from isceobj.Planet.Planet import Planet
|
||||
from iscesys.Component.Component import Component
|
||||
from isceobj.Sensor import xmlPrefix
|
||||
from isceobj.Util import Polynomial
|
||||
from iscesys.DateTimeUtil import secondsSinceMidnight
|
||||
import numpy as np
|
||||
import struct
|
||||
|
||||
import isceobj
|
||||
|
||||
#changed to use the following parameters
|
||||
IMAGE_FILE = Component.Parameter('imageFile',
|
||||
public_name='image file',
|
||||
type = str,
|
||||
default=None,
|
||||
mandatory = True,
|
||||
doc = 'ALOS-2 CEOS image file')
|
||||
|
||||
LEADER_FILE = Component.Parameter('leaderFile',
|
||||
public_name='leader file',
|
||||
type = str,
|
||||
default=None,
|
||||
mandatory = True,
|
||||
doc = 'ALOS-2 CEOS leader file')
|
||||
|
||||
OUTPUT_FILE = Component.Parameter('outputFile',
|
||||
public_name='output file',
|
||||
type = str,
|
||||
default=None,
|
||||
mandatory = True,
|
||||
doc = 'output file')
|
||||
|
||||
USE_VIRTUAL_FILE = Component.Parameter('useVirtualFile',
|
||||
public_name='use virtual file',
|
||||
type=bool,
|
||||
default=True,
|
||||
mandatory=False,
|
||||
doc='use virtual files instead of using disk space')
|
||||
|
||||
####List of facilities
|
||||
TRACK = Component.Facility('track',
|
||||
public_name='track',
|
||||
module = 'isceobj.Sensor.MultiMode',
|
||||
factory='createTrack',
|
||||
args = (),
|
||||
mandatory = True,
|
||||
doc = 'A track of ALOS-2 SLCs populated by the reader')
|
||||
|
||||
|
||||
class ALOS2(Component):
|
||||
"""
|
||||
ALOS-2 multi-mode reader
|
||||
"""
|
||||
family = 'alos2multimode'
|
||||
logging = 'isce.sensor.alos2multimode'
|
||||
|
||||
parameter_list = (IMAGE_FILE,
|
||||
LEADER_FILE,
|
||||
OUTPUT_FILE,
|
||||
USE_VIRTUAL_FILE)
|
||||
|
||||
facility_list = (TRACK,)
|
||||
|
||||
# Range sampling rate
|
||||
fsampConst = { 104: 1.047915957140240E+08,
|
||||
52: 5.239579785701190E+07,
|
||||
34: 3.493053190467460E+07,
|
||||
17: 1.746526595233730E+07 }
|
||||
# Orbital Elements (Quality) Designator, data format P68
|
||||
orbitElementsDesignator = {'0':'0: preliminary',
|
||||
'1':'1: decision',
|
||||
'2':'2: high precision'}
|
||||
# Operation mode, data format P50
|
||||
operationModeDesignator = {'00': '00: Spotlight mode',
|
||||
'01': '01: Ultra-fine mode',
|
||||
'02': '02: High-sensitive mode',
|
||||
'03': '03: Fine mode',
|
||||
'04': '04: spare',
|
||||
'05': '05: spare',
|
||||
'08': '08: ScanSAR nominal mode',
|
||||
'09': '09: ScanSAR wide mode',
|
||||
'18': '18: Full (Quad.) pol./High-sensitive mode',
|
||||
'19': '19: Full (Quad.) pol./Fine mode',
|
||||
'64': '64: Manual observation'}
|
||||
|
||||
def __init__(self, name=''):
|
||||
super().__init__(family=self.__class__.family, name=name)
|
||||
|
||||
return
|
||||
|
||||
|
||||
def readImage(self):
|
||||
'''
|
||||
read image and get parameters
|
||||
'''
|
||||
try:
|
||||
fp = open(self.imageFile,'rb')
|
||||
except IOError as errs:
|
||||
errno,strerr = errs
|
||||
print("IOError: %s" % strerr)
|
||||
return
|
||||
|
||||
#read meta data
|
||||
imageFDR = CEOS.CEOSDB(xml=os.path.join(xmlPrefix,'alos2_slc/image_file.xml'), dataFile=fp)
|
||||
imageFDR.parse()
|
||||
fp.seek(imageFDR.getEndOfRecordPosition())
|
||||
|
||||
#record length: header (544 bytes) + SAR data (width*8 bytes)
|
||||
recordlength = imageFDR.metadata['SAR DATA record length']
|
||||
width = imageFDR.metadata['Number of pixels per line per SAR channel']
|
||||
length = imageFDR.metadata['Number of SAR DATA records']
|
||||
|
||||
#line header
|
||||
imageData = CEOS.CEOSDB(xml=os.path.join(xmlPrefix,'alos2_slc/image_record.xml'), dataFile=fp)
|
||||
imageData.parseFast()
|
||||
|
||||
#creat vrt and xml files for sar data
|
||||
image = isceobj.createSlcImage()
|
||||
image.setFilename(self.outputFile)
|
||||
image.setWidth(width)
|
||||
image.setLength(length)
|
||||
image.renderHdr()
|
||||
|
||||
#sar data
|
||||
fileHeaderBytes = 720
|
||||
lineHeaderBytes = 544
|
||||
if self.useVirtualFile:
|
||||
#this overwrites the previous vrt
|
||||
with open(self.outputFile+'.vrt', 'w') as fid:
|
||||
fid.write('''<VRTDataset rasterXSize="{0}" rasterYSize="{1}">
|
||||
<VRTRasterBand band="1" dataType="CFloat32" subClass="VRTRawRasterBand">
|
||||
<SourceFilename relativeToVRT="0">{2}</SourceFilename>
|
||||
<ByteOrder>MSB</ByteOrder>
|
||||
<ImageOffset>{3}</ImageOffset>
|
||||
<PixelOffset>8</PixelOffset>
|
||||
<LineOffset>{4}</LineOffset>
|
||||
</VRTRasterBand>
|
||||
</VRTDataset>'''.format(width, length,
|
||||
self.imageFile,
|
||||
fileHeaderBytes + lineHeaderBytes,
|
||||
width*8 + lineHeaderBytes))
|
||||
else:
|
||||
#read sar data line by line
|
||||
try:
|
||||
fp2 = open(self.outputFile,'wb')
|
||||
except IOError as errs:
|
||||
errno,strerr = errs
|
||||
print("IOError: %s" % strerr)
|
||||
return
|
||||
fp.seek(-lineHeaderBytes, 1)
|
||||
for line in range(length):
|
||||
if (((line+1)%1000) == 0):
|
||||
print("extracting line %6d of %6d" % (line+1, length), end='\r', flush=True)
|
||||
fp.seek(lineHeaderBytes, 1)
|
||||
IQLine = np.fromfile(fp, dtype='>f', count=2*width)
|
||||
self.writeRawData(fp2, IQLine)
|
||||
#IQLine.tofile(fp2)
|
||||
print("extracting line %6d of %6d" % (length, length))
|
||||
fp2.close()
|
||||
|
||||
#close input image file
|
||||
fp.close()
|
||||
|
||||
return (imageFDR, imageData)
|
||||
|
||||
|
||||
def readLeader(self):
|
||||
'''
|
||||
read meta data from leader
|
||||
'''
|
||||
try:
|
||||
fp = open(self.leaderFile,'rb')
|
||||
except IOError as errs:
|
||||
errno,strerr = errs
|
||||
print("IOError: %s" % strerr)
|
||||
return
|
||||
|
||||
# Leader record
|
||||
leaderFDR = CEOS.CEOSDB(xml=os.path.join(xmlPrefix,'alos2_slc/leader_file.xml'),dataFile=fp)
|
||||
leaderFDR.parse()
|
||||
fp.seek(leaderFDR.getEndOfRecordPosition())
|
||||
|
||||
# Scene Header
|
||||
sceneHeaderRecord = CEOS.CEOSDB(xml=os.path.join(xmlPrefix,'alos2_slc/scene_record.xml'),dataFile=fp)
|
||||
sceneHeaderRecord.parse()
|
||||
fp.seek(sceneHeaderRecord.getEndOfRecordPosition())
|
||||
|
||||
# Platform Position
|
||||
platformPositionRecord = CEOS.CEOSDB(xml=os.path.join(xmlPrefix,'alos2_slc/platform_position_record.xml'),dataFile=fp)
|
||||
platformPositionRecord.parse()
|
||||
fp.seek(platformPositionRecord.getEndOfRecordPosition())
|
||||
|
||||
#####Skip attitude information
|
||||
fp.seek(16384,1)
|
||||
#####Skip radiometric information
|
||||
fp.seek(9860,1)
|
||||
####Skip the data quality information
|
||||
fp.seek(1620,1)
|
||||
####Skip facility 1-4
|
||||
fp.seek(325000 + 511000 + 3072 + 728000, 1)
|
||||
|
||||
####Read facility 5
|
||||
facilityRecord = CEOS.CEOSDB(xml=os.path.join(xmlPrefix,'alos2_slc/facility_record.xml'), dataFile=fp)
|
||||
facilityRecord.parse()
|
||||
|
||||
###close file
|
||||
fp.close()
|
||||
|
||||
return (leaderFDR, sceneHeaderRecord, platformPositionRecord, facilityRecord)
|
||||
|
||||
|
||||
def setTrack(self, leaderFDR, sceneHeaderRecord, platformPositionRecord, facilityRecord, imageFDR, imageData):
|
||||
'''
|
||||
set track parameters
|
||||
'''
|
||||
track = self.track
|
||||
|
||||
#passDirection
|
||||
passDirection = sceneHeaderRecord.metadata['Time direction indicator along line direction']
|
||||
if passDirection == 'ASCEND':
|
||||
track.passDirection = 'ascending'
|
||||
elif passDirection == 'DESCEND':
|
||||
track.passDirection = 'descending'
|
||||
else:
|
||||
raise Exception('Unknown passDirection. passDirection = {0}'.format(passDirection))
|
||||
|
||||
#pointingDirection
|
||||
######ALOS-2 includes this information in clock angle
|
||||
clockAngle = sceneHeaderRecord.metadata['Sensor clock angle']
|
||||
if clockAngle == 90.0:
|
||||
track.pointingDirection = 'right'
|
||||
elif clockAngle == -90.0:
|
||||
track.pointingDirection = 'left'
|
||||
else:
|
||||
raise Exception('Unknown look side. Clock Angle = {0}'.format(clockAngle))
|
||||
|
||||
#operation mode
|
||||
track.operationMode = self.operationModeDesignator[
|
||||
(sceneHeaderRecord.metadata['Sensor ID and mode of operation for this channel'])[10:12]
|
||||
]
|
||||
|
||||
#use this instead. 30-JAN-2020
|
||||
track.operationMode = os.path.basename(self.leaderFile).split('-')[-1][0:3]
|
||||
|
||||
#radarWavelength
|
||||
track.radarWavelength = sceneHeaderRecord.metadata['Radar wavelength']
|
||||
|
||||
#orbit
|
||||
orb = self.readOrbit(platformPositionRecord)
|
||||
track.orbit.setOrbitSource(orb.getOrbitSource())
|
||||
track.orbit.setOrbitQuality(orb.getOrbitQuality())
|
||||
#add orbit from frame
|
||||
for sv in orb:
|
||||
addOrbit = True
|
||||
#Orbit class does not check this
|
||||
for x in track.orbit:
|
||||
if x.getTime() == sv.getTime():
|
||||
addOrbit = False
|
||||
break
|
||||
if addOrbit:
|
||||
track.orbit.addStateVector(sv)
|
||||
|
||||
# the following are to be set when mosaicking frames.
|
||||
# 'numberOfSamples',
|
||||
# 'numberOfLines',
|
||||
# 'startingRange',
|
||||
# 'rangeSamplingRate',
|
||||
# 'rangePixelSize',
|
||||
# 'sensingStart',
|
||||
# 'prf',
|
||||
# 'azimuthPixelSize'
|
||||
|
||||
|
||||
def setFrame(self, leaderFDR, sceneHeaderRecord, platformPositionRecord, facilityRecord, imageFDR, imageData):
|
||||
'''
|
||||
set frame parameters
|
||||
'''
|
||||
frame = self.track.frames[-1]
|
||||
|
||||
#get frame number from file name
|
||||
frame.frameNumber = os.path.basename(self.imageFile).split('-')[2][-4:]
|
||||
frame.processingFacility = sceneHeaderRecord.metadata['Processing facility identifier']
|
||||
frame.processingSystem = sceneHeaderRecord.metadata['Processing system identifier']
|
||||
frame.processingSoftwareVersion = sceneHeaderRecord.metadata['Processing version identifier']
|
||||
#orbit quality
|
||||
orb = self.readOrbit(platformPositionRecord)
|
||||
frame.orbitQuality = orb.getOrbitQuality()
|
||||
|
||||
# the following are to be set when mosaicking swaths
|
||||
# 'numberOfSamples',
|
||||
# 'numberOfLines',
|
||||
# 'startingRange',
|
||||
# 'rangeSamplingRate',
|
||||
# 'rangePixelSize',
|
||||
# 'sensingStart',
|
||||
# 'prf',
|
||||
# 'azimuthPixelSize'
|
||||
|
||||
|
||||
def setSwath(self, leaderFDR, sceneHeaderRecord, platformPositionRecord, facilityRecord, imageFDR, imageData):
|
||||
'''
|
||||
set swath parameters
|
||||
'''
|
||||
swath = self.track.frames[-1].swaths[-1]
|
||||
operationMode = (sceneHeaderRecord.metadata['Sensor ID and mode of operation for this channel'])[10:12]
|
||||
|
||||
#set swath number here regardless of operation mode, will be updated for ScanSAR later
|
||||
swath.swathNumber = 1
|
||||
|
||||
#polarization
|
||||
polDesignator = {0: 'H',
|
||||
1: 'V'}
|
||||
swath.polarization = '{}{}'.format(polDesignator[imageData.metadata['Transmitted polarization']],
|
||||
polDesignator[imageData.metadata['Received polarization']])
|
||||
|
||||
#image dimensions
|
||||
swath.numberOfSamples = imageFDR.metadata['Number of pixels per line per SAR channel']
|
||||
swath.numberOfLines = imageFDR.metadata['Number of SAR DATA records']
|
||||
|
||||
#range
|
||||
swath.startingRange = imageData.metadata['Slant range to 1st data sample']
|
||||
swath.rangeSamplingRate = self.fsampConst[int(sceneHeaderRecord.metadata['Range sampling rate in MHz'])]
|
||||
swath.rangePixelSize = Const.c/(2.0*swath.rangeSamplingRate)
|
||||
swath.rangeBandwidth =abs((sceneHeaderRecord.metadata['Nominal range pulse (chirp) amplitude coefficient linear term']) *
|
||||
(sceneHeaderRecord.metadata['Range pulse length in microsec']*1.0e-6))
|
||||
|
||||
#sensingStart
|
||||
yr = imageData.metadata['Sensor acquisition year']
|
||||
dys = imageData.metadata['Sensor acquisition day of year']
|
||||
msecs = imageData.metadata['Sensor acquisition milliseconds of day']
|
||||
usecs = imageData.metadata['Sensor acquisition micro-seconds of day']
|
||||
swath.sensingStart = datetime.datetime(yr,1,1) + datetime.timedelta(days=(dys-1)) + datetime.timedelta(seconds = usecs*1e-6)
|
||||
|
||||
#prf
|
||||
if operationMode == '08' or operationMode == '09':
|
||||
# Operation mode
|
||||
# '00': 'Spotlight mode',
|
||||
# '01': 'Ultra-fine mode',
|
||||
# '02': 'High-sensitive mode',
|
||||
# '03': 'Fine mode',
|
||||
# '04': 'spare',
|
||||
# '05': 'spare',
|
||||
# '08': 'ScanSAR nominal mode',
|
||||
# '09': 'ScanSAR wide mode',
|
||||
# '18': 'Full (Quad.) pol./High-sensitive mode',
|
||||
# '19': 'Full (Quad.) pol./Fine mode',
|
||||
# '64': 'Manual observation'
|
||||
#print('ScanSAR mode, using PRF from the line header')
|
||||
swath.prf = imageData.metadata['PRF'] * 1.0e-3
|
||||
else:
|
||||
#print('not ScanSAR mode, using PRF from leader file')
|
||||
swath.prf = sceneHeaderRecord.metadata['Pulse Repetition Frequency in mHz']*1.0e-3
|
||||
|
||||
#azimuth pixel size at swath center on ground
|
||||
azimuthTime = swath.sensingStart + datetime.timedelta(seconds=swath.numberOfLines/swath.prf/2.0)
|
||||
orbit = self.readOrbit(platformPositionRecord)
|
||||
svmid = orbit.interpolateOrbit(azimuthTime, method='hermite')
|
||||
height = np.linalg.norm(svmid.getPosition())
|
||||
velocity = np.linalg.norm(svmid.getVelocity())
|
||||
#earth radius in meters
|
||||
r = 6371 * 1000.0
|
||||
swath.azimuthPixelSize = velocity / swath.prf * r / height
|
||||
swath.azimuthLineInterval = 1.0 / swath.prf
|
||||
|
||||
#doppler
|
||||
swath.dopplerVsPixel = self.reformatDoppler(sceneHeaderRecord, imageFDR, imageData)
|
||||
|
||||
#azimuth FM rate
|
||||
azimuthTime = swath.sensingStart + datetime.timedelta(seconds=swath.numberOfLines/swath.prf/2.0)
|
||||
swath.azimuthFmrateVsPixel = self.computeAzimuthFmrate(sceneHeaderRecord, platformPositionRecord, imageFDR, imageData, azimuthTime)
|
||||
|
||||
|
||||
#burst information estimated from azimuth spectrum. Cunren, 14-DEC-2015
|
||||
if operationMode == '08' or operationMode == '09':
|
||||
sceneCenterIncidenceAngle = sceneHeaderRecord.metadata['Incidence angle at scene centre']
|
||||
sarChannelId = imageData.metadata['SAR channel indicator']
|
||||
#Scan ID starts with 1, ScanSAR = 1 to 7, Except ScanSAR = 0
|
||||
scanId = imageData.metadata['Scan ID']
|
||||
swath.swathNumber = scanId
|
||||
|
||||
#looks like all ScanSAR nominal modes (WBS,WBD,WWS,WWD) have same burst parameters, so remove the limitation here
|
||||
#if (sceneCenterIncidenceAngle > 39.032 - 5.0 and sceneCenterIncidenceAngle < 39.032 + 5.0) and (sarChannelId == 2):
|
||||
if operationMode == '08':
|
||||
#burst parameters, currently only for the second, dual polarization, ScanSAR nominal mode
|
||||
#that is the second WBD mode
|
||||
#p.25 and p.115 of ALOS-2/PALSAR-2 Level 1.1/1.5/2.1/3.1 CEOS SAR Product Format Description
|
||||
#for the definations of wide swath mode
|
||||
nbraw = [358, 470, 358, 355, 487]
|
||||
ncraw = [2086.26, 2597.80, 1886.18, 1779.60, 2211.17]
|
||||
|
||||
swath.burstLength = nbraw[scanId-1]
|
||||
swath.burstCycleLength = ncraw[scanId-1]
|
||||
|
||||
#this is the prf fraction (total azimuth bandwith) used in extracting burst
|
||||
#here the total bandwith is 0.93 * prfs[3] for all subswaths, which is the following values:
|
||||
#[0.7933, 0.6371, 0.8774, 0.9300, 0.7485]
|
||||
prfs=[2661.847, 3314.512, 2406.568, 2270.575, 2821.225]
|
||||
swath.prfFraction = 0.93 * prfs[3]/prfs[scanId-1]
|
||||
|
||||
#compute burst start time
|
||||
if operationMode == '08':
|
||||
(burstStartTime, burstCycleLengthNew) = self.burstTimeRefining(self.outputFile,
|
||||
swath.numberOfSamples,
|
||||
swath.numberOfLines,
|
||||
swath.prf,
|
||||
swath.burstLength,
|
||||
swath.burstCycleLength,
|
||||
swath.azimuthFmrateVsPixel,
|
||||
swath.sensingStart,
|
||||
self.useVirtualFile)
|
||||
swath.burstStartTime = burstStartTime
|
||||
swath.burstCycleLength = burstCycleLengthNew
|
||||
|
||||
|
||||
def computeAzimuthFmrate(self, sceneHeaderRecord, platformPositionRecord, imageFDR, imageData, azimuthTime):
|
||||
import copy
|
||||
'''
|
||||
compute azimuth FM rate, copied from Piyush's code.
|
||||
azimuthTime: middle of the scene should be a good time
|
||||
'''
|
||||
#parameters required
|
||||
orbit = self.readOrbit(platformPositionRecord)
|
||||
dopplerVsPixel = self.reformatDoppler(sceneHeaderRecord, imageFDR, imageData)
|
||||
width = imageFDR.metadata['Number of pixels per line per SAR channel']
|
||||
|
||||
startingRange = imageData.metadata['Slant range to 1st data sample']
|
||||
rangeSamplingRate = self.fsampConst[int(sceneHeaderRecord.metadata['Range sampling rate in MHz'])]
|
||||
radarWavelength = sceneHeaderRecord.metadata['Radar wavelength']
|
||||
|
||||
clockAngle = sceneHeaderRecord.metadata['Sensor clock angle']
|
||||
if clockAngle == 90.0:
|
||||
#right
|
||||
pointingDirection = -1
|
||||
elif clockAngle == -90.0:
|
||||
#left
|
||||
pointingDirection = 1
|
||||
else:
|
||||
raise Exception('Unknown look side. Clock Angle = {0}'.format(clockAngle))
|
||||
|
||||
##We have to compute FM rate here.
|
||||
##Cunren's observation that this is all set to zero in CEOS file.
|
||||
##Simplification from Cunren's fmrate.py script
|
||||
##Should be the same as the one in focus.py
|
||||
planet = Planet(pname='Earth')
|
||||
elp = copy.copy(planet.ellipsoid)
|
||||
svmid = orbit.interpolateOrbit(azimuthTime, method='hermite')
|
||||
xyz = svmid.getPosition()
|
||||
vxyz = svmid.getVelocity()
|
||||
llh = elp.xyz_to_llh(xyz)
|
||||
hdg = orbit.getENUHeading(azimuthTime)
|
||||
|
||||
elp.setSCH(llh[0], llh[1], hdg)
|
||||
sch, schvel = elp.xyzdot_to_schdot(xyz, vxyz)
|
||||
|
||||
##Computeation of acceleration
|
||||
dist= np.linalg.norm(xyz)
|
||||
r_spinvec = np.array([0., 0., planet.spin])
|
||||
r_tempv = np.cross(r_spinvec, xyz)
|
||||
inert_acc = np.array([-planet.GM*x/(dist**3) for x in xyz])
|
||||
r_tempa = np.cross(r_spinvec, vxyz)
|
||||
r_tempvec = np.cross(r_spinvec, r_tempv)
|
||||
axyz = inert_acc - 2 * r_tempa - r_tempvec
|
||||
|
||||
schbasis = elp.schbasis(sch)
|
||||
schacc = np.dot(schbasis.xyz_to_sch, axyz).tolist()[0]
|
||||
|
||||
##Jumping back straight into Cunren's script here
|
||||
centerVel = schvel
|
||||
centerAcc = schacc
|
||||
avghgt = llh[2]
|
||||
radiusOfCurvature = elp.pegRadCur
|
||||
|
||||
fmrate = []
|
||||
lookSide = pointingDirection
|
||||
centerVelNorm = np.linalg.norm(centerVel)
|
||||
|
||||
##Retaining Cunren's code for computing at every pixel.
|
||||
##Can be done every 10th pixel since we only fit a quadratic/ cubic.
|
||||
##Also can be vectorized for speed.
|
||||
|
||||
for ii in range(width):
|
||||
rg = startingRange + ii * 0.5 * Const.c / rangeSamplingRate
|
||||
#don't forget to flip coefficients
|
||||
dop = np.polyval(dopplerVsPixel[::-1], ii)
|
||||
|
||||
th = np.arccos(((avghgt+radiusOfCurvature)**2 + rg**2 -radiusOfCurvature**2)/(2.0 * (avghgt + radiusOfCurvature) * rg))
|
||||
thaz = np.arcsin(((radarWavelength*dop/(2.0*np.sin(th))) + (centerVel[2] / np.tan(th))) / np.sqrt(centerVel[0]**2 + centerVel[1]**2)) - lookSide * np.arctan(centerVel[1]/centerVel[0])
|
||||
|
||||
lookVec = [ np.sin(th) * np.sin(thaz),
|
||||
np.sin(th) * np.cos(thaz) * lookSide,
|
||||
-np.cos(th)]
|
||||
|
||||
vdotl = np.dot(lookVec, centerVel)
|
||||
adotl = np.dot(lookVec, centerAcc)
|
||||
fmratex = 2.0*(adotl + (vdotl**2 - centerVelNorm**2)/rg)/(radarWavelength)
|
||||
fmrate.append(fmratex)
|
||||
|
||||
##Fitting order 2 polynomial to FM rate
|
||||
p = np.polyfit(np.arange(width), fmrate, 2)
|
||||
azimuthFmrateVsPixel = [p[2], p[1], p[0], 0.]
|
||||
|
||||
return azimuthFmrateVsPixel
|
||||
|
||||
|
||||
def reformatDoppler(self, sceneHeaderRecord, imageFDR, imageData):
|
||||
'''
|
||||
reformat Doppler coefficients
|
||||
'''
|
||||
dopplerCoeff = [sceneHeaderRecord.metadata['Doppler center frequency constant term'],
|
||||
sceneHeaderRecord.metadata['Doppler center frequency linear term']]
|
||||
|
||||
width = imageFDR.metadata['Number of pixels per line per SAR channel']
|
||||
startingRange = imageData.metadata['Slant range to 1st data sample']
|
||||
rangeSamplingRate = self.fsampConst[int(sceneHeaderRecord.metadata['Range sampling rate in MHz'])]
|
||||
|
||||
rng = startingRange + np.arange(0,width,100) * 0.5 * Const.c / rangeSamplingRate
|
||||
doppler = dopplerCoeff[0] + dopplerCoeff[1] * rng / 1000.
|
||||
dfit = np.polyfit(np.arange(0, width, 100), doppler, 1)
|
||||
dopplerVsPixel = [dfit[1], dfit[0], 0., 0.]
|
||||
|
||||
return dopplerVsPixel
|
||||
|
||||
|
||||
def readOrbit(self, platformPositionRecord):
|
||||
'''
|
||||
reformat orbit from platformPositionRecord
|
||||
'''
|
||||
orb=Orbit()
|
||||
orb.setOrbitSource('leaderfile')
|
||||
orb.setOrbitQuality(self.orbitElementsDesignator[platformPositionRecord.metadata['Orbital elements designator']])
|
||||
|
||||
t0 = datetime.datetime(year=platformPositionRecord.metadata['Year of data point'],
|
||||
month=platformPositionRecord.metadata['Month of data point'],
|
||||
day=platformPositionRecord.metadata['Day of data point'])
|
||||
t0 = t0 + datetime.timedelta(seconds=platformPositionRecord.metadata['Seconds of day'])
|
||||
|
||||
#####Read in orbit in inertial coordinates
|
||||
deltaT = platformPositionRecord.metadata['Time interval between data points']
|
||||
numPts = platformPositionRecord.metadata['Number of data points']
|
||||
for i in range(numPts):
|
||||
vec = StateVector()
|
||||
t = t0 + datetime.timedelta(seconds=i*deltaT)
|
||||
vec.setTime(t)
|
||||
|
||||
dataPoints = platformPositionRecord.metadata['Positional Data Points'][i]
|
||||
pos = [dataPoints['Position vector X'], dataPoints['Position vector Y'], dataPoints['Position vector Z']]
|
||||
vel = [dataPoints['Velocity vector X'], dataPoints['Velocity vector Y'], dataPoints['Velocity vector Z']]
|
||||
vec.setPosition(pos)
|
||||
vec.setVelocity(vel)
|
||||
orb.addStateVector(vec)
|
||||
|
||||
return orb
|
||||
|
||||
|
||||
def burstTimeRefining(self, slcFile, numberOfSamples, numberOfLines, pulseRepetitionFrequency, burstLength, burstCycleLength, azimuthFmrateVsPixel, sensingStart, useVirtualFile=True):
|
||||
'''
|
||||
compute start time of raw burst
|
||||
'''
|
||||
#number of lines from start and end of file
|
||||
#this mainly considers ALOS-2 full-aperture length, should be updated for ALOS-4?
|
||||
delta_line = 15000
|
||||
|
||||
#first estimate at file start
|
||||
start_line1 = delta_line
|
||||
(burstStartLine1, burstStartTime1, burstStartLineEstimated1) = self.burstTime(slcFile,
|
||||
numberOfSamples,
|
||||
numberOfLines,
|
||||
pulseRepetitionFrequency,
|
||||
burstLength,
|
||||
burstCycleLength,
|
||||
azimuthFmrateVsPixel,
|
||||
sensingStart,
|
||||
start_line1,
|
||||
1000,
|
||||
1,
|
||||
useVirtualFile)
|
||||
|
||||
#estimate again at file end
|
||||
#number of burst cycles
|
||||
num_nc = np.around((numberOfLines - delta_line*2) / burstCycleLength)
|
||||
start_line2 = int(np.around(start_line1 + num_nc * burstCycleLength))
|
||||
(burstStartLine2, burstStartTime2, burstStartLineEstimated2) = self.burstTime(slcFile,
|
||||
numberOfSamples,
|
||||
numberOfLines,
|
||||
pulseRepetitionFrequency,
|
||||
burstLength,
|
||||
burstCycleLength,
|
||||
azimuthFmrateVsPixel,
|
||||
sensingStart,
|
||||
start_line2,
|
||||
1000,
|
||||
1,
|
||||
useVirtualFile)
|
||||
|
||||
#correct burst cycle value
|
||||
LineDiffIndex = 0
|
||||
LineDiffMin = np.fabs(burstStartLineEstimated1 + burstCycleLength * LineDiffIndex - burstStartLineEstimated2)
|
||||
for i in range(0, 100000):
|
||||
LineDiffMinx = np.fabs(burstStartLineEstimated1 + burstCycleLength * i - burstStartLineEstimated2)
|
||||
if LineDiffMinx <= LineDiffMin:
|
||||
LineDiffMin = LineDiffMinx
|
||||
LineDiffIndex = i
|
||||
burstCycleLengthNew = burstCycleLength - (burstStartLineEstimated1 + burstCycleLength * LineDiffIndex - burstStartLineEstimated2) / LineDiffIndex
|
||||
|
||||
#use correct burstCycleLength to do final estimation
|
||||
start_line = int(np.around(numberOfLines/2.0))
|
||||
(burstStartLine, burstStartTime, burstStartLineEstimated) = self.burstTime(slcFile,
|
||||
numberOfSamples,
|
||||
numberOfLines,
|
||||
pulseRepetitionFrequency,
|
||||
burstLength,
|
||||
burstCycleLengthNew,
|
||||
azimuthFmrateVsPixel,
|
||||
sensingStart,
|
||||
start_line,
|
||||
1000,
|
||||
1,
|
||||
useVirtualFile)
|
||||
|
||||
#return burstStartTime and refined burstCycleLength
|
||||
return (burstStartTime, burstCycleLengthNew)
|
||||
|
||||
|
||||
def burstTime(self, slcFile, numberOfSamples, numberOfLines, pulseRepetitionFrequency, burstLength, burstCycleLength, azimuthFmrateVsPixel, sensingStart, startLine=500, startColumn=500, pow2=1, useVirtualFile=True):
|
||||
'''
|
||||
compute start time of raw burst
|
||||
'''
|
||||
#######################################################
|
||||
#set these parameters
|
||||
width = numberOfSamples
|
||||
length = numberOfLines
|
||||
prf = pulseRepetitionFrequency
|
||||
nb = burstLength
|
||||
nc = burstCycleLength
|
||||
fmrateCoeff = azimuthFmrateVsPixel
|
||||
sensing_start = sensingStart
|
||||
saz = startLine #start line to be used (included, index start with 0. default: 500)
|
||||
srg = startColumn #start column to be used (included, index start with 0. default: 500)
|
||||
p2 = pow2 #must be 1(default) or power of 2. azimuth fft length = THIS ARGUMENT * next of power of 2 of full-aperture length.
|
||||
#######################################################
|
||||
|
||||
def create_lfm(ns, it, offset, k):
|
||||
'''
|
||||
# create linear FM signal
|
||||
# ns: number of samples
|
||||
# it: time interval of the samples
|
||||
# offset: offset
|
||||
# k: linear FM rate
|
||||
#offset-centered, this applies to both odd and even cases
|
||||
'''
|
||||
ht = (ns - 1) / 2.0
|
||||
t = np.arange(-ht, ht+1.0, 1)
|
||||
t = (t + offset) * it
|
||||
cj = np.complex64(1j)
|
||||
lfm = np.exp(cj * np.pi * k * t**2)
|
||||
|
||||
return lfm
|
||||
|
||||
|
||||
def next_pow2(a):
|
||||
x=2
|
||||
while x < a:
|
||||
x *= 2
|
||||
return x
|
||||
|
||||
|
||||
def is_power2(num):
|
||||
'''states if a number is a power of two'''
|
||||
return num != 0 and ((num & (num - 1)) == 0)
|
||||
|
||||
|
||||
if not (p2 == 1 or is_power2(p2)):
|
||||
raise Exception('pow2 must be 1 or power of 2\n')
|
||||
|
||||
#fmrate, use the convention that ka > 0
|
||||
ka = -np.polyval(fmrateCoeff[::-1], np.arange(width))
|
||||
|
||||
#area to be used for estimation
|
||||
naz = int(np.round(nc)) #number of lines to be used.
|
||||
eaz = saz+naz-1 #ending line to be used (included)
|
||||
caz = int(np.round((saz+eaz)/2.0)) #central line of the lines used.
|
||||
caz_deramp = (saz+eaz)/2.0 #center of deramp signal (may be fractional line number)
|
||||
|
||||
nrg = 400 #number of columns to be used
|
||||
erg = srg+nrg-1 #ending column to be used (included)
|
||||
crg = int(np.round((srg+erg)/2.0)) #central column of the columns used.
|
||||
|
||||
#check parameters
|
||||
if not (saz >=0 and saz <= length - 1):
|
||||
raise Exception('wrong starting line\n')
|
||||
if not (eaz >=0 and eaz <= length - 1):
|
||||
raise Exception('wrong ending line\n')
|
||||
if not (srg >=0 and srg <= width - 1):
|
||||
raise Exception('wrong starting column\n')
|
||||
if not (erg >=0 and erg <= width - 1):
|
||||
raise Exception('wrong ending column\n')
|
||||
|
||||
#number of lines of a full-aperture
|
||||
nfa = int(np.round(prf / ka[crg] / (1.0 / prf)))
|
||||
#use nfa to determine fft size. fft size can be larger than this
|
||||
nazfft = next_pow2(nfa) * p2
|
||||
|
||||
#deramp signal
|
||||
deramp = np.zeros((naz, nrg), dtype=np.complex64)
|
||||
for i in range(nrg):
|
||||
deramp[:, i] = create_lfm(naz, 1.0/prf, 0, -ka[i+srg])
|
||||
|
||||
#read data, python should be faster
|
||||
useGdal = False
|
||||
if useGdal:
|
||||
from osgeo import gdal
|
||||
###Read in chunk of data
|
||||
ds = gdal.Open(slcFile + '.vrt', gdal.GA_ReadOnly)
|
||||
data = ds.ReadAsArray(srg, saz, nrg, naz)
|
||||
ds = None
|
||||
else:
|
||||
#!!!hard-coded: ALOS-2 image file header 720 bytes, line header 544 bytes
|
||||
if useVirtualFile == True:
|
||||
fileHeader = 720
|
||||
lineHeader = 544
|
||||
#lineHeader is just integer multiples of complex pixle size, so it's good
|
||||
lineHeaderSamples = int(lineHeader/np.dtype(np.complex64).itemsize)
|
||||
slcFile = self.find_keyword(slcFile+'.vrt', 'SourceFilename')
|
||||
else:
|
||||
fileHeader = 0
|
||||
lineHeader = 0
|
||||
lineHeaderSamples = 0
|
||||
data = np.memmap(slcFile, np.complex64,'r', offset = fileHeader, shape=(numberOfLines,lineHeaderSamples+numberOfSamples))
|
||||
data = data[saz:eaz+1, lineHeaderSamples+srg:lineHeaderSamples+erg+1]
|
||||
if useVirtualFile == True:
|
||||
data = data.byteswap()
|
||||
|
||||
#deramp data
|
||||
datadr = deramp * data
|
||||
|
||||
#spectrum
|
||||
spec = np.fft.fft(datadr, n=nazfft, axis=0)
|
||||
|
||||
#shift zero-frequency component to center of spectrum
|
||||
spec = np.fft.fftshift(spec, axes=0)
|
||||
|
||||
specm=np.mean(np.absolute(spec), axis=1)
|
||||
|
||||
#number of samples of the burst in frequncy domain
|
||||
nbs = int(np.round(nb*(1.0/prf)*ka[crg]/prf*nazfft));
|
||||
#number of samples of the burst cycle in frequncy domain
|
||||
ncs = int(np.round(nc*(1.0/prf)*ka[crg]/prf*nazfft));
|
||||
rect = np.ones(nbs, dtype=np.float32)
|
||||
|
||||
#make sure orders of specm and rect are correct, so that peaks
|
||||
#happen in the same order as their corresponding bursts
|
||||
corr=np.correlate(specm, rect,'same')
|
||||
|
||||
#find burst spectrum center
|
||||
ncs_rh = int(np.round((nazfft - ncs) / 2.0))
|
||||
#corr_bc = corr[ncs_rh: ncs_rh+ncs]
|
||||
#offset between spectrum center and center
|
||||
offset_spec = np.argmax(corr[ncs_rh: ncs_rh+ncs])+ncs_rh - (nazfft - 1.0) / 2.0
|
||||
#offset in number of azimuth lines
|
||||
offset_naz = offset_spec / nazfft * prf / ka[crg] / (1.0/prf)
|
||||
|
||||
#start line of burst (fractional line number)
|
||||
saz_burst = -offset_naz + caz_deramp - (nb - 1.0) / 2.0
|
||||
|
||||
#find out the start line of all bursts (fractional line number,
|
||||
#line index start with 0, line 0 is the first SLC line)
|
||||
#now only find first burst
|
||||
for i in range(-100000, 100000):
|
||||
saz_burstx = saz_burst + nc * i
|
||||
st_burstx = sensing_start + datetime.timedelta(seconds=saz_burstx * (1.0/prf))
|
||||
if saz_burstx >= 0.0 and saz_burstx <= length:
|
||||
burstStartLine = saz_burstx
|
||||
burstStartTime = st_burstx
|
||||
break
|
||||
burstStartLineEstimated = saz_burst
|
||||
|
||||
#dump spectrum and correlation
|
||||
debug = False
|
||||
if debug:
|
||||
specm_corr = ''
|
||||
for i in range(nazfft):
|
||||
specm_corr += '{:6d} {:f} {:6d} {:f}\n'.format(i, specm[i], i, corr[i])
|
||||
specm_corr_name = str(sensingStart.year)[2:] + '%02d' % sensingStart.month + '%02d' % sensingStart.day + '_spec_corr.txt'
|
||||
with open(specm_corr_name, 'w') as f:
|
||||
f.write(specm_corr)
|
||||
|
||||
return (burstStartLine, burstStartTime, burstStartLineEstimated)
|
||||
|
||||
|
||||
def find_keyword(self, xmlfile, keyword):
|
||||
from xml.etree.ElementTree import ElementTree
|
||||
|
||||
value = None
|
||||
xmlx = ElementTree(file=open(xmlfile,'r')).getroot()
|
||||
#try 10 times
|
||||
for i in range(10):
|
||||
path=''
|
||||
for j in range(i):
|
||||
path += '*/'
|
||||
value0 = xmlx.find(path+keyword)
|
||||
if value0 != None:
|
||||
value = value0.text
|
||||
break
|
||||
|
||||
return value
|
||||
|
||||
|
||||
def writeRawData(self, fp, line):
|
||||
'''
|
||||
Convert complex integer to complex64 format.
|
||||
'''
|
||||
cJ = np.complex64(1j)
|
||||
data = line[0::2] + cJ * line[1::2]
|
||||
data.tofile(fp)
|
||||
|
||||
|
||||
|
||||
if __name__ == '__main__':
|
||||
|
||||
main()
|
||||
|
||||
|
|
@ -0,0 +1,7 @@
|
|||
InstallSameDir(
|
||||
__init__.py
|
||||
ALOS2.py
|
||||
Frame.py
|
||||
Swath.py
|
||||
Track.py
|
||||
)
|
||||
|
|
@ -0,0 +1,164 @@
|
|||
#!/usr/bin/env python3
|
||||
|
||||
#Author: Cunren Liang, 2015-
|
||||
|
||||
import isce
|
||||
import datetime
|
||||
import isceobj
|
||||
import numpy as np
|
||||
from iscesys.Component.Component import Component
|
||||
from iscesys.Traits import datetimeType
|
||||
|
||||
|
||||
####List of parameters
|
||||
FRAME_NUMBER = Component.Parameter('frameNumber',
|
||||
public_name = 'frame number',
|
||||
default = None,
|
||||
type = str,
|
||||
mandatory = True,
|
||||
doc = 'frame number in unpacked file names (not in zip file name!)')
|
||||
|
||||
PROCESSING_FACILITY = Component.Parameter('processingFacility',
|
||||
public_name='processing facility',
|
||||
default=None,
|
||||
type = str,
|
||||
mandatory = False,
|
||||
doc = 'processing facility information')
|
||||
|
||||
PROCESSING_SYSTEM = Component.Parameter('processingSystem',
|
||||
public_name='processing system',
|
||||
default=None,
|
||||
type = str,
|
||||
mandatory = False,
|
||||
doc = 'processing system information')
|
||||
|
||||
PROCESSING_SYSTEM_VERSION = Component.Parameter('processingSoftwareVersion',
|
||||
public_name='processing software version',
|
||||
default=None,
|
||||
type = str,
|
||||
mandatory = False,
|
||||
doc = 'processing system software version')
|
||||
|
||||
ORBIT_QUALITY = Component.Parameter('orbitQuality',
|
||||
public_name='orbit quality',
|
||||
default=None,
|
||||
type = str,
|
||||
mandatory = False,
|
||||
doc = 'orbit quality. 0: preliminary, 1: decision, 2: high precision')
|
||||
|
||||
#note that following parameters consider range/azimuth number of looks in interferogram formation
|
||||
#except: rangeSamplingRate, prf
|
||||
|
||||
NUMBER_OF_SAMPLES = Component.Parameter('numberOfSamples',
|
||||
public_name='number of samples',
|
||||
default=None,
|
||||
type=int,
|
||||
mandatory=True,
|
||||
doc='width of the burst slc')
|
||||
|
||||
NUMBER_OF_LINES = Component.Parameter('numberOfLines',
|
||||
public_name='number of lines',
|
||||
default=None,
|
||||
type=int,
|
||||
mandatory=True,
|
||||
doc='length of the burst slc')
|
||||
|
||||
STARTING_RANGE = Component.Parameter('startingRange',
|
||||
public_name='starting range',
|
||||
default=None,
|
||||
type=float,
|
||||
mandatory=True,
|
||||
doc='slant range to first pixel in m')
|
||||
|
||||
RANGE_SAMPLING_RATE = Component.Parameter('rangeSamplingRate',
|
||||
public_name = 'range sampling rate',
|
||||
default = None,
|
||||
type = float,
|
||||
mandatory = True,
|
||||
doc = 'range sampling rate in Hz')
|
||||
|
||||
RANGE_PIXEL_SIZE = Component.Parameter('rangePixelSize',
|
||||
public_name = 'range pixel size',
|
||||
default = None,
|
||||
type=float,
|
||||
mandatory = True,
|
||||
doc = 'slant range pixel size in m')
|
||||
|
||||
SENSING_START = Component.Parameter('sensingStart',
|
||||
public_name='sensing start',
|
||||
default=None,
|
||||
type=datetimeType,
|
||||
mandatory=True,
|
||||
doc='UTC time corresponding to first line of swath SLC')
|
||||
|
||||
PRF = Component.Parameter('prf',
|
||||
public_name = 'pulse repetition frequency',
|
||||
default = None,
|
||||
type = float,
|
||||
mandatory = True,
|
||||
doc = 'pulse repetition frequency in Hz')
|
||||
|
||||
AZIMUTH_PIXEL_SIZE = Component.Parameter('azimuthPixelSize',
|
||||
public_name = 'azimuth pixel size',
|
||||
default = None,
|
||||
type=float,
|
||||
mandatory = True,
|
||||
doc = 'azimuth pixel size on ground in m')
|
||||
|
||||
AZIMUTH_LINE_INTERVAL = Component.Parameter('azimuthLineInterval',
|
||||
public_name = 'azimuth line interval',
|
||||
default = None,
|
||||
type=float,
|
||||
mandatory = True,
|
||||
doc = 'azimuth line interval in s')
|
||||
|
||||
####List of facilities
|
||||
SWATHS = Component.Facility('swaths',
|
||||
public_name='swaths',
|
||||
module = 'iscesys.Component',
|
||||
factory = 'createTraitSeq',
|
||||
args=('swath',),
|
||||
mandatory = False,
|
||||
doc = 'trait sequence of swath SLCs')
|
||||
|
||||
class Frame(Component):
|
||||
"""A class to represent a frame"""
|
||||
|
||||
family = 'frame'
|
||||
logging_name = 'isce.frame'
|
||||
|
||||
|
||||
|
||||
|
||||
parameter_list = (FRAME_NUMBER,
|
||||
PROCESSING_FACILITY,
|
||||
PROCESSING_SYSTEM,
|
||||
PROCESSING_SYSTEM_VERSION,
|
||||
ORBIT_QUALITY,
|
||||
NUMBER_OF_SAMPLES,
|
||||
NUMBER_OF_LINES,
|
||||
STARTING_RANGE,
|
||||
RANGE_SAMPLING_RATE,
|
||||
RANGE_PIXEL_SIZE,
|
||||
SENSING_START,
|
||||
PRF,
|
||||
AZIMUTH_PIXEL_SIZE,
|
||||
AZIMUTH_LINE_INTERVAL
|
||||
)
|
||||
|
||||
|
||||
facility_list = (SWATHS,)
|
||||
|
||||
|
||||
def __init__(self,name=''):
|
||||
super(Frame, self).__init__(family=self.__class__.family, name=name)
|
||||
return None
|
||||
|
||||
|
||||
def clone(self):
|
||||
import copy
|
||||
res = copy.deepcopy(self)
|
||||
res.image._accessor = None
|
||||
res.image._factory = None
|
||||
|
||||
return res
|
||||
|
|
@ -0,0 +1,31 @@
|
|||
#~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
|
||||
#
|
||||
# Walter Szeliga
|
||||
# NASA Jet Propulsion Laboratory
|
||||
# California Institute of Technology
|
||||
# (c) 2010 All Rights Reserved
|
||||
#
|
||||
#~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
|
||||
|
||||
|
||||
#!/usr/bin/env python
|
||||
import os
|
||||
|
||||
Import('envSensor')
|
||||
envMultiMode = envSensor.Clone()
|
||||
project = 'MultiMode'
|
||||
package = envMultiMode['PACKAGE']
|
||||
envMultiMode['PROJECT'] = project
|
||||
envMultiMode['SENSOR_SCONS_INSTALL'] = os.path.join(
|
||||
envMultiMode['PRJ_SCONS_INSTALL'], package, 'Sensor',project)
|
||||
install = envMultiMode['SENSOR_SCONS_INSTALL']
|
||||
|
||||
listFiles = ['__init__.py','ALOS2.py','Frame.py','Swath.py','Track.py']
|
||||
|
||||
helpList,installHelp = envMultiMode['HELP_BUILDER'](envMultiMode,'__init__.py',install)
|
||||
|
||||
envMultiMode.Install(installHelp,helpList)
|
||||
envMultiMode.Alias('install',installHelp)
|
||||
|
||||
envMultiMode.Install(install,listFiles)
|
||||
envMultiMode.Alias('install',install)
|
||||
|
|
@ -0,0 +1,236 @@
|
|||
#!/usr/bin/env python3
|
||||
|
||||
#Author: Cunren Liang, 2015-
|
||||
|
||||
import isce
|
||||
import datetime
|
||||
import isceobj
|
||||
import numpy as np
|
||||
from iscesys.Component.Component import Component
|
||||
from isceobj.Image.Image import Image
|
||||
from isceobj.Orbit.Orbit import Orbit
|
||||
from isceobj.Util.decorators import type_check
|
||||
from iscesys.Traits import datetimeType
|
||||
|
||||
|
||||
####List of parameters
|
||||
SWATH_NUMBER = Component.Parameter('swathNumber',
|
||||
public_name = 'swath number',
|
||||
default = None,
|
||||
type = int,
|
||||
mandatory = True,
|
||||
doc = 'swath number for bookkeeping')
|
||||
|
||||
POLARIZATION = Component.Parameter('polarization',
|
||||
public_name = 'polarization',
|
||||
default = None,
|
||||
type = str,
|
||||
mandatory = True,
|
||||
doc = 'polarization')
|
||||
|
||||
NUMBER_OF_SAMPLES = Component.Parameter('numberOfSamples',
|
||||
public_name='number of samples',
|
||||
default=None,
|
||||
type=int,
|
||||
mandatory=True,
|
||||
doc='width of the burst slc')
|
||||
|
||||
NUMBER_OF_LINES = Component.Parameter('numberOfLines',
|
||||
public_name='number of lines',
|
||||
default=None,
|
||||
type=int,
|
||||
mandatory=True,
|
||||
doc='length of the burst slc')
|
||||
|
||||
STARTING_RANGE = Component.Parameter('startingRange',
|
||||
public_name='starting range',
|
||||
default=None,
|
||||
type=float,
|
||||
mandatory=True,
|
||||
doc='slant range to first pixel in m')
|
||||
|
||||
RANGE_SAMPLING_RATE = Component.Parameter('rangeSamplingRate',
|
||||
public_name = 'range sampling rate',
|
||||
default = None,
|
||||
type = float,
|
||||
mandatory = True,
|
||||
doc = 'range sampling rate in Hz')
|
||||
|
||||
RANGE_PIXEL_SIZE = Component.Parameter('rangePixelSize',
|
||||
public_name = 'range pixel size',
|
||||
default = None,
|
||||
type=float,
|
||||
mandatory = True,
|
||||
doc = 'slant range pixel size in m')
|
||||
|
||||
RANGE_BANDWIDTH = Component.Parameter('rangeBandwidth',
|
||||
public_name = 'range bandwidth',
|
||||
default = None,
|
||||
type=float,
|
||||
mandatory = True,
|
||||
doc = 'range bandwidth in Hz')
|
||||
|
||||
SENSING_START = Component.Parameter('sensingStart',
|
||||
public_name='sensing start',
|
||||
default=None,
|
||||
type=datetimeType,
|
||||
mandatory=True,
|
||||
doc='UTC time corresponding to first line of swath SLC')
|
||||
|
||||
PRF = Component.Parameter('prf',
|
||||
public_name = 'pulse repetition frequency',
|
||||
default = None,
|
||||
type = float,
|
||||
mandatory = True,
|
||||
doc = 'pulse repetition frequency in Hz')
|
||||
|
||||
AZIMUTH_PIXEL_SIZE = Component.Parameter('azimuthPixelSize',
|
||||
public_name = 'azimuth pixel size',
|
||||
default = None,
|
||||
type=float,
|
||||
mandatory = True,
|
||||
doc = 'azimuth pixel size on ground in m')
|
||||
|
||||
AZIMUTH_LINE_INTERVAL = Component.Parameter('azimuthLineInterval',
|
||||
public_name = 'azimuth line interval',
|
||||
default = None,
|
||||
type=float,
|
||||
mandatory = True,
|
||||
doc = 'azimuth line interval in s')
|
||||
|
||||
DOPPLER_VS_PIXEL = Component.Parameter('dopplerVsPixel',
|
||||
public_name = 'doppler vs pixel',
|
||||
default = None,
|
||||
type = float,
|
||||
mandatory = True,
|
||||
container = list,
|
||||
doc = 'Doppler (Hz) polynomial coefficients vs range pixel number')
|
||||
|
||||
AZIMUTH_FMRATE_VS_PIXEL = Component.Parameter('azimuthFmrateVsPixel',
|
||||
public_name = 'azimuth fm rate vs pixel',
|
||||
default = [],
|
||||
type = float,
|
||||
mandatory = True,
|
||||
container = list,
|
||||
doc = 'azimuth FM rate (Hz/s) polynomial coefficients vs range pixel number')
|
||||
|
||||
#for ScanSAR full-aperture product
|
||||
BURST_LENGTH = Component.Parameter('burstLength',
|
||||
public_name = 'Burst Length',
|
||||
default = None,
|
||||
type = float,
|
||||
# type = int,
|
||||
mandatory = False,
|
||||
doc = 'number of pulses in a raw burst')
|
||||
|
||||
BURST_CYCLE_LENGTH = Component.Parameter('burstCycleLength',
|
||||
public_name = 'Burst cycle length',
|
||||
default = None,
|
||||
type = float,
|
||||
mandatory = False,
|
||||
doc = 'number of pulses in a raw burst cycle')
|
||||
|
||||
BURST_START_TIME = Component.Parameter('burstStartTime',
|
||||
public_name='Burst start time',
|
||||
default=None,
|
||||
type=datetimeType,
|
||||
mandatory=False,
|
||||
doc='start time of a raw burst')
|
||||
|
||||
#for ScanSAR burst-by-burst processing
|
||||
PRF_FRACTION = Component.Parameter('prfFraction',
|
||||
public_name = 'prf fraction',
|
||||
default = None,
|
||||
type = float,
|
||||
mandatory = False,
|
||||
doc = 'fraction of PRF for extracting bursts for bookkeeping')
|
||||
|
||||
NUMBER_OF_BURSTS = Component.Parameter('numberOfBursts',
|
||||
public_name='number of bursts',
|
||||
default=None,
|
||||
type=int,
|
||||
mandatory=False,
|
||||
doc='number of bursts in a swath')
|
||||
|
||||
FIRST_BURST_RAW_START_TIME = Component.Parameter('firstBurstRawStartTime',
|
||||
public_name='start time of first raw burst',
|
||||
default=None,
|
||||
type=datetimeType,
|
||||
mandatory=False,
|
||||
doc='start time of first raw burst')
|
||||
|
||||
FIRST_BURST_SLC_START_TIME = Component.Parameter('firstBurstSlcStartTime',
|
||||
public_name='start time of first burst slc',
|
||||
default=None,
|
||||
type=datetimeType,
|
||||
mandatory=False,
|
||||
doc='start time of first burst slc')
|
||||
|
||||
BURST_SLC_FIRST_LINE_OFFSETS = Component.Parameter('burstSlcFirstLineOffsets',
|
||||
public_name = 'burst SLC first line offsets',
|
||||
default = None,
|
||||
type = int,
|
||||
mandatory = False,
|
||||
container = list,
|
||||
doc = 'burst SLC first line offsets')
|
||||
|
||||
BURST_SLC_NUMBER_OF_SAMPLES = Component.Parameter('burstSlcNumberOfSamples',
|
||||
public_name='burst slc number of samples',
|
||||
default=None,
|
||||
type=int,
|
||||
mandatory=False,
|
||||
doc='burst slc width of the burst slc')
|
||||
|
||||
BURST_SLC_NUMBER_OF_LINES = Component.Parameter('burstSlcNumberOfLines',
|
||||
public_name='burst slc number of lines',
|
||||
default=None,
|
||||
type=int,
|
||||
mandatory=False,
|
||||
doc='burst slc length of the burst slc')
|
||||
|
||||
|
||||
class Swath(Component):
|
||||
"""A class to represent a swath SLC"""
|
||||
|
||||
family = 'swath'
|
||||
logging_name = 'isce.swath'
|
||||
|
||||
parameter_list = (SWATH_NUMBER,
|
||||
POLARIZATION,
|
||||
NUMBER_OF_SAMPLES,
|
||||
NUMBER_OF_LINES,
|
||||
STARTING_RANGE,
|
||||
RANGE_SAMPLING_RATE,
|
||||
RANGE_PIXEL_SIZE,
|
||||
RANGE_BANDWIDTH,
|
||||
SENSING_START,
|
||||
PRF,
|
||||
AZIMUTH_PIXEL_SIZE,
|
||||
AZIMUTH_LINE_INTERVAL,
|
||||
DOPPLER_VS_PIXEL,
|
||||
AZIMUTH_FMRATE_VS_PIXEL,
|
||||
BURST_LENGTH,
|
||||
BURST_CYCLE_LENGTH,
|
||||
BURST_START_TIME,
|
||||
PRF_FRACTION,
|
||||
NUMBER_OF_BURSTS,
|
||||
FIRST_BURST_RAW_START_TIME,
|
||||
FIRST_BURST_SLC_START_TIME,
|
||||
BURST_SLC_FIRST_LINE_OFFSETS,
|
||||
BURST_SLC_NUMBER_OF_SAMPLES,
|
||||
BURST_SLC_NUMBER_OF_LINES
|
||||
)
|
||||
|
||||
|
||||
def __init__(self,name=''):
|
||||
super(Swath, self).__init__(family=self.__class__.family, name=name)
|
||||
return None
|
||||
|
||||
|
||||
def clone(self):
|
||||
import copy
|
||||
res = copy.deepcopy(self)
|
||||
res.image._accessor = None
|
||||
res.image._factory = None
|
||||
|
||||
return res
|
||||
|
|
@ -0,0 +1,186 @@
|
|||
#!/usr/bin/env python3
|
||||
|
||||
#Author: Cunren Liang, 2015-
|
||||
|
||||
import isce
|
||||
import datetime
|
||||
import isceobj
|
||||
import numpy as np
|
||||
from iscesys.Component.Component import Component
|
||||
from isceobj.Image.Image import Image
|
||||
from isceobj.Orbit.Orbit import Orbit
|
||||
from isceobj.Util.decorators import type_check
|
||||
from iscesys.Traits import datetimeType
|
||||
|
||||
|
||||
####List of parameters
|
||||
PASS_DIRECTION = Component.Parameter('passDirection',
|
||||
public_name='pass direction',
|
||||
default = None,
|
||||
type=str,
|
||||
mandatory=True,
|
||||
doc = 'satellite flying direction, ascending/descending')
|
||||
|
||||
POINTING_DIRECTION = Component.Parameter('pointingDirection',
|
||||
public_name='pointing direction',
|
||||
default=None,
|
||||
type = str,
|
||||
mandatory = True,
|
||||
doc = 'antenna point direction: right/left')
|
||||
|
||||
OPERATION_MODE = Component.Parameter('operationMode',
|
||||
public_name='operation mode',
|
||||
default=None,
|
||||
type = str,
|
||||
mandatory = True,
|
||||
doc = 'JAXA ALOS-2 operation mode code')
|
||||
|
||||
RADAR_WAVELENGTH = Component.Parameter('radarWavelength',
|
||||
public_name = 'radarWavelength',
|
||||
default = None,
|
||||
type = float,
|
||||
mandatory = True,
|
||||
doc = 'radar wavelength in m')
|
||||
|
||||
NUMBER_OF_SAMPLES = Component.Parameter('numberOfSamples',
|
||||
public_name='number of samples',
|
||||
default=None,
|
||||
type=int,
|
||||
mandatory=True,
|
||||
doc='width of the burst slc')
|
||||
|
||||
NUMBER_OF_LINES = Component.Parameter('numberOfLines',
|
||||
public_name='number of lines',
|
||||
default=None,
|
||||
type=int,
|
||||
mandatory=True,
|
||||
doc='length of the burst slc')
|
||||
|
||||
STARTING_RANGE = Component.Parameter('startingRange',
|
||||
public_name='starting range',
|
||||
default=None,
|
||||
type=float,
|
||||
mandatory=True,
|
||||
doc='slant range to first pixel in m')
|
||||
|
||||
RANGE_SAMPLING_RATE = Component.Parameter('rangeSamplingRate',
|
||||
public_name = 'range sampling rate',
|
||||
default = None,
|
||||
type = float,
|
||||
mandatory = True,
|
||||
doc = 'range sampling rate in Hz')
|
||||
|
||||
RANGE_PIXEL_SIZE = Component.Parameter('rangePixelSize',
|
||||
public_name = 'range pixel size',
|
||||
default = None,
|
||||
type=float,
|
||||
mandatory = True,
|
||||
doc = 'slant range pixel size in m')
|
||||
|
||||
SENSING_START = Component.Parameter('sensingStart',
|
||||
public_name='sensing start',
|
||||
default=None,
|
||||
type=datetimeType,
|
||||
mandatory=True,
|
||||
doc='UTC time corresponding to first line of swath SLC')
|
||||
|
||||
PRF = Component.Parameter('prf',
|
||||
public_name = 'pulse repetition frequency',
|
||||
default = None,
|
||||
type = float,
|
||||
mandatory = True,
|
||||
doc = 'pulse repetition frequency in Hz')
|
||||
|
||||
AZIMUTH_PIXEL_SIZE = Component.Parameter('azimuthPixelSize',
|
||||
public_name = 'azimuth pixel size',
|
||||
default = None,
|
||||
type=float,
|
||||
mandatory = True,
|
||||
doc = 'azimuth pixel size on ground in m')
|
||||
|
||||
AZIMUTH_LINE_INTERVAL = Component.Parameter('azimuthLineInterval',
|
||||
public_name = 'azimuth line interval',
|
||||
default = None,
|
||||
type=float,
|
||||
mandatory = True,
|
||||
doc = 'azimuth line interval in s')
|
||||
|
||||
#########################################################################################################
|
||||
#for dense offset
|
||||
DOPPLER_VS_PIXEL = Component.Parameter('dopplerVsPixel',
|
||||
public_name = 'doppler vs pixel',
|
||||
default = None,
|
||||
type = float,
|
||||
mandatory = True,
|
||||
container = list,
|
||||
doc = 'Doppler (Hz) polynomial coefficients vs range pixel number')
|
||||
#########################################################################################################
|
||||
|
||||
|
||||
#ProductManager cannot handle two or more layers of createTraitSeq
|
||||
#use list instead for bookkeeping
|
||||
#can creat a class Frames(Component) and wrap trait sequence, but it
|
||||
#leads to more complicated output xml file, which is not good for viewing
|
||||
FRAMES = Component.Parameter('frames',
|
||||
public_name = 'frames',
|
||||
default = [],
|
||||
#type = float,
|
||||
mandatory = True,
|
||||
container = list,
|
||||
doc = 'sequence of frames')
|
||||
|
||||
|
||||
####List of facilities
|
||||
ORBIT = Component.Facility('orbit',
|
||||
public_name='orbit',
|
||||
module='isceobj.Orbit.Orbit',
|
||||
factory='createOrbit',
|
||||
args=(),
|
||||
doc = 'orbit state vectors')
|
||||
|
||||
# FRAMES = Component.Facility('frames',
|
||||
# public_name='frames',
|
||||
# module = 'iscesys.Component',
|
||||
# factory = 'createTraitSeq',
|
||||
# args=('frame',),
|
||||
# mandatory = False,
|
||||
# doc = 'trait sequence of frames')
|
||||
|
||||
class Track(Component):
|
||||
"""A class to represent a track"""
|
||||
|
||||
family = 'track'
|
||||
logging_name = 'isce.track'
|
||||
##############################################################################
|
||||
parameter_list = (PASS_DIRECTION,
|
||||
POINTING_DIRECTION,
|
||||
OPERATION_MODE,
|
||||
RADAR_WAVELENGTH,
|
||||
NUMBER_OF_SAMPLES,
|
||||
NUMBER_OF_LINES,
|
||||
STARTING_RANGE,
|
||||
RANGE_SAMPLING_RATE,
|
||||
RANGE_PIXEL_SIZE,
|
||||
SENSING_START,
|
||||
PRF,
|
||||
AZIMUTH_PIXEL_SIZE,
|
||||
AZIMUTH_LINE_INTERVAL,
|
||||
DOPPLER_VS_PIXEL,
|
||||
FRAMES
|
||||
)
|
||||
|
||||
facility_list = (ORBIT,
|
||||
)
|
||||
|
||||
def __init__(self,name=''):
|
||||
super(Track, self).__init__(family=self.__class__.family, name=name)
|
||||
return None
|
||||
|
||||
|
||||
def clone(self):
|
||||
import copy
|
||||
res = copy.deepcopy(self)
|
||||
res.image._accessor = None
|
||||
res.image._factory = None
|
||||
|
||||
return res
|
||||
|
|
@ -0,0 +1,55 @@
|
|||
#Author: Cunren Liang, 2015-
|
||||
|
||||
def createSwath():
|
||||
from .Swath import Swath
|
||||
return Swath()
|
||||
|
||||
def createFrame():
|
||||
from .Frame import Frame
|
||||
return Frame()
|
||||
|
||||
def createTrack():
|
||||
from .Track import Track
|
||||
return Track()
|
||||
|
||||
|
||||
def createALOS2(name=None):
|
||||
from .ALOS2 import ALOS2
|
||||
return ALOS2()
|
||||
|
||||
|
||||
SENSORS = {
|
||||
'ALOS2' : createALOS2,
|
||||
}
|
||||
|
||||
def getFactoriesInfo():
|
||||
"""
|
||||
Returns a dictionary with information on how to create an object Sensor from its factory
|
||||
"""
|
||||
return {'MultiModeSensor':
|
||||
{'args':
|
||||
{
|
||||
'sensor':{'value':list(SENSORS.keys()),'type':'str','optional':False}
|
||||
},
|
||||
'factory':'createSensor'
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
|
||||
def createSensor(sensor='', name=None):
|
||||
|
||||
try:
|
||||
cls = SENSORS[str(sensor).upper()]
|
||||
try:
|
||||
instance = cls(name)
|
||||
except AttributeError:
|
||||
raise TypeError("'sensor name'=%s cannot be interpreted" %
|
||||
str(sensor))
|
||||
pass
|
||||
except:
|
||||
print("Sensor type not recognized. Valid Sensor types:\n",
|
||||
SENSORS.keys())
|
||||
instance = None
|
||||
pass
|
||||
return instance
|
||||
|
|
@ -57,3 +57,4 @@ SConscript(os.path.join('src', 'SConscript'),
|
|||
SConscript(os.path.join('TOPS','SConscript'))
|
||||
SConscript(os.path.join('GRD', 'SConscript'))
|
||||
SConscript(os.path.join('ScanSAR', 'SConscript'))
|
||||
SConscript(os.path.join('MultiMode', 'SConscript'))
|
||||
|
|
|
|||
|
|
@ -473,7 +473,7 @@ def subband(self, ionParam):
|
|||
|
||||
#subband
|
||||
rg_filter(tmpFilename,
|
||||
burst.numberOfSamples,
|
||||
#burst.numberOfSamples,
|
||||
2,
|
||||
[os.path.join(lowerDir, tmpFilename2), os.path.join(upperDir, tmpFilename2)],
|
||||
[ionParam.rgBandwidthSub / rangeSamplingRate, ionParam.rgBandwidthSub / rangeSamplingRate],
|
||||
|
|
|
|||
|
|
@ -1,28 +1,20 @@
|
|||
#!/usr/bin/env python3
|
||||
|
||||
#~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
|
||||
# Copyright 2012 California Institute of Technology. ALL RIGHTS RESERVED.
|
||||
# copyright: 2012 to the present, california institute of technology.
|
||||
# all rights reserved. united states government sponsorship acknowledged.
|
||||
# any commercial use must be negotiated with the office of technology transfer
|
||||
# at the california institute of technology.
|
||||
#
|
||||
# Licensed under the Apache License, Version 2.0 (the "License");
|
||||
# you may not use this file except in compliance with the License.
|
||||
# You may obtain a copy of the License at
|
||||
# this software may be subject to u.s. export control laws. by accepting this
|
||||
# software, the user agrees to comply with all applicable u.s. export laws and
|
||||
# regulations. user has the responsibility to obtain export licenses, or other
|
||||
# export authority as may be required before exporting such information to
|
||||
# foreign countries or providing access to foreign persons.
|
||||
#
|
||||
# http://www.apache.org/licenses/LICENSE-2.0
|
||||
#
|
||||
# Unless required by applicable law or agreed to in writing, software
|
||||
# distributed under the License is distributed on an "AS IS" BASIS,
|
||||
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||
# See the License for the specific language governing permissions and
|
||||
# limitations under the License.
|
||||
#
|
||||
# United States Government Sponsorship acknowledged. This software is subject to
|
||||
# U.S. export control laws and regulations and has been classified as 'EAR99 NLR'
|
||||
# (No [Export] License Required except when exporting to an embargoed country,
|
||||
# end user, or in support of a prohibited end use). By downloading this software,
|
||||
# the user agrees to comply with all applicable U.S. export laws and regulations.
|
||||
# The user has the responsibility to obtain export licenses, or other export
|
||||
# authority as may be required before exporting this software to any 'EAR99'
|
||||
# embargoed foreign country or citizen of those countries.
|
||||
# installation and use of this software is restricted by a license agreement
|
||||
# between the licensee and the california institute of technology. it is the
|
||||
# user's responsibility to abide by the terms of the license agreement.
|
||||
#
|
||||
# Author: Giangi Sacco
|
||||
#~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
|
||||
|
|
@ -41,7 +33,7 @@ from iscesys.Compatibility import Compatibility
|
|||
Compatibility.checkPythonVersion()
|
||||
from mroipac.ampcor import ampcor
|
||||
from isceobj.Util.mathModule import is_power2
|
||||
from isceobj.Util.decorators import use_api
|
||||
#from isceobj.Util.decorators import use_api
|
||||
|
||||
WINDOW_SIZE_WIDTH = Component.Parameter('windowSizeWidth',
|
||||
public_name='WINDOW_SIZE_WIDTH',
|
||||
|
|
@ -297,7 +289,7 @@ class Ampcor(Component):
|
|||
DEBUG_FLAG,
|
||||
DISPLAY_FLAG)
|
||||
|
||||
@use_api
|
||||
# @use_api
|
||||
def ampcor(self,slcImage1 = None,slcImage2 = None, band1=None, band2=None):
|
||||
if not (slcImage1 == None):
|
||||
self.slcImage1 = slcImage1
|
||||
|
|
@ -396,8 +388,8 @@ class Ampcor(Component):
|
|||
#if self.searchWindowSizeHeight >= 2*self.windowSizeHeight :
|
||||
# raise ValueError('Search Window Size Height should be < 2 * Window Size Height')
|
||||
|
||||
if self.zoomWindowSize >= min(self.searchWindowSizeWidth, self.searchWindowSizeHeight):
|
||||
raise ValueError('Zoom window size should be <= Search window size')
|
||||
#if self.zoomWindowSize >= min(self.searchWindowSizeWidth, self.searchWindowSizeHeight):
|
||||
# raise ValueError('Zoom window size should be <= Search window size')
|
||||
|
||||
|
||||
def checkSkip(self):
|
||||
|
|
@ -519,6 +511,12 @@ class Ampcor(Component):
|
|||
ampcor.setAcrossLooks_Py(self.acrossLooks)
|
||||
ampcor.setDownLooks_Py(self.downLooks)
|
||||
|
||||
#reference values
|
||||
#self.winsizeFilt = 8
|
||||
#self.oversamplingFactorFilt = 64
|
||||
ampcor.setWinsizeFilt_Py(self.winsizeFilt)
|
||||
ampcor.setOversamplingFactorFilt_Py(self.oversamplingFactorFilt)
|
||||
|
||||
return
|
||||
|
||||
def setImageDataType1(self, var):
|
||||
|
|
@ -641,6 +639,14 @@ class Ampcor(Component):
|
|||
raise ValueError('Oversampling factor needs to be a power of 2.')
|
||||
self.oversamplingFactor = temp
|
||||
|
||||
def setWinsizeFilt(self, var):
|
||||
temp = int(var)
|
||||
self.winsizeFilt = temp
|
||||
|
||||
def setOversamplingFactorFilt(self, var):
|
||||
temp = int(var)
|
||||
self.oversamplingFactorFilt = temp
|
||||
|
||||
def setSearchWindowSizeWidth(self, var):
|
||||
self.searchWindowSizeWidth = int(var)
|
||||
return
|
||||
|
|
@ -822,6 +828,8 @@ class Ampcor(Component):
|
|||
self.scaleFactorX = None
|
||||
self.scaleFactorY = None
|
||||
self.numRows = None
|
||||
self.winsizeFilt = 1
|
||||
self.oversamplingFactorFilt = 64
|
||||
self.dictionaryOfVariables = { \
|
||||
'IMAGETYPE1' : ['imageDataType1', 'str', 'optional'], \
|
||||
'IMAGETYPE2' : ['imageDataType2', 'str', 'optional'], \
|
||||
|
|
|
|||
|
|
@ -632,8 +632,8 @@ class DenseAmpcor(Component):
|
|||
if self.searchWindowSizeHeight >= 2*self.windowSizeHeight :
|
||||
raise ValueError('Search Window Size Height should be < 2 * Window Size Height')
|
||||
|
||||
if self.zoomWindowSize >= min(self.searchWindowSizeWidth, self.searchWindowSizeHeight):
|
||||
raise ValueError('Zoom window size should be <= Search window size')
|
||||
if self.zoomWindowSize > min(self.searchWindowSizeWidth*2+1, self.searchWindowSizeHeight*2+1):
|
||||
raise ValueError('Zoom window size should be <= Search window size * 2 + 1')
|
||||
|
||||
if self._stdWriter is None:
|
||||
self._stdWriter = create_writer("log", "", True, filename="denseampcor.log")
|
||||
|
|
|
|||
|
|
@ -724,3 +724,27 @@ PyObject * getCov3_C(PyObject* self, PyObject* args)
|
|||
delete [] vectorV;
|
||||
return Py_BuildValue("N",list);
|
||||
}
|
||||
|
||||
|
||||
|
||||
PyObject* setWinsizeFilt_C(PyObject* self, PyObject* args)
|
||||
{
|
||||
int factor;
|
||||
if( !PyArg_ParseTuple(args,"i",&factor) )
|
||||
{
|
||||
return NULL;
|
||||
}
|
||||
setWinsizeFilt_f(&factor);
|
||||
return Py_BuildValue("i",0);
|
||||
}
|
||||
|
||||
PyObject* setOversamplingFactorFilt_C(PyObject* self, PyObject* args)
|
||||
{
|
||||
int factor;
|
||||
if( !PyArg_ParseTuple(args,"i",&factor) )
|
||||
{
|
||||
return NULL;
|
||||
}
|
||||
setOversamplingFactorFilt_f(&factor);
|
||||
return Py_BuildValue("i",0);
|
||||
}
|
||||
|
|
|
|||
|
|
@ -152,6 +152,10 @@ extern "C"
|
|||
PyObject * setScaleFactorX_C(PyObject*, PyObject*);
|
||||
PyObject * setScaleFactorY_C(PyObject*, PyObject*);
|
||||
|
||||
void setOversamplingFactorFilt_f(int*);
|
||||
PyObject* setOversamplingFactorFilt_C(PyObject*, PyObject*);
|
||||
void setWinsizeFilt_f(int*);
|
||||
PyObject* setWinsizeFilt_C(PyObject*, PyObject*);
|
||||
}
|
||||
|
||||
|
||||
|
|
@ -226,6 +230,9 @@ static PyMethodDef ampcor_methods[] =
|
|||
{ "deallocate_cov2Ret_Py", deallocate_cov2Ret_C, METH_VARARGS, " "},
|
||||
{ "deallocate_cov3Ret_Py", deallocate_cov3Ret_C, METH_VARARGS, " "},
|
||||
|
||||
{ "setWinsizeFilt_Py", setWinsizeFilt_C, METH_VARARGS, " "},
|
||||
{ "setOversamplingFactorFilt_Py", setOversamplingFactorFilt_C, METH_VARARGS, " "},
|
||||
|
||||
{NULL, NULL, 0 , NULL}
|
||||
};
|
||||
|
||||
|
|
|
|||
|
|
@ -67,6 +67,8 @@
|
|||
#define deallocate_cov2Ret_f deallocate_cov2ret_
|
||||
#define deallocate_cov3Ret_f deallocate_cov3ret_
|
||||
|
||||
#define setWinsizeFilt_f setwinsizefilt_
|
||||
#define setOversamplingFactorFilt_f setoversamplingfactorfilt_
|
||||
|
||||
#else
|
||||
#error Unknown translation for FORTRAN external symbols
|
||||
|
|
|
|||
|
|
@ -1,3 +1,14 @@
|
|||
!c This program has been upgraded for matching ScanSAR full-aperture images.
|
||||
!c 1. setting the following two parameters to use:
|
||||
!c winsize_filt = 8
|
||||
!c i_covs_filt = 64
|
||||
!c 2. use same original parameter values as you use in the original program for
|
||||
!c ScanSAR full-aperture image matching.
|
||||
!c 3. Original matching method is still available by setting winsize_filt to 1.
|
||||
!c In this case, i_covs_filt has no effects.
|
||||
|
||||
!c Cunren Liang, 25-DEC-2019, Caltech
|
||||
|
||||
!c****************************************************************
|
||||
|
||||
subroutine ampcor(imgAccessor1, imgAccessor2, band1, band2)
|
||||
|
|
@ -126,6 +137,24 @@
|
|||
external seconds
|
||||
integer count
|
||||
|
||||
!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!
|
||||
!c for ScanSAR full-aperture mode matching
|
||||
real*4 r_shfty_filt,r_shftx_filt
|
||||
integer i_shiftx_filt,i_shifty_filt
|
||||
!integer winsize_filt
|
||||
integer i_wsyi_filt
|
||||
integer i_wsyj_filt
|
||||
integer iii, num_pixel
|
||||
!integer i_covs_filt, i_cw_filt
|
||||
integer i_cw_filt
|
||||
real, dimension(:,:), allocatable :: r_imgi_filt, r_imgj_filt, r_imgc_filt
|
||||
complex, dimension(:), allocatable :: c_corr_filt, c_corrt_filt
|
||||
real tmp_corr
|
||||
integer continue_fine_matching
|
||||
|
||||
!c added to avoid accessing indexes out of bounds (segmentation fault) 02-FEB-2020
|
||||
integer x_index
|
||||
!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!
|
||||
|
||||
write(6,*) 'Input Bands: ', band1, band2
|
||||
|
||||
|
|
@ -204,6 +233,48 @@
|
|||
i_n2wsxj = 2**(nextpower(i_wsxjp))
|
||||
i_n2wsyj = 2**(nextpower(i_wsyjp))
|
||||
|
||||
!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!
|
||||
!c for ScanSAR full-aperture mode matching
|
||||
!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!
|
||||
!input parameter reference values:
|
||||
!winsize_filt should be power of 2 to faciliate subsequent processing
|
||||
!winsize_filt = 8
|
||||
!i_covs_filt = i_covs
|
||||
!i_covs_filt = 64
|
||||
!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!
|
||||
|
||||
!better be power of 2 for fft
|
||||
i_cw_filt = (i_wsyj - i_wsyi) / winsize_filt
|
||||
i_wsyi_filt = i_wsyi / winsize_filt
|
||||
i_wsyj_filt = i_wsyj / winsize_filt
|
||||
|
||||
if(winsize_filt .ne. 1)then
|
||||
write(6,*) ''
|
||||
write(6,*) ' *** using ScanSAR full-aperture mode for gross offset estimation ***'
|
||||
write(6,*) 'azimuth multi-looking window size: ', winsize_filt
|
||||
write(6,*) 'number of azimuth samples before and after multi-looking (master): ', i_wsyi, i_wsyi_filt
|
||||
write(6,*) 'number of azimuth samples before and after multi-looking (slave): ', i_wsyj, i_wsyj_filt
|
||||
write(6,*) 'azimuth covariance surface oversampling factor: ', i_covs_filt
|
||||
write(6,*) 'total number of azimuth samples to be oversampled', i_cw_filt
|
||||
write(6,*) ''
|
||||
endif
|
||||
|
||||
if(i_cw_filt .lt. 4)then
|
||||
write(6,*) 'ERROR - number of samples availabe for estating gross offset is too small:', i_cw_filt
|
||||
write(6,*) ' the value is computed as 2*i_srchy/winsize_filt'
|
||||
write(6,*) ' current i_srchy (azimuth search window size):', i_srchy
|
||||
write(6,*) ' current winsize_filt (azimuth filtering window size):', winsize_filt
|
||||
return
|
||||
endif
|
||||
|
||||
if(i_cw_filt .ne. 2**nextpower(i_cw_filt))then
|
||||
write(6,*) 'WARNING - number of samples availabe for estating gross offset is NOT power of 2:', i_cw_filt
|
||||
write(6,*) ' the value is computed as 2*i_srchy/winsize_filt'
|
||||
write(6,*) ' better to make it power of 2 for FFT'
|
||||
write(6,*) ' current i_srchy (azimuth search window size):', i_srchy
|
||||
write(6,*) ' current winsize_filt (azimuth filtering window size):', winsize_filt
|
||||
endif
|
||||
!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!
|
||||
|
||||
!c Set max width to largest of the width
|
||||
i_maxsamp = max(i_samples(1), i_samples(2))
|
||||
|
|
@ -230,6 +301,15 @@
|
|||
allocate( c_ossch(i_ovs*i_n2wsxj*i_ovs*i_n2wsyj) )
|
||||
allocate( c_osref(i_ovs*i_n2wsxi*i_ovs*i_n2wsyi) )
|
||||
|
||||
!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!
|
||||
!c for ScanSAR full-aperture mode matching
|
||||
allocate( r_imgi_filt(i_wsxi,i_wsyi_filt))
|
||||
allocate( r_imgj_filt(i_wsxj,i_wsyj_filt))
|
||||
allocate( r_imgc_filt(i_wsxj,i_wsyj_filt))
|
||||
allocate( c_corr_filt(i_covs_filt*i_cw_filt*i_covs_filt*i_cw_filt) )
|
||||
allocate( c_corrt_filt(i_cw_filt*i_cw_filt) )
|
||||
!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!
|
||||
|
||||
!c-------------------------------
|
||||
!c begin ruggedize ... a bunch of input checking
|
||||
|
||||
|
|
@ -485,13 +565,27 @@
|
|||
|
||||
do i_yy = 1,i_wsyi
|
||||
do i_xx = 1,i_wsxi
|
||||
r_imgi(i_xx,i_yy) = cabs(c_refimg(i_x+i_xx-1,i_yy))
|
||||
|
||||
x_index = i_x+i_xx-1
|
||||
if ((x_index .lt. 1).or.(x_index .gt. i_maxsamp)) then
|
||||
r_imgi(i_xx,i_yy) = 0.0
|
||||
else
|
||||
r_imgi(i_xx,i_yy) = cabs(c_refimg(x_index,i_yy))
|
||||
endif
|
||||
|
||||
end do
|
||||
end do
|
||||
|
||||
do i_yy = 1, i_wsyj
|
||||
do i_xx = 1 , i_wsxj
|
||||
r_imgj(i_xx,i_yy) = cabs(c_srchimg(i_xlu+i_xx-1-i_srchx+i_grossx,i_yy))
|
||||
|
||||
x_index = i_xlu+i_xx-1-i_srchx+i_grossx
|
||||
if ((x_index .lt. 1).or.(x_index .gt. i_maxsamp)) then
|
||||
r_imgj(i_xx,i_yy) = 0.0
|
||||
else
|
||||
r_imgj(i_xx,i_yy) = cabs(c_srchimg(x_index,i_yy))
|
||||
endif
|
||||
|
||||
end do
|
||||
end do
|
||||
|
||||
|
|
@ -504,8 +598,201 @@
|
|||
call dump_chip_r4(a_debugfile,r_imgj,1,i_wsxj,1,i_wsyj,i_wsxj,i_wsyj)
|
||||
endif
|
||||
|
||||
!c correlate the subimages
|
||||
!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!
|
||||
!c for ScanSAR full-aperture mode matching
|
||||
|
||||
!c correlate azimuth-multiple-looked images
|
||||
if (winsize_filt .ne. 1) then
|
||||
!c get azimuth-multiple-looked images
|
||||
do i_yy = 1,i_wsyi_filt
|
||||
do i_xx = 1,i_wsxi
|
||||
r_imgi_filt(i_xx,i_yy) = 0.
|
||||
num_pixel = 0
|
||||
do iii = 1,winsize_filt
|
||||
if(r_imgi(i_xx,(i_yy-1)*winsize_filt+iii) .ne. 0) then
|
||||
num_pixel = num_pixel + 1
|
||||
r_imgi_filt(i_xx,i_yy) = r_imgi_filt(i_xx,i_yy) + r_imgi(i_xx,(i_yy-1)*winsize_filt+iii)**2
|
||||
endif
|
||||
end do
|
||||
if(num_pixel .ne. 0) then
|
||||
r_imgi_filt(i_xx,i_yy) = sqrt(r_imgi_filt(i_xx,i_yy)/num_pixel)
|
||||
endif
|
||||
end do
|
||||
end do
|
||||
|
||||
|
||||
do i_yy = 1, i_wsyj_filt
|
||||
do i_xx = 1 , i_wsxj
|
||||
r_imgj_filt(i_xx,i_yy) = 0.
|
||||
num_pixel = 0
|
||||
do iii = 1,winsize_filt
|
||||
if(r_imgj(i_xx,(i_yy-1)*winsize_filt+iii) .ne. 0) then
|
||||
num_pixel = num_pixel + 1
|
||||
r_imgj_filt(i_xx,i_yy) = r_imgj_filt(i_xx,i_yy) + r_imgj(i_xx,(i_yy-1)*winsize_filt+iii)**2
|
||||
endif
|
||||
end do
|
||||
if(num_pixel .ne. 0) then
|
||||
r_imgj_filt(i_xx,i_yy) = sqrt(r_imgj_filt(i_xx,i_yy)/num_pixel)
|
||||
endif
|
||||
end do
|
||||
end do
|
||||
|
||||
!c correlate images
|
||||
!c i_avgx = i_avgy = 1
|
||||
call correlate(r_imgi_filt,r_imgj_filt,i_wsxi,i_wsyi_filt,i_wsxj,
|
||||
& i_wsyj_filt,1,1,1,r_meani,r_stdvi,r_meanj,
|
||||
& r_stdvj,r_peak,r_noise,r_cov,r_eval1,
|
||||
& r_eval2,r_evec1,r_evec2,r_imgc_filt,i_shiftx_filt,i_shifty_filt,i_edge,
|
||||
& i_flag,l_debug)
|
||||
|
||||
r_shftx_filt=float(i_shiftx_filt) - i_srchx + i_grossx
|
||||
r_shfty_filt=float(i_shifty_filt) - float(i_srchy)/winsize_filt + float(i_grossy)/winsize_filt
|
||||
r_shfty_filt=r_shfty_filt*winsize_filt
|
||||
|
||||
if(i_flag .eq. 0 .and. i_edge(1) .eq. 0 .and.
|
||||
& i_edge(2) .eq. 0)then !found a potentially good data point
|
||||
|
||||
r_outside = 0.0
|
||||
i_cnta = 0
|
||||
do l=max(i_shifty_filt-9,1),min(i_shifty_filt+11,i_wsyj_filt-i_wsyi_filt)
|
||||
do k=max(i_shiftx_filt-9,1),min(i_shiftx_filt+11,i_wsxj-i_wsxi)
|
||||
i_cnta = i_cnta + 1
|
||||
r_outside = r_outside + r_imgc_filt(k,l)**2
|
||||
enddo
|
||||
enddo
|
||||
r_outside = r_outside - r_peak**2
|
||||
r_outside = r_outside/(i_cnta-1)
|
||||
|
||||
r_snr = r_peak**2/max(r_outside,1.e-10)
|
||||
|
||||
if(r_snr .gt. r_snrth .and. r_cov(1) .lt. r_covth .and. r_cov(2) .lt. r_covth)then
|
||||
continue_fine_matching = 1
|
||||
else
|
||||
continue_fine_matching = 0
|
||||
endif
|
||||
|
||||
else
|
||||
continue_fine_matching = 0
|
||||
endif
|
||||
|
||||
!c compute finer offset by oversampling covariance surface
|
||||
if(continue_fine_matching .ne. 0)then
|
||||
r_max = 0.0
|
||||
r_mean_cor = 0.0
|
||||
i_cnta = 0
|
||||
i_px = i_shiftx_filt+1
|
||||
i_py = i_shifty_filt+1
|
||||
|
||||
do i_yy=-i_cw_filt/2,i_cw_filt/2-1
|
||||
|
||||
do i_xx=-i_cw_filt/2,i_cw_filt/2-1
|
||||
|
||||
i_index = (i_yy+i_cw_filt/2)*i_cw_filt + i_xx + i_cw_filt/2 + 1
|
||||
|
||||
if (i_xx+i_px .ge. 1 .and. i_xx+i_px .le. (2*i_srchx+1)*1 .and.
|
||||
& i_yy+i_py .ge. 1 .and. i_yy+i_py .le. (2*i_srchy+1)*1 )then
|
||||
c_corrt_filt(i_index) = cmplx(abs(r_imgc_filt(i_xx+i_px,i_yy+i_py)/r_peak),0.)
|
||||
r_mean_cor = r_mean_cor + cabs(c_corrt_filt(i_index))
|
||||
i_cnta = i_cnta + 1
|
||||
else
|
||||
c_corrt_filt(i_index) = cmplx(0.0, 0.0)
|
||||
endif
|
||||
|
||||
if(cabs(c_corrt_filt(i_index)) .gt. r_max)then
|
||||
r_max = cabs(c_corrt_filt(i_index))
|
||||
i_p1 = i_xx
|
||||
i_p2 = i_yy
|
||||
endif
|
||||
|
||||
enddo
|
||||
|
||||
enddo
|
||||
|
||||
!c substract off the mean
|
||||
!c looks like it does not do anything, so can comment out these
|
||||
!c r_mean_cor = r_mean_cor/max(i_cnta,1)
|
||||
!c r_mean_cor = 0.0
|
||||
!c do i_yy=-i_cw_filt/2,i_cw_filt/2-1
|
||||
!c do i_xx=-i_cw_filt/2,i_cw_filt/2-1
|
||||
!c i_index = (i_yy+i_cw_filt/2)*i_cw_filt + i_xx + i_cw_filt/2 + 1
|
||||
!c c_corrt_filt(i_index) = c_corrt_filt(i_index) - cmplx(r_mean_cor,0.0)
|
||||
!c enddo
|
||||
!c enddo
|
||||
|
||||
!c oversample via Fourier transforms
|
||||
!c forward fft the data
|
||||
i_nn(1) = i_cw_filt
|
||||
i_nn(2) = i_cw_filt
|
||||
i_dir = 1
|
||||
call fourn2d(c_corrt_filt,i_nn,i_dir)
|
||||
|
||||
!c spread the spectral data out for inverse transforms
|
||||
i_nn(1) = i_cw_filt*i_covs_filt
|
||||
i_nn(2) = i_cw_filt*i_covs_filt
|
||||
i_dir = -1
|
||||
|
||||
do k=1,i_nn(2)
|
||||
do l=1,i_nn(1)
|
||||
i_index = (k-1)*i_nn(1) + l
|
||||
c_corr_filt(i_index) = 0.0
|
||||
enddo
|
||||
enddo
|
||||
|
||||
do l=1,i_cw_filt/2
|
||||
do k=1,i_cw_filt/2
|
||||
i_index = (k-1)*i_nn(1) + l
|
||||
i_indexi = (k-1)*i_cw_filt + l
|
||||
c_corr_filt(i_index) = c_corrt_filt(i_indexi)
|
||||
i_index = l + (i_nn(2)-i_cw_filt/2+k-1)*i_nn(1)
|
||||
i_indexi = l + (k+i_cw_filt/2-1)*i_cw_filt
|
||||
c_corr_filt(i_index) = c_corrt_filt(i_indexi)
|
||||
i_index = i_nn(1)-i_cw_filt/2+l + (k-1)*i_nn(2)
|
||||
i_indexi = l+i_cw_filt/2 + (k-1)*i_cw_filt
|
||||
c_corr_filt(i_index) = c_corrt_filt(i_indexi)
|
||||
i_index = i_nn(1)-i_cw_filt/2+l + (i_nn(2)-i_cw_filt/2+k-1)*i_nn(1)
|
||||
i_indexi = l+i_cw_filt/2 + (k+i_cw_filt/2-1)*i_cw_filt
|
||||
c_corr_filt(i_index) = c_corrt_filt(i_indexi)
|
||||
enddo
|
||||
enddo
|
||||
|
||||
!c inverse transform
|
||||
call fourn2d(c_corr_filt,i_nn,i_dir)
|
||||
|
||||
|
||||
!c detect the peak
|
||||
r_max=0.
|
||||
do i_yy=1,i_cw_filt*i_covs_filt
|
||||
do i_xx=1,i_cw_filt*i_covs_filt
|
||||
i_index = (i_yy-1)*i_cw_filt*i_covs_filt + i_xx
|
||||
tmp_corr = cabs(c_corr_filt(i_index))/((i_cw_filt**2)*(i_cw_filt*i_covs_filt)**2)
|
||||
if (abs(i_xx-i_cw_filt*i_covs_filt/2) .le. i_covs_filt .and.
|
||||
& abs(i_yy-i_cw_filt*i_covs_filt/2) .le. i_covs_filt) then
|
||||
if (tmp_corr .ge. r_max) then
|
||||
r_max = tmp_corr
|
||||
i_cpeak(1) = i_xx - i_cw_filt/2*i_covs_filt
|
||||
i_cpeak(2) = i_yy - i_cw_filt/2*i_covs_filt
|
||||
endif
|
||||
endif
|
||||
enddo
|
||||
enddo
|
||||
|
||||
r_oscoroff(1) = float(i_cpeak(1)-1)/float(i_covs_filt)
|
||||
r_oscoroff(2) = float(i_cpeak(2)-1)/float(i_covs_filt)
|
||||
r_oscoroff(2) = r_oscoroff(2) * winsize_filt
|
||||
|
||||
r_shftx = r_oscoroff(1)/1 + r_shftx_filt + i_xlu - i_x
|
||||
r_shfty = r_oscoroff(2)/1 + r_shfty_filt + i_ylu - i_y
|
||||
|
||||
!get integer values for subsequent use. note that all four variables
|
||||
!are used, so they need to be consistent
|
||||
r_shftx = nint(r_shftx)
|
||||
r_shfty = nint(r_shfty)
|
||||
i_shiftx = nint(r_shftx) + i_srchx - i_grossx
|
||||
i_shifty = nint(r_shfty) + i_srchy - i_grossy
|
||||
endif
|
||||
else
|
||||
!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!
|
||||
!c correlate original images
|
||||
call correlate(r_imgi,r_imgj,i_wsxi,i_wsyi,i_wsxj,
|
||||
& i_wsyj,i_avgx,i_avgy,1,r_meani,r_stdvi,r_meanj,
|
||||
& r_stdvj,r_peak,r_noise,r_cov,r_eval1,
|
||||
|
|
@ -546,9 +833,21 @@
|
|||
|
||||
r_snr = r_peak**2/max(r_outside,1.e-10)
|
||||
!ccccc write(6,'(a,1x,2(f20.10,1x))') 'Peak/SNR = ',r_peak,r_snr
|
||||
|
||||
if(r_snr .gt. r_snrth .and. r_cov(1) .lt. r_covth .and. r_cov(2) .lt. r_covth)then
|
||||
continue_fine_matching = 1
|
||||
else
|
||||
continue_fine_matching = 0
|
||||
endif
|
||||
else
|
||||
continue_fine_matching = 0
|
||||
endif
|
||||
!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!
|
||||
endif
|
||||
!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!
|
||||
|
||||
!c this is just used to keep the original indentation level
|
||||
if(1 .eq. 1)then
|
||||
if(continue_fine_matching .ne. 0)then
|
||||
!c oversample the region around the peak 2 to 1 to estimate the fractional offset
|
||||
|
||||
!c write the reference image and search image around the peak into arrays
|
||||
|
|
@ -1138,6 +1437,16 @@
|
|||
deallocate( c_chipsch)
|
||||
deallocate( c_ossch)
|
||||
deallocate( c_osref)
|
||||
|
||||
!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!
|
||||
!c for ScanSAR full-aperture mode matching
|
||||
deallocate( r_imgi_filt)
|
||||
deallocate( r_imgj_filt)
|
||||
deallocate( r_imgc_filt)
|
||||
deallocate( c_corr_filt)
|
||||
deallocate( c_corrt_filt)
|
||||
!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!
|
||||
|
||||
close(13)
|
||||
close(14)
|
||||
!c close(15)
|
||||
|
|
|
|||
|
|
@ -26,7 +26,9 @@
|
|||
write(6,*) "r_covth = ",r_covth
|
||||
write(6,*) "l_debug = ",l_debug
|
||||
write(6,*) "l_display = ",l_display
|
||||
|
||||
|
||||
write(6,*) "winsize_filt = ",winsize_filt
|
||||
write(6,*) "i_covs_filt = ",i_covs_filt
|
||||
return
|
||||
end
|
||||
|
||||
|
|
|
|||
|
|
@ -198,3 +198,16 @@
|
|||
r_scaley = var
|
||||
end
|
||||
|
||||
subroutine setWinsizeFilt(winsize_filt_val)
|
||||
use ampcorState
|
||||
implicit none
|
||||
integer winsize_filt_val
|
||||
winsize_filt = winsize_filt_val
|
||||
end
|
||||
|
||||
subroutine setOversamplingFactorFilt(i_covs_filt_val)
|
||||
use ampcorState
|
||||
implicit none
|
||||
integer i_covs_filt_val
|
||||
i_covs_filt = i_covs_filt_val
|
||||
end
|
||||
|
|
|
|||
|
|
@ -33,4 +33,7 @@
|
|||
!c we only know the max number of rows. at the end of the ampcor we can get it
|
||||
integer numRowTable
|
||||
|
||||
integer winsize_filt
|
||||
integer i_covs_filt
|
||||
|
||||
end module ampcorState
|
||||
|
|
|
|||
|
|
@ -7,7 +7,9 @@ add_subdirectory(downsample_unwrapper)
|
|||
|
||||
#add_subdirectory(PyCuAmpcor)
|
||||
add_subdirectory(splitSpectrum)
|
||||
add_subdirectory(alos2filter)
|
||||
add_subdirectory(alos2proc)
|
||||
add_subdirectory(alos2proc_f)
|
||||
add_subdirectory(rfi)
|
||||
add_subdirectory(mdx)
|
||||
|
||||
|
|
|
|||
|
|
@ -77,7 +77,9 @@ SConscript(rfi)
|
|||
|
||||
SConscript('PyCuAmpcor/SConscript')
|
||||
SConscript('splitSpectrum/SConscript')
|
||||
SConscript('alos2filter/SConscript')
|
||||
SConscript('alos2proc/SConscript')
|
||||
SConscript('alos2proc_f/SConscript')
|
||||
|
||||
if os.path.exists('geo_autoRIFT'):
|
||||
SConscript('geo_autoRIFT/SConscript')
|
||||
|
|
|
|||
|
|
@ -0,0 +1,6 @@
|
|||
add_library(alos2filter SHARED src/psfilt1.c)
|
||||
InstallSameDir(
|
||||
alos2filter
|
||||
__init__.py
|
||||
alos2filter.py
|
||||
)
|
||||
|
|
@ -0,0 +1,25 @@
|
|||
#!/usr/bin/env python
|
||||
|
||||
#Cunren Liang, 2015-2018
|
||||
|
||||
import os
|
||||
|
||||
Import('envcontrib')
|
||||
envalos2filter = envcontrib.Clone()
|
||||
package = envcontrib['PACKAGE']
|
||||
project = 'alos2filter'
|
||||
Export('envalos2filter')
|
||||
|
||||
|
||||
|
||||
|
||||
srcScons = os.path.join('src','SConscript')
|
||||
varDir = os.path.join(envalos2filter['PRJ_SCONS_BUILD'],package,project,'src')
|
||||
SConscript(srcScons, variant_dir = varDir)
|
||||
|
||||
|
||||
install = os.path.join(envcontrib['PRJ_SCONS_INSTALL'],package,project)
|
||||
listFiles = ['__init__.py','alos2filter.py']
|
||||
envcontrib.Install(install,listFiles)
|
||||
envcontrib.Alias('install',install)
|
||||
|
||||
|
|
@ -0,0 +1 @@
|
|||
#!/usr/bin/env python3
|
||||
|
|
@ -0,0 +1,17 @@
|
|||
import os
|
||||
import copy
|
||||
import ctypes
|
||||
import logging
|
||||
import isceobj
|
||||
from xml.etree.ElementTree import ElementTree
|
||||
|
||||
def psfilt1(inputfile, outputfile, width, alpha, fftw, step):
|
||||
filters = ctypes.cdll.LoadLibrary(os.path.join(os.path.dirname(__file__),'libalos2filter.so'))
|
||||
filters.psfilt1(
|
||||
ctypes.c_char_p(bytes(inputfile,'utf-8')),
|
||||
ctypes.c_char_p(bytes(outputfile,'utf-8')),
|
||||
ctypes.c_int(width),
|
||||
ctypes.c_double(alpha),
|
||||
ctypes.c_int(fftw),
|
||||
ctypes.c_int(step)
|
||||
)
|
||||
|
|
@ -0,0 +1,23 @@
|
|||
#!/usr/bin/env python
|
||||
|
||||
import os
|
||||
|
||||
Import('envalos2filter')
|
||||
|
||||
install = os.path.join(envalos2filter['PRJ_SCONS_INSTALL'], envalos2filter['PACKAGE'], 'alos2filter')
|
||||
listFiles = ['psfilt1.c']
|
||||
|
||||
# -shared
|
||||
# -D_LARGEFILE64_SOURCE -D_FILE_OFFSET_BITS=64 -lm
|
||||
# -lfftw3f_threads -lfftw3f -lpthread -fopenmp -O3
|
||||
|
||||
#envalos2proc.Append(CFLAGS=['-D_LARGEFILE64_SOURCE', '-D_FILE_OFFSET_BITS=64', '-lm', '-shared', '-fopenmp', '-O3'])
|
||||
#envalos2proc.Append(LIBS=['fftw3f', 'fftw3f_threads', 'pthread'])
|
||||
|
||||
lib = envalos2filter.LoadableModule(target = 'libalos2filter.so', source = listFiles, parse_flags='-fopenmp')
|
||||
envalos2filter.Install(install,lib)
|
||||
envalos2filter.Alias('install',install)
|
||||
|
||||
|
||||
|
||||
|
||||
|
|
@ -0,0 +1,496 @@
|
|||
#include <stdlib.h>
|
||||
#include <stdio.h>
|
||||
#include <string.h>
|
||||
#include <math.h>
|
||||
|
||||
#define PLUS 1
|
||||
#define MINU 2
|
||||
#define CHG 3
|
||||
#define GUID 4
|
||||
#define LSNR 8
|
||||
#define VIST 16
|
||||
#define BRPT 32
|
||||
#define CUT 64
|
||||
#define LAWN 128
|
||||
#define TREE 128
|
||||
|
||||
#define NFFT 32 /* size of FFT */
|
||||
#define STEP NFFT/2 /* stepsize in range and azimuth for filter */
|
||||
#define ALPHA 0.5 /* default exponent for weighting of the spectrum */
|
||||
|
||||
#define REL_BEGIN 0 /* fseek relative to beginning of file */
|
||||
#define REL_CUR 1 /* fseek relative to current position in the file */
|
||||
#define REL_EOF 2 /* fseek relative to end of file */
|
||||
|
||||
#define SQR(a) ( (a)*(a) )
|
||||
#define PI 3.14159265359
|
||||
#define TWO_PI 6.28318530718
|
||||
#define SQRT2 1.41421356237 /* square root of 2 */
|
||||
#define RTD 57.2957795131 /* radians to degrees */
|
||||
#define DTR .0174532925199 /* degrees to radians */
|
||||
#define C 2.99792458e8
|
||||
|
||||
#define NR_END 1
|
||||
#define FREE_ARG char*
|
||||
|
||||
typedef struct{float re,im;} fcomplex;
|
||||
|
||||
void fourn(float *, unsigned int *, int ndim, int isign);
|
||||
void psd_wgt(fcomplex **cmp, fcomplex **seg_fft, double, int, int, int);
|
||||
|
||||
void start_timing(); /* timing routines */
|
||||
void stop_timing();
|
||||
|
||||
unsigned int nfft[3];
|
||||
int xmin=0; /* window column minima */
|
||||
int ymin=0; /* window row minima */
|
||||
int ymax, xmax; /* interferogram width, window maxima */
|
||||
|
||||
fcomplex **cmatrix(int nrl, int nrh, int ncl, int nch);
|
||||
void free_cmatrix(fcomplex **m, int nrl, int nrh, int ncl, int nch);
|
||||
void nrerror(char error_text[]);
|
||||
signed char IsFinite(double d);
|
||||
|
||||
int psfilt1(char *inputfile, char *outputfile, int width, double alpha, int fftw, int step)
|
||||
{
|
||||
fcomplex *bufcz, **cmp; /* interferogram line buffer, complex input data, row pointers */
|
||||
fcomplex **sm, **seg_fft, *seg_fftb; /* smoothed interferogram, 2d fft of segment */
|
||||
fcomplex **tmp, **tmp1; /* arrays of pointers for temp storage of line pointers in circular buffers */
|
||||
double **wf, *wfb; /* 2-D weights */
|
||||
|
||||
float *data; /* pointer to floats for FFT, union with seg_fft */
|
||||
//double alpha; /* exponent used to to determine spectal weighting function */
|
||||
double rw,azw; /* range and azimuth weights used in window function */
|
||||
|
||||
int nlines=0; /* number of lines in the file */
|
||||
int offs; /* width and height of file segment*/
|
||||
//int fftw; /* fft window size*/
|
||||
//int step; /* step size in range and azimuth for filtering of interferogram */
|
||||
int xw,yh; /* width, height of processed region */
|
||||
int i,j,i1,j1; /* loop counters */
|
||||
int ndim; /* number of dimensions of FFT */
|
||||
int isign; /* direction of FFT */
|
||||
int nlc; /* number of guides, number of low correlation pixels */
|
||||
int lc; /* line counter */
|
||||
|
||||
FILE *int_file, *sm_file;
|
||||
|
||||
int k;
|
||||
float sf; // scale factor for FFT, otherwise FFT will magnify the data by FFT length
|
||||
// usually the magnitude of the interferogram is very large, so the data are
|
||||
// multiplied by this factor before FFT, rather than after FFT in this program.
|
||||
float sf0; // an extra factor to scale the data
|
||||
sf0 = 1.0;
|
||||
|
||||
|
||||
fprintf(stderr,"*** Weighted power spectrum interferogram filter v1.0 clw 19-Feb-97 ***\n");
|
||||
if(0){
|
||||
//fprintf(stderr,"\nUsage: %s <interferogram> <smoothed interferogram> <width> [alpha] [fftw] [step] [xmin] [xmax] [ymin] [ymax]\n\n",argv[0]) ;
|
||||
|
||||
fprintf(stderr,"input parameters: \n");
|
||||
fprintf(stderr," interferogram complex interferogram image filename\n");
|
||||
fprintf(stderr," smoothed interf. smoothed interferogram filename\n");
|
||||
fprintf(stderr," width number of samples/row\n");
|
||||
fprintf(stderr," alpha spectrum amplitude scale factor (default=.5)\n");
|
||||
fprintf(stderr," fftw fft window size in both range and azimuth directions \n");
|
||||
fprintf(stderr," step moving step size in both range and azimuth directions (default = fftw/2)\n");
|
||||
fprintf(stderr," xmin offset to starting range pixel (default = 0)\n");
|
||||
fprintf(stderr," xmax offset last range pixel (default = width-1)\n");
|
||||
fprintf(stderr," ymin offset to starting azimuth row (default = 0)\n");
|
||||
fprintf(stderr," ymax offset to last azimuth row (default = nlines-1)\n\n");
|
||||
exit(-1);
|
||||
}
|
||||
|
||||
start_timing();
|
||||
int_file = fopen(inputfile,"rb");
|
||||
if (int_file == NULL){fprintf(stderr,"cannot open interferogram file: %s\n",inputfile); exit(-1);}
|
||||
|
||||
sm_file = fopen(outputfile,"wb");
|
||||
if (sm_file == NULL){fprintf(stderr,"cannot create smoothed interferogram file: %s\n",outputfile); exit(-1);}
|
||||
|
||||
//sscanf(argv[3],"%d",&width);
|
||||
xmax = width-1;
|
||||
|
||||
fseeko(int_file, 0L, REL_EOF); /* determine # lines in the file */
|
||||
nlines=(int)(ftello(int_file)/(width*2*sizeof(float)));
|
||||
fprintf(stderr,"#lines in the interferogram file: %d\n",nlines);
|
||||
rewind(int_file);
|
||||
|
||||
|
||||
//alpha = ALPHA;
|
||||
//if(argc >= 4)sscanf(argv[4],"%lf",&alpha);
|
||||
fprintf(stdout,"spectrum weighting exponent: %8.4f\n",alpha);
|
||||
|
||||
//fftw = NFFT;
|
||||
//if (argc >5)sscanf(argv[5],"%d",&fftw);
|
||||
fprintf(stdout,"FFT window size: %5d\n",fftw);
|
||||
|
||||
sf = fftw * fftw * sf0;
|
||||
|
||||
//step = fftw/2;
|
||||
//if (argc >6)sscanf(argv[6],"%d",&step);
|
||||
if (step <= 0 || step > fftw){
|
||||
fprintf(stdout,"WARNING: wrong step size: %5d, using %5d instead\n",step, fftw/2);
|
||||
step = fftw/2;
|
||||
}
|
||||
fprintf(stdout,"range and azimuth step size (pixels): %5d\n",step);
|
||||
|
||||
ymax=nlines-1; /* default value of ymax */
|
||||
//if(argc > 7)sscanf(argv[7],"%d",&xmin); /* window to process */
|
||||
//if(argc > 8)sscanf(argv[8],"%d",&xmax);
|
||||
//if(argc > 9)sscanf(argv[9],"%d",&ymin);
|
||||
//if(argc > 10)sscanf(argv[10],"%d",&ymax);
|
||||
|
||||
if (ymax > nlines-1){
|
||||
ymax = nlines-1;
|
||||
fprintf(stderr,"WARNING: insufficient #lines in the file for given input range: ymax: %d\n",ymax);
|
||||
}
|
||||
|
||||
if (xmax > width-1) xmax=width-1; /* check to see if xmax within bounds */
|
||||
xw=xmax-xmin+1; /* width of array */
|
||||
yh=ymax-ymin+1; /* height of array */
|
||||
offs=ymin; /* first line of file to start reading/writing */
|
||||
fprintf(stdout,"array width, height, offset: %5d %5d %5d\n",xw,yh,offs);
|
||||
|
||||
cmp = cmatrix(0, fftw-1, -fftw,width+fftw); /* add space around the arrays */
|
||||
sm = cmatrix(0,fftw-1,-fftw,width+fftw);
|
||||
|
||||
tmp = (fcomplex **)malloc(sizeof(fcomplex *)*step);
|
||||
tmp1 = (fcomplex **)malloc(sizeof(fcomplex *)*step);
|
||||
if (tmp == NULL || tmp1==NULL){fprintf(stderr,"ERROR: failure to allocate space for circular buffer pointers\n"); exit(-1);}
|
||||
|
||||
bufcz = (fcomplex *)malloc(sizeof(fcomplex)*width);
|
||||
if(bufcz == NULL){fprintf(stderr,"ERROR: failure to allocate space for input line buffer\n"); exit(-1);}
|
||||
|
||||
seg_fftb = (fcomplex *)malloc(sizeof(fcomplex)*fftw*fftw);
|
||||
if(seg_fftb == NULL){fprintf(stderr,"ERROR: failure to allocate space for FFT data\n"); exit(-1);}
|
||||
seg_fft = (fcomplex **)malloc(sizeof(fcomplex *)*fftw);
|
||||
if(seg_fft == NULL){fprintf(stderr,"ERROR: failure to allocate space for FFT data pointers\n"); exit(-1);}
|
||||
|
||||
wfb = (double *)malloc(sizeof(double)*fftw*fftw);
|
||||
if (wfb == NULL){fprintf(stderr,"ERROR: weight memory allocation failure...\n"); exit(-1);}
|
||||
wf = (double **)malloc(sizeof(double *)*fftw);
|
||||
if (wf == NULL){fprintf(stderr,"ERROR: weight pointers memory allocation failure...\n"); exit(-1);}
|
||||
|
||||
for(i=0; i < fftw; i++) seg_fft[i] = seg_fftb + i*fftw;
|
||||
for(j=0; j < fftw; j++) wf[j] = wfb + j*fftw;
|
||||
|
||||
for(j=0; j < width; j++){bufcz[j].re=0.; bufcz[j].im=0.;}
|
||||
|
||||
for(i=0; i < fftw; i++){ /* initialize circular data buffers */
|
||||
for(j= -fftw; j < width+fftw; j++){
|
||||
cmp[i][j].re = 0.0; cmp[i][j].im = 0.0;
|
||||
sm[i][j].re = 0.0; sm[i][j].im = 0.0;
|
||||
}
|
||||
}
|
||||
|
||||
for (i=0; i < fftw; i++){
|
||||
for (j=0; j < fftw; j++){
|
||||
azw = 1.0 - fabs(2.0*(double)(i-fftw/2)/(fftw+1));
|
||||
rw = 1.0 - fabs(2.0*(double)(j-fftw/2)/(fftw+1));
|
||||
wf[i][j]=azw*rw/(double)(fftw*fftw);
|
||||
#ifdef DEBUG
|
||||
fprintf(stderr,"i,j,wf: %5d %5d %12.4e\n",i,j,wf[i][j]);
|
||||
#endif
|
||||
}
|
||||
}
|
||||
|
||||
nfft[1] = fftw;
|
||||
nfft[2] = nfft[1];
|
||||
nfft[0] = 0;
|
||||
ndim = 2;
|
||||
isign = 1; /* initialize FFT parameter values, inverse FFT */
|
||||
|
||||
|
||||
fseek(int_file, offs*width*sizeof(fcomplex), REL_BEGIN); /* seek offset to start line of interferogram */
|
||||
for (i=0; i < fftw - step; i++){
|
||||
fread((char *)cmp[i], sizeof(fcomplex), width, int_file);
|
||||
for(k = 0; k < width; k++){
|
||||
cmp[i][k].re /= sf;
|
||||
cmp[i][k].im /= sf;
|
||||
}
|
||||
}
|
||||
lc=0;
|
||||
|
||||
for (i=0; i < yh; i += step){
|
||||
for(i1=fftw - step; i1 < fftw; i1++){
|
||||
fread((char *)cmp[i1], sizeof(fcomplex), width, int_file);
|
||||
for(k = 0; k < width; k++){
|
||||
cmp[i1][k].re /= sf;
|
||||
cmp[i1][k].im /= sf;
|
||||
}
|
||||
if (feof(int_file) != 0){ /* fill with zero if at end of file */
|
||||
for(j1= -fftw; j1 < width+fftw; j1++){cmp[i1][j1].re=0.0; cmp[i1][j1].im=0.0;}
|
||||
}
|
||||
for(j1= -fftw; j1 < width+fftw; j1++){
|
||||
sm[i1][j1].re=0.0; sm[i1][j1].im=0.0; /* clear out area for new sum */
|
||||
}
|
||||
}
|
||||
if(i%(2*step) == 0)fprintf(stderr,"\rprogress: %3d%%", (int)(i*100/yh + 0.5));
|
||||
|
||||
for (j=0; j < width; j += step){
|
||||
psd_wgt(cmp, seg_fft, alpha, j, i, fftw);
|
||||
fourn((float *)seg_fft[0]-1,nfft,ndim,isign); /* 2D inverse FFT of region, get back filtered fringes */
|
||||
|
||||
for (i1=0; i1 < fftw; i1++){ /* save filtered output values */
|
||||
for (j1=0; j1 < fftw; j1++){
|
||||
if(cmp[i1][j+j1].re !=0.0){
|
||||
sm[i1][j+j1].re += wf[i1][j1]*seg_fft[i1][j1].re;
|
||||
sm[i1][j+j1].im += wf[i1][j1]*seg_fft[i1][j1].im;
|
||||
}
|
||||
else{
|
||||
sm[i1][j+j1].re=0.0;
|
||||
sm[i1][j+j1].im=0.0;
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
for (i1=0; i1 < step; i1++){
|
||||
if (lc < yh){
|
||||
for(k = 0; k < width; k++){
|
||||
if(!IsFinite(sm[i1][k].re))
|
||||
sm[i1][k].re = 0.0;
|
||||
if(!IsFinite(sm[i1][k].im))
|
||||
sm[i1][k].im = 0.0;
|
||||
if(!IsFinite(sqrt(sm[i1][k].re*sm[i1][k].re + sm[i1][k].im*sm[i1][k].im))){
|
||||
sm[i1][k].re = 0.0;
|
||||
sm[i1][k].im = 0.0;
|
||||
}
|
||||
}
|
||||
fwrite((char *)sm[i1], sizeof(fcomplex), width, sm_file);
|
||||
}
|
||||
lc++;
|
||||
}
|
||||
for (i1=0; i1 < step; i1++){tmp[i1] = cmp[i1]; tmp1[i1] = sm[i1];} /* save pointers to lines just written out */
|
||||
for (i1=0; i1 < fftw - step; i1++){cmp[i1] = cmp[i1+step]; sm[i1] = sm[i1+step];} /* shift the data just processed */
|
||||
for (i1=0; i1 < step; i1++){cmp[fftw - step+i1] = tmp[i1]; sm[fftw - step+i1]=tmp1[i1];} /* copy pointers back */
|
||||
}
|
||||
fprintf(stderr,"\rprogress: %3d%%", 100);
|
||||
|
||||
for(i=lc; i < yh; i++){ /* write null lines of filtered complex data */
|
||||
for(k = 0; k < width; k++){
|
||||
if(!IsFinite(bufcz[k].re))
|
||||
bufcz[k].re = 0.0;
|
||||
if(!IsFinite(bufcz[k].im))
|
||||
bufcz[k].im = 0.0;
|
||||
if(!IsFinite(sqrt(bufcz[k].re*bufcz[k].re + bufcz[k].im*bufcz[k].im))){
|
||||
bufcz[k].re = 0.0;
|
||||
bufcz[k].im = 0.0;
|
||||
}
|
||||
}
|
||||
fwrite((char *)bufcz, sizeof(fcomplex), width, sm_file);
|
||||
lc++;
|
||||
}
|
||||
|
||||
fprintf(stdout,"\nnumber of lines written to file: %d\n",lc);
|
||||
stop_timing();
|
||||
|
||||
free(bufcz);
|
||||
//free_cmatrix(cmp, 0, fftw-1, -fftw,width+fftw);
|
||||
//free_cmatrix(sm, 0,fftw-1,-fftw,width+fftw);
|
||||
free(seg_fft);
|
||||
free(seg_fftb);
|
||||
free(tmp);
|
||||
free(tmp1);
|
||||
free(wf);
|
||||
free(wfb);
|
||||
fclose(int_file);
|
||||
fclose(sm_file);
|
||||
|
||||
return(0);
|
||||
}
|
||||
|
||||
void psd_wgt(fcomplex **cmp, fcomplex **seg_fft, double alpha, int ix, int iy, int fftw)
|
||||
/*
|
||||
subroutine to perform non-linear spectral filtering 17-Feb-97 clw
|
||||
*/
|
||||
|
||||
{
|
||||
double psd,psd_sc; /* power spectrum, scale factor */
|
||||
int i,j; /* loop counters */
|
||||
int ndim,isign; /* number of dimensions in fft */
|
||||
|
||||
int ic;
|
||||
|
||||
unsigned int nfft[3];
|
||||
ic = 0;
|
||||
|
||||
ndim=2, isign = -1, nfft[1]=fftw, nfft[2]=fftw, nfft[0]=0; /* fft initialization */
|
||||
|
||||
for (i=0; i < fftw; i++){ /* load up data array */
|
||||
for (j=ix; j < ix+fftw; j++){
|
||||
seg_fft[i][j-ix].re = cmp[i][j].re;
|
||||
seg_fft[i][j-ix].im = cmp[i][j].im;
|
||||
}
|
||||
}
|
||||
|
||||
fourn((float *)seg_fft[0]-1, nfft, ndim, isign); /* 2D forward FFT of region */
|
||||
|
||||
for (i=0; i < fftw; i++){
|
||||
for (j=0; j < fftw; j++){
|
||||
psd = seg_fft[i][j].re * seg_fft[i][j].re + seg_fft[i][j].im * seg_fft[i][j].im;
|
||||
psd_sc = pow(psd,alpha/2.);
|
||||
seg_fft[i][j].re *= psd_sc;
|
||||
seg_fft[i][j].im *= psd_sc;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
#define SWAP(a,b) tempr=(a);(a)=(b);(b)=tempr
|
||||
void fourn(float data[], unsigned int nn[], int ndim, int isign)
|
||||
{
|
||||
int idim;
|
||||
unsigned long i1,i2,i3,i2rev,i3rev,ip1,ip2,ip3,ifp1,ifp2;
|
||||
unsigned long ibit,k1,k2,n,nprev,nrem,ntot;
|
||||
float tempi,tempr;
|
||||
double theta,wi,wpi,wpr,wr,wtemp;
|
||||
|
||||
for (ntot=1,idim=1;idim<=ndim;idim++)
|
||||
ntot *= nn[idim];
|
||||
nprev=1;
|
||||
for (idim=ndim;idim>=1;idim--) {
|
||||
n=nn[idim];
|
||||
nrem=ntot/(n*nprev);
|
||||
ip1=nprev << 1;
|
||||
ip2=ip1*n;
|
||||
ip3=ip2*nrem;
|
||||
i2rev=1;
|
||||
for (i2=1;i2<=ip2;i2+=ip1) {
|
||||
if (i2 < i2rev) {
|
||||
for (i1=i2;i1<=i2+ip1-2;i1+=2) {
|
||||
for (i3=i1;i3<=ip3;i3+=ip2) {
|
||||
i3rev=i2rev+i3-i2;
|
||||
SWAP(data[i3],data[i3rev]);
|
||||
SWAP(data[i3+1],data[i3rev+1]);
|
||||
}
|
||||
}
|
||||
}
|
||||
ibit=ip2 >> 1;
|
||||
while (ibit >= ip1 && i2rev > ibit) {
|
||||
i2rev -= ibit;
|
||||
ibit >>= 1;
|
||||
}
|
||||
i2rev += ibit;
|
||||
}
|
||||
ifp1=ip1;
|
||||
while (ifp1 < ip2) {
|
||||
ifp2=ifp1 << 1;
|
||||
theta=isign*6.28318530717959/(ifp2/ip1);
|
||||
wtemp=sin(0.5*theta);
|
||||
wpr = -2.0*wtemp*wtemp;
|
||||
wpi=sin(theta);
|
||||
wr=1.0;
|
||||
wi=0.0;
|
||||
for (i3=1;i3<=ifp1;i3+=ip1) {
|
||||
for (i1=i3;i1<=i3+ip1-2;i1+=2) {
|
||||
for (i2=i1;i2<=ip3;i2+=ifp2) {
|
||||
k1=i2;
|
||||
k2=k1+ifp1;
|
||||
tempr=(float)wr*data[k2]-(float)wi*data[k2+1];
|
||||
tempi=(float)wr*data[k2+1]+(float)wi*data[k2];
|
||||
data[k2]=data[k1]-tempr;
|
||||
data[k2+1]=data[k1+1]-tempi;
|
||||
data[k1] += tempr;
|
||||
data[k1+1] += tempi;
|
||||
}
|
||||
}
|
||||
wr=(wtemp=wr)*wpr-wi*wpi+wr;
|
||||
wi=wi*wpr+wtemp*wpi+wi;
|
||||
}
|
||||
ifp1=ifp2;
|
||||
}
|
||||
nprev *= n;
|
||||
}
|
||||
}
|
||||
|
||||
#undef SWAP
|
||||
|
||||
fcomplex **cmatrix(int nrl, int nrh, int ncl, int nch)
|
||||
/* allocate a fcomplex matrix with subscript range m[nrl..nrh][ncl..nch] */
|
||||
{
|
||||
int i, nrow=nrh-nrl+1,ncol=nch-ncl+1;
|
||||
fcomplex **m;
|
||||
|
||||
/* allocate pointers to rows */
|
||||
m=(fcomplex **)malloc((size_t)((nrow+NR_END)*sizeof(fcomplex*)));
|
||||
if (!m) nrerror("ERROR: allocation failure 1 in cmatrix()");
|
||||
m += NR_END;
|
||||
m -= nrl;
|
||||
|
||||
/* allocate rows and set pointers to them */
|
||||
m[nrl]=(fcomplex *) malloc((size_t)((nrow*ncol+NR_END)*sizeof(fcomplex)));
|
||||
if (!m[nrl]) nrerror("ERROR: allocation failure 2 in cmatrix()");
|
||||
m[nrl] += NR_END;
|
||||
m[nrl] -= ncl;
|
||||
|
||||
for(i=nrl+1;i<=nrh;i++) m[i]=m[i-1]+ncol;
|
||||
|
||||
/* return pointer to array of pointers to rows */
|
||||
return m;
|
||||
}
|
||||
|
||||
void free_cmatrix(fcomplex **m, int nrl, int nrh, int ncl, int nch)
|
||||
/* free a float matrix allocated by matrix() */
|
||||
{
|
||||
free((FREE_ARG) (m[nrl]+ncl-NR_END));
|
||||
free((FREE_ARG) (m+nrl-NR_END));
|
||||
}
|
||||
|
||||
void nrerror(char error_text[])
|
||||
/* Numerical Recipes standard error handler */
|
||||
{
|
||||
fprintf(stdout,"Numerical Recipes run-time error...\n");
|
||||
fprintf(stdout,"%s\n",error_text);
|
||||
fprintf(stdout,"...now exiting to system...\n");
|
||||
exit(1);
|
||||
}
|
||||
|
||||
#include <sys/types.h>
|
||||
#include <sys/time.h>
|
||||
#include <sys/times.h>
|
||||
#include <unistd.h>
|
||||
#include <limits.h>
|
||||
|
||||
struct tms buffer;
|
||||
int user_time, system_time, start_time;
|
||||
|
||||
void start_timing()
|
||||
{
|
||||
start_time = (int) times(&buffer);
|
||||
user_time = (int) buffer.tms_utime;
|
||||
system_time = (int) buffer.tms_stime;
|
||||
}
|
||||
|
||||
void stop_timing()
|
||||
{
|
||||
int end_time,elapsed_time;
|
||||
int clk_tck;
|
||||
|
||||
clk_tck = (int)sysconf(_SC_CLK_TCK);
|
||||
|
||||
end_time = (int) times(&buffer);
|
||||
user_time = (int) (buffer.tms_utime - user_time);
|
||||
system_time = (int) (buffer.tms_stime - system_time);
|
||||
elapsed_time = (end_time - start_time);
|
||||
|
||||
fprintf(stdout,"\n\nuser time (s): %10.3f\n", (double)user_time/clk_tck);
|
||||
fprintf(stdout,"system time (s): %10.3f\n", (double)system_time/clk_tck);
|
||||
fprintf(stdout,"elapsed time (s): %10.3f\n\n", (double) elapsed_time/clk_tck);
|
||||
}
|
||||
|
||||
/* function: IsFinite()
|
||||
* --------------------
|
||||
* This function takes a double and returns a nonzero value if
|
||||
* the arguemnt is finite (not NaN and not infinite), and zero otherwise.
|
||||
* Different implementations are given here since not all machines have
|
||||
* these functions available.
|
||||
*/
|
||||
signed char IsFinite(double d){
|
||||
|
||||
return(finite(d));
|
||||
/* return(isfinite(d)); */
|
||||
/* return(!(isnan(d) || isinf(d))); */
|
||||
/* return(TRUE) */
|
||||
}
|
||||
|
||||
|
|
@ -5,6 +5,10 @@ Python_add_library(libalos2proc MODULE
|
|||
src/mbf.c
|
||||
src/lib_array.c
|
||||
src/lib_func.c
|
||||
src/resamp.c
|
||||
src/mosaicsubswath.c
|
||||
src/look.c
|
||||
src/extract_burst.c
|
||||
)
|
||||
target_include_directories(libalos2proc PUBLIC include)
|
||||
target_link_libraries(libalos2proc PUBLIC
|
||||
|
|
|
|||
|
|
@ -6,13 +6,12 @@ import copy
|
|||
import ctypes
|
||||
import logging
|
||||
import isceobj
|
||||
from xml.etree.ElementTree import ElementTree
|
||||
|
||||
|
||||
def mbf(inputfile, outputfile, nrg, prf, prf_frac, nb, nbg, nboff, bsl, kacoeff, dopcoeff1, dopcoeff2):
|
||||
def mbf(inputfile, outputfile, prf, prf_frac, nb, nbg, nboff, bsl, kacoeff, dopcoeff1, dopcoeff2):
|
||||
#############################
|
||||
# inputfile: input file
|
||||
# outputfile: output file
|
||||
# nrg: file width
|
||||
# prf: PRF
|
||||
# prf_frac: fraction of PRF processed
|
||||
# (represents azimuth bandwidth)
|
||||
|
|
@ -27,8 +26,8 @@ def mbf(inputfile, outputfile, nrg, prf, prf_frac, nb, nbg, nboff, bsl, kacoeff,
|
|||
# (float, the line number of the first line of the full-aperture SLC is zero)
|
||||
# (no need to be first burst, any one is OK)
|
||||
|
||||
# kacoeff[0-2]: FM rate coefficients
|
||||
# (three coefficients of a quadratic polynomial with regard to)
|
||||
# kacoeff[0-3]: FM rate coefficients
|
||||
# (four coefficients of a third order polynomial with regard to)
|
||||
# (range sample number. range sample number starts with zero)
|
||||
|
||||
# dopcoeff1[0-3]: Doppler centroid frequency coefficients of this image
|
||||
|
|
@ -41,18 +40,34 @@ def mbf(inputfile, outputfile, nrg, prf, prf_frac, nb, nbg, nboff, bsl, kacoeff,
|
|||
#############################
|
||||
|
||||
#examples:
|
||||
# kacoeff = [-625.771055784221, 0.007887946763383646, -9.10142814131697e-08]
|
||||
# kacoeff = [-625.771055784221, 0.007887946763383646, -9.10142814131697e-08, 0.0]
|
||||
# dopcoeff1 = [-0.013424025141940908, -6.820475445542178e-08, 0.0, 0.0]
|
||||
# dopcoeff2 = [-0.013408164465406417, -7.216577938502655e-08, 3.187158113584236e-24, -9.081842749918244e-28]
|
||||
|
||||
inputfile2 = copy.deepcopy(inputfile)
|
||||
outputfile2 = copy.deepcopy(outputfile)
|
||||
inputfile = bytes(inputfile,'utf-8')
|
||||
outputfile = bytes(outputfile,'utf-8')
|
||||
img = isceobj.createSlcImage()
|
||||
img.load(inputfile + '.xml')
|
||||
|
||||
width = img.getWidth()
|
||||
length = img.getLength()
|
||||
|
||||
inputimage = find_vrt_file(inputfile+'.vrt', 'SourceFilename')
|
||||
byteorder = find_vrt_keyword(inputfile+'.vrt', 'ByteOrder')
|
||||
if byteorder == 'LSB':
|
||||
byteorder = 0
|
||||
else:
|
||||
byteorder = 1
|
||||
imageoffset = find_vrt_keyword(inputfile+'.vrt', 'ImageOffset')
|
||||
imageoffset = int(imageoffset)
|
||||
lineoffset = find_vrt_keyword(inputfile+'.vrt', 'LineOffset')
|
||||
lineoffset = int(lineoffset)
|
||||
|
||||
#lineoffset = lineoffset - width * 8
|
||||
#imageoffset = imageoffset - lineoffset
|
||||
|
||||
if type(kacoeff) != list:
|
||||
raise Exception('kacoeff must be a python list.\n')
|
||||
if len(kacoeff) != 3:
|
||||
raise Exception('kacoeff must have three elements.\n')
|
||||
if len(kacoeff) != 4:
|
||||
raise Exception('kacoeff must have four elements.\n')
|
||||
if type(dopcoeff1) != list:
|
||||
raise Exception('dopcoeff1 must be a python list.\n')
|
||||
if len(dopcoeff1) != 4:
|
||||
|
|
@ -64,9 +79,10 @@ def mbf(inputfile, outputfile, nrg, prf, prf_frac, nb, nbg, nboff, bsl, kacoeff,
|
|||
|
||||
filters = ctypes.cdll.LoadLibrary(os.path.join(os.path.dirname(__file__),'libalos2proc.so'))
|
||||
filters.mbf(
|
||||
ctypes.c_char_p(inputfile),
|
||||
ctypes.c_char_p(outputfile),
|
||||
ctypes.c_int(nrg),
|
||||
ctypes.c_char_p(bytes(inputimage,'utf-8')),
|
||||
ctypes.c_char_p(bytes(outputfile,'utf-8')),
|
||||
ctypes.c_int(width),
|
||||
ctypes.c_int(length),
|
||||
ctypes.c_float(prf),
|
||||
ctypes.c_float(prf_frac),
|
||||
ctypes.c_float(nb),
|
||||
|
|
@ -76,24 +92,26 @@ def mbf(inputfile, outputfile, nrg, prf, prf_frac, nb, nbg, nboff, bsl, kacoeff,
|
|||
(ctypes.c_float * len(kacoeff))(*kacoeff),
|
||||
(ctypes.c_float * len(dopcoeff1))(*dopcoeff1),
|
||||
(ctypes.c_float * len(dopcoeff2))(*dopcoeff2),
|
||||
ctypes.c_int(byteorder),
|
||||
ctypes.c_long(imageoffset),
|
||||
ctypes.c_long(lineoffset)
|
||||
)
|
||||
|
||||
img = isceobj.createSlcImage()
|
||||
img.load(inputfile2 + '.xml')
|
||||
img.setFilename(outputfile2)
|
||||
img.extraFilename = outputfile2 + '.vrt'
|
||||
#img = isceobj.createSlcImage()
|
||||
#img.load(inputfile + '.xml')
|
||||
img.setFilename(outputfile)
|
||||
img.extraFilename = outputfile + '.vrt'
|
||||
img.setAccessMode('READ')
|
||||
img.renderHdr()
|
||||
|
||||
|
||||
def rg_filter(inputfile, nrg, nout, outputfile, bw, bc, nfilter, nfft, beta, zero_cf, offset):
|
||||
def rg_filter(inputfile, nout, outputfile, bw, bc, nfilter, nfft, beta, zero_cf, offset):
|
||||
#############################
|
||||
# inputfile: input file
|
||||
# nrg file width
|
||||
# nout: number of output files
|
||||
# outputfile: (value_of_out_1, value_of_out_2, value_of_out_3...) output files
|
||||
# bw: (value_of_out_1, value_of_out_2, value_of_out_3...) filter bandwidth divided by sampling frequency [0, 1]
|
||||
# bc: (value_of_out_1, value_of_out_2, value_of_out_3...) filter center frequency divided by sampling frequency
|
||||
# outputfile: [value_of_out_1, value_of_out_2, value_of_out_3...] output files
|
||||
# bw: [value_of_out_1, value_of_out_2, value_of_out_3...] filter bandwidth divided by sampling frequency [0, 1]
|
||||
# bc: [value_of_out_1, value_of_out_2, value_of_out_3...] filter center frequency divided by sampling frequency
|
||||
|
||||
# nfilter: number samples of the filter (odd). Reference Value: 65
|
||||
# nfft: number of samples of the FFT. Reference Value: 1024
|
||||
|
|
@ -103,19 +121,35 @@ def rg_filter(inputfile, nrg, nout, outputfile, bw, bc, nfilter, nfft, beta, zer
|
|||
#############################
|
||||
|
||||
#examples
|
||||
#outputfile = [bytes('result/crop_filt_1.slc','utf-8'), bytes('result/crop_filt_2.slc','utf-8')]
|
||||
#outputfile = ['result/crop_filt_1.slc', 'result/crop_filt_2.slc']
|
||||
#bw = [0.3, 0.3]
|
||||
#bc = [0.1, -0.1]
|
||||
|
||||
inputfile2 = copy.deepcopy(inputfile)
|
||||
img = isceobj.createSlcImage()
|
||||
img.load(inputfile + '.xml')
|
||||
|
||||
width = img.getWidth()
|
||||
length = img.getLength()
|
||||
|
||||
inputimage = find_vrt_file(inputfile+'.vrt', 'SourceFilename')
|
||||
byteorder = find_vrt_keyword(inputfile+'.vrt', 'ByteOrder')
|
||||
if byteorder == 'LSB':
|
||||
byteorder = 0
|
||||
else:
|
||||
byteorder = 1
|
||||
imageoffset = find_vrt_keyword(inputfile+'.vrt', 'ImageOffset')
|
||||
imageoffset = int(imageoffset)
|
||||
lineoffset = find_vrt_keyword(inputfile+'.vrt', 'LineOffset')
|
||||
lineoffset = int(lineoffset)
|
||||
|
||||
#lineoffset = lineoffset - width * 8
|
||||
#imageoffset = imageoffset - lineoffset
|
||||
|
||||
outputfile2 = copy.deepcopy(outputfile)
|
||||
|
||||
inputfile = bytes(inputfile,'utf-8')
|
||||
|
||||
if type(outputfile) != list:
|
||||
raise Exception('outputfile must be a python list.\n')
|
||||
if len(outputfile) != nout:
|
||||
raise Exception('number of output files is not equal to list length.\n')
|
||||
raise Exception('number of output files is not equal to outputfile list length.\n')
|
||||
else:
|
||||
tmp = []
|
||||
for x in outputfile:
|
||||
|
|
@ -125,17 +159,18 @@ def rg_filter(inputfile, nrg, nout, outputfile, bw, bc, nfilter, nfft, beta, zer
|
|||
if type(bw) != list:
|
||||
raise Exception('bw must be a python list.\n')
|
||||
if len(bw) != nout:
|
||||
raise Exception('number of output files is not equal to list length.\n')
|
||||
raise Exception('number of output files is not equal to bw list length.\n')
|
||||
|
||||
if type(bc) != list:
|
||||
raise Exception('bc must be a python list.\n')
|
||||
if len(bc) != nout:
|
||||
raise Exception('number of output files is not equal to list length.\n')
|
||||
raise Exception('number of output files is not equal to bc list length.\n')
|
||||
|
||||
filters = ctypes.cdll.LoadLibrary(os.path.join(os.path.dirname(__file__),'libalos2proc.so'))
|
||||
filters.rg_filter(
|
||||
ctypes.c_char_p(inputfile),
|
||||
ctypes.c_int(nrg),
|
||||
ctypes.c_char_p(bytes(inputimage,'utf-8')),
|
||||
ctypes.c_int(width),
|
||||
ctypes.c_int(length),
|
||||
ctypes.c_int(nout),
|
||||
(ctypes.c_char_p * len(outputfile))(*outputfile),
|
||||
(ctypes.c_float * len(bw))(*bw),
|
||||
|
|
@ -144,13 +179,286 @@ def rg_filter(inputfile, nrg, nout, outputfile, bw, bc, nfilter, nfft, beta, zer
|
|||
ctypes.c_int(nfft),
|
||||
ctypes.c_float(beta),
|
||||
ctypes.c_int(zero_cf),
|
||||
ctypes.c_float(offset)
|
||||
ctypes.c_float(offset),
|
||||
ctypes.c_int(byteorder),
|
||||
ctypes.c_long(imageoffset),
|
||||
ctypes.c_long(lineoffset)
|
||||
)
|
||||
|
||||
img = isceobj.createSlcImage()
|
||||
img.load(inputfile2 + '.xml')
|
||||
#img = isceobj.createSlcImage()
|
||||
#img.load(inputfile + '.xml')
|
||||
for x in outputfile2:
|
||||
img.setFilename(x)
|
||||
img.extraFilename = x + '.vrt'
|
||||
img.setAccessMode('READ')
|
||||
img.renderHdr()
|
||||
|
||||
|
||||
def resamp(slc2, rslc2, rgoff_file, azoff_file, nrg1, naz1, prf, dopcoeff, rgcoef=[0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0], azcoef=[0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0], azpos_off=0.0, verbose=0):
|
||||
#############################
|
||||
# mandatory:
|
||||
# slc2: slave image
|
||||
# rslc2: resampled slave image
|
||||
# rgoff_file: range offset file. if no range offset file, specify 'fake'
|
||||
# azoff_file: azimuth offset file. if no azimuth offset file, specify 'fake'
|
||||
# nrg1: number of columns in master image
|
||||
# naz1: number of lines in master image
|
||||
# prf: PRF of slave image
|
||||
# dopcoeff[0]-[3]: Doppler centroid frequency coefficents
|
||||
# optional:
|
||||
# rgcoef[0]-[9]: range offset polynomial coefficents. First of two fit results of resamp_roi
|
||||
# azcoef[0]-[9]: azimuth offset polynomial coefficents. First of two fit results of resamp_roi
|
||||
# azpos_off: azimuth position offset. Azimuth line number (column 3) of first offset in culled offset file
|
||||
# verbose: if not zero, print resampling info
|
||||
#############################
|
||||
|
||||
#examples:
|
||||
# dopcoeff = [-0.013424025141940908, -6.820475445542178e-08, 0.0, 0.0]
|
||||
|
||||
img = isceobj.createSlcImage()
|
||||
img.load(slc2 + '.xml')
|
||||
|
||||
width = img.getWidth()
|
||||
length = img.getLength()
|
||||
|
||||
inputimage = find_vrt_file(slc2+'.vrt', 'SourceFilename')
|
||||
byteorder = find_vrt_keyword(slc2+'.vrt', 'ByteOrder')
|
||||
if byteorder == 'LSB':
|
||||
byteorder = 0
|
||||
else:
|
||||
byteorder = 1
|
||||
imageoffset = find_vrt_keyword(slc2+'.vrt', 'ImageOffset')
|
||||
imageoffset = int(imageoffset)
|
||||
lineoffset = find_vrt_keyword(slc2+'.vrt', 'LineOffset')
|
||||
lineoffset = int(lineoffset)
|
||||
|
||||
#lineoffset = lineoffset - width * 8
|
||||
#imageoffset = imageoffset - lineoffset
|
||||
|
||||
if type(dopcoeff) != list:
|
||||
raise Exception('dopcoeff must be a python list.\n')
|
||||
if len(dopcoeff) != 4:
|
||||
raise Exception('dopcoeff must have four elements.\n')
|
||||
if type(rgcoef) != list:
|
||||
raise Exception('rgcoef must be a python list.\n')
|
||||
if len(rgcoef) != 10:
|
||||
raise Exception('rgcoef must have 10 elements.\n')
|
||||
if type(azcoef) != list:
|
||||
raise Exception('azcoef must be a python list.\n')
|
||||
if len(azcoef) != 10:
|
||||
raise Exception('azcoef must have 10 elements.\n')
|
||||
|
||||
filters = ctypes.cdll.LoadLibrary(os.path.join(os.path.dirname(__file__),'libalos2proc.so'))
|
||||
filters.resamp(
|
||||
ctypes.c_char_p(bytes(inputimage,'utf-8')),
|
||||
ctypes.c_char_p(bytes(rslc2,'utf-8')),
|
||||
ctypes.c_char_p(bytes(rgoff_file,'utf-8')),
|
||||
ctypes.c_char_p(bytes(azoff_file,'utf-8')),
|
||||
ctypes.c_int(nrg1),
|
||||
ctypes.c_int(naz1),
|
||||
ctypes.c_int(width),
|
||||
ctypes.c_int(length),
|
||||
ctypes.c_float(prf),
|
||||
(ctypes.c_float * len(dopcoeff))(*dopcoeff),
|
||||
(ctypes.c_float * len(rgcoef))(*rgcoef),
|
||||
(ctypes.c_float * len(azcoef))(*azcoef),
|
||||
ctypes.c_float(azpos_off),
|
||||
ctypes.c_int(byteorder),
|
||||
ctypes.c_long(imageoffset),
|
||||
ctypes.c_long(lineoffset),
|
||||
ctypes.c_int(verbose)
|
||||
)
|
||||
|
||||
#img = isceobj.createSlcImage()
|
||||
#img.load(inputfile + '.xml')
|
||||
img.setFilename(rslc2)
|
||||
img.extraFilename = rslc2 + '.vrt'
|
||||
img.setWidth(nrg1)
|
||||
img.setLength(naz1)
|
||||
img.setAccessMode('READ')
|
||||
img.renderHdr()
|
||||
|
||||
|
||||
def mosaicsubswath(outputfile, nrgout, nazout, delta, diffflag, n, inputfile, nrgin, nrgoff, nazoff, phc, oflag):
|
||||
'''
|
||||
outputfile: (char) output file
|
||||
nrgout: (int) number of output samples
|
||||
nazout: (int) number of output lines
|
||||
delta: (int) edge to be removed of the overlap area (number of samples)
|
||||
diffflag: (int) whether output the overlap area as two-band BIL image. 0: yes, otherwise: no
|
||||
n: (int) number of input file
|
||||
inputfile: (char list) [value_of_out_1, value_of_out_2, value_of_out_3...] input files to mosaic
|
||||
nrgin: (int list) [value_of_out_1, value_of_out_2, value_of_out_3...] input file widths
|
||||
nrgoff: (int list) [value_of_out_1, value_of_out_2, value_of_out_3...] input file range offsets
|
||||
nazoff: (int list) [value_of_out_1, value_of_out_2, value_of_out_3...] input file azimuth offsets
|
||||
phc: (float list) [value_of_out_1, value_of_out_2, value_of_out_3...] input file compensation phase
|
||||
oflag: (int list) [value_of_out_1, value_of_out_2, value_of_out_3...] overlap area mosaicking flag
|
||||
|
||||
for each frame
|
||||
range offset is relative to the first sample of last subswath
|
||||
azimuth offset is relative to the uppermost line
|
||||
'''
|
||||
|
||||
if type(inputfile) != list:
|
||||
raise Exception('inputfile must be a python list.\n')
|
||||
if len(inputfile) != n:
|
||||
raise Exception('number of input files is not equal to inputfile list length.\n')
|
||||
else:
|
||||
inputfile = [bytes(x,'utf-8') for x in inputfile]
|
||||
|
||||
filters = ctypes.cdll.LoadLibrary(os.path.join(os.path.dirname(__file__),'libalos2proc.so'))
|
||||
filters.mosaicsubswath(
|
||||
ctypes.c_char_p(bytes(outputfile,'utf-8')),
|
||||
ctypes.c_int(nrgout),
|
||||
ctypes.c_int(nazout),
|
||||
ctypes.c_int(delta),
|
||||
ctypes.c_int(diffflag),
|
||||
ctypes.c_int(n),
|
||||
(ctypes.c_char_p * len(inputfile))(*inputfile),
|
||||
(ctypes.c_int * len(nrgin))(*nrgin),
|
||||
(ctypes.c_int * len(nrgoff))(*nrgoff),
|
||||
(ctypes.c_int * len(nazoff))(*nazoff),
|
||||
(ctypes.c_float * len(phc))(*phc),
|
||||
(ctypes.c_int * len(oflag))(*oflag)
|
||||
)
|
||||
|
||||
|
||||
def look(inputfile, outputfile, nrg, nrlks, nalks, ft=0, sum=0, avg=0):
|
||||
'''
|
||||
inputfile: input file
|
||||
outputfile: output file
|
||||
nrg: file width
|
||||
nrlks: number of looks in range (default: 4)
|
||||
nalks: number of looks in azimuth (default: 4)
|
||||
ft: file type (default: 0)
|
||||
0: signed char
|
||||
1: int
|
||||
2: float
|
||||
3: double
|
||||
4: complex (real and imagery: float)
|
||||
5: complex (real and imagery: double)
|
||||
sum: sum method (default: 0)
|
||||
0: simple sum
|
||||
1: power sum (if complex, do this for each channel seperately)
|
||||
avg: take average (default: 0)
|
||||
0: no
|
||||
1: yes
|
||||
'''
|
||||
|
||||
filters = ctypes.cdll.LoadLibrary(os.path.join(os.path.dirname(__file__),'libalos2proc.so'))
|
||||
filters.look(
|
||||
ctypes.c_char_p(bytes(inputfile,'utf-8')),
|
||||
ctypes.c_char_p(bytes(outputfile,'utf-8')),
|
||||
ctypes.c_long(nrg),
|
||||
ctypes.c_int(nrlks),
|
||||
ctypes.c_int(nalks),
|
||||
ctypes.c_int(ft),
|
||||
ctypes.c_int(sum),
|
||||
ctypes.c_int(avg)
|
||||
)
|
||||
|
||||
|
||||
def extract_burst(inputf, outputf, prf, prf_frac, nb, nbg, bsl, kacoeff, dopcoeff, az_ratio, min_line_offset):
|
||||
'''
|
||||
see extract_burst.c for usage
|
||||
'''
|
||||
|
||||
img = isceobj.createSlcImage()
|
||||
img.load(inputf + '.xml')
|
||||
|
||||
width = img.getWidth()
|
||||
length = img.getLength()
|
||||
|
||||
inputimage = find_vrt_file(inputf+'.vrt', 'SourceFilename')
|
||||
byteorder = find_vrt_keyword(inputf+'.vrt', 'ByteOrder')
|
||||
if byteorder == 'LSB':
|
||||
byteorder = 0
|
||||
else:
|
||||
byteorder = 1
|
||||
imageoffset = find_vrt_keyword(inputf+'.vrt', 'ImageOffset')
|
||||
imageoffset = int(imageoffset)
|
||||
lineoffset = find_vrt_keyword(inputf+'.vrt', 'LineOffset')
|
||||
lineoffset = int(lineoffset)
|
||||
|
||||
if type(kacoeff) != list:
|
||||
raise Exception('kacoeff must be a python list.\n')
|
||||
if len(kacoeff) != 4:
|
||||
raise Exception('kacoeff must have four elements.\n')
|
||||
if type(dopcoeff) != list:
|
||||
raise Exception('dopcoeff must be a python list.\n')
|
||||
if len(dopcoeff) != 4:
|
||||
raise Exception('dopcoeff must have four elements.\n')
|
||||
|
||||
filters = ctypes.cdll.LoadLibrary(os.path.join(os.path.dirname(__file__),'libalos2proc.so'))
|
||||
filters.extract_burst(
|
||||
ctypes.c_char_p(bytes(inputimage,'utf-8')),
|
||||
ctypes.c_char_p(bytes(outputf,'utf-8')),
|
||||
ctypes.c_int(width),
|
||||
ctypes.c_int(length),
|
||||
ctypes.c_float(prf),
|
||||
ctypes.c_float(prf_frac),
|
||||
ctypes.c_float(nb),
|
||||
ctypes.c_float(nbg),
|
||||
ctypes.c_float(bsl),
|
||||
(ctypes.c_float * len(kacoeff))(*kacoeff),
|
||||
(ctypes.c_float * len(dopcoeff))(*dopcoeff),
|
||||
ctypes.c_float(az_ratio),
|
||||
ctypes.c_float(min_line_offset),
|
||||
ctypes.c_int(byteorder),
|
||||
ctypes.c_long(imageoffset),
|
||||
ctypes.c_long(lineoffset)
|
||||
)
|
||||
|
||||
#img = isceobj.createSlcImage()
|
||||
#img.load(inputfile + '.xml')
|
||||
#img.setFilename(outputfile)
|
||||
#img.extraFilename = outputfile + '.vrt'
|
||||
#img.setAccessMode('READ')
|
||||
#img.renderHdr()
|
||||
|
||||
|
||||
def find_vrt_keyword(xmlfile, keyword):
|
||||
from xml.etree.ElementTree import ElementTree
|
||||
|
||||
value = None
|
||||
xmlx = ElementTree(file=open(xmlfile,'r')).getroot()
|
||||
#try 10 times
|
||||
for i in range(10):
|
||||
path=''
|
||||
for j in range(i):
|
||||
path += '*/'
|
||||
value0 = xmlx.find(path+keyword)
|
||||
if value0 != None:
|
||||
value = value0.text
|
||||
break
|
||||
|
||||
return value
|
||||
|
||||
|
||||
|
||||
def find_vrt_file(xmlfile, keyword, relative_path=True):
|
||||
'''
|
||||
find file in vrt in another directory
|
||||
xmlfile: vrt file
|
||||
relative_path: True: return relative (to current directory) path of the file
|
||||
False: return absolute path of the file
|
||||
'''
|
||||
import os
|
||||
#get absolute directory of xmlfile
|
||||
xmlfile_dir = os.path.dirname(os.path.abspath(xmlfile))
|
||||
#find source file path
|
||||
file = find_vrt_keyword(xmlfile, keyword)
|
||||
#get absolute path of source file
|
||||
file = os.path.abspath(os.path.join(xmlfile_dir, file))
|
||||
#get relative path of source file
|
||||
if relative_path:
|
||||
file = os.path.relpath(file, './')
|
||||
return file
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
|
|
|||
|
|
@ -5,7 +5,7 @@ import os
|
|||
Import('envalos2proc')
|
||||
|
||||
install = os.path.join(envalos2proc['PRJ_SCONS_INSTALL'], envalos2proc['PACKAGE'], 'alos2proc')
|
||||
listFiles = ['lib_array.c', 'lib_cpx.c', 'lib_file.c', 'lib_func.c', 'mbf.c', 'rg_filter.c']
|
||||
listFiles = ['lib_array.c', 'lib_cpx.c', 'lib_file.c', 'lib_func.c', 'mbf.c', 'rg_filter.c', 'resamp.c', 'mosaicsubswath.c', 'look.c', 'extract_burst.c']
|
||||
|
||||
# -shared
|
||||
# -D_LARGEFILE64_SOURCE -D_FILE_OFFSET_BITS=64 -lm
|
||||
|
|
@ -14,7 +14,7 @@ listFiles = ['lib_array.c', 'lib_cpx.c', 'lib_file.c', 'lib_func.c', 'mbf.c', 'r
|
|||
#envalos2proc.Append(CFLAGS=['-D_LARGEFILE64_SOURCE', '-D_FILE_OFFSET_BITS=64', '-lm', '-shared', '-fopenmp', '-O3'])
|
||||
#envalos2proc.Append(LIBS=['fftw3f', 'fftw3f_threads', 'pthread'])
|
||||
|
||||
lib = envalos2proc.LoadableModule(target = 'libalos2proc.so', source = listFiles)
|
||||
lib = envalos2proc.LoadableModule(target = 'libalos2proc.so', source = listFiles, parse_flags='-fopenmp')
|
||||
envalos2proc.Install(install,lib)
|
||||
envalos2proc.Alias('install',install)
|
||||
|
||||
|
|
|
|||
|
|
@ -0,0 +1,576 @@
|
|||
//////////////////////////////////////
|
||||
// Cunren Liang, NASA JPL/Caltech
|
||||
// Copyright 2017
|
||||
//////////////////////////////////////
|
||||
|
||||
|
||||
#include "resamp.h"
|
||||
#include <fftw3.h>
|
||||
|
||||
#define SWAP4(a) (*(unsigned int *)&(a) = (((*(unsigned int *)&(a) & 0x000000ff) << 24) | ((*(unsigned int *)&(a) & 0x0000ff00) << 8) | ((*(unsigned int *)&(a) >> 8) & 0x0000ff00) | ((*(unsigned int *)&(a) >> 24) & 0x000000ff)))
|
||||
|
||||
|
||||
int extract_burst(char *inputf, char *outputf, int nrg, int naz, float prf, float prf_frac, float nb, float nbg, float bsl, float *kacoeff, float *dopcoeff, float az_ratio, float min_line_offset, int byteorder, long imageoffset, long lineoffset){
|
||||
FILE *infp;
|
||||
FILE *outfp;
|
||||
FILE *infofp;
|
||||
|
||||
char output_filename[512];
|
||||
char burst_num[512];
|
||||
|
||||
fcomplex **in; //data read in
|
||||
fcomplex **out; //data written to output file
|
||||
fcomplex **filter; //multi-band bandpass filter
|
||||
fcomplex **deramp; //deramp signal
|
||||
|
||||
fcomplex *data; //data to be filtered.
|
||||
|
||||
//int nrg; //file width
|
||||
//int naz; //file length
|
||||
int naz_burst_in; //number of lines of the input burst
|
||||
int naz_burst_out; //number of lines of the output burst
|
||||
|
||||
//float prf;
|
||||
float pri; // 1.0/prf
|
||||
//float prf_frac; // azimuth bandwidth used for burst extraction = prf_frac * prf
|
||||
//float kacoeff[3]; //FM rate along range (experessed by quadratic polynomial
|
||||
//as a function of range sample number)
|
||||
//float dopcoeff[4]; //doppler centroid frequency along range (expressed by quadratic polynomial
|
||||
//as a function of range sample number). this image
|
||||
|
||||
//float nb; //burst length in terms of pri. number of lines
|
||||
//float nbg; //burst gap length in terms of pri. number of lines
|
||||
//float bsl; //burst start line, input float
|
||||
float bcl; //burst center line, float
|
||||
float bfw; //burst bandwidth
|
||||
//float az_ratio; //azimuth sampling interval of output burst: az_ratio * pri;
|
||||
|
||||
float *ka; //azimuth fm rate
|
||||
float *dop; //doppler centroid frequency
|
||||
float *nfa;
|
||||
|
||||
float *start_line; //burst imaged area start line number for each column
|
||||
float *end_line; //burst imaged area ending line number for each column
|
||||
|
||||
float min_line; //minimum of start_line
|
||||
float max_line; //maximum of end_line
|
||||
int min_line_column; //column of minimum
|
||||
int max_line_column; //column of maximum
|
||||
|
||||
int *output_start; //relative start line in the output burst for each column
|
||||
int *output_end; //relative end line in the output burst for each column
|
||||
|
||||
int min_line_in; //first line of input burst
|
||||
float min_line_out; //first line of output burst
|
||||
float min_line_out_first; //first line of first output burst
|
||||
int offset_from_first_burst; //offset between first burst and this burst in az_ratio * pri
|
||||
int offset_from_first_burst0; //offset between first burst and last burst in az_ratio * pri
|
||||
|
||||
//float min_line_offset; // the offset of first line of output burst in pri, compared with roundfi(min_line)
|
||||
// this is mainly used to adjust the output burst location. so usually can be set to 0
|
||||
|
||||
int burst_index;
|
||||
int burst_index_tmp;
|
||||
int burst_index_first;
|
||||
|
||||
int nfft; //fft length
|
||||
int nfilter; //filter length, MUST BE ODD
|
||||
int hnfilter; //half filter length
|
||||
float beta; //kaiser window beta of filter
|
||||
float sc; //constant to scale the data read in to avoid large values during fft and ifft
|
||||
|
||||
//resampling parameters
|
||||
float beta_resamp; //beta of kaiser window of resampling kernal
|
||||
int n; //number of samples to be used in the resampling(odd)
|
||||
int m; //multiples of n, so that a lookup table can be generated(even)
|
||||
|
||||
int hn; //half of n
|
||||
int hnm; //half of n*m
|
||||
float *sincc; //sinc coefficents
|
||||
float *kaiserc; // kaiser window coefficents
|
||||
float *kernel; // sincc*kaiserc
|
||||
|
||||
float tmpa, tmpb, tmpc; //temperal variables effective for a longer time
|
||||
float tmp1, tmp2, tmp3; //temperal variables effective for a shorter time
|
||||
fcomplex reramp;
|
||||
int index;
|
||||
|
||||
int i, j, k;
|
||||
|
||||
fftwf_plan p_forward;
|
||||
fftwf_plan p_backward;
|
||||
|
||||
/*****************************************************************************/
|
||||
//I just put these parametes which can be set here. These can also be set via
|
||||
//arguments before running the programs if modifying the code to accept these
|
||||
//arguments.
|
||||
//min_line_offset = 0.0;
|
||||
|
||||
//filtering parameters
|
||||
beta = 1.0;
|
||||
nfilter = 257; //MUST BE ODD
|
||||
sc = 10000.0;
|
||||
|
||||
//resampling parameters
|
||||
beta_resamp = 2.5;
|
||||
n = 9; //MUST BE ODD
|
||||
m = 10000; //MUST BE EVEN
|
||||
|
||||
/*****************************************************************************/
|
||||
|
||||
if(0){
|
||||
//if(argc != 18){
|
||||
fprintf(stderr, "\nusage: %s inputf outputf nrg naz prf prf_frac nb nbg bsl kacoeff[0-3] dopcoeff[0-3] az_ratio min_line_offset byteorder imageoffset lineoffset\n");
|
||||
fprintf(stderr, "\nmandatory:\n");
|
||||
fprintf(stderr, " inputf: input file\n");
|
||||
fprintf(stderr, " outputf: prefix of output files\n");
|
||||
fprintf(stderr, " nrg: file width\n");
|
||||
fprintf(stderr, " naz: file length\n");
|
||||
fprintf(stderr, " prf: PRF\n");
|
||||
fprintf(stderr, " prf_frac: fraction of PRF used for burst generation\n");
|
||||
fprintf(stderr, " (represents azimuth bandwidth)\n");
|
||||
fprintf(stderr, " nb: number of lines in a burst\n");
|
||||
fprintf(stderr, " (float, in terms of 1/PRF)\n");
|
||||
fprintf(stderr, " nbg: number of lines in a burst gap\n");
|
||||
fprintf(stderr, " (float, in terms of 1/PRF)\n");
|
||||
fprintf(stderr, " bsl: start line number of a burst\n");
|
||||
fprintf(stderr, " (float, the line number of the first line of the full-aperture SLC is zero)\n");
|
||||
fprintf(stderr, " (no need to be first burst, any one is OK)\n");
|
||||
|
||||
fprintf(stderr, " kacoeff[0-3]: FM rate coefficients\n");
|
||||
fprintf(stderr, " (four coefficients of a third order polynomial with regard to)\n");
|
||||
fprintf(stderr, " (range sample number. range sample number starts with zero)\n");
|
||||
|
||||
fprintf(stderr, " dopcoeff[0-3]: Doppler centroid frequency coefficients of this image\n");
|
||||
fprintf(stderr, " (four coefficients of a third order polynomial with regard to)\n");
|
||||
fprintf(stderr, " (range sample number. range sample number starts with zero)\n");
|
||||
fprintf(stderr, " az_ratio: line interval of output burst: az_ratio * (1/PRF)\n");
|
||||
fprintf(stderr, " min_line_offset: adjust output line location by this offset\n");
|
||||
fprintf(stderr, " (in terms of 1/PRF, within [-50/PRF, 50/PRF])\n");
|
||||
fprintf(stderr, " (offset < 0, start earlier than original)\n");
|
||||
fprintf(stderr, " (offset = 0, original)\n");
|
||||
fprintf(stderr, " (offset > 0, start later than original)\n");
|
||||
|
||||
fprintf(stderr, "byteorder: (0) LSB, little endian; (1) MSB, big endian of intput file\n");
|
||||
fprintf(stderr, "imageoffset: offset from start of the image of input file\n");
|
||||
fprintf(stderr, "lineoffset: length of each line of input file\n\n");
|
||||
|
||||
exit(1);
|
||||
}
|
||||
|
||||
infofp = openfile("extract_burst.txt", "w");
|
||||
|
||||
//open files
|
||||
infp = openfile(inputf, "rb");
|
||||
//nrg = atoi(argv[3]);
|
||||
//prf = atof(argv[4]);
|
||||
//prf_frac = atof(argv[5]);
|
||||
//nb = atof(argv[6]);
|
||||
//nbg = atof(argv[7]);
|
||||
//bsl = atof(argv[8]);
|
||||
|
||||
//kacoeff[0] = atof(argv[9]);
|
||||
//kacoeff[1] = atof(argv[10]);
|
||||
//kacoeff[2] = atof(argv[11]);
|
||||
|
||||
//dopcoeff[0] = atof(argv[12]);
|
||||
//dopcoeff[1] = atof(argv[13]);
|
||||
//dopcoeff[2] = atof(argv[14]);
|
||||
//dopcoeff[3] = atof(argv[15]);
|
||||
|
||||
//az_ratio = atof(argv[16]);
|
||||
//min_line_offset = atof(argv[17]);
|
||||
|
||||
|
||||
fprintf(infofp, "\n\ninput parameters:\n");
|
||||
fprintf(infofp, "input file: %s\n", inputf);
|
||||
fprintf(infofp, "prefix of output files: %s\n", outputf);
|
||||
fprintf(infofp, "nrg: %d\n", nrg);
|
||||
fprintf(infofp, "prf: %f\n", prf);
|
||||
fprintf(infofp, "prf_frac: %f\n", prf_frac);
|
||||
fprintf(infofp, "nb: %f\n", nb);
|
||||
fprintf(infofp, "nbg: %f\n", nbg);
|
||||
fprintf(infofp, "bsl: %f\n", bsl);
|
||||
|
||||
fprintf(infofp, "kacoeff: %f, %f, %f, %f\n", kacoeff[0], kacoeff[1], kacoeff[2], kacoeff[3]);
|
||||
fprintf(infofp, "dopcoeff1: %f, %f, %f, %f\n", dopcoeff[0], dopcoeff[1], dopcoeff[2], dopcoeff[3]);
|
||||
|
||||
fprintf(infofp, "az_ratio: %f\n", az_ratio);
|
||||
fprintf(infofp, "offset: %f\n\n", min_line_offset);
|
||||
|
||||
if(fabs(min_line_offset) > 50.0){
|
||||
fprintf(stderr, "offset too big!\n");
|
||||
exit(1);
|
||||
}
|
||||
|
||||
if(nfilter % 2 != 1){
|
||||
fprintf(stderr, "filter length must be odd!\n");
|
||||
exit(1);
|
||||
}
|
||||
|
||||
if(n % 2 != 1){
|
||||
fprintf(stderr, "resample kernal length must be odd!\n");
|
||||
exit(1);
|
||||
}
|
||||
if(n < 7){
|
||||
fprintf(stderr, "resample kernal length too small!\n");
|
||||
exit(1);
|
||||
}
|
||||
|
||||
if(m % 2 != 0){
|
||||
fprintf(stderr, "m must be even!\n");
|
||||
exit(1);
|
||||
}
|
||||
if(m < 1000){
|
||||
fprintf(stderr, "m too small!\n");
|
||||
exit(1);
|
||||
}
|
||||
|
||||
pri = 1.0/prf;
|
||||
hnfilter = (nfilter - 1) / 2;
|
||||
|
||||
hn = n / 2;
|
||||
hnm = n * m / 2;
|
||||
|
||||
|
||||
//naz = file_length(infp, nrg, sizeof(fcomplex));
|
||||
fprintf(infofp, "file width: %d, file length: %d\n\n", nrg, naz);
|
||||
|
||||
ka = array1d_float(nrg);
|
||||
dop = array1d_float(nrg);
|
||||
nfa = array1d_float(nrg);
|
||||
|
||||
start_line = array1d_float(nrg);
|
||||
end_line = array1d_float(nrg);
|
||||
output_start = array1d_int(nrg);
|
||||
output_end = array1d_int(nrg);
|
||||
|
||||
sincc = vector_float(-hnm, hnm);
|
||||
kaiserc = vector_float(-hnm, hnm);
|
||||
kernel = vector_float(-hnm, hnm);
|
||||
|
||||
//initialize sinc coefficents
|
||||
sinc(n, m, sincc);
|
||||
kaiser(n, m, kaiserc, beta_resamp);
|
||||
for(i = -hnm; i <= hnm; i++)
|
||||
kernel[i] = kaiserc[i] * sincc[i];
|
||||
|
||||
//calculate some range variant variables
|
||||
for(i = 0; i < nrg; i++){
|
||||
//azimuth FM rate. we follow the convention ka > 0
|
||||
ka[i] = kacoeff[3] * i * i * i + kacoeff[2] * i * i + kacoeff[1] * i + kacoeff[0];
|
||||
ka[i] = -ka[i];
|
||||
|
||||
//doppler centroid frequency
|
||||
dop[i] = dopcoeff[0] + dopcoeff[1] * i + dopcoeff[2] * i * i + dopcoeff[3] * i * i * i;
|
||||
//dop[i] *= prf;
|
||||
|
||||
//full-aperture length
|
||||
nfa[i] = prf * prf_frac / ka[i] / pri;
|
||||
}
|
||||
|
||||
tmp1 = -1.0; //maximum oversampling ratio
|
||||
tmp2 = 10000000000.0; //minimum oversampling ratio
|
||||
for(i = 0; i < nrg; i++){
|
||||
tmp3 = 1.0 / (az_ratio * pri) / (nb * pri * ka[i]);
|
||||
if(tmp3 > tmp1)
|
||||
tmp1 = tmp3;
|
||||
if(tmp3 < tmp2)
|
||||
tmp2 = tmp3;
|
||||
}
|
||||
|
||||
fprintf(infofp, "azimuth oversampling ratio of output burst, minimum: %6.2f, maximum: %6.2f\n\n", tmp2, tmp1);
|
||||
|
||||
|
||||
//find burst starting line closest to first line and after first line
|
||||
//to make sure the bsl used in the following is not too big to avoid overflow
|
||||
//bsl is defined by 0 = first line of input SLC, this defines the absolute line numbers used in the following
|
||||
//here we stop at burst_index_tmp
|
||||
for(i = -100000; i < 100000; i++){
|
||||
tmp1 = bsl + (nb + nbg) * i;
|
||||
if(tmp1 >= 0){
|
||||
bsl = tmp1;
|
||||
burst_index_tmp = i;
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
//starting and ending lines for each column
|
||||
for(i = 0; i < nrg; i++){
|
||||
//starting index
|
||||
start_line[i] = bsl + (nb - 1.0) / 2.0 + dop[i] / ka[i] / pri - (nfa[i] - nb - 1.0) / 2.0;
|
||||
//ending index
|
||||
end_line[i] = bsl + (nb - 1.0) / 2.0 + dop[i] / ka[i] / pri + (nfa[i] - nb - 1.0) / 2.0;
|
||||
}
|
||||
|
||||
//starting and ending lines for the whole block
|
||||
min_line = start_line[0];
|
||||
max_line = end_line[0];
|
||||
for(i = 0; i < nrg; i++){
|
||||
if(start_line[i] <= min_line){
|
||||
min_line = start_line[i];
|
||||
min_line_column = i;
|
||||
}
|
||||
if(end_line[i] >= max_line){
|
||||
max_line = end_line[i];
|
||||
max_line_column = i;
|
||||
}
|
||||
}
|
||||
|
||||
//number of lines of the input burst
|
||||
naz_burst_in = roundfi((max_line - min_line) + 2 * hnfilter);
|
||||
//number of lines of the output burst
|
||||
naz_burst_out = roundfi((max_line - min_line) / az_ratio);
|
||||
//to make circular convolution equivalent to linear convolution
|
||||
nfft = next_pow2(naz_burst_in + nfilter - 1);
|
||||
|
||||
fprintf(infofp, "for all the output bursts:\n");
|
||||
fprintf(infofp, "input data block length: %d\n", naz_burst_in);
|
||||
fprintf(infofp, "output burst length: %d\n", naz_burst_out);
|
||||
fprintf(infofp, "fft length: %d\n\n", nfft);
|
||||
|
||||
//calculate relative start and end lines in the output burst
|
||||
for(i = 0; i < nrg; i++){
|
||||
output_start[i] = roundfi((start_line[i] - min_line) / az_ratio); //made sure: first line has output. Include this start line
|
||||
output_end[i] = naz_burst_out - 1 + roundfi((end_line[i] - max_line) / az_ratio); //made sure: last line has output. Include this end line
|
||||
}
|
||||
|
||||
in = array2d_fcomplex(naz_burst_in, nrg);
|
||||
out = array2d_fcomplex(naz_burst_out, nrg);
|
||||
deramp = array2d_fcomplex(naz_burst_in, nrg);
|
||||
filter = array2d_fcomplex(nrg, nfft);
|
||||
data = array1d_fcomplex(nfft);
|
||||
|
||||
fprintf(infofp, "calculating filter...\n\n");
|
||||
|
||||
//create plans before initializing data, because FFTW_MEASURE overwrites the in/out arrays.
|
||||
p_forward = fftwf_plan_dft_1d(nfft, (fftwf_complex*)data, (fftwf_complex*)data, FFTW_FORWARD, FFTW_ESTIMATE);
|
||||
p_backward = fftwf_plan_dft_1d(nfft, (fftwf_complex*)data, (fftwf_complex*)data, FFTW_BACKWARD, FFTW_ESTIMATE);
|
||||
|
||||
//create filter, ZERO center frequency for all columns
|
||||
for(i = 0; i < nrg; i++){
|
||||
bfw = nb * pri * ka[i];
|
||||
//create filter: first sample corresponding to first fully convolution sample
|
||||
bandpass_filter(bfw/prf, 0.0/prf, nfilter, nfft, (nfilter-1)/2, beta, filter[i]);
|
||||
//forward fft
|
||||
//four1((float *)filter[i] - 1, nfft, -1);
|
||||
//data = filter[i];
|
||||
memcpy((void *) data, (const void *) filter[i], (size_t) nfft * sizeof(fcomplex));
|
||||
fftwf_execute(p_forward);
|
||||
//filter[i] = data;
|
||||
memcpy((void *) filter[i], (const void *) data, (size_t) nfft * sizeof(fcomplex));
|
||||
}
|
||||
|
||||
|
||||
//let's extract burst now, start from burst_index_tmp where we stop last time
|
||||
burst_index_first = burst_index_tmp - 1;
|
||||
tmpa = min_line; //save min_line caculated last time
|
||||
offset_from_first_burst0 = 0;
|
||||
for(burst_index = burst_index_tmp; burst_index < 100000; burst_index++){
|
||||
|
||||
//burst first line number
|
||||
tmpb = bsl + (burst_index - burst_index_tmp) * (nb + nbg);
|
||||
//burst center line number
|
||||
bcl = tmpb + (nb - 1.0) / 2.0;
|
||||
//minimum line of imaged area of the burst
|
||||
min_line = tmpa + (burst_index - burst_index_tmp) * (nb + nbg);
|
||||
//minimum line of input burst
|
||||
min_line_in = roundfi(min_line) - hnfilter;
|
||||
|
||||
//skip bursts that are not or partly in the image
|
||||
if(min_line_in < 0)
|
||||
continue;
|
||||
//stop at last burst that is fully in the image
|
||||
if(min_line_in + naz_burst_in - 1 > naz - 1)
|
||||
break;
|
||||
|
||||
|
||||
/*********************************************************
|
||||
(int)
|
||||
min_line_in
|
||||
------
|
||||
(float) | | (float)
|
||||
min_line | | min_line_out
|
||||
------ | | ------
|
||||
| | | | | |
|
||||
| | ====> | | ====> | |
|
||||
| | | | | |
|
||||
------ | | ------
|
||||
burst imaged | | output burst
|
||||
area ------
|
||||
burst read in
|
||||
*********************************************************/
|
||||
|
||||
//first burst
|
||||
if(burst_index_first == burst_index_tmp - 1){
|
||||
burst_index_first = burst_index;
|
||||
|
||||
min_line_out = roundfi(min_line) + min_line_offset;
|
||||
|
||||
min_line_out_first = min_line_out;
|
||||
offset_from_first_burst = 0;
|
||||
|
||||
fprintf(infofp, "line number of first line of original SLC is 0.\n");
|
||||
fprintf(infofp, "line number of first line of first output burst in original SLC (1.0/prf): %f\n", min_line_out);
|
||||
fprintf(infofp, "bsl of first output burst: %f\n\n", tmpb);
|
||||
}
|
||||
//adjust starting line of following bursts
|
||||
else{
|
||||
min_line_out = min_line + min_line_offset;
|
||||
offset_from_first_burst = roundfi((min_line_out - min_line_out_first) / az_ratio);
|
||||
tmp1 = offset_from_first_burst - (min_line_out - min_line_out_first) / az_ratio;
|
||||
min_line_out = min_line_out + tmp1 * az_ratio;
|
||||
}
|
||||
|
||||
fprintf(infofp, "extracting burst %3d\n", burst_index - burst_index_first + 1);
|
||||
fprintf(infofp, "offset from first burst: %5d, offset from last burst: %5d (az_ratio/prf)\n\n", offset_from_first_burst, offset_from_first_burst - offset_from_first_burst0);
|
||||
offset_from_first_burst0 = offset_from_first_burst;
|
||||
|
||||
//read data block
|
||||
//fseeko(infp, (size_t)min_line_in * (size_t)nrg * sizeof(fcomplex), SEEK_SET);
|
||||
//readdata((fcomplex *)in[0], (size_t)naz_burst_in * (size_t)nrg * sizeof(fcomplex), infp);
|
||||
|
||||
fseeko(infp, (size_t)imageoffset + (size_t)min_line_in * (size_t)lineoffset, SEEK_SET);
|
||||
for(i = 0; i < naz_burst_in; i++){
|
||||
if(i!=0)
|
||||
fseek(infp, lineoffset-(size_t)nrg*sizeof(fcomplex), SEEK_CUR);
|
||||
readdata((fcomplex *)in[i], (size_t)nrg * sizeof(fcomplex), infp);
|
||||
}
|
||||
|
||||
if(byteorder!=0){
|
||||
//printf("swapping bytes...\n");
|
||||
for(i = 0; i < naz_burst_in; i++)
|
||||
for(j = 0; j < nrg; j++){
|
||||
SWAP4(in[i][j].re);
|
||||
SWAP4(in[i][j].im);
|
||||
}
|
||||
}
|
||||
|
||||
//create deramping signal: make center of azimuth spectrum ZERO
|
||||
for(i = 0; i < nrg; i++){
|
||||
for(j = 0; j < naz_burst_in; j++){
|
||||
//distance from raw burst center in number of lines
|
||||
tmp1 = j + min_line_in - bcl;
|
||||
tmp2 = - PI * ka[i] * (tmp1 * pri) * (tmp1 * pri);
|
||||
deramp[j][i].re = cos(tmp2);
|
||||
deramp[j][i].im = sin(tmp2);
|
||||
}
|
||||
}
|
||||
|
||||
//do the filtering column by column
|
||||
for(i = 0; i < nrg; i++){
|
||||
//prepare data
|
||||
for(j = 0; j < nfft; j++){
|
||||
if(j < naz_burst_in){
|
||||
data[j].re = in[j][i].re / sc;
|
||||
data[j].im = in[j][i].im / sc;
|
||||
}
|
||||
else{
|
||||
data[j].re = 0.0;
|
||||
data[j].im = 0.0;
|
||||
}
|
||||
}
|
||||
|
||||
//deramp the data
|
||||
for(j = 0; j < naz_burst_in; j++){
|
||||
data[j] = cmul(data[j], deramp[j][i]);
|
||||
}
|
||||
|
||||
//forward fft
|
||||
//four1((float *)data - 1, nfft, -1);
|
||||
fftwf_execute(p_forward);
|
||||
|
||||
//multiplication in the frequency domain
|
||||
for(j = 0; j < nfft; j++)
|
||||
data[j] = cmul(data[j], filter[i][j]);
|
||||
|
||||
//backward fft
|
||||
//four1((float *)data - 1, nfft, 1);
|
||||
fftwf_execute(p_backward);
|
||||
|
||||
//put filtered data back
|
||||
for(j = 0; j < naz_burst_in; j++){
|
||||
in[j][i].re = data[j].re * sc / nfft;
|
||||
in[j][i].im = data[j].im * sc / nfft;
|
||||
}
|
||||
}
|
||||
|
||||
//zero output
|
||||
for(i = 0; i < naz_burst_out; i++){
|
||||
for(j = 0; j < nrg; j++){
|
||||
out[i][j].re = 0.0;
|
||||
out[i][j].im = 0.0;
|
||||
}
|
||||
}
|
||||
|
||||
//do the resampling column by column
|
||||
for(i = 0; i < nrg; i++){
|
||||
//resampling to output grid
|
||||
for(j = 0; j < naz_burst_out; j++){
|
||||
if((j < output_start[i]) || (j > output_end[i]))
|
||||
continue;
|
||||
|
||||
//location of output line in the data block read in
|
||||
tmp1 = min_line_out + j * az_ratio - min_line_in;
|
||||
|
||||
//interpolation
|
||||
for(k = -hn; k <= hn; k++){
|
||||
index = roundfi(tmp1) + k;
|
||||
tmp2 = index - tmp1;
|
||||
|
||||
if( (index < 0) || (index > naz_burst_in - 1) )
|
||||
continue;
|
||||
//verified: roundfi(tmp2*m) won't be out of [-hnm, hnm], if no computation error of floating point
|
||||
out[j][i].re += in[index][i].re * kernel[roundfi(tmp2*m)];
|
||||
out[j][i].im += in[index][i].im * kernel[roundfi(tmp2*m)];
|
||||
}
|
||||
|
||||
//reramp
|
||||
tmp1 = j * az_ratio + min_line_out - bcl;
|
||||
tmp2 = PI * ka[i] * (tmp1 * pri) * (tmp1 * pri);
|
||||
reramp.re = cos(tmp2);
|
||||
reramp.im = sin(tmp2);
|
||||
|
||||
out[j][i] = cmul(out[j][i], reramp);
|
||||
|
||||
}
|
||||
}
|
||||
|
||||
//write to file
|
||||
strcpy(output_filename, outputf);
|
||||
sprintf(burst_num, "_%02d.slc", burst_index - burst_index_first + 1);
|
||||
strcat(output_filename, burst_num);
|
||||
|
||||
outfp = openfile(output_filename, "wb");
|
||||
writedata((fcomplex *)out[0], (size_t)naz_burst_out * (size_t)nrg * sizeof(fcomplex), outfp);
|
||||
fclose(outfp);
|
||||
}
|
||||
|
||||
fprintf(infofp, "total number of bursts extracted: %3d\n\n", burst_index - burst_index_first);
|
||||
|
||||
fftwf_destroy_plan(p_forward);
|
||||
fftwf_destroy_plan(p_backward);
|
||||
|
||||
free_array1d_float(ka);
|
||||
free_array1d_float(dop);
|
||||
free_array1d_float(nfa);
|
||||
|
||||
free_array1d_float(start_line);
|
||||
free_array1d_float(end_line);
|
||||
free_array1d_int(output_start);
|
||||
free_array1d_int(output_end);
|
||||
|
||||
free_vector_float(sincc, -hnm, hnm);
|
||||
free_vector_float(kaiserc, -hnm, hnm);
|
||||
free_vector_float(kernel, -hnm, hnm);
|
||||
|
||||
free_array2d_fcomplex(in);
|
||||
free_array2d_fcomplex(out);
|
||||
free_array2d_fcomplex(deramp);
|
||||
free_array2d_fcomplex(filter);
|
||||
free_array1d_fcomplex(data);
|
||||
|
||||
//close files
|
||||
fclose(infp);
|
||||
fclose(infofp);
|
||||
}
|
||||
|
|
@ -0,0 +1,327 @@
|
|||
//////////////////////////////////////
|
||||
// Cunren Liang, NASA JPL/Caltech
|
||||
// Copyright 2017
|
||||
//////////////////////////////////////
|
||||
|
||||
|
||||
//a program for taking looks for single band file
|
||||
|
||||
#include "resamp.h"
|
||||
|
||||
int look(char *inputfile, char *outputfile, long nrg, int nrlks, int nalks, int ft, int sum, int avg){
|
||||
|
||||
FILE *infp;
|
||||
FILE *outfp;
|
||||
|
||||
signed char *in0;
|
||||
int *in1;
|
||||
float *in2;
|
||||
double *in3;
|
||||
fcomplex *in4;
|
||||
dcomplex *in5;
|
||||
|
||||
signed char *out0;
|
||||
int *out1;
|
||||
float *out2;
|
||||
double *out3;
|
||||
fcomplex *out4;
|
||||
dcomplex *out5;
|
||||
|
||||
int sum_nz;
|
||||
double sum1, sum2;
|
||||
|
||||
long index;
|
||||
|
||||
long naz;
|
||||
long nrg1, naz1;
|
||||
//int nrlks, nalks;
|
||||
|
||||
//int ft, sum, avg;
|
||||
|
||||
int i, j;
|
||||
int ii, jj;
|
||||
|
||||
|
||||
// if(argc < 4){
|
||||
// fprintf(stderr, "\nUsage: %s infile outfile nrg [nrlks] [nalks] [ft] [sum] [avg]\n", argv[0]);
|
||||
// fprintf(stderr, " infile: input file\n");
|
||||
// fprintf(stderr, " outfile: output file\n");
|
||||
// fprintf(stderr, " nrg: file width\n");
|
||||
// fprintf(stderr, " nrlks: number of looks in range (default: 4)\n");
|
||||
// fprintf(stderr, " nalks: number of looks in azimuth (default: 4)\n");
|
||||
// fprintf(stderr, " ft: file type (default: 0)\n");
|
||||
// fprintf(stderr, " 0: signed char\n");
|
||||
// fprintf(stderr, " 1: int\n");
|
||||
// fprintf(stderr, " 2: float\n");
|
||||
// fprintf(stderr, " 3: double\n");
|
||||
// fprintf(stderr, " 4: complex (real and imagery: float)\n");
|
||||
// fprintf(stderr, " 5: complex (real and imagery: double)\n");
|
||||
// fprintf(stderr, " sum: sum method (default: 0)\n");
|
||||
// fprintf(stderr, " 0: simple sum\n");
|
||||
// fprintf(stderr, " 1: power sum (if complex, do this for each channel seperately)\n");
|
||||
// fprintf(stderr, " avg: take average (default: 0)\n");
|
||||
// fprintf(stderr, " 0: no\n");
|
||||
// fprintf(stderr, " 1: yes\n\n");
|
||||
|
||||
// exit(1);
|
||||
// }
|
||||
|
||||
infp = openfile(inputfile, "rb");
|
||||
outfp = openfile(outputfile, "wb");
|
||||
|
||||
//nrg = atoi(argv[3]);
|
||||
|
||||
//if(argc > 4)
|
||||
// nrlks = atoi(argv[4]);
|
||||
//else
|
||||
// nrlks = 4;
|
||||
|
||||
//if(argc > 5)
|
||||
// nalks = atoi(argv[5]);
|
||||
//else
|
||||
// nalks = 4;
|
||||
|
||||
//if(argc > 6)
|
||||
// ft = atoi(argv[6]);
|
||||
//else
|
||||
// ft = 0;
|
||||
|
||||
//if(argc > 7)
|
||||
// sum = atoi(argv[7]);
|
||||
//else
|
||||
// sum = 0;
|
||||
|
||||
//if(argc > 8)
|
||||
// avg = atoi(argv[8]);
|
||||
//else
|
||||
// avg = 0;
|
||||
|
||||
nrg1 = nrg / nrlks;
|
||||
|
||||
if(ft == 0){
|
||||
in0 = array1d_char(nrg*nalks);
|
||||
out0 = array1d_char(nrg1);
|
||||
naz = file_length(infp, nrg, sizeof(signed char));
|
||||
}
|
||||
else if(ft == 1){
|
||||
in1 = array1d_int(nrg*nalks);
|
||||
out1 = array1d_int(nrg1);
|
||||
naz = file_length(infp, nrg, sizeof(int));
|
||||
}
|
||||
else if(ft == 2){
|
||||
in2 = array1d_float(nrg*nalks);
|
||||
out2 = array1d_float(nrg1);
|
||||
naz = file_length(infp, nrg, sizeof(float));
|
||||
}
|
||||
else if(ft == 3){
|
||||
in3 = array1d_double(nrg*nalks);
|
||||
out3 = array1d_double(nrg1);
|
||||
naz = file_length(infp, nrg, sizeof(double));
|
||||
}
|
||||
else if(ft == 4){
|
||||
in4 = array1d_fcomplex(nrg*nalks);
|
||||
out4 = array1d_fcomplex(nrg1);
|
||||
naz = file_length(infp, nrg, sizeof(fcomplex));
|
||||
}
|
||||
else if(ft == 5){
|
||||
in5 = array1d_dcomplex(nrg*nalks);
|
||||
out5 = array1d_dcomplex(nrg1);
|
||||
naz = file_length(infp, nrg, sizeof(dcomplex));
|
||||
}
|
||||
else{
|
||||
fprintf(stderr, "Error: file type not supported.\n\n");
|
||||
exit(1);
|
||||
}
|
||||
|
||||
naz1 = naz / nalks;
|
||||
|
||||
for(i = 0; i < naz1; i++){
|
||||
|
||||
if((i + 1) % 100 == 0)
|
||||
fprintf(stderr,"processing line: %6d of %6d\r", i+1, naz1);
|
||||
|
||||
//read data
|
||||
if(ft == 0){
|
||||
readdata((signed char *)in0, (size_t)nalks * (size_t)nrg * sizeof(signed char), infp);
|
||||
}
|
||||
else if(ft == 1){
|
||||
readdata((int *)in1, (size_t)nalks * (size_t)nrg * sizeof(int), infp);
|
||||
}
|
||||
else if(ft == 2){
|
||||
readdata((float *)in2, (size_t)nalks * (size_t)nrg * sizeof(float), infp);
|
||||
}
|
||||
else if(ft == 3){
|
||||
readdata((double *)in3, (size_t)nalks * (size_t)nrg * sizeof(double), infp);
|
||||
}
|
||||
else if(ft == 4){
|
||||
readdata((fcomplex *)in4, (size_t)nalks * (size_t)nrg * sizeof(fcomplex), infp);
|
||||
}
|
||||
else if(ft == 5){
|
||||
readdata((dcomplex *)in5, (size_t)nalks * (size_t)nrg * sizeof(dcomplex), infp);
|
||||
}
|
||||
|
||||
//process data
|
||||
for(j = 0; j < nrg1; j++){
|
||||
//get sum
|
||||
sum_nz = 0;
|
||||
sum1 = 0.0;
|
||||
sum2 = 0.0;
|
||||
for(ii = 0; ii < nalks; ii++){
|
||||
for(jj = 0; jj < nrlks; jj++){
|
||||
index = ii * nrg + j * nrlks + jj;
|
||||
if(ft == 0){
|
||||
if(in0[index] != 0){
|
||||
if(sum == 0)
|
||||
sum1 += in0[index];
|
||||
else
|
||||
sum1 += in0[index] * in0[index];
|
||||
sum_nz += 1;
|
||||
}
|
||||
}
|
||||
else if(ft == 1){
|
||||
if(in1[index] != 0){
|
||||
if(sum == 0)
|
||||
sum1 += in1[index];
|
||||
else
|
||||
sum1 += in1[index] * in1[index];
|
||||
sum_nz += 1;
|
||||
}
|
||||
}
|
||||
else if(ft == 2){
|
||||
if(in2[index] != 0){
|
||||
if(sum == 0)
|
||||
sum1 += in2[index];
|
||||
else
|
||||
sum1 += in2[index] * in2[index];
|
||||
sum_nz += 1;
|
||||
}
|
||||
}
|
||||
else if(ft == 3){
|
||||
if(in3[index] != 0){
|
||||
if(sum == 0)
|
||||
sum1 += in3[index];
|
||||
else
|
||||
sum1 += in3[index] * in3[index];
|
||||
sum_nz += 1;
|
||||
}
|
||||
}
|
||||
else if(ft == 4){
|
||||
if(in4[index].re != 0 || in4[index].im != 0){
|
||||
if(sum ==0){
|
||||
sum1 += in4[index].re;
|
||||
sum2 += in4[index].im;
|
||||
}
|
||||
else{
|
||||
sum1 += in4[index].re * in4[index].re;
|
||||
sum2 += in4[index].im * in4[index].im;
|
||||
}
|
||||
sum_nz += 1;
|
||||
}
|
||||
}
|
||||
else if(ft == 5){
|
||||
if(in5[index].re != 0 || in5[index].im != 0){
|
||||
if(sum == 0){
|
||||
sum1 += in5[index].re;
|
||||
sum2 += in5[index].im;
|
||||
}
|
||||
else{
|
||||
sum1 += in5[index].re * in5[index].re;
|
||||
sum2 += in5[index].im * in5[index].im;
|
||||
}
|
||||
sum_nz += 1;
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
//preprocessing
|
||||
if(avg == 1){
|
||||
if(sum_nz != 0){
|
||||
sum1 /= sum_nz;
|
||||
if(ft == 4 || ft == 5)
|
||||
sum2 /= sum_nz;
|
||||
}
|
||||
}
|
||||
if(sum == 1){
|
||||
if(sum_nz != 0){
|
||||
sum1 = sqrt(sum1);
|
||||
if(ft == 4 || ft ==5)
|
||||
sum2 = sqrt(sum2);
|
||||
}
|
||||
}
|
||||
|
||||
//get data
|
||||
if(ft == 0){
|
||||
out0[j] = (signed char)(roundfi(sum1));
|
||||
}
|
||||
else if(ft == 1){
|
||||
out1[j] = (int)(roundfi(sum1));
|
||||
}
|
||||
else if(ft == 2){
|
||||
out2[j] = sum1;
|
||||
}
|
||||
else if(ft == 3){
|
||||
out3[j] = sum1;
|
||||
}
|
||||
else if(ft == 4){
|
||||
out4[j].re = sum1;
|
||||
out4[j].im = sum2;
|
||||
}
|
||||
else if(ft == 5){
|
||||
out5[j].re = sum1;
|
||||
out5[j].im = sum2;
|
||||
}
|
||||
}
|
||||
|
||||
//write data
|
||||
if(ft == 0){
|
||||
writedata((signed char *)out0, nrg1 * sizeof(signed char), outfp);
|
||||
}
|
||||
else if(ft == 1){
|
||||
writedata((int *)out1, nrg1 * sizeof(int), outfp);
|
||||
}
|
||||
else if(ft == 2){
|
||||
writedata((float *)out2, nrg1 * sizeof(float), outfp);
|
||||
}
|
||||
else if(ft == 3){
|
||||
writedata((double *)out3, nrg1 * sizeof(double), outfp);
|
||||
}
|
||||
else if(ft == 4){
|
||||
writedata((fcomplex *)out4, nrg1 * sizeof(fcomplex), outfp);
|
||||
}
|
||||
else if(ft == 5){
|
||||
writedata((dcomplex *)out5, nrg1 * sizeof(dcomplex), outfp);
|
||||
}
|
||||
}
|
||||
fprintf(stderr,"processing line: %6d of %6d\n", naz1, naz1);
|
||||
|
||||
//clear up
|
||||
if(ft == 0){
|
||||
free_array1d_char(in0);
|
||||
free_array1d_char(out0);
|
||||
}
|
||||
else if(ft == 1){
|
||||
free_array1d_int(in1);
|
||||
free_array1d_int(out1);
|
||||
}
|
||||
else if(ft == 2){
|
||||
free_array1d_float(in2);
|
||||
free_array1d_float(out2);
|
||||
}
|
||||
else if(ft == 3){
|
||||
free_array1d_double(in3);
|
||||
free_array1d_double(out3);
|
||||
}
|
||||
else if(ft == 4){
|
||||
free_array1d_fcomplex(in4);
|
||||
free_array1d_fcomplex(out4);
|
||||
}
|
||||
else if(ft == 5){
|
||||
free_array1d_dcomplex(in5);
|
||||
free_array1d_dcomplex(out5);
|
||||
}
|
||||
fclose(infp);
|
||||
fclose(outfp);
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
|
@ -6,14 +6,17 @@
|
|||
|
||||
#include "resamp.h"
|
||||
#include <fftw3.h>
|
||||
#include <omp.h>
|
||||
|
||||
#define SWAP4(a) (*(unsigned int *)&(a) = (((*(unsigned int *)&(a) & 0x000000ff) << 24) | ((*(unsigned int *)&(a) & 0x0000ff00) << 8) | ((*(unsigned int *)&(a) >> 8) & 0x0000ff00) | ((*(unsigned int *)&(a) >> 24) & 0x000000ff)))
|
||||
|
||||
int mbf(char *inputfile, char *outputfile, int nrg, float prf, float prf_frac, float nb, float nbg, float nboff, float bsl, float *kacoeff, float *dopcoeff1, float *dopcoeff2){
|
||||
int mbf(char *inputfile, char *outputfile, int nrg, int naz, float prf, float prf_frac, float nb, float nbg, float nboff, float bsl, float *kacoeff, float *dopcoeff1, float *dopcoeff2, int byteorder, long imageoffset, long lineoffset){
|
||||
/*
|
||||
|
||||
inputfile: input file
|
||||
outputfile: output file
|
||||
nrg: file width
|
||||
naz: file length
|
||||
prf: PRF
|
||||
prf_frac: fraction of PRF processed
|
||||
(represents azimuth bandwidth)
|
||||
|
|
@ -28,8 +31,8 @@ int mbf(char *inputfile, char *outputfile, int nrg, float prf, float prf_frac, f
|
|||
(float, the line number of the first line of the full-aperture SLC is zero)
|
||||
(no need to be first burst, any one is OK)
|
||||
|
||||
kacoeff[0-2]: FM rate coefficients
|
||||
(three coefficients of a quadratic polynomial with regard to)
|
||||
kacoeff[0-3]: FM rate coefficients
|
||||
(four coefficients of a third order polynomial with regard to)
|
||||
(range sample number. range sample number starts with zero)
|
||||
|
||||
dopcoeff1[0-3]: Doppler centroid frequency coefficients of this image
|
||||
|
|
@ -40,6 +43,9 @@ int mbf(char *inputfile, char *outputfile, int nrg, float prf, float prf_frac, f
|
|||
(four coefficients of a third order polynomial with regard to)
|
||||
(range sample number. range sample number starts with zero)
|
||||
|
||||
byteorder: (0) LSB, little endian; (1) MSB, big endian of intput file
|
||||
imageoffset: offset from start of the image of input file
|
||||
lineoffset: length of each line of input file
|
||||
*/
|
||||
|
||||
FILE *infp;
|
||||
|
|
@ -54,7 +60,7 @@ int mbf(char *inputfile, char *outputfile, int nrg, float prf, float prf_frac, f
|
|||
fcomplex *data; //data to be filtered.
|
||||
|
||||
//int nrg; //file width
|
||||
int naz; //file length
|
||||
//int naz; //file length
|
||||
//float prf; //assume prf are the same
|
||||
//float prf_frac; // azimuth processed bandwidth = prf_frac * prf
|
||||
//float nb; //burst length in terms of pri. number of lines
|
||||
|
|
@ -168,17 +174,36 @@ int mbf(char *inputfile, char *outputfile, int nrg, float prf, float prf_frac, f
|
|||
printf("nboff: %f\n", nboff);
|
||||
printf("bsl: %f\n", bsl);
|
||||
|
||||
printf("kacoeff: %f, %f, %f\n", kacoeff[0], kacoeff[1], kacoeff[2]);
|
||||
printf("kacoeff: %f, %f, %f, %f\n", kacoeff[0], kacoeff[1], kacoeff[2], kacoeff[3]);
|
||||
printf("dopcoeff1: %f, %f, %f, %f\n", dopcoeff1[0], dopcoeff1[1], dopcoeff1[2], dopcoeff1[3]);
|
||||
printf("dopcoeff2: %f, %f, %f, %f\n", dopcoeff2[0], dopcoeff2[1], dopcoeff2[2], dopcoeff2[3]);
|
||||
|
||||
if(byteorder == 0){
|
||||
printf("inputfile byte order: little endian\n");
|
||||
}
|
||||
else{
|
||||
printf("inputfile byte order: big endian\n");
|
||||
}
|
||||
printf("input file image offset [byte]: %ld\n", imageoffset);
|
||||
printf("input file line offset [byte]: %ld\n", lineoffset);
|
||||
if(imageoffset < 0){
|
||||
fprintf(stderr, "image offset must be >= 0\n");
|
||||
exit(1);
|
||||
}
|
||||
if(lineoffset < 0){
|
||||
fprintf(stderr, "lineoffset offset must be >= 0\n");
|
||||
exit(1);
|
||||
}
|
||||
|
||||
if(nfilter % 2 != 1){
|
||||
fprintf(stderr, "filter length must be odd!\n");
|
||||
exit(1);
|
||||
}
|
||||
|
||||
naz = file_length(infp, nrg, sizeof(fcomplex));
|
||||
//naz = file_length(infp, nrg, sizeof(fcomplex));
|
||||
//fseeko(infp,0L,SEEK_END);
|
||||
//naz = (ftello(infp) - imageoffset) / (lineoffset + nrg*sizeof(fcomplex));
|
||||
//rewind(infp);
|
||||
printf("file width: %d, file length: %d\n\n", nrg, naz);
|
||||
|
||||
|
||||
|
|
@ -216,14 +241,14 @@ int mbf(char *inputfile, char *outputfile, int nrg, float prf, float prf_frac, f
|
|||
for(i = 0; i < nrg; i++){
|
||||
|
||||
//azimuth FM rate. we follow the convention ka > 0
|
||||
ka[i] = kacoeff[2] * i * i + kacoeff[1] * i + kacoeff[0];
|
||||
ka[i] = kacoeff[3] * i * i * i + kacoeff[2] * i * i + kacoeff[1] * i + kacoeff[0];
|
||||
ka[i] = -ka[i];
|
||||
|
||||
//doppler centroid frequency
|
||||
dop1[i] = dopcoeff1[0] + dopcoeff1[1] * i + dopcoeff1[2] * i * i + dopcoeff1[3] * i * i * i;
|
||||
dop1[i] *= prf;
|
||||
//dop1[i] *= prf;
|
||||
dop2[i] = dopcoeff2[0] + dopcoeff2[1] * i + dopcoeff2[2] * i * i + dopcoeff2[3] * i * i * i;
|
||||
dop2[i] *= prf;
|
||||
//dop2[i] *= prf;
|
||||
|
||||
//full aperture length
|
||||
nfa[i] = prf * prf_frac / ka[i] / pri;
|
||||
|
|
@ -299,9 +324,47 @@ int mbf(char *inputfile, char *outputfile, int nrg, float prf, float prf_frac, f
|
|||
}
|
||||
}
|
||||
|
||||
|
||||
//read in data
|
||||
readdata((fcomplex *)in[0], (size_t)naz * (size_t)nrg * sizeof(fcomplex), infp);
|
||||
///////////////////////////////////////////////////////////////////////////////////////
|
||||
//This section is for reading data
|
||||
printf("reading data...\n");
|
||||
|
||||
//skip image header
|
||||
fseek(infp, imageoffset, SEEK_SET);
|
||||
|
||||
for(i = 0; i < naz; i++){
|
||||
if(i!=0)
|
||||
fseek(infp, lineoffset-(size_t)nrg*sizeof(fcomplex), SEEK_CUR);
|
||||
readdata((fcomplex *)in[i], (size_t)nrg * sizeof(fcomplex), infp);
|
||||
}
|
||||
|
||||
//read image data
|
||||
//if(lineoffset == 0){
|
||||
// readdata((fcomplex *)in[0], (size_t)naz * (size_t)nrg * sizeof(fcomplex), infp);
|
||||
//}
|
||||
//else{
|
||||
// for(i = 0; i < naz; i++){
|
||||
// fseek(infp, lineoffset, SEEK_CUR);
|
||||
// readdata((fcomplex *)in[i], (size_t)nrg * sizeof(fcomplex), infp);
|
||||
// }
|
||||
//}
|
||||
|
||||
//swap bytes
|
||||
if(byteorder!=0){
|
||||
printf("swapping bytes...\n");
|
||||
for(i = 0; i < naz; i++)
|
||||
for(j = 0; j < nrg; j++){
|
||||
SWAP4(in[i][j].re);
|
||||
SWAP4(in[i][j].im);
|
||||
}
|
||||
}
|
||||
|
||||
int debug=0;
|
||||
if(debug){
|
||||
printf("%f, %f\n", in[0][0].re, in[0][0].im);
|
||||
printf("%f, %f\n", in[100][100].re, in[100][100].im);
|
||||
printf("%f, %f\n", in[naz-1][nrg-1].re, in[naz-1][nrg-1].im);
|
||||
}
|
||||
///////////////////////////////////////////////////////////////////////////////////////
|
||||
|
||||
//initialize output data
|
||||
//for(j = 0; j < naz; j++){
|
||||
|
|
@ -311,7 +374,7 @@ int mbf(char *inputfile, char *outputfile, int nrg, float prf, float prf_frac, f
|
|||
// }
|
||||
//}
|
||||
|
||||
|
||||
printf("filtering image...\n");
|
||||
for(i = 0; i < nrg; i++){
|
||||
|
||||
if((i + 1) % 100 == 0 || (i+1) == nrg)
|
||||
|
|
@ -566,6 +629,7 @@ int mbf(char *inputfile, char *outputfile, int nrg, float prf, float prf_frac, f
|
|||
|
||||
}//i: each column
|
||||
|
||||
printf("writing filtering result...\n");
|
||||
writedata((fcomplex *)in[0], (size_t)naz * (size_t)nrg * sizeof(fcomplex), outfp);
|
||||
|
||||
//free arrays
|
||||
|
|
@ -590,9 +654,3 @@ int mbf(char *inputfile, char *outputfile, int nrg, float prf, float prf_frac, f
|
|||
|
||||
return 0;
|
||||
}//end main()
|
||||
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////////////////////////////
|
||||
|
||||
|
||||
|
||||
|
|
|
|||
|
|
@ -0,0 +1,386 @@
|
|||
//////////////////////////////////////
|
||||
// Cunren Liang, NASA JPL/Caltech
|
||||
// Copyright 2017
|
||||
//////////////////////////////////////
|
||||
|
||||
|
||||
// program for mosaicking multiple consecutive subswaths
|
||||
// Cunren Liang, 03-JUN-2015
|
||||
// JPL/Caltech
|
||||
|
||||
//////////////////////////////////////////////////////////////////
|
||||
//update history
|
||||
//12-APR-2016, CL. output data of both adjacent subswaths as BIL
|
||||
// file, instead of output the difference.
|
||||
//////////////////////////////////////////////////////////////////
|
||||
|
||||
|
||||
#include "resamp.h"
|
||||
|
||||
//int main(int argc, char *argv[]){
|
||||
int mosaicsubswath(char *outputfile, int nrgout, int nazout, int delta, int diffflag, int n, char **inputfile, int *nrgin, int *nrgoff, int *nazoff, float *phc, int *oflag){
|
||||
|
||||
FILE **infp;
|
||||
FILE *outfp;
|
||||
|
||||
fcomplex **in;
|
||||
fcomplex *out, out1, out2;
|
||||
//fcomplex *leftoverlap;
|
||||
//fcomplex *rightoverlap;
|
||||
fcomplex tmp;
|
||||
int cnt;
|
||||
|
||||
//int n;
|
||||
//int *nrgin;
|
||||
int *nazin;
|
||||
//int *nrgoff;
|
||||
//int *nazoff;
|
||||
//int *oflag;
|
||||
//int nrgout;
|
||||
//int nazout;
|
||||
int nrginmax;
|
||||
|
||||
int los, loe, low; //start, end and width of left overlap area
|
||||
int ros, roe, row; //start, end and width of right overlap area
|
||||
int cnw; //width of center area
|
||||
|
||||
int paroff;
|
||||
int parcyc;
|
||||
|
||||
char diffname[256][256];
|
||||
FILE **difffp;
|
||||
fcomplex **diff;
|
||||
fcomplex **diff2;
|
||||
//int diffflag;
|
||||
//diffflag = 0;
|
||||
|
||||
int ns;
|
||||
float r;
|
||||
|
||||
int i, j, k, l;
|
||||
|
||||
//int delta; //edge to be removed of the overlap area (number of samples)
|
||||
//delta = 20;
|
||||
|
||||
|
||||
// if(argc < 5){
|
||||
// fprintf(stderr, "\nUsage: %s outputfile nrgout nazout delta diffflag n [inputfile0] [nrgin0] [nrgoff0] [nazoff0] [oflag0] (repeat...)\n\n", argv[0]);
|
||||
// fprintf(stderr, " for each frame\n");
|
||||
// fprintf(stderr, " range offset is relative to the first sample of last subswath\n");
|
||||
// fprintf(stderr, " azimuth offset is relative to the uppermost line\n\n");
|
||||
// exit(1);
|
||||
// }
|
||||
|
||||
|
||||
//read mandatory parameters
|
||||
outfp = openfile(outputfile, "wb");
|
||||
//nrgout = atoi(argv[2]);
|
||||
//nazout = atoi(argv[3]);
|
||||
//delta = atoi(argv[4]);
|
||||
//diffflag = atoi(argv[5]);
|
||||
//n = atoi(argv[6]);
|
||||
|
||||
|
||||
//allocate memory
|
||||
infp = array1d_FILE(n);
|
||||
//nrgin = array1d_int(n);
|
||||
nazin = array1d_int(n);
|
||||
//nrgoff = array1d_int(n); //nrgoff must be <= 0
|
||||
//nazoff = array1d_int(n); //nazoff must be <= 0
|
||||
//oflag = array1d_int(n);
|
||||
|
||||
difffp = array1d_FILE(n - 1);
|
||||
|
||||
//read optional parameters
|
||||
paroff = 6;
|
||||
parcyc = 5;
|
||||
for(i = 0; i < n; i++){
|
||||
infp[i] = openfile(inputfile[i], "rb");
|
||||
//nrgin[i] = atoi(argv[paroff + parcyc*i + 2]);
|
||||
//nrgoff[i] = atoi(argv[paroff + parcyc*i + 3]);
|
||||
//nazoff[i] = atoi(argv[paroff + parcyc*i + 4]);
|
||||
//oflag[i] = atoi(argv[paroff + parcyc*i + 5]);
|
||||
nazin[i] = file_length(infp[i], nrgin[i], sizeof(fcomplex));
|
||||
if(nrgoff[i] > 0){
|
||||
fprintf(stderr,"Error: positive range offset: %d\n\n", nrgoff[i]);
|
||||
exit(1);
|
||||
}
|
||||
if(nazoff[i] > 0){
|
||||
fprintf(stderr,"Error: positive azimuth offset: %d\n\n", nazoff[i]);
|
||||
exit(1);
|
||||
}
|
||||
if(nazout < nazin[i] - nazoff[i]){
|
||||
fprintf(stderr,"Error: ouput length < nazin[%d] - nazoff[%d], %d, %d\n\n", i, i, nazout, nazin[i] - nazoff[i]);
|
||||
exit(1);
|
||||
}
|
||||
}
|
||||
|
||||
//find max width
|
||||
nrginmax = nrgin[0];
|
||||
for(i = 0; i < n; i++)
|
||||
if(nrgin[i] > nrginmax)
|
||||
nrginmax = nrgin[i];
|
||||
|
||||
in = array2d_fcomplex(n, nrginmax);
|
||||
out = array1d_fcomplex(nrgout);
|
||||
//out1 = array1d_fcomplex(nrginmax);
|
||||
//out2 = array1d_fcomplex(nrginmax);
|
||||
diff = array2d_fcomplex(n-1, nrginmax);
|
||||
diff2 = array2d_fcomplex(n-1, nrginmax);
|
||||
|
||||
if(diffflag == 0)
|
||||
for(i = 0; i < n - 1; i++){
|
||||
sprintf(diffname[i], "%d-%d.int", i, i+1);
|
||||
difffp[i] = openfile(diffname[i], "wb");
|
||||
}
|
||||
|
||||
|
||||
for(i = 0; i < nazout; i++){
|
||||
|
||||
if((i + 1) % 1000 == 0)
|
||||
fprintf(stderr,"processing line: %6d of %6d\r", i + 1, nazout);
|
||||
if(i + 1 == nazout)
|
||||
fprintf(stderr,"processing line: %6d of %6d\n\n", i + 1, nazout);
|
||||
|
||||
//prepare for writing data
|
||||
for(j = 0; j < nrgout; j++){
|
||||
out[j].re = 0.0;
|
||||
out[j].im = 0.0;
|
||||
}
|
||||
|
||||
//prepare for reading data
|
||||
for(j = 0; j < n; j++){
|
||||
for(k = 0; k < nrginmax; k++){
|
||||
in[j][k].re = 0.0;
|
||||
in[j][k].im = 0.0;
|
||||
}
|
||||
}
|
||||
|
||||
for(j = 0; j < n; j++){
|
||||
if(i + nazoff[j] >= 0 && i + nazoff[j] <= nazin[j] - 1)
|
||||
readdata((fcomplex *)in[j], nrgin[j] * sizeof(fcomplex), infp[j]);
|
||||
|
||||
if(phc[j]!=0.0){
|
||||
tmp.re = cos(phc[j]);
|
||||
tmp.im = sin(phc[j]);
|
||||
for(k = 0; k < nrgin[j]; k++)
|
||||
in[j][k] = cmul(in[j][k], tmp);
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
cnt = 0;
|
||||
for(j = 0; j < n; j++){
|
||||
|
||||
//we follow the following convention: line and column number start with 0.
|
||||
//left overlap area of subswath j
|
||||
if(j != 0){
|
||||
los = - nrgoff[j];
|
||||
loe = nrgin[j-1] - 1;
|
||||
low = loe - los + 1;
|
||||
if(low < delta * 2){
|
||||
fprintf(stderr,"Error: not enough overlap area between subswath: %d and %d\n\n", j-1, j);
|
||||
exit(1);
|
||||
}
|
||||
}
|
||||
else{
|
||||
los = 0;
|
||||
loe = 0;
|
||||
low = 0;
|
||||
}
|
||||
|
||||
//right overlap area of subswath j
|
||||
if(j != n - 1){
|
||||
ros = - nrgoff[j+1];
|
||||
roe = nrgin[j] - 1;
|
||||
row = roe - ros + 1;
|
||||
if(row < delta * 2){
|
||||
fprintf(stderr,"Error: not enough overlap area between subswath: %d and %d\n\n", j, j+1);
|
||||
exit(1);
|
||||
}
|
||||
}
|
||||
else{
|
||||
ros = 0;
|
||||
roe = 0;
|
||||
row = 0;
|
||||
}
|
||||
|
||||
//center non-overlap area of subswath j
|
||||
//should add a check here?
|
||||
cnw = nrgin[j] - low - row;
|
||||
|
||||
//deal with center non-overlap area.
|
||||
//this only excludes the right overlap area for the first subswath
|
||||
//this only excludes the left overlap area for the last subswath
|
||||
for(k = 0; k < cnw; k++){
|
||||
out[cnt + k].re = in[j][low + k].re;
|
||||
out[cnt + k].im = in[j][low + k].im;
|
||||
}
|
||||
cnt += cnw;
|
||||
|
||||
//deal with right overlap area of subswath j, which is also the left overlap area
|
||||
//of subswath j + 1 (next subswath)
|
||||
|
||||
//for last subswath, just skip
|
||||
if(j == n - 1){
|
||||
break;
|
||||
}
|
||||
|
||||
|
||||
for(k = 0; k < nrginmax; k++){
|
||||
diff[j][k].re = 0.0;
|
||||
diff[j][k].im = 0.0;
|
||||
diff2[j][k].re = 0.0;
|
||||
diff2[j][k].im = 0.0;
|
||||
}
|
||||
|
||||
for(k = 0; k < row; k++){
|
||||
|
||||
|
||||
out1.re = in[j][low + cnw + k].re;
|
||||
out1.im = in[j][low + cnw + k].im;
|
||||
out2.re = in[j+1][k].re;
|
||||
out2.im = in[j+1][k].im;
|
||||
|
||||
//left edge of overlap area
|
||||
//use current subswath: subswath j
|
||||
if(k < delta){
|
||||
out[cnt + k].re = out1.re;
|
||||
out[cnt + k].im = out1.im;
|
||||
}
|
||||
else if(k >= delta && k < row - delta){
|
||||
|
||||
//output difference of overlap area
|
||||
//diffflag 0: subswath j phase - subswath j+1 phase
|
||||
if(diffflag == 0){
|
||||
if(out1.re != 0.0 && out1.im != 0.0 && out2.re != 0.0 && out2.im != 0.0){
|
||||
//diff[j][k - delta] = cmul(out1, cconj(out2));
|
||||
diff[j][k - delta] = out1;
|
||||
diff2[j][k - delta] = out2;
|
||||
}
|
||||
}
|
||||
//diffflag 1: subswath j - subswath j+1
|
||||
//else if(diffflag == 1){
|
||||
// if(out1.re != 0.0 && out1.im != 0.0 && out2.re != 0.0 && out2.im != 0.0){
|
||||
// diff[j][k - delta].re = out1.re - out2.re;
|
||||
// diff[j][k - delta].im = out1.im - out2.im;
|
||||
// }
|
||||
//}
|
||||
else{
|
||||
;
|
||||
}
|
||||
|
||||
//mosaic overlap area
|
||||
//case 0: mosaic at the center of overlap area
|
||||
if(oflag[j] == 0){
|
||||
if(k < row / 2){
|
||||
//avoid holes, Cunren Liang, Dec. 18, 2015.
|
||||
if(out1.re != 0.0 && out1.im != 0.0){
|
||||
out[cnt + k].re = out1.re;
|
||||
out[cnt + k].im = out1.im;
|
||||
}
|
||||
else{
|
||||
out[cnt + k].re = out2.re;
|
||||
out[cnt + k].im = out2.im;
|
||||
}
|
||||
}
|
||||
else{
|
||||
//avoid holes, Cunren Liang, Dec. 18, 2015.
|
||||
if(out2.re != 0.0 && out2.im != 0.0){
|
||||
out[cnt + k].re = out2.re;
|
||||
out[cnt + k].im = out2.im;
|
||||
}
|
||||
else{
|
||||
out[cnt + k].re = out1.re;
|
||||
out[cnt + k].im = out1.im;
|
||||
}
|
||||
}
|
||||
}
|
||||
//case 1: mosaic at the right egde of overlap area
|
||||
else if(oflag[j] == 1){
|
||||
out[cnt + k].re = out1.re;
|
||||
out[cnt + k].im = out1.im;
|
||||
}
|
||||
//case 2: mosaic at the left edge of overlap area
|
||||
else if(oflag[j] == 2){
|
||||
out[cnt + k].re = out2.re;
|
||||
out[cnt + k].im = out2.im;
|
||||
}
|
||||
//case 3: add overlap area
|
||||
else if(oflag[j] == 3){
|
||||
out[cnt + k].re = out1.re + out2.re;
|
||||
out[cnt + k].im = out1.im + out2.im;
|
||||
|
||||
if(out1.re != 0.0 && out1.im != 0.0 && out2.re != 0.0 && out2.im != 0.0){
|
||||
out[cnt + k].re /= 2.0;
|
||||
out[cnt + k].im /= 2.0;
|
||||
}
|
||||
|
||||
}
|
||||
//case 4: add by weight determined by distance to overlap center
|
||||
//perform overlapp area smoothing using a method discribed in:
|
||||
//C. Liang, Q. Zeng, J. Jia, J. Jiao, and X. Cui, ScanSAR interferometric processing
|
||||
//using existing standard InSAR software for measuring large scale land deformation
|
||||
//Computers & Geosciences, 2013.
|
||||
else{
|
||||
l = k - delta + 1; // l start with 1
|
||||
ns = row - 2 * delta;
|
||||
|
||||
if(out1.re != 0.0 && out1.im != 0.0 && out2.re != 0.0 && out2.im != 0.0){
|
||||
r = sqrt((out1.re * out1.re + out1.im * out1.im) / (out2.re * out2.re + out2.im * out2.im));
|
||||
out[cnt + k].re = ((ns - l + 0.5) * out1.re + r * (l - 0.5) * out2.re) / ns;
|
||||
out[cnt + k].im = ((ns - l + 0.5) * out1.im + r * (l - 0.5) * out2.im) / ns;
|
||||
}
|
||||
else{
|
||||
out[cnt + k].re = out1.re + out2.re;
|
||||
out[cnt + k].im = out1.im + out2.im;
|
||||
}
|
||||
}
|
||||
//cnt += row - 2 * delta;
|
||||
}
|
||||
//right edge of overlap area
|
||||
//use next subswath: subswath j+1
|
||||
//else if(k >= row - delta){
|
||||
else{
|
||||
out[cnt + k].re = out2.re;
|
||||
out[cnt + k].im = out2.im;
|
||||
}
|
||||
//cnt += 1;
|
||||
}
|
||||
cnt += row;
|
||||
|
||||
if(diffflag == 0){
|
||||
writedata((fcomplex *)diff[j], (row - 2 * delta) * sizeof(fcomplex), difffp[j]);
|
||||
writedata((fcomplex *)diff2[j], (row - 2 * delta) * sizeof(fcomplex), difffp[j]);
|
||||
}
|
||||
|
||||
} //loop of j, subswath
|
||||
writedata((fcomplex *)out, nrgout * sizeof(fcomplex), outfp);
|
||||
} //loop of i, output line
|
||||
|
||||
for(i = 0; i < n; i++)
|
||||
fclose(infp[i]);
|
||||
fclose(outfp);
|
||||
|
||||
if(diffflag == 0)
|
||||
for(i = 0; i < n - 1; i++)
|
||||
fclose(difffp[i]);
|
||||
|
||||
free_array1d_FILE(infp);
|
||||
free_array1d_FILE(difffp);
|
||||
|
||||
free_array2d_fcomplex(in);
|
||||
free_array1d_fcomplex(out);
|
||||
|
||||
//free_array1d_int(nrgin);
|
||||
free_array1d_int(nazin);
|
||||
//free_array1d_int(nrgoff); //nrgoff must be <= 0
|
||||
//free_array1d_int(nazoff); //nazoff must be <= 0
|
||||
//free_array1d_int(oflag);
|
||||
|
||||
free_array2d_fcomplex(diff);
|
||||
free_array2d_fcomplex(diff2);
|
||||
|
||||
return 0;
|
||||
|
||||
}
|
||||
|
|
@ -0,0 +1,401 @@
|
|||
//////////////////////////////////////
|
||||
// Cunren Liang, NASA JPL/Caltech
|
||||
// Copyright 2017
|
||||
//////////////////////////////////////
|
||||
//update: add default value azpos_off = 0.0; 12-DEC-2019
|
||||
//update: normalization of resampling kernals. 12-DEC-2019
|
||||
|
||||
|
||||
#include "resamp.h"
|
||||
|
||||
#define SWAP4(a) (*(unsigned int *)&(a) = (((*(unsigned int *)&(a) & 0x000000ff) << 24) | ((*(unsigned int *)&(a) & 0x0000ff00) << 8) | ((*(unsigned int *)&(a) >> 8) & 0x0000ff00) | ((*(unsigned int *)&(a) >> 24) & 0x000000ff)))
|
||||
|
||||
void normalize_kernel(float *kernel, long start_index, long end_index);
|
||||
|
||||
int resamp(char *slc2, char *rslc2, char *rgoff_file, char *azoff_file, int nrg1, int naz1, int nrg2, int naz2, float prf, float *dopcoeff, float *rgcoef, float *azcoef, float azpos_off, int byteorder, long imageoffset, long lineoffset, int verbose){
|
||||
/*
|
||||
mandatory:
|
||||
slc2: slave image
|
||||
rslc2: resampled slave image
|
||||
rgoff_file: range offset file. if no range offset file, specify fake
|
||||
azoff_file: azimuth offset file. if no azimuth offset file, specify fake
|
||||
nrg1: number of columns in master image
|
||||
naz1: number of lines in master image
|
||||
nrg2: number of columns in slave image
|
||||
naz2: number of lines in slave image
|
||||
prf: PRF of slave image
|
||||
dopcoeff[0]-[3]: Doppler centroid frequency coefficents
|
||||
optional:
|
||||
rgcoef[0]-[9]: range offset polynomial coefficents. First of two fit results of resamp_roi
|
||||
azcoef[0]-[9]: azimuth offset polynomial coefficents. First of two fit results of resamp_roi
|
||||
azpos_off: azimuth position offset. Azimuth line number (column 3) of first offset in culled offset file
|
||||
|
||||
byteorder: (0) LSB, little endian; (1) MSB, big endian of intput file
|
||||
imageoffset: offset from start of the image of input file
|
||||
lineoffset: length of each line of input file
|
||||
*/
|
||||
|
||||
FILE *slc2fp;
|
||||
FILE *rslc2fp;
|
||||
FILE *rgoffp;
|
||||
FILE *azoffp;
|
||||
int rgflag;
|
||||
int azflag;
|
||||
//int nrg1;
|
||||
//int naz1;
|
||||
//int nrg2;
|
||||
//int naz2;
|
||||
//float prf;
|
||||
//float dopcoeff[4];
|
||||
//float rgcoef[10];
|
||||
//float azcoef[10];
|
||||
//float azpos_off;
|
||||
float beta;
|
||||
int n;
|
||||
int m;
|
||||
int interp_method;
|
||||
int edge_method;
|
||||
float rgpos;
|
||||
float azpos;
|
||||
float rgoff;
|
||||
float azoff;
|
||||
float rgoff1;
|
||||
float azoff1;
|
||||
float *rgoff2;
|
||||
float *azoff2;
|
||||
float rg2;
|
||||
float az2;
|
||||
int rgi2;
|
||||
int azi2;
|
||||
float rgf;
|
||||
float azf;
|
||||
int rgfn;
|
||||
int azfn;
|
||||
int hnm;
|
||||
int hn;
|
||||
float *sincc;
|
||||
float *kaiserc;
|
||||
float *kernel;
|
||||
float *rgkernel;
|
||||
float *azkernel;
|
||||
fcomplex *azkernel_fc;
|
||||
fcomplex *rgrs;
|
||||
fcomplex *azca;
|
||||
fcomplex *rgrsb;
|
||||
fcomplex *azrs;
|
||||
float *dop;
|
||||
float dopx;
|
||||
fcomplex **inb;
|
||||
int i, j, k, k1, k2;
|
||||
int tmp1, tmp2;
|
||||
int zero_flag;
|
||||
float ftmp1, ftmp2;
|
||||
fcomplex fctmp1, fctmp2;
|
||||
beta = 2.5;
|
||||
n = 9;
|
||||
m = 10000;
|
||||
interp_method = 0;
|
||||
edge_method = 0;
|
||||
|
||||
|
||||
slc2fp = openfile(slc2, "rb");
|
||||
rslc2fp = openfile(rslc2, "wb");
|
||||
rgflag = 0;
|
||||
azflag = 0;
|
||||
if (strcmp(rgoff_file, "fake") == 0){
|
||||
rgflag = 0;
|
||||
printf("range offset file not provided\n");
|
||||
}
|
||||
else{
|
||||
rgflag = 1;
|
||||
rgoffp = openfile(rgoff_file, "rb");
|
||||
}
|
||||
if (strcmp(azoff_file, "fake") == 0){
|
||||
azflag = 0;
|
||||
printf("azimuth offset file not provided\n");
|
||||
}
|
||||
else{
|
||||
azflag = 1;
|
||||
azoffp = openfile(azoff_file, "rb");
|
||||
}
|
||||
//nrg1 = atoi(argv[5]);
|
||||
//naz1 = atoi(argv[6]);
|
||||
//nrg2 = atoi(argv[7]);
|
||||
//naz2 = atoi(argv[8]);
|
||||
//prf = atof(argv[9]);
|
||||
//for(i = 0; i < 4; i++){
|
||||
// dopcoeff[i] = atof(argv[10+i]);
|
||||
//}
|
||||
//for(i = 0; i < 10; i++){
|
||||
// if(argc > 14 + i)
|
||||
// rgcoef[i] = atof(argv[14+i]);
|
||||
// else
|
||||
// rgcoef[i] = 0.0;
|
||||
//}
|
||||
//for(i = 0; i < 10; i++){
|
||||
// if(argc > 24 + i)
|
||||
// azcoef[i] = atof(argv[24+i]);
|
||||
// else
|
||||
// azcoef[i] = 0.0;
|
||||
//}
|
||||
//if(argc > 34)
|
||||
// azpos_off = atof(argv[34]);
|
||||
//else
|
||||
// azpos_off = 0.0;
|
||||
if(verbose != 0){
|
||||
printf("\n\ninput parameters:\n");
|
||||
printf("slc2: %s\n", slc2);
|
||||
printf("rslc2: %s\n", rslc2);
|
||||
printf("rgoff_file: %s\n", rgoff_file);
|
||||
printf("azoff_file: %s\n\n", azoff_file);
|
||||
printf("nrg1: %d\n", nrg1);
|
||||
printf("naz1: %d\n", naz1);
|
||||
printf("nrg2: %d\n", nrg2);
|
||||
printf("naz2: %d\n\n", naz2);
|
||||
printf("prf: %f\n\n", prf);
|
||||
for(i = 0; i < 4; i++){
|
||||
printf("dopcoeff[%d]: %e\n", i, dopcoeff[i]);
|
||||
}
|
||||
printf("\n");
|
||||
for(i = 0; i < 10; i++){
|
||||
printf("rgcoef[%d]: %e\n", i, rgcoef[i]);
|
||||
}
|
||||
printf("\n");
|
||||
for(i = 0; i < 10; i++){
|
||||
printf("azcoef[%d]: %e\n", i, azcoef[i]);
|
||||
}
|
||||
printf("\n");
|
||||
printf("azpos_off: %f\n\n", azpos_off);
|
||||
|
||||
if(byteorder == 0){
|
||||
printf("inputfile byte order: little endian\n");
|
||||
}
|
||||
else{
|
||||
printf("inputfile byte order: big endian\n");
|
||||
}
|
||||
printf("input file image offset [byte]: %ld\n", imageoffset);
|
||||
printf("input file line offset [byte]: %ld\n", lineoffset);
|
||||
}
|
||||
|
||||
if(imageoffset < 0){
|
||||
fprintf(stderr, "image offset must be >= 0\n");
|
||||
exit(1);
|
||||
}
|
||||
if(lineoffset < 0){
|
||||
fprintf(stderr, "lineoffset offset must be >= 0\n");
|
||||
exit(1);
|
||||
}
|
||||
|
||||
hn = n / 2;
|
||||
hnm = n * m / 2;
|
||||
rgoff2 = array1d_float(nrg1);
|
||||
azoff2 = array1d_float(nrg1);
|
||||
sincc = vector_float(-hnm, hnm);
|
||||
kaiserc = vector_float(-hnm, hnm);
|
||||
kernel = vector_float(-hnm, hnm);
|
||||
rgkernel = vector_float(-hn, hn);
|
||||
azkernel = vector_float(-hn, hn);
|
||||
azkernel_fc = vector_fcomplex(-hn, hn);
|
||||
rgrs = vector_fcomplex(-hn, hn);
|
||||
azca = vector_fcomplex(-hn, hn);
|
||||
rgrsb = vector_fcomplex(-hn, hn);
|
||||
azrs = array1d_fcomplex(nrg1);
|
||||
dop = array1d_float(nrg2);
|
||||
inb = array2d_fcomplex(naz2, nrg2);
|
||||
sinc(n, m, sincc);
|
||||
kaiser(n, m, kaiserc, beta);
|
||||
for(i = -hnm; i <= hnm; i++)
|
||||
kernel[i] = kaiserc[i] * sincc[i];
|
||||
if(verbose != 0)
|
||||
printf("\n");
|
||||
for(i = 0; i < nrg2; i++){
|
||||
dop[i] = dopcoeff[0] + dopcoeff[1] * i + dopcoeff[2] * i * i + dopcoeff[3] * i * i * i;
|
||||
//get rid of this bad convention from roi_pac
|
||||
//dop[i] *= prf;
|
||||
if(verbose != 0)
|
||||
if(i % 500 == 0)
|
||||
printf("range sample: %5d, doppler centroid frequency: %8.2f Hz\n", i, dop[i]);
|
||||
}
|
||||
if(verbose != 0)
|
||||
printf("\n");
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////////////////////
|
||||
//skip image header
|
||||
fseek(slc2fp, imageoffset, SEEK_SET);
|
||||
|
||||
for(i = 0; i < naz2; i++){
|
||||
if(i!=0)
|
||||
fseek(slc2fp, lineoffset - (size_t)nrg2 * sizeof(fcomplex), SEEK_CUR);
|
||||
readdata((fcomplex *)inb[i], (size_t)nrg2 * sizeof(fcomplex), slc2fp);
|
||||
}
|
||||
|
||||
//read image data
|
||||
//if(lineoffset == 0){
|
||||
// readdata((fcomplex *)inb[0], (size_t)naz2 * (size_t)nrg2 * sizeof(fcomplex), slc2fp);
|
||||
//}
|
||||
//else{
|
||||
// for(i = 0; i < naz2; i++){
|
||||
// fseek(slc2fp, lineoffset, SEEK_CUR);
|
||||
// readdata((fcomplex *)inb[i], (size_t)nrg2 * sizeof(fcomplex), slc2fp);
|
||||
// }
|
||||
//}
|
||||
//swap bytes
|
||||
if(byteorder!=0){
|
||||
printf("swapping bytes...\n");
|
||||
for(i = 0; i < naz2; i++)
|
||||
for(j = 0; j < nrg2; j++){
|
||||
SWAP4(inb[i][j].re);
|
||||
SWAP4(inb[i][j].im);
|
||||
}
|
||||
}
|
||||
//////////////////////////////////////////////////////////////////////////////////////////////
|
||||
|
||||
for(i = 0; i < naz1; i++){
|
||||
if((i + 1) % 100 == 0)
|
||||
fprintf(stderr,"processing line: %6d of %6d\r", i+1, naz1);
|
||||
if (rgflag == 1){
|
||||
readdata((float *)rgoff2, nrg1 * sizeof(float), rgoffp);
|
||||
}
|
||||
if (azflag == 1){
|
||||
readdata((float *)azoff2, nrg1 * sizeof(float), azoffp);
|
||||
}
|
||||
for(j = 0; j < nrg1; j++){
|
||||
azrs[j].re = 0.0;
|
||||
azrs[j].im = 0.0;
|
||||
}
|
||||
for(j = 0; j < nrg1; j++){
|
||||
rgpos = j;
|
||||
azpos = i - azpos_off;
|
||||
rgoff1 = rgcoef[0] + azpos*(rgcoef[2] + \
|
||||
azpos*(rgcoef[5] + azpos*rgcoef[9])) + \
|
||||
rgpos*(rgcoef[1] + rgpos*(rgcoef[4] + \
|
||||
rgpos*rgcoef[8])) + \
|
||||
rgpos*azpos*(rgcoef[3] + azpos*rgcoef[6] + \
|
||||
rgpos*rgcoef[7]);
|
||||
azoff1 = azcoef[0] + azpos*(azcoef[2] + \
|
||||
azpos*(azcoef[5] + azpos*azcoef[9])) + \
|
||||
rgpos*(azcoef[1] + rgpos*(azcoef[4] + \
|
||||
rgpos*azcoef[8])) + \
|
||||
rgpos*azpos*(azcoef[3] + azpos*azcoef[6] + \
|
||||
rgpos*azcoef[7]);
|
||||
if (rgflag == 1){
|
||||
rgoff = rgoff1 + rgoff2[j];
|
||||
}
|
||||
else{
|
||||
rgoff = rgoff1;
|
||||
}
|
||||
if (azflag == 1){
|
||||
azoff = azoff1 + azoff2[j];
|
||||
}
|
||||
else{
|
||||
azoff = azoff1;
|
||||
}
|
||||
rg2 = j + rgoff;
|
||||
az2 = i + azoff;
|
||||
rgi2 = roundfi(rg2);
|
||||
azi2 = roundfi(az2);
|
||||
rgf = rg2 - rgi2;
|
||||
azf = az2 - azi2;
|
||||
rgfn = roundfi(rgf * m);
|
||||
azfn = roundfi(azf * m);
|
||||
for(k = -hn; k <= hn; k++){
|
||||
tmp1 = k * m - rgfn;
|
||||
tmp2 = k * m - azfn;
|
||||
if(tmp1 > hnm) tmp1 = hnm;
|
||||
if(tmp2 > hnm) tmp2 = hnm;
|
||||
if(tmp1 < -hnm) tmp1 = -hnm;
|
||||
if(tmp2 < -hnm) tmp2 = -hnm;
|
||||
rgkernel[k] = kernel[tmp1];
|
||||
azkernel[k] = kernel[tmp2];
|
||||
}
|
||||
normalize_kernel(rgkernel, -hn, hn);
|
||||
normalize_kernel(azkernel, -hn, hn);
|
||||
for(k1 = -hn; k1 <= hn; k1++){
|
||||
rgrs[k1].re = 0.0;
|
||||
rgrs[k1].im = 0.0;
|
||||
if(edge_method == 0){
|
||||
if(azi2 < hn || azi2 > naz2 - 1 - hn || rgi2 < hn || rgi2 > nrg2 - 1 - hn){
|
||||
continue;
|
||||
}
|
||||
}
|
||||
else if(edge_method == 1){
|
||||
if(azi2 < 0 || azi2 > naz2 - 1 || rgi2 < 0 || rgi2 > nrg2 - 1){
|
||||
continue;
|
||||
}
|
||||
}
|
||||
else{
|
||||
if(azi2 < -hn || azi2 > naz2 - 1 + hn || rgi2 < -hn || rgi2 > nrg2 - 1 + hn){
|
||||
continue;
|
||||
}
|
||||
}
|
||||
for(k2 = -hn; k2 <= hn; k2++){
|
||||
if(azi2 + k1 < 0 || azi2 + k1 > naz2 - 1 || rgi2 + k2 < 0 || rgi2 + k2 > nrg2 - 1)
|
||||
continue;
|
||||
rgrs[k1].re += inb[azi2 + k1][rgi2 + k2].re * rgkernel[k2];
|
||||
rgrs[k1].im += inb[azi2 + k1][rgi2 + k2].im * rgkernel[k2];
|
||||
}
|
||||
}
|
||||
for(k = -hn; k <= hn; k++){
|
||||
if(rgrs[k].re == 0.0 && rgrs[k].im == 0.0)
|
||||
continue;
|
||||
dopx = dopcoeff[0] + dopcoeff[1] * rg2 + dopcoeff[2] * rg2 * rg2 + dopcoeff[3] * rg2 * rg2 * rg2;
|
||||
//get rid of this bad convention from roi_pac
|
||||
//dopx *= prf;
|
||||
ftmp1 = 2.0 * PI * dopx * k / prf;
|
||||
azca[k].re = cos(ftmp1);
|
||||
azca[k].im = sin(ftmp1);
|
||||
if(interp_method == 0){
|
||||
rgrsb[k] = cmul(rgrs[k], cconj(azca[k]));
|
||||
azrs[j].re += rgrsb[k].re * azkernel[k];
|
||||
azrs[j].im += rgrsb[k].im * azkernel[k];
|
||||
}
|
||||
else{
|
||||
azkernel_fc[k].re = azca[k].re * azkernel[k];
|
||||
azkernel_fc[k].im = azca[k].im * azkernel[k];
|
||||
azrs[j] = cadd(azrs[j], cmul(rgrs[k], azkernel_fc[k]));
|
||||
}
|
||||
}
|
||||
if(interp_method == 0){
|
||||
ftmp1 = 2.0 * PI * dopx * azf / prf;
|
||||
fctmp1.re = cos(ftmp1);
|
||||
fctmp1.im = sin(ftmp1);
|
||||
azrs[j] = cmul(azrs[j], fctmp1);
|
||||
}
|
||||
}
|
||||
writedata((fcomplex *)azrs, nrg1 * sizeof(fcomplex), rslc2fp);
|
||||
}
|
||||
fprintf(stderr,"processing line: %6d of %6d\n", naz1, naz1);
|
||||
free_array1d_float(rgoff2);
|
||||
free_array1d_float(azoff2);
|
||||
free_vector_float(sincc, -hnm, hnm);
|
||||
free_vector_float(kaiserc, -hnm, hnm);
|
||||
free_vector_float(kernel, -hnm, hnm);
|
||||
free_vector_float(rgkernel, -hn, hn);
|
||||
free_vector_float(azkernel, -hn, hn);
|
||||
free_vector_fcomplex(azkernel_fc, -hn, hn);
|
||||
free_vector_fcomplex(rgrs, -hn, hn);
|
||||
free_vector_fcomplex(azca, -hn, hn);
|
||||
free_vector_fcomplex(rgrsb, -hn, hn);
|
||||
free_array1d_fcomplex(azrs);
|
||||
free_array1d_float(dop);
|
||||
free_array2d_fcomplex(inb);
|
||||
fclose(slc2fp);
|
||||
fclose(rslc2fp);
|
||||
if (rgflag == 1){
|
||||
fclose(rgoffp);
|
||||
}
|
||||
if (azflag == 1){
|
||||
fclose(azoffp);
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
void normalize_kernel(float *kernel, long start_index, long end_index){
|
||||
double sum;
|
||||
long i;
|
||||
sum = 0.0;
|
||||
for(i = start_index; i <= end_index; i++)
|
||||
sum += kernel[i];
|
||||
if(sum!=0)
|
||||
for(i = start_index; i <= end_index; i++)
|
||||
kernel[i] /= sum;
|
||||
}
|
||||
|
|
@ -8,8 +8,9 @@
|
|||
#include <fftw3.h>
|
||||
#include <omp.h>
|
||||
|
||||
#define SWAP4(a) (*(unsigned int *)&(a) = (((*(unsigned int *)&(a) & 0x000000ff) << 24) | ((*(unsigned int *)&(a) & 0x0000ff00) << 8) | ((*(unsigned int *)&(a) >> 8) & 0x0000ff00) | ((*(unsigned int *)&(a) >> 24) & 0x000000ff)))
|
||||
|
||||
int rg_filter(char *inputfile, int nrg, int nout, char **outputfile, float *bw, float *bc, int nfilter, int nfft, float beta, int zero_cf, float offset){
|
||||
int rg_filter(char *inputfile, int nrg, int naz, int nout, char **outputfile, float *bw, float *bc, int nfilter, int nfft, float beta, int zero_cf, float offset, int byteorder, long imageoffset, long lineoffset){
|
||||
/*
|
||||
inputfile: input file
|
||||
nrg file width
|
||||
|
|
@ -23,6 +24,10 @@ int rg_filter(char *inputfile, int nrg, int nout, char **outputfile, float *bw,
|
|||
beta: kaiser window beta. Reference Value: 1.0
|
||||
zero_cf: if bc != 0.0, move center frequency to zero? 0: Yes (Reference Value). 1: No.
|
||||
offset: offset (in samples) of linear phase for moving center frequency. Reference Value: 0.0
|
||||
|
||||
byteorder: (0) LSB, little endian; (1) MSB, big endian of intput file
|
||||
imageoffset: offset from start of the image of input file
|
||||
lineoffset: length of each line of input file
|
||||
*/
|
||||
|
||||
///////////////////////////////
|
||||
|
|
@ -64,7 +69,7 @@ int rg_filter(char *inputfile, int nrg, int nout, char **outputfile, float *bw,
|
|||
|
||||
//int nout; //number of output files
|
||||
//int nrg; //file width
|
||||
int naz; //file length
|
||||
//int naz; //file length
|
||||
|
||||
//int nfft; //fft length
|
||||
//int nfilter; //filter length
|
||||
|
|
@ -107,7 +112,10 @@ int rg_filter(char *inputfile, int nrg, int nout, char **outputfile, float *bw,
|
|||
/*****************************************************************************/
|
||||
|
||||
infp = openfile(inputfile, "rb");
|
||||
naz = file_length(infp, nrg, sizeof(fcomplex));
|
||||
//naz = file_length(infp, nrg, sizeof(fcomplex));
|
||||
//fseeko(infp,0L,SEEK_END);
|
||||
//naz = (ftello(infp) - imageoffset) / (lineoffset + nrg*sizeof(fcomplex));
|
||||
//rewind(infp);
|
||||
printf("file width: %d, file length: %d\n\n", nrg, naz);
|
||||
if(nout < 1){
|
||||
fprintf(stderr, "there should be at least one output file!\n");
|
||||
|
|
@ -128,6 +136,23 @@ int rg_filter(char *inputfile, int nrg, int nout, char **outputfile, float *bw,
|
|||
exit(1);
|
||||
}
|
||||
|
||||
if(byteorder == 0){
|
||||
printf("inputfile byte order: little endian\n");
|
||||
}
|
||||
else{
|
||||
printf("inputfile byte order: big endian\n");
|
||||
}
|
||||
printf("input file image offset [byte]: %ld\n", imageoffset);
|
||||
printf("input file line offset [byte]: %ld\n", lineoffset);
|
||||
if(imageoffset < 0){
|
||||
fprintf(stderr, "image offset must be >= 0\n");
|
||||
exit(1);
|
||||
}
|
||||
if(lineoffset < 0){
|
||||
fprintf(stderr, "lineoffset offset must be >= 0\n");
|
||||
exit(1);
|
||||
}
|
||||
|
||||
//compute block processing parameters
|
||||
hnfilter = (nfilter - 1) / 2;
|
||||
nblock_in = nfft - nfilter + 1;
|
||||
|
|
@ -211,6 +236,11 @@ int rg_filter(char *inputfile, int nrg, int nout, char **outputfile, float *bw,
|
|||
}
|
||||
fftwf_destroy_plan(p_forward_filter);
|
||||
|
||||
|
||||
//skip image header
|
||||
if(imageoffset != 0)
|
||||
fseek(infp, imageoffset, SEEK_SET);
|
||||
|
||||
//process data
|
||||
for(i = 0; i < naz; i++){
|
||||
//progress report
|
||||
|
|
@ -220,7 +250,17 @@ int rg_filter(char *inputfile, int nrg, int nout, char **outputfile, float *bw,
|
|||
fprintf(stderr,"\n\n");
|
||||
|
||||
//read data
|
||||
if(i != 0)
|
||||
fseek(infp, lineoffset-(size_t)nrg * sizeof(fcomplex), SEEK_CUR);
|
||||
readdata((fcomplex *)in, (size_t)nrg * sizeof(fcomplex), infp);
|
||||
//swap bytes
|
||||
if(byteorder!=0){
|
||||
for(j = 0; j < nrg; j++){
|
||||
SWAP4(in[j].re);
|
||||
SWAP4(in[j].im);
|
||||
}
|
||||
}
|
||||
|
||||
#pragma omp parallel for private(j) shared(nrg,in, zeroflag, sc)
|
||||
for(j = 0; j < nrg; j++){
|
||||
if(in[j].re != 0.0 || in[j].im != 0.0){
|
||||
|
|
|
|||
Some files were not shown because too many files have changed in this diff Show More
Loading…
Reference in New Issue