SIMOrthoProgram-Orth_LT1AB-.../Ortho/OrthoAlg.py

2986 lines
140 KiB
Python
Raw Normal View History

# -*- coding: UTF-8 -*-
"""
@Project microproduct
@File OneOrthoAlg.py
@Function 正射校正算法
@Author KHZ
@Contact
@Date 2021/8/14
@Version 1.0.0
"""
# from re import I, T, X, match
# from types import DynamicClassAttribute
# from numpy.core.einsumfunc import _parse_possible_contraction
# from numpy.core.fromnumeric import shape
# from numpy.core.shape_base import block
# from numpy.lib import row_stack
# from numpy.lib.function_base import delete
import psutil
import os
import gc
# import sys
# import scipy
# from scipy.sparse import data
# from scipy.sparse.construct import random
import xmltodict
import numpy as np
import json
import datetime, time
import yaml
import math
import time
#import cv2
#import cv2 as cv
from osgeo import gdal, gdalconst
# from yaml.events import AliasEvent, NodeEvent
from OrthoAuxData import OrthoAuxData
# from OrthoImage import ImageHandler
from tool.algorithm.image.ImageHandle import ImageHandler
from tool.algorithm.algtools.MetaDataHandler import MetaDataHandler
# from logHandler import LogHandler
from osgeo import osr
from scipy import interpolate
import scipy.io as scipyio
import copy
import scipy.sparse as ss
import shutil
import pandas
import uuid
from concurrent.futures._base import as_completed, wait
from concurrent.futures.thread import ThreadPoolExecutor
from multiprocessing import Pool
class ScatteringAlg:
def __init__(self):
pass
@staticmethod
def sar_backscattering_coef(in_sar_tif, meta_file_path, out_sar_tif, replece_VV = False, is_DB = True):
# 读取原始SAR影像
proj, geotrans, in_data = ImageHandler.read_img(in_sar_tif)
# 计算强度信息
I = np.array(in_data[0], dtype="float32")
Q = np.array(in_data[1], dtype="float32")
where_9999_0 = np.where(I == -9999)
where_9999_1 = np.where(Q == -9999)
I[where_9999_0] = 1.0
Q[where_9999_1] = 1.0
I2 = np.square(I)
Q2 = np.square(Q)
intensity_arr = I2 + Q2
# 获取极化类型
if 'HH' in os.path.basename(in_sar_tif):
polarization = 'HH'
elif 'HV' in os.path.basename(in_sar_tif):
polarization = 'HV'
elif 'VH' in os.path.basename(in_sar_tif):
polarization = 'VH'
elif 'VV' in os.path.basename(in_sar_tif):
polarization = 'VV'
if replece_VV:
polarization = 'HV' #土壤水分算法中可能会用HV替换VV
elif 'DH' in os.path.basename(in_sar_tif):
polarization = 'HH'
else:
raise Exception ('there are not HH、HV、VH、VV in path:',in_sar_tif)
# 获取参数
QualifyValue = MetaDataHandler.get_QualifyValue(meta_file_path, polarization)
Kdb = MetaDataHandler.get_Kdb(meta_file_path, polarization)
# 计算后向散射系数
#对数形式
coef_arr = 10 * (np.log10(intensity_arr * ((QualifyValue/32767)**2))) - Kdb
coef_arr[np.isnan(coef_arr)] = -9999
coef_arr[np.isinf(coef_arr)] = -9999
coef_arr[where_9999_0] = -9999
coef_arr[where_9999_1] = -9999
## 输出的SAR后向散射系数产品
# ImageHandler.write_img(out_sar_tif, proj, geotrans, coef_arr, 0)
tif_array = np.power(10.0, coef_arr / 10.0) # dB --> 线性值 后向散射系数
tif_array[np.isnan(tif_array)] = 0
tif_array[np.isinf(tif_array)] = 0
tif_array[where_9999_0] = 0
tif_array[where_9999_1] = 0
ImageHandler.write_img(out_sar_tif, proj, geotrans, tif_array, 0)
return True
@staticmethod
def lin_to_db(lin_path, db_path):
proj, geotrans, in_data = ImageHandler.read_img(lin_path)
db_arr = 10 * np.log10(in_data)
# db_arr[np.isnan(db_arr)] = -9999
# db_arr[np.isinf(db_arr)] = -9999
ImageHandler.write_img(db_path, proj, geotrans, db_arr, -9999)
def FindInfomationFromJson(HeaderFile_dom_json, node_path_list):
"""
在Json文件中按照指定路径解析出制定节点
"""
result_node = HeaderFile_dom_json
for nodename in node_path_list:
result_node = result_node[nodename]
return result_node
def GetVectorNorm(Vecter):
"""
得到向量的模
"""
Vecter = Vecter.reshape(-1,1)
Vecter_Norm_pow = np.matmul(Vecter.T,Vecter)
return np.sqrt(Vecter_Norm_pow)
def XYZOuterM2(A, B):
"""
外积叉乘,日后版本换成可以任意维度的外积运算方程
args:
A:nx3
B:nx3
"""
cnt = A.shape[0]
C = np.zeros((cnt, 3))
C[:, 0] = A[:, 1] * B[:, 2] - A[:, 2] * B[:, 1]
C[:, 1] = A[:, 2] * B[:, 0] - A[:, 0] * B[:, 2]
C[:, 2] = A[:, 0] * B[:, 1] - A[:, 1] * B[:, 0]
return C
def LinearSampling_raster(source_raster,tar_raster,source_start_row,source_start_col,tar_start_row,tar_start_col):
''' 双线性重采样
agrs:
source_raster:原影像
tar_raster:目标影像
source_start_row:原影像的起始行号
source_start_col:原影像的起始列号
tar_start_row:目标影像的起始行号
tar_start_col:目标影像的起始列号
return:
tar_raster:目标影像
'''
# 根据原影像的起始行列号与目标影像行列号,计算目标影像行列号的校正值
d_row=tar_start_row-source_start_row #
d_col=tar_start_col-source_start_col #
source_height=source_raster.shape[0]
source_width=source_raster.shape[1]
tar_height=tar_raster.shape[0]
tar_width=tar_raster.shape[1]
source_row=(np.ones((source_width,source_height))*range(source_height)).transpose(1,0)
source_col=np.ones((source_height,source_width))*range(source_width)
tar_row=(np.ones((tar_width,tar_height))*range(tar_height)).transpose(1,0)
tar_col=np.ones((tar_height,tar_width))*range(tar_width)
tar_row=tar_row+d_row # 坐标系变换
tar_col=tar_col+d_col # 坐标系变换
# 确定行列号
last_source_row=np.floor(tar_row)
last_source_col=np.floor(tar_col)
next_source_row=np.ceil(tar_row)
next_source_col=np.ceil(tar_col)
# 双线性重采样模型示意图,
# y1 r1 y2
#
# r
#
# y3 r2 y4
# 计算重采样
r1=source_raster[last_source_row,last_source_col]*(tar_col-last_source_col)+source_raster[last_source_row,next_source_col]*(next_source_col-tar_col)
r2=source_raster[next_source_row,last_source_col]*(tar_col-last_source_col)+source_raster[next_source_row,next_source_col]*(next_source_col-tar_col)
tar_raster=r1*(tar_row-last_source_row)+r2*(next_source_row-tar_row)
tar_raster=tar_raster.reshape(tar_height,tar_width) # 目标影像
return tar_raster.copy()
'''-----双线性重采样-----'''
""" RPC 校正部分 """
def parse_rpc_file(rpc_file):
# rpc_file:.rpc文件的绝对路径
# rpc_dict符号RPC域下的16个关键字的字典
# 参考网址http://geotiff.maptools.org/rpc_prop.html
# https://www.osgeo.cn/gdal/development/rfc/rfc22_rpc.html
rpc_dict = {}
with open(rpc_file) as f:
text = f.read()
# .rpc文件中的RPC关键词
words = ['errBias', 'errRand', 'lineOffset', 'sampOffset', 'latOffset',
'longOffset', 'heightOffset', 'lineScale', 'sampScale', 'latScale',
'longScale', 'heightScale', 'lineNumCoef', 'lineDenCoef','sampNumCoef', 'sampDenCoef',]
# GDAL库对应的RPC关键词
keys = ['ERR_BIAS', 'ERR_RAND', 'LINE_OFF', 'SAMP_OFF', 'LAT_OFF', 'LONG_OFF',
'HEIGHT_OFF', 'LINE_SCALE', 'SAMP_SCALE', 'LAT_SCALE',
'LONG_SCALE', 'HEIGHT_SCALE', 'LINE_NUM_COEFF', 'LINE_DEN_COEFF',
'SAMP_NUM_COEFF', 'SAMP_DEN_COEFF']
for old, new in zip(words, keys):
text = text.replace(old, new)
# 以‘;\n作为分隔符
text_list = text.split(';\n')
# 删掉无用的行
text_list = text_list[3:-2]
#
text_list[0] = text_list[0].split('\n')[1]
# 去掉制表符、换行符、空格
text_list = [item.strip('\t').replace('\n', '').replace(' ', '') for item in text_list]
for item in text_list:
# 去掉‘=
key, value = item.split('=')
# 去掉多余的括号‘()
if '(' in value:
value = value.replace('(', '').replace(')', '')
rpc_dict[key] = value
for key in keys[:12]:
# 为正数添加符号‘+
if not rpc_dict[key].startswith('-'):
rpc_dict[key] = '+' + rpc_dict[key]
# 为归一化项和误差标志添加单位
if key in ['LAT_OFF', 'LONG_OFF', 'LAT_SCALE', 'LONG_SCALE']:
rpc_dict[key] = rpc_dict[key] + ' degrees'
if key in ['LINE_OFF', 'SAMP_OFF', 'LINE_SCALE', 'SAMP_SCALE']:
rpc_dict[key] = rpc_dict[key] + ' pixels'
if key in ['ERR_BIAS', 'ERR_RAND', 'HEIGHT_OFF', 'HEIGHT_SCALE']:
rpc_dict[key] = rpc_dict[key] + ' meters'
# 处理有理函数项
for key in keys[-4:]:
values = []
for item in rpc_dict[key].split(','):
#print(item)
if not item.startswith('-'):
values.append('+'+item)
else:
values.append(item)
rpc_dict[key] = ' '.join(values)
return rpc_dict
def write_rpc_to_tiff(inputpath,rpc_file,ap = True,outpath = None):
rpc_dict = parse_rpc_file(rpc_file)
if ap:
# 可修改读取
dataset = gdal.Open(inputpath,gdal.GA_Update)
# 向tif影像写入rpc域信息
# 注意这里虽然写入了RPC域信息但实际影像还没有进行实际的RPC校正
# 尽管有些RS/GIS能加载RPC域信息并进行动态校正
for k in rpc_dict.keys():
dataset.SetMetadataItem(k, rpc_dict[k], 'RPC')
dataset.FlushCache()
del dataset
else:
dataset = gdal.Open(inputpath,gdal.GA_Update)
tiff_driver= gdal.GetDriverByName('Gtiff')
out_ds = tiff_driver.CreateCopy(outpath, dataset, 1)
for k in rpc_dict.keys():
out_ds.SetMetadataItem(k, rpc_dict[k], 'RPC')
out_ds.FlushCache()
def rpc_correction(inputpath,rpc_file,corrtiff,dem_tif_file = None):
## 设置rpc校正的参数
# 原图像和输出影像缺失值设置为0输出影像坐标系为WGS84(EPSG:4326), 重采样方法为双线性插值bilinear还有最邻近near、三次卷积cubic等可选)
# 注意DEM的覆盖范围要比原影像的范围大此外DEM不能有缺失值有缺失值会报错
# 通常DEM在水域是没有值的即缺失值的情况因此需要将其填充设置为0否则在RPC校正时会报错
# 这里使用的DEM是填充0值后的SRTM V4.1 3秒弧度的DEM(分辨率为90m)
# RPC_DEMINTERPOLATION=bilinear 表示对DEM重采样使用双线性插值算法
# 如果要修改输出的坐标系则要修改dstSRS参数值使用该坐标系统的EPSG代码
# 可以在网址https://spatialreference.org/ref/epsg/32650/ 查询得到EPSG代码
write_rpc_to_tiff(inputpath,rpc_file,ap = True,outpath = None)
if dem_tif_file is None:
wo = gdal.WarpOptions(srcNodata=0, dstNodata=0, dstSRS='EPSG:4326', resampleAlg='bilinear',
format='Gtiff',rpc=True, warpOptions=["INIT_DEST=NO_DATA"])
wr = gdal.Warp(corrtiff, inputpath, options=wo)
print("RPC_GEOcorr>>>")
else:
wo = gdal.WarpOptions(srcNodata=0, dstNodata=0, dstSRS='EPSG:4326', resampleAlg='bilinear', format='Gtiff',rpc=True, warpOptions=["INIT_DEST=NO_DATA"],
transformerOptions=["RPC_DEM=%s"%(dem_tif_file), "RPC_DEMINTERPOLATION=bilinear"])
wr = gdal.Warp(corrtiff, inputpath, options=wo)
print("RPC_GEOcorr>>>")
## 对于全海域的影像或者不使用DEM校正的话可以将transformerOptions有关的RPC DEM关键字删掉
## 即将上面gdal.WarpOptions注释掉将下面的语句取消注释无DEM时影像范围的高程默认全为0
del wr
##########################
# 输出RPC 行列号到 经纬度的变换
##########################
#最大迭代次数超过则报错
class MaxLocalizationIterationsError(Exception):
"""
Custom rpcm Exception.
"""
pass
def apply_poly(poly, x, y, z):
"""
Evaluates a 3-variables polynom of degree 3 on a triplet of numbers.
将三次多项式的统一模式构建为一个单独的函数
Args:
poly: list of the 20 coefficients of the 3-variate degree 3 polynom,
ordered following the RPC convention.
x, y, z: triplet of floats. They may be numpy arrays of same length.
Returns:
the value(s) of the polynom on the input point(s).
"""
out = 0
out += poly[0]
out += poly[1]*y + poly[2]*x + poly[3]*z
out += poly[4]*y*x + poly[5]*y*z +poly[6]*x*z
out += poly[7]*y*y + poly[8]*x*x + poly[9]*z*z
out += poly[10]*x*y*z
out += poly[11]*y*y*y
out += poly[12]*y*x*x + poly[13]*y*z*z + poly[14]*y*y*x
out += poly[15]*x*x*x
out += poly[16]*x*z*z + poly[17]*y*y*z + poly[18]*x*x*z
out += poly[19]*z*z*z
return out
def apply_rfm(num, den, x, y, z):
"""
Evaluates a Rational Function Model (rfm), on a triplet of numbers.
执行20个参数的分子和20个参数的除法
Args:
num: list of the 20 coefficients of the numerator
den: list of the 20 coefficients of the denominator
All these coefficients are ordered following the RPC convention.
x, y, z: triplet of floats. They may be numpy arrays of same length.
Returns:
the value(s) of the rfm on the input point(s).
"""
return apply_poly(num, x, y, z) / apply_poly(den, x, y, z)
def rpc_from_geotiff(geotiff_path):
"""
Read the RPC coefficients from a GeoTIFF file and return an RPCModel object.
该函数返回影像的Gdal格式的影像和RPCmodel
Args:
geotiff_path (str): path or url to a GeoTIFF file
Returns:
instance of the rpc_model.RPCModel class
"""
# with rasterio.open(geotiff_path, 'r') as src:
#
dataset = gdal.Open(geotiff_path, gdal.GA_ReadOnly)
rpc_dict = dataset.GetMetadata("RPC")
# 同时返回影像与rpc
return dataset, RPCModel(rpc_dict,'geotiff')
def read_rpc_file(rpc_file):
"""
Read RPC from a RPC_txt file and return a RPCmodel
从TXT中直接单独读取RPC模型
Args:
rpc_file: RPC sidecar file path
Returns:
dictionary read from the RPC file, or an empty dict if fail
"""
rpc = parse_rpc_file(rpc_file)
return RPCModel(rpc)
class RPCModel:
def __init__(self, d, dict_format="geotiff"):
"""
Args:
d (dict): dictionary read from a geotiff file with
rasterio.open('/path/to/file.tiff', 'r').tags(ns='RPC'),
or from the .__dict__ of an RPCModel object.
dict_format (str): format of the dictionary passed in `d`.
Either "geotiff" if read from the tags of a geotiff file,
or "rpcm" if read from the .__dict__ of an RPCModel object.
"""
if dict_format == "geotiff":
self.row_offset = float(d['LINE_OFF'][0:d['LINE_OFF'].rfind(' ')])
self.col_offset = float(d['SAMP_OFF'][0:d['SAMP_OFF'].rfind(' ')])
self.lat_offset = float(d['LAT_OFF'][0:d['LAT_OFF'].rfind(' ')])
self.lon_offset = float(d['LONG_OFF'][0:d['LONG_OFF'].rfind(' ')])
self.alt_offset = float(d['HEIGHT_OFF'][0:d['HEIGHT_OFF'].rfind(' ')])
self.row_scale = float(d['LINE_SCALE'][0:d['LINE_SCALE'].rfind(' ')])
self.col_scale = float(d['SAMP_SCALE'][0:d['SAMP_SCALE'].rfind(' ')])
self.lat_scale = float(d['LAT_SCALE'][0:d['LAT_SCALE'].rfind(' ')])
self.lon_scale = float(d['LONG_SCALE'][0:d['LONG_SCALE'].rfind(' ')])
self.alt_scale = float(d['HEIGHT_SCALE'][0:d['HEIGHT_SCALE'].rfind(' ')])
self.row_num = list(map(float, d['LINE_NUM_COEFF'].split()))
self.row_den = list(map(float, d['LINE_DEN_COEFF'].split()))
self.col_num = list(map(float, d['SAMP_NUM_COEFF'].split()))
self.col_den = list(map(float, d['SAMP_DEN_COEFF'].split()))
if 'LON_NUM_COEFF' in d:
self.lon_num = list(map(float, d['LON_NUM_COEFF'].split()))
self.lon_den = list(map(float, d['LON_DEN_COEFF'].split()))
self.lat_num = list(map(float, d['LAT_NUM_COEFF'].split()))
self.lat_den = list(map(float, d['LAT_DEN_COEFF'].split()))
elif dict_format == "rpcm":
self.__dict__ = d
else:
raise ValueError(
"dict_format '{}' not supported. "
"Should be {{'geotiff','rpcm'}}".format(dict_format)
)
def projection(self, lon, lat, alt):
"""
Convert geographic coordinates of 3D points into image coordinates.
正投影从地理坐标到图像坐标
Args:
lon (float or list): longitude(s) of the input 3D point(s)
lat (float or list): latitude(s) of the input 3D point(s)
alt (float or list): altitude(s) of the input 3D point(s)
Returns:
float or list: horizontal image coordinate(s) (column index, ie x)
float or list: vertical image coordinate(s) (row index, ie y)
"""
nlon = (np.asarray(lon) - self.lon_offset) / self.lon_scale
nlat = (np.asarray(lat) - self.lat_offset) / self.lat_scale
nalt = (np.asarray(alt) - self.alt_offset) / self.alt_scale
col = apply_rfm(self.col_num, self.col_den, nlat, nlon, nalt)
row = apply_rfm(self.row_num, self.row_den, nlat, nlon, nalt)
col = col * self.col_scale + self.col_offset
row = row * self.row_scale + self.row_offset
return col, row
def localization(self, col, row, alt, return_normalized=False):
"""
Convert image coordinates plus altitude into geographic coordinates.
反投影从图像坐标到地理坐标
Args:
col (float or list): x image coordinate(s) of the input point(s)
row (float or list): y image coordinate(s) of the input point(s)
alt (float or list): altitude(s) of the input point(s)
Returns:
float or list: longitude(s)
float or list: latitude(s)
"""
ncol = (np.asarray(col) - self.col_offset) / self.col_scale
nrow = (np.asarray(row) - self.row_offset) / self.row_scale
nalt = (np.asarray(alt) - self.alt_offset) / self.alt_scale
if not hasattr(self, 'lat_num'):
lon, lat = self.localization_iterative(ncol, nrow, nalt)
else:
lon = apply_rfm(self.lon_num, self.lon_den, nrow, ncol, nalt)
lat = apply_rfm(self.lat_num, self.lat_den, nrow, ncol, nalt)
if not return_normalized:
lon = lon * self.lon_scale + self.lon_offset
lat = lat * self.lat_scale + self.lat_offset
return lon, lat
def localization_iterative(self, col, row, alt):
"""
Iterative estimation of the localization function (image to ground),
for a list of image points expressed in image coordinates.
逆投影时的迭代函数
Args:
col, row: normalized image coordinates (between -1 and 1)
alt: normalized altitude (between -1 and 1) of the corresponding 3D
point
Returns:
lon, lat: normalized longitude and latitude
Raises:
MaxLocalizationIterationsError: if the while loop exceeds the max
number of iterations, which is set to 100.
"""
# target point: Xf (f for final)
Xf = np.vstack([col, row]).T
# use 3 corners of the lon, lat domain and project them into the image
# to get the first estimation of (lon, lat)
# EPS is 2 for the first iteration, then 0.1.
lon = -col ** 0 # vector of ones
lat = -col ** 0
EPS = 2
x0 = apply_rfm(self.col_num, self.col_den, lat, lon, alt)
y0 = apply_rfm(self.row_num, self.row_den, lat, lon, alt)
x1 = apply_rfm(self.col_num, self.col_den, lat, lon + EPS, alt)
y1 = apply_rfm(self.row_num, self.row_den, lat, lon + EPS, alt)
x2 = apply_rfm(self.col_num, self.col_den, lat + EPS, lon, alt)
y2 = apply_rfm(self.row_num, self.row_den, lat + EPS, lon, alt)
n = 0
while not np.all((x0 - col) ** 2 + (y0 - row) ** 2 < 1e-18):
if n > 100:
raise MaxLocalizationIterationsError("Max localization iterations (100) exceeded")
X0 = np.vstack([x0, y0]).T
X1 = np.vstack([x1, y1]).T
X2 = np.vstack([x2, y2]).T
e1 = X1 - X0
e2 = X2 - X0
u = Xf - X0
# project u on the base (e1, e2): u = a1*e1 + a2*e2
# the exact computation is given by:
# M = np.vstack((e1, e2)).T
# a = np.dot(np.linalg.inv(M), u)
# but I don't know how to vectorize this.
# Assuming that e1 and e2 are orthogonal, a1 is given by
# <u, e1> / <e1, e1>
num = np.sum(np.multiply(u, e1), axis=1)
den = np.sum(np.multiply(e1, e1), axis=1)
a1 = np.divide(num, den).squeeze()
num = np.sum(np.multiply(u, e2), axis=1)
den = np.sum(np.multiply(e2, e2), axis=1)
a2 = np.divide(num, den).squeeze()
# use the coefficients a1, a2 to compute an approximation of the
# point on the gound which in turn will give us the new X0
lon += a1 * EPS
lat += a2 * EPS
# update X0, X1 and X2
EPS = .1
x0 = apply_rfm(self.col_num, self.col_den, lat, lon, alt)
y0 = apply_rfm(self.row_num, self.row_den, lat, lon, alt)
x1 = apply_rfm(self.col_num, self.col_den, lat, lon + EPS, alt)
y1 = apply_rfm(self.row_num, self.row_den, lat, lon + EPS, alt)
x2 = apply_rfm(self.col_num, self.col_den, lat + EPS, lon, alt)
y2 = apply_rfm(self.row_num, self.row_den, lat + EPS, lon, alt)
n += 1
return lon, lat
#############################################
# 校正影像 输出影像转换表
#############################################
"""
[pool.putRequest(req) for req in requests]等同于
  for req in requests:
     pool.putRequest(req)
"""
def rpc_row_col(params):
rpc_mdl,r_block,c_block,ati_block,i,block_shape=params
r_block ,c_block = rpc_mdl.localization(r_block,c_block,0)
print("\t{}\t".format(i))
return [i,r_block ,c_block,block_shape]
def get_RPC_lon_lat(in_rpc_tiff,out_rpc_rc_path):
exe_path=r".\baseTool\x64\Release\SIMOrthoProgram.exe"
exe_cmd=r"set PROJ_LIB=.\baseTool\x64\Release; & {0} {1} {2} {3} ".format(exe_path,8,in_rpc_tiff,out_rpc_rc_path)
print(exe_cmd)
print(os.system(exe_cmd))
print("==========================================================================")
def getRCImageRC2(inputPath,out_rpc_rc_path):
#shutil.copy2(inputPath, out_rpc_rc_path)
# 创建重采样输出文件(设置投影及六参数)
input_rpc_sar=gdal.Open(inputPath)
driver = gdal.GetDriverByName('GTiff')
output = driver.Create(out_rpc_rc_path, input_rpc_sar.RasterXSize,input_rpc_sar.RasterYSize, 2,gdal.GDT_Float32)
output.SetGeoTransform(list(input_rpc_sar.GetGeoTransform()))
output.SetProjection(input_rpc_sar.GetProjection())
# 参数说明 输入数据集、输出文件、输入投影、参考投影、重采样方法(最邻近内插\双线性内插\三次卷积等)、回调函数
rpc_rc_img=output
# 计算行列号
rc_height=rpc_rc_img.RasterYSize
rc_width=rpc_rc_img.RasterXSize
for i in range(0,rc_height,100):
c_block=np.ones((100,rc_width)).astype(np.float32)*(np.array(list(range(rc_width))).reshape(1,rc_width))
r_block=np.ones((100,rc_width)).astype(np.float32)*(np.array(list(range(100))).reshape(100,1))
r_block=r_block+i
if rc_height-i>100:
rpc_rc_img.GetRasterBand(1).WriteArray(r_block.astype(np.float32),0,i)
rpc_rc_img.GetRasterBand(2).WriteArray(c_block.astype(np.float32),0,i)
else:
num=rc_height-i
rpc_rc_img.GetRasterBand(1).WriteArray(r_block[:num,:].astype(np.float32),0,i)
rpc_rc_img.GetRasterBand(2).WriteArray(c_block[:num,:].astype(np.float32),0,i)
del rpc_rc_img,output,input_rpc_sar
def getRCImageRC(inputPath,out_rpc_rc_path,rpc_file_path):
rpc_tool = read_rpc_file(rpc_file_path)
#shutil.copy2(inputPath, out_rpc_rc_path)
# 创建重采样输出文件(设置投影及六参数)
input_rpc_sar=gdal.Open(inputPath)
driver = gdal.GetDriverByName('GTiff')
output = driver.Create(out_rpc_rc_path, input_rpc_sar.RasterXSize,input_rpc_sar.RasterYSize, 2,gdal.GDT_Float32)
output.SetGeoTransform(list(input_rpc_sar.GetGeoTransform()))
output.SetProjection(input_rpc_sar.GetProjection())
# 参数说明 输入数据集、输出文件、输入投影、参考投影、重采样方法(最邻近内插\双线性内插\三次卷积等)、回调函数
rpc_rc_img=output
# 计算行列号
rc_height=rpc_rc_img.RasterYSize
rc_width=rpc_rc_img.RasterXSize
with Pool(8) as t:
plist=[]
for i in range(0,rc_height,1000):
c_block=np.ones((1000,rc_width)).astype(np.float32)*(np.array(list(range(rc_width))).reshape(1,rc_width))
r_block=np.ones((1000,rc_width)).astype(np.float32)*(np.array(list(range(1000))).reshape(1000,1))
r_block=r_block+i
if not rc_height-i>1000:
num=rc_height-i
r_block=r_block[:num,:].astype(np.float32)
c_block=c_block[:num,:].astype(np.float32)
block_shape=r_block.shape
plist.append(t.apply_async(rpc_row_col,args=([rpc_tool,r_block.reshape(-1).astype(np.int32),c_block.reshape(-1).astype(np.int32) ,c_block.reshape(-1)*0+0,i,block_shape],)))
t.close()
t.join()
for future in plist:
data = future.get()
i,r_block ,c_block,block_shape=data
rpc_rc_img.GetRasterBand(1).WriteArray(r_block.reshape(block_shape).astype(np.float32),0,i)
rpc_rc_img.GetRasterBand(2).WriteArray(c_block.reshape(block_shape).astype(np.float32),0,i)
del rpc_rc_img,output,input_rpc_sar
""" RPC 结束 """
class SatelliteOrbit(object):
def __init__(self) -> None:
super().__init__()
self.starttime = 1262275200.0
self.modelName=""
def get_starttime(self):
'''
返回卫星轨道时间起算点
'''
return self.starttime
def ReconstructionSatelliteOrbit(self, GPSPoints_list):
'''
重建卫星轨道使用多项式拟合法
args:
GPSPoints_list:GPS 卫星轨道点
return
SatelliteOrbitModel 卫星轨道模型
'''
self.SatelliteOrbitModel = None
def SatelliteSpaceState(self, time_float):
'''
根据时间戳返回对应时间的卫星的轨迹状态
args:
time_float:时间戳
return
State_list:[time,Xp,Yp,Zp,Vx,Vy,Vz]
'''
return None
class SatelliteOrbitFitPoly(SatelliteOrbit):
'''
继承于SatelliteOribit类为拟合多项式实现方法
'''
def __init__(self) -> None:
super().__init__()
self.modelName="多项式"
self.polynum=4
def ReconstructionSatelliteOrbit(self, GPSPoints_list, starttime):
if len(GPSPoints_list)==2:
self.polynum=1
self.starttime = starttime
record_count = len(GPSPoints_list)
time_arr = np.zeros((record_count, 1), dtype=np.float64) # 使用np.float64只是为了精度高些如果32位也能满足需求请用32位
state_arr = np.zeros((record_count, 6), dtype=np.float64)
A_arr = np.zeros((self.polynum+1, 6), dtype=np.float64) # 四次项
X=np.ones((record_count,self.polynum+1),dtype=np.float64) # 记录时间坐标
# 将点记录转换为自变量矩阵、因变量矩阵
for i in range(record_count):
GPSPoint = GPSPoints_list[i]
time_ = GPSPoint[0] - self.starttime # 为了保证精度,对时间进行缩放
X[i,:]=np.array([1,time_])
state_arr[i, :] = np.array(GPSPoint[1:],dtype=np.float64).reshape(1,6) # 空间坐标
self.model_f=[]
for i in range(6):
Y = state_arr[:, i].reshape(-1,1)
A_arr[:,i]=np.matmul(np.matmul(np.linalg.inv(np.matmul(X.T,X)),X.T),Y)[:,0]
self.A_arr=copy.deepcopy(A_arr.copy())
return self.A_arr
elif len(GPSPoints_list) > 6:
self.polynum=4
# 多项式的节点数理论上是超过5个可以起算这里为了精度选择10个点起算。
# 多项式 XA=Y ==> A=(X'X)^X'Y其中 A 为待求系数X为变量Y为因变量
# 这里使用三次项多项式共有6组参数。
# 声明自变量,因变量,系数矩阵
self.starttime = starttime
record_count = len(GPSPoints_list)
time_arr = np.zeros((record_count, 1), dtype=np.float64) # 使用np.float64只是为了精度高些如果32位也能满足需求请用32位
state_arr = np.zeros((record_count, 6), dtype=np.float64)
A_arr = np.zeros((self.polynum+1, 6), dtype=np.float64) # 四次项
X=np.ones((record_count,self.polynum+1),dtype=np.float64) # 记录时间坐标
# 将点记录转换为自变量矩阵、因变量矩阵
for i in range(record_count):
GPSPoint = GPSPoints_list[i]
time_ = GPSPoint[0] - self.starttime # 为了保证精度,对时间进行缩放
X[i,:]=np.array([1,time_,time_**2,time_**3,time_**4])
state_arr[i, :] = np.array(GPSPoint[1:],dtype=np.float64).reshape(1,6) # 空间坐标
self.model_f=[]
for i in range(6):
Y = state_arr[:, i].reshape(-1,1)
A_arr[:,i]=np.matmul(np.matmul(np.linalg.inv(np.matmul(X.T,X)),X.T),Y)[:,0]
self.A_arr=copy.deepcopy(A_arr.copy())
''' 测试误差
from matplotlib import pyplot
label_list=['x','y','z','vx','vy','vz']
color_list=['r','g','b','gold','gray','pink']
pyplot.figure()
for i in range(6):
Y = state_arr[:, i]
Y_predict=self.model_f[i](X)
pyplot.subplot(int("23{}".format(i+1)))
d=Y-Y_predict
pyplot.plot(X,d,label=label_list[i],color=color_list[i])
pyplot.title("max:{}".format(np.max(d)))
#self.model_f.append(interpolate.interp1d(X,Y,kind='cubic',fill_value='extrapolate'))
pyplot.legend()
pyplot.show()
'''
return self.A_arr
else:
self.A_arr = None
return None
def SatelliteSpaceState(self, time_float):
'''
逐像素求解
根据时间戳返回对应时间的卫星的轨迹状态会自动计算与起算时间之差
args:
time_float:时间戳
return
State_list:[time,Xp,Yp,Zp,Vx,Vy,Vz]
'''
if self.model_f is None:
return None
result_arr=np.zeros((1,7))
time_float = time_float - self.starttime
result_arr[0,0]=time_float
#time_arr[0, 4] = time_arr[0, 3] * time_float ** 4
time_float=np.array([1,time_float,time_float**2,time_float**3,time_float**4]).reshape(1,5)
result_arr=np.matmul(time_float,self.A_arr)
return [time_float,result_arr]
def getSatelliteSpaceState(self, time_array):
'''
矩阵求解
根据时间戳矩阵返回对应时刻的卫星空间状态位置速度且会自动计算与起算时间之差
args:
time_array:nparray nx1 时间戳
return:
SatellitSpaceStateArray:nparray nx6 状态信息
'''
if self.model_f is None:
return None # 返回None,表示没有结果
if self.polynum==4:
n=time_array.shape[0]
result_arr_=np.zeros((n,6),dtype=np.float64)
time_float = time_array - self.starttime
time_float=time_float.reshape(-1) # nx1
time_arr=np.ones((time_float.shape[0],5)) # nx5
time_arr[:,1]=time_float
time_arr[:,2]=time_float**2
time_arr[:,3]=time_float**3
time_arr[:,4]=time_float**4
result_arr_=np.matmul(time_arr,self.A_arr) # nx5 5x6
#time_arr[0, 4] = time_arr[0, 3] * time_float ** 4
#result_arr=result_arr_
return result_arr_ # 位置矩阵
else:
n=time_array.shape[0]
result_arr_=np.zeros((n,6),dtype=np.float64)
time_float = time_array - self.starttime
time_float=time_float.reshape(-1) # nx1
time_arr=np.ones((time_float.shape[0],self.polynum+1)) # nx5
time_arr[:,1]=time_float
result_arr_=np.matmul(time_arr,self.A_arr) # nx5 5x6
#time_arr[0, 4] = time_arr[0, 3] * time_float ** 4
#result_arr=result_arr_
return result_arr_ # 位置矩阵
def ReconstructionSatelliteOrbit(GPSPoints_list, starttime):
'''
构建卫星轨道
args:
GPSPoints_list:卫星轨道点
starttime:起算时间
'''
if len(GPSPoints_list) > 10:
SatelliteOrbitModel = SatelliteOrbitFitPoly()
if SatelliteOrbitModel.ReconstructionSatelliteOrbit(GPSPoints_list, starttime=starttime) is None:
return None
return SatelliteOrbitModel
elif len(GPSPoints_list)==2:
SatelliteOrbitModel = SatelliteOrbitFitPoly()
if SatelliteOrbitModel.ReconstructionSatelliteOrbit(GPSPoints_list, starttime=starttime) is None:
return None
return SatelliteOrbitModel
class DEMProcess(object):
def __init__(self):
pass
@staticmethod
def get_extent(fn):
'''
原文链接https://blog.csdn.net/XBR_2014/article/details/85255412
'''
ds = gdal.Open(fn)
rows = ds.RasterYSize
cols = ds.RasterXSize
# 获取图像角点坐标
gt = ds.GetGeoTransform()
minx = gt[0]
maxy = gt[3]
maxx = gt[0] + gt[1] * rows
miny = gt[3] + gt[5] * cols
return (minx, maxy, maxx, miny)
@staticmethod
def img_mosaic(in_files, out_dem_path):
# 通过两两比较大小,将最终符合条件的四个角点坐标保存
# 即为拼接图像的四个角点坐标
minX, maxY, maxX, minY = DEMProcess.get_extent(in_files[0])
for fn in in_files[1:]:
minx, maxy, maxx, miny = DEMProcess.get_extent(fn)
minX = min(minX, minx)
maxY = max(maxY, maxy)
maxX = max(maxX, maxx)
minY = min(minY, miny)
# 获取输出图像的行列数
in_ds = gdal.Open(in_files[0])
bands_num = in_ds.RasterCount
gt = in_ds.GetGeoTransform()
rows = int((maxX - minX) / abs(gt[5]))
cols = int((maxY - minY) / gt[1])
# 判断栅格数据的数据类型
datatype = gdal.GDT_UInt16
# 创建输出图像
driver = gdal.GetDriverByName('GTiff')
out_dem = os.path.join(out_dem_path, 'mosaic0.tif')
out_ds = driver.Create(out_dem, cols, rows, bands_num, datatype)
out_ds.SetProjection(in_ds.GetProjection())
gt = list(in_ds.GetGeoTransform())
gt[0], gt[3] = minX, maxY
out_ds.SetGeoTransform(gt)
for fn in in_files:
in_ds = gdal.Open(fn)
x_size = in_ds.RasterXSize
y_size = in_ds.RasterYSize
trans = gdal.Transformer(in_ds, out_ds, [])
success, xyz = trans.TransformPoint(False, 0, 0)
x, y, z = map(int, xyz)
for i in range(1, bands_num + 1):
data = in_ds.GetRasterBand(i).ReadAsArray()
out_band = out_ds.GetRasterBand(i)
out_data = out_band.ReadAsArray(x, y, x_size, y_size)
data = np.maximum(data, out_data)
out_band.WriteArray(data, x, y)
del in_ds, out_band, out_ds
@staticmethod
def dem_clip(OutFilePath, DEMFilePath, SelectArea):
'''
根据选择范围裁剪DEM,并输出
agrs:
outFilePath:裁剪DEM输出地址
DEMFilePath:被裁减DEM地址
SelectArea:list [(xmin,ymax),(xmax,ymin)] 框选范围 左上角右下角
'''
DEM_ptr = gdal.Open(DEMFilePath)
DEM_GeoTransform = DEM_ptr.GetGeoTransform() # 读取影像的投影变换
DEM_InvGeoTransform = gdal.InvGeoTransform(DEM_GeoTransform)
SelectAreaArrayPoints = [gdal.ApplyGeoTransform(DEM_InvGeoTransform, p[0], p[1]) for p in SelectArea]
SelectAreaArrayPoints = list(map(lambda p: (int(p[0]), int(p[1])), SelectAreaArrayPoints)) # 确定坐标
[(ulx, uly), (brx, bry)] = SelectAreaArrayPoints
rowCount, colCount = bry - uly, brx - ulx
# 输出DEM的桌面坐标转换
Out_Transfrom = list(DEM_GeoTransform)
Out_Transfrom[0] = SelectArea[0][0]
Out_Transfrom[3] = SelectArea[0][1]
# 构建输出DEM
Bands_num = DEM_ptr.RasterCount
gtiff_driver = gdal.GetDriverByName('GTiff')
datatype = gdal.GDT_UInt16
out_dem = gtiff_driver.Create(OutFilePath, colCount, rowCount, Bands_num, datatype)
out_dem.SetProjection(DEM_ptr.GetProjection())
out_dem.SetGeoTransform(Out_Transfrom)
for i in range(1, Bands_num + 1):
data_band = DEM_ptr.GetRasterBand(i)
out_band = out_dem.GetRasterBand(i)
data = data_band.ReadAsArray(ulx, uly, colCount, rowCount)
out_band.WriteArray(data)
del out_dem
@staticmethod
def dem_merged(in_dem_path, meta_file_path, out_dem_path):
'''
DEM重采样函数默认坐标系为WGS84
agrs:
in_dem_path: 输入的DEM文件夹路径
meta_file_path: 输入的xml元文件路径
out_dem_path: 输出的DEM文件夹路径
'''
# 读取文件夹中所有的DEM
dem_file_paths=[os.path.join(in_dem_path,dem_name) for dem_name in os.listdir(in_dem_path) if dem_name.find(".tif")>=0 and dem_name.find(".tif.")==-1]
spatialreference=osr.SpatialReference()
spatialreference.SetWellKnownGeogCS("WGS84") # 设置地理坐标,单位为度 degree # 设置投影坐标,单位为度 degree
spatialproj=spatialreference.ExportToWkt() # 导出投影结果
# 将DEM拼接成一张大图
mergeFile =gdal.BuildVRT(os.path.join(out_dem_path,"mergedDEM_VRT.tif"),dem_file_paths)
out_DEM=os.path.join(out_dem_path,"mergedDEM.tif")
gdal.Warp(out_DEM,
mergeFile,
format="GTiff",
dstSRS=spatialproj,
dstNodata=-9999,
outputType=gdal.GDT_Float32)
time.sleep(3)
#gdal.CloseDir(out_DEM)
return out_DEM
@staticmethod
def dem_resampled(in_dem_path,out_dem_path,samling_f):
in_dem=gdal.Open(in_dem_path,gdalconst.GA_ReadOnly)
width=in_dem.RasterXSize
height=in_dem.RasterYSize
gt=list(in_dem.GetGeoTransform())
width=width*samling_f
height=height*samling_f
gt=[gt[0],gt[1]/samling_f,gt[2]/samling_f,gt[3],gt[4]/samling_f,gt[5]/samling_f]
driver = gdal.GetDriverByName('GTiff')
output = driver.Create(out_dem_path, width,height, 1,in_dem.GetRasterBand(1).DataType)
output.SetGeoTransform(gt)
output.SetProjection(in_dem.GetProjection())
# 参数说明 输入数据集、输出文件、输入投影、参考投影、重采样方法(最邻近内插\双线性内插\三次卷积等)、回调函数
gdal.ReprojectImage(in_dem, output, in_dem.GetProjection(), output.GetProjection(), gdalconst.GRA_CubicSpline,0.0,0.0,)
return out_dem_path
@staticmethod
def dem_resampled_RPC(in_dem_path,refrence_img_path,out_dem_path):
in_dem=gdal.Open(in_dem_path,gdalconst.GA_ReadOnly)
refrence_img=gdal.Open(refrence_img_path,gdalconst.GA_ReadOnly)
width=refrence_img.RasterXSize
height=refrence_img.RasterYSize
gt=list(refrence_img.GetGeoTransform())
driver = gdal.GetDriverByName('GTiff')
output = driver.Create(out_dem_path, width,height, 1,in_dem.GetRasterBand(1).DataType)
output.SetGeoTransform(gt)
output.SetProjection(refrence_img.GetProjection())
# 参数说明 输入数据集、输出文件、输入投影、参考投影、重采样方法(最邻近内插\双线性内插\三次卷积等)、回调函数
gdal.ReprojectImage(in_dem, output, in_dem.GetProjection(), output.GetProjection(), gdalconst.GRA_CubicSpline,0.0,0.0,)
return out_dem_path
# referencefile = gdal.Open(referencefilefilePath, gdal.GA_ReadOnly)
# referencefileProj = referencefile.GetProjection()
# referencefileTrans = referencefile.GetGeoTransform()
# bandreferencefile = referencefile.GetRasterBand(1)
# Width= referencefile.RasterXSize
# Height = referencefile.RasterYSize
# nbands = referencefile.RasterCount
# # 创建重采样输出文件(设置投影及六参数)
# driver = gdal.GetDriverByName('GTiff')
# output = driver.Create(outputfilePath, Width,Height, nbands, bandreferencefile.DataType)
# output.SetGeoTransform(referencefileTrans)
# output.SetProjection(referencefileProj)
# # 参数说明 输入数据集、输出文件、输入投影、参考投影、重采样方法(最邻近内插\双线性内插\三次卷积等)、回调函数
# gdal.ReprojectImage(inputrasfile, output, inputProj, referencefileProj, gdalconst.GRA_Bilinear,0.0,0.0,)
class Orthorectification(object):
"""
正射校正模块类
"""
def __init__(self, configPath="./config.ymal") -> None:
super().__init__()
# 常量声明
# 加载配置文件
d=os.listdir(".")
with open(configPath, 'r', encoding='utf-8') as f:
const = f.read()
self.config = yaml.load(const, Loader=yaml.FullLoader)
self.config['SatelliteOribit']['StartTime'] = datetime.datetime.strptime(
self.config['SatelliteOribit']['StartTime']['Value'],
self.config['SatelliteOribit']['StartTime']['format']).timestamp() # 转化成UTC时间格式
self.R_e = self.config['SatelliteOribit']['ReferenceSpheroid']['Re'] # m
self.R_p = self.config['SatelliteOribit']['ReferenceSpheroid']['Rp'] # m
self.w_e = self.config['SatelliteOribit']['ReferenceSpheroid']['we'] # rad/s
def ParseHearderFile(self, HeaderFilePath_str):
"""
解析头文件返回计算所需要的必要信息
args:
HeaderFilePath_str: 头文件地址
return:
HeaderFileInfomation_json: 头文件信息包
"""
with open(HeaderFilePath_str, 'r', encoding='utf-8') as fp:
HeaderFile_dom_str = fp.read()
HeaderFile_dom = xmltodict.parse(HeaderFile_dom_str) # 将XML转成json文本
HeaderFile_dom_json = json.loads(json.dumps(HeaderFile_dom)) # 将json字符串转成json对象对应于python中的dict
# 获取头文件
HeaderInformation_json = {}
# 解析轨道节点假定是GPS节点
LightSpeed = self.config['LightSpeed']
HeaderInformation_json['GPS'] = []
# GPS 解析信息
GPSNode_Path = self.config['GPS']['GPSNode_Path']
GPSNodeNames_list = self.config['GPS']['NodeInfomation_Name']
GPSTime_Format = self.config['GPS']['Time_format']
GPSPoints = FindInfomationFromJson(HeaderFile_dom_json, GPSNode_Path)
for GPSPoint in GPSPoints:
GPSPoint = [
datetime.datetime.strptime(GPSPoint[GPSNodeNames_list[0]], GPSTime_Format).timestamp(), # TimeStamp
float(GPSPoint[GPSNodeNames_list[1]]), # Xp
float(GPSPoint[GPSNodeNames_list[2]]), # Yp
float(GPSPoint[GPSNodeNames_list[3]]), # Zp
float(GPSPoint[GPSNodeNames_list[4]]), # Vx
float(GPSPoint[GPSNodeNames_list[5]]), # Vy
float(GPSPoint[GPSNodeNames_list[6]])] # VZ
HeaderInformation_json['GPS'].append(GPSPoint)
# 提取成像相关信息
HeaderInformation_json['ImageInformation'] = {}
# 1、开始成像时间
HeaderInformation_json['ImageInformation']['StartTime'] = datetime.datetime.strptime(
FindInfomationFromJson(HeaderFile_dom_json, self.config['imageinfo']['StartImageTime']['NodePath']),
self.config['imageinfo']['StartImageTime']['Format']
).timestamp()
# 2、结束成像时间
HeaderInformation_json['ImageInformation']['EndTime'] = datetime.datetime.strptime(
FindInfomationFromJson(HeaderFile_dom_json, self.config['imageinfo']['EndImageTime']['NodePath']),
self.config['imageinfo']['StartImageTime']['Format']
).timestamp()
# 3、影像的宽高
HeaderInformation_json['ImageInformation']['height'] = int(
FindInfomationFromJson(HeaderFile_dom_json, self.config['imageinfo']['ImageHeight']['NodePath']))
HeaderInformation_json['ImageInformation']['width'] = int(
FindInfomationFromJson(HeaderFile_dom_json, self.config['imageinfo']['ImageWidth']['NodePath']))
# 方位,距离分辨率
HeaderInformation_json['ImageInformation']['Groundspace'] = float(
FindInfomationFromJson(HeaderFile_dom_json, self.config['imageinfo']['Groundspace']['NodePath']))
HeaderInformation_json['ImageInformation']['Azspace'] = float(
FindInfomationFromJson(HeaderFile_dom_json, self.config['imageinfo']['Azspace']['NodePath']))
# 4、影像的近斜距
NearRange = float(FindInfomationFromJson(HeaderFile_dom_json, self.config['imageinfo']['NearRange']['NodePath']))
NearRange = NearRange * LightSpeed / 2
HeaderInformation_json['ImageInformation']['NearRange'] = float(NearRange)
FarRange = float(FindInfomationFromJson(HeaderFile_dom_json, self.config['imageinfo']['FarRange']['NodePath']))
FarRange = FarRange * LightSpeed / 2
# 远斜距
HeaderInformation_json['ImageInformation']['FarRange'] = float(FarRange)
# 5、入射角
# HeaderInformation_json['ImageInformation']['incidenceAngle'] = {
# 'NearRange': float(FindInfomationFromJson(HeaderFile_dom_json,
# self.config['imageinfo']['incidenceAngle']['NearRange'][
# 'NodePath'])),
# 'FarRange': float(FindInfomationFromJson(HeaderFile_dom_json,
# self.config['imageinfo']['incidenceAngle']['FarRange'][
# 'NodePath']))
# }
# 6、成像时刻影像带宽
# HeaderInformation_json['ImageInformation']['bandWidth'] = float(
# FindInfomationFromJson(HeaderFile_dom_json, self.config['sensor']['bandWidth']['NodePath']))
# 7、多普勒质心常数
# DopplerCentroidCoefficients_list = FindInfomationFromJson(HeaderFile_dom_json, self.config['imageinfo'][
# 'DopplerCentroidCoefficients']['NodePath'])
# HeaderInformation_json['ImageInformation']['DopplerCentroidCoefficients'] = [
# float(DopplerCentroidCoefficients_list[
# self.config['imageinfo']['DopplerCentroidCoefficients']['DopplerCentroidCoefficients_Name'][0]]),
# float(DopplerCentroidCoefficients_list[
# self.config['imageinfo']['DopplerCentroidCoefficients']['DopplerCentroidCoefficients_Name'][1]]),
# float(DopplerCentroidCoefficients_list[
# self.config['imageinfo']['DopplerCentroidCoefficients']['DopplerCentroidCoefficients_Name'][2]]),
# float(DopplerCentroidCoefficients_list[
# self.config['imageinfo']['DopplerCentroidCoefficients']['DopplerCentroidCoefficients_Name'][3]]),
# float(DopplerCentroidCoefficients_list[
# self.config['imageinfo']['DopplerCentroidCoefficients']['DopplerCentroidCoefficients_Name'][4]]),
# ]
# 8、波长
CenterFrequency = float(FindInfomationFromJson(HeaderFile_dom_json, self.config['imageinfo']['CenterFrequency']['NodePath']))
HeaderInformation_json['ImageInformation']['lambda'] = float(LightSpeed / CenterFrequency)
# 9、中心像元对应的中心经纬度
# CenterPoint = FindInfomationFromJson(HeaderFile_dom_json,
# self.config['imageinfo']['CenterImagePositon']['NodePath'])
# HeaderInformation_json['ImageInformation']['centerPosition'] = [
# float(CenterPoint[self.config['imageinfo']['CenterImagePositon']['Value'][0]]), # 纬度
# float(CenterPoint[self.config['imageinfo']['CenterImagePositon']['Value'][1]]), # 经度
# ]
# 10、多普勒参数参考时间
HeaderInformation_json['ImageInformation']['DopplerParametersReferenceTime'] = float(
FindInfomationFromJson(HeaderFile_dom_json,
self.config['imageinfo']['DopplerParametersReferenceTime']['NodePath']))
# 多普勒Rate
DopplerRates = FindInfomationFromJson(HeaderFile_dom_json, self.config['imageinfo']['DopplerRate']['NodePath'])
DopplerRate = []
for doppler in DopplerRates:
DopplerRate.append(doppler.get('#text'))
HeaderInformation_json['ImageInformation']['DopplerRate'] = DopplerRate
# 11、参考斜距
# HeaderInformation_json['ImageInformation']['refRange'] = float(
# FindInfomationFromJson(HeaderFile_dom_json, self.config['imageinfo']['ReferenceRange']['NodePath']))
ImageHeight = int(FindInfomationFromJson(HeaderFile_dom_json, self.config['imageinfo']['ImageHeight']['NodePath']))
StartImageTime = datetime.datetime.strptime(
FindInfomationFromJson(HeaderFile_dom_json, self.config['imageinfo']['StartImageTime']['NodePath']),
self.config['imageinfo']['StartImageTime']['Format']).timestamp()
EndImageTime = datetime.datetime.strptime(
FindInfomationFromJson(HeaderFile_dom_json, self.config['imageinfo']['EndImageTime']['NodePath']),
self.config['imageinfo']['StartImageTime']['Format']).timestamp()
lastpixeltime=float(FindInfomationFromJson(HeaderFile_dom_json, self.config['imageinfo']['FarRange']['NodePath']))
firstpixeltime=float(FindInfomationFromJson(HeaderFile_dom_json, self.config['imageinfo']['NearRange']['NodePath']))
eqvFs = ((ImageHeight - 2)/(lastpixeltime - firstpixeltime))/2
# 12、PRF
# HeaderInformation_json['PRF'] = float(
# FindInfomationFromJson(HeaderFile_dom_json, self.config['sensor']['PRF']['NodePath']))
HeaderInformation_json['PRF'] = float((ImageHeight-2)/(EndImageTime-StartImageTime)) # eqvPRF
HeaderInformation_json['Fs'] = float(eqvFs) # FindInfomationFromJson(HeaderFile_dom_json, self.config['sensor']['Fs']['NodePath'])
# 13、中心时间
HeaderInformation_json['ImageInformation']['CenterTime'] = (EndImageTime + StartImageTime)/2
# datetime.datetime.strptime(
# FindInfomationFromJson(HeaderFile_dom_json, self.config['imageinfo']['CenterImageTime']['NodePath']),
# self.config['imageinfo']['CenterImageTime']['Format']
# ).timestamp()
#14. 影像的空间间隔分辨率
HeaderInformation_json['ImageInformation']['ImageWidthSpace']=float(
FindInfomationFromJson(HeaderFile_dom_json, self.config['imageinfo']['ImageWidthSpace']['NodePath']).get('#text'))
HeaderInformation_json['ImageInformation']['ImageHeightSpace']=float(
FindInfomationFromJson(HeaderFile_dom_json, self.config['imageinfo']['ImageHeightSpace']['NodePath']).get('#text'))
# 部分需要解析
self.lamda=HeaderInformation_json['ImageInformation']['lambda']
self.PRF= HeaderInformation_json['PRF']
self.imgwidth=HeaderInformation_json['ImageInformation']['width']
self.imgheight=HeaderInformation_json['ImageInformation']['height']
self.imgstarttime=HeaderInformation_json['ImageInformation']['StartTime']
self.widthspace=HeaderInformation_json['ImageInformation']['ImageWidthSpace']
self.heightspace=HeaderInformation_json['ImageInformation']['ImageHeightSpace']
# self.refrangerefrange=HeaderInformation_json['ImageInformation']['refRange']
self.refrangerefrange=0
self.nearrange=HeaderInformation_json['ImageInformation']['NearRange']
self.Fs = HeaderInformation_json['Fs'] # Mhz todo
return HeaderInformation_json
pass
def LLA_to_XYZ(self, latitude, longitude, altitude):
"""
经纬度转大地坐标系
args:
latitude:纬度
longitude:经纬
altitude:海拔高程
refrence: https://blog.csdn.net/dulingwen/article/details/96868530
"""
# 经纬度的余弦值
cosLat = math.cos(latitude * math.pi / 180)
sinLat = math.sin(latitude * math.pi / 180)
cosLon = math.cos(longitude * math.pi / 180)
sinLon = math.sin(longitude * math.pi / 180)
# WGS84坐标系的参数
rad = 6378137.0 # 地球赤道平均半径椭球长半轴a
f = 1.0 / 298.257224 # WGS84椭球扁率 :f = (a-b)/a
C = 1.0 / math.sqrt(cosLat * cosLat + (1 - f) * (1 - f) * sinLat * sinLat)
S = (1 - f) * (1 - f) * C
h = altitude
# 计算XYZ坐标
X = (rad * C + h) * cosLat * cosLon
Y = (rad * C + h) * cosLat * sinLon
Z = (rad * S + h) * sinLat
return np.array([X, Y, Z]).reshape(1, 3)
def XYZ_to_LLA(self, X, Y, Z):
"""
大地坐标系转经纬度
适用于WGS84坐标系
args:
x,y,z
return:
lat,lon,altitude
"""
# WGS84坐标系的参数
a = 6378137.0 # 椭球长半轴
b = 6356752.314245 # 椭球短半轴
ea = np.sqrt((a ** 2 - b ** 2) / a ** 2)
eb = np.sqrt((a ** 2 - b ** 2) / b ** 2)
p = np.sqrt(X ** 2 + Y ** 2)
theta = np.arctan2(Z * a, p * b)
# 计算经纬度及海拔
longitude = np.arctan2(Y, X)
latitude = np.arctan2(Z + eb ** 2 * b * np.sin(theta) ** 3, p - ea ** 2 * a * np.cos(theta) ** 3)
N = a / np.sqrt(1 - ea ** 2 * np.sin(latitude) ** 2)
altitude = p / np.cos(latitude) - N
return np.array([np.degrees(latitude), np.degrees(longitude), altitude])
def getRByColumnCode(self, c):
"""
根据列号计算斜距
args:
c: 列号
"""
return self.R0 + c * self.delta_R
pass
def getTimeByLineCode(self, r):
"""
根据行号计算成像时间
args:
r: 行号
"""
return np.matmul(
np.concatenate([np.array([r ** i]).reshape(1, 1) for i in range(self.r2t_A_arr.shape[0])], axis=1),
self.r2t_A_arr)
def ReconstuctionTimesOflyDirectionPositionModel(self, timePoints_list):
"""
构建飞行向坐标与时间的转换模型,注意这里没有调整时间的起算点
args:
timePoints_list:时间点坐标 [r,t]
"""
# 根据点数确定模型最高为3次项模型
Y = np.zeros((len(timePoints_list), 1))
X = np.zeros((len(timePoints_list), 1))
for i in range(len(timePoints_list)):
Y[i, 0] = timePoints_list[i][1]
X[i, 0] = timePoints_list[i][0]
if len(timePoints_list) == 2: # 一次项
X = np.concatenate([np.ones((len(timePoints_list), 1)), X], axis=1)
A = np.matmul(np.matmul(np.linalg.inv(np.matmul(X.T, X)), X.T), Y)
elif len(timePoints_list) >= 3: # 二次项
X = np.concatenate([np.ones(len(timePoints_list), 1), X, np.power(X, 2)], axis=1)
A = np.matmul(np.matmul(np.linalg.inv(np.matmul(X.T, X)), X.T), Y)
elif len(timePoints_list) >= 8: # 三次项
X = np.concatenate([np.ones(len(timePoints_list), 1), X, np.power(X, 2), np.power(X, 3)], axis=1)
A = np.matmul(np.matmul(np.linalg.inv(np.matmul(X.T, X)), X.T), Y)
self.r2t_A_arr = A
def PrepareConvertSystem(self):
"""
计算常量
在数据计算之前提前处理部分常量信息
构建r,c到坐标斜距的计算公式
"""
self.R0 = self.header_info['ImageInformation']['NearRange'] # 起始斜距/近斜距
self.ReconstuctionTimesOflyDirectionPositionModel([
[0, self.header_info['ImageInformation']['StartTime']],
[self.header_info['ImageInformation']['height'] - 1, self.header_info['ImageInformation']['EndTime']]
]) # 构建坐标到时间的变换,这里仅用两个数据点构建
self.delta_R = self.widthspace
def ConvertCoordinary(self):
"""
批量求解点坐标
"""
pass
def Orthorectification(self, FilePath_str):
"""
正射校正组件
正射校正整体可以分为两个步骤
Step 1计算出栅格坐标对应的真实的大地坐标系坐标
Step 2根据大地坐标系将影像重采样到大地坐标系空间中
args:
FilePath_str:影像所在文件夹
"""
# 分离需要校正对象
file_name_list = os.listdir(FilePath_str)
header_name = [file_name for file_name in file_name_list if
file_name.rfind(".meta.xml") == len(file_name) - len('.meta.xml')][0] # xml头文件存储在list中
tiff_name = [file_name for file_name in file_name_list if
file_name.rfind(".tiff") == len(file_name) - len('.tiff')] # tif影像文件存储在list中
# 解析头文件
self.header_info = self.ParseHearderFile(os.path.join(FilePath_str, header_name))
# 构建轨道模型
self.SatelliteOrbitModel = ReconstructionSatelliteOrbit(self.header_info['GPS'],
starttime=self.config['SatelliteOribit']['StartTime'])
# 求解模型前计算常数变换模型
self.PrepareConvertSystem()
# 批量计算空间坐标
self.ConvertCoordinary()
'''
卫星轨道定位法修改为静态类
间接定法法模拟SAR方法的静态方法与类独立方便使用多进程
'''
def getSatelliteSpaceState(time_array,SatelliteOrbitModelstarttime,SatelliteOrbitModelParameters=None,SatelliteOrbitModelName="多项式"):
if SatelliteOrbitModelName=="多项式":
if SatelliteOrbitModelParameters is None:
return None # 返回None,表示没有结果
n=time_array.shape[0]
result_arr_=np.zeros((n,6),dtype=np.float64)
time_float = time_array - SatelliteOrbitModelstarttime
time_float=time_float.reshape(-1) # nx1
time_arr=np.ones((time_float.shape[0],5)) # nx5
time_arr[:,1]=time_float
time_arr[:,2]=time_float**2
time_arr[:,3]=time_float**3
time_arr[:,4]=time_float**4
result_arr_=np.matmul(time_arr,SatelliteOrbitModelParameters) # nx5 5x6
#time_arr[0, 4] = time_arr[0, 3] * time_float ** 4
#result_arr=result_arr_
return result_arr_ # 位置矩阵
'''
双线性重采样
'''
def LinearSampling(ori_dem,sampling_f,offset_row=1,offset_col=1):
'''
简化双线性重采样模型
根据重采样率对原始对象进行重采样
双线性重采样这里去栅格所涉及的四个角点作为起算点
模型示意图
y1 r1 y2
r
y3 r2 y4
args:
ori_dem:原始DEM
sampling_f:采样率 int
return:
new_dem:采样结果
'''
# 原始dem的行列号
ori_height=ori_dem.shape[0]-offset_row
ori_width=ori_dem.shape[1]-offset_col
# 采样之后的影像的范围大小
new_height=int(ori_height*sampling_f)
new_width=int(ori_width*sampling_f)
# 获取采样之后的栅格单元对应的原DEM的行列号
row_index_list=list(range(new_height))
col_index_list=list(range(new_width))
new_dem=np.ones((new_height,new_width))
row_index_arr=(new_dem.transpose(1,0)*row_index_list).transpose(1,0)
col_index_arr=new_dem*col_index_list
row_index_arr=row_index_arr*1.0/sampling_f
col_index_arr=col_index_arr*1.0/sampling_f
# 初始化
new_dem=0
# 计算权重
row_index_arr=row_index_arr.reshape(-1)
col_index_arr=col_index_arr.reshape(-1)
last_row_index_arr=np.floor(row_index_arr).astype(np.int32)
next_row_index_arr=np.ceil(row_index_arr).astype(np.int32)
last_col_index_arr=np.floor(col_index_arr).astype(np.int32)
next_col_index_arr=np.ceil(col_index_arr).astype(np.int32)
# 双线性重采样模型示意图,
# y1 r1 y2
#
# r
#
# y3 r2 y4
# 计算重采样
R1=ori_dem[last_row_index_arr,last_col_index_arr]*(col_index_arr-last_col_index_arr)+ori_dem[last_row_index_arr,next_col_index_arr]*(next_col_index_arr-col_index_arr)
R2=ori_dem[next_row_index_arr,last_col_index_arr]*(col_index_arr-last_col_index_arr)+ori_dem[next_row_index_arr,next_col_index_arr]*(next_col_index_arr-col_index_arr)
new_dem=R1*(row_index_arr-last_row_index_arr)+R2*(next_row_index_arr-row_index_arr) # 双线性重采样
new_dem=new_dem.reshape(new_height,new_width)
del R1,R2,next_row_index_arr,next_col_index_arr,last_row_index_arr,last_col_index_arr,row_index_arr,col_index_arr
result_dem=np.ones((new_height,new_width,3))
result_dem[:,:,2]=new_dem
result_dem[:,:,0]=(np.ones((new_height,new_width)).transpose(1,0)*list(range(new_height))).transpose(1,0)
result_dem[:,:,1]=np.ones((new_height,new_width))*col_index_list
return result_dem
pass
class IndirectOrthorectification(Orthorectification):
"""
间接定位法
"""
def outParameterText(self,outparameter_path):
'''
生成配置文件
'''
with open(outparameter_path,"w",encoding='utf-8') as fp:
# 输出文件
fp.write("{}\n".format(self.header_info['ImageInformation']['height']))
fp.write("{}\n".format(self.header_info['ImageInformation']['width']))
fp.write("{}\n".format(self.header_info['ImageInformation']['NearRange'])) # 近斜距
# fp.write("{}\n".format(self.header_info['ImageInformation']['incidenceAngle']['NearRange'])) # 近斜距入射角
# fp.write("{}\n".format(self.header_info['ImageInformation']['incidenceAngle']['FarRange'])) # 远距入射角
fp.write("{}\n".format(self.header_info['ImageInformation']['Groundspace']))
fp.write("{}\n".format(self.header_info['ImageInformation']['Azspace']))
fp.write("{}\n".format(self.config['LightSpeed'])) # 光速
fp.write("{}\n".format(self.header_info['ImageInformation']['lambda']))
fp.write("{}\n".format(self.header_info['ImageInformation']['StartTime']))
fp.write("{}\n".format(self.header_info['PRF']))
fp.write("{}\n".format(self.header_info['ImageInformation']['NearRange'])) # LT
fp.write("{}\n".format(self.Fs/2))
fp.write("{}\n".format(self.header_info['ImageInformation']['DopplerParametersReferenceTime']))
#fp.write("{}\n".format(self.widthspace))
# 多普勒系数
# fp.write("{}\n".format(len(self.header_info['ImageInformation']['DopplerCentroidCoefficients'])))
# for i in range(len(self.header_info['ImageInformation']['DopplerCentroidCoefficients'])):
# fp.write("{}\n".format(self.header_info['ImageInformation']['DopplerCentroidCoefficients'][i]))
fp.write("{}\n".format(len(self.header_info['ImageInformation']['DopplerRate'])))
for i in range(len(self.header_info['ImageInformation']['DopplerRate'])):
fp.write("{}\n".format(self.header_info['ImageInformation']['DopplerRate'][i]))
fp.write("{}\n".format(1))
fp.write("{}\n".format(self.SatelliteOrbitModel.polynum))
fp.write("{}\n".format(self.SatelliteOrbitModel.get_starttime()))
# X
for i in range(self.SatelliteOrbitModel.polynum+1):
fp.write("{}\n".format(self.SatelliteOrbitModel.A_arr[i,0]))
# Y
for i in range(self.SatelliteOrbitModel.polynum+1):
fp.write("{}\n".format(self.SatelliteOrbitModel.A_arr[i,1]))
# Z
for i in range(self.SatelliteOrbitModel.polynum+1):
fp.write("{}\n".format(self.SatelliteOrbitModel.A_arr[i,2]))
# Vx
for i in range(self.SatelliteOrbitModel.polynum+1):
fp.write("{}\n".format(self.SatelliteOrbitModel.A_arr[i,3]))
# Vy
for i in range(self.SatelliteOrbitModel.polynum+1):
fp.write("{}\n".format(self.SatelliteOrbitModel.A_arr[i,4]))
# vz
for i in range(self.SatelliteOrbitModel.polynum+1):
fp.write("{}\n".format(self.SatelliteOrbitModel.A_arr[i,5]))
# UTC参数
startTime=time.localtime(self.header_info['ImageInformation']["StartTime"])
fp.write("{}\n".format(startTime.tm_year))
fp.write("{}\n".format(startTime.tm_mon))
fp.write("{}".format(startTime.tm_mday))
self.paramterFile_path=outparameter_path
def IndirectOrthorectification(self, FilePath_str,workspace_dir):
"""
正射校正组件
正射校正整体可以分为两个步骤
Step 1计算出栅格坐标对应的真实的大地坐标系坐标
Step 2根据大地坐标系将影像重采样到大地坐标系空间中
args:
FilePath_str影像所在文件夹
dem_resampled_path重采样后的DEM路径
lut_tif_path输出的r,c,ti数据影像
work_temp_path: 输出的临时文件地址路径方便存放计算临时文件
"""
# 分离需要校正对象
file_name_list = os.listdir(FilePath_str)
header_name = [file_name for file_name in file_name_list if
file_name.rfind(".meta.xml") == len(file_name) - len('.meta.xml')][0] # 头文件
# 解析头文件
self.header_info = self.ParseHearderFile(os.path.join(FilePath_str, header_name))
# 构建轨道模型
self.SatelliteOrbitModel = ReconstructionSatelliteOrbit(self.header_info['GPS'],
starttime=self.header_info['ImageInformation']['CenterTime']) # 构建卫星轨道模型,取第0个节点的时间
# 获取所有轨道节点时间
gpslist=np.array(self.header_info['GPS']).reshape(-1,7)
# 验证轨道模型
statepoints=self.SatelliteOrbitModel.getSatelliteSpaceState(gpslist[:,0].reshape(-1))
# 计算轨道差距
statepoints_dist=statepoints-gpslist[:,1:]
statepoints_dist_line=statepoints_dist[:,:3]
statepoints_dist_line=np.sum(statepoints_dist_line**2,axis=1)**0.5
statepoints_dist_ver=np.sum(statepoints_dist[:,3:]**2,axis=1)**0.5
print("sata Point distance:\t{}\t -\t{}\t ".format(np.min(statepoints_dist_line),np.max(statepoints_dist_line)))
# 求解模型前计算常数变换模型
self.PrepareConvertSystem()
self.outParameterText(os.path.join(workspace_dir,"orth_para.txt"))
def preCaldem_sar_rc(self,dem_path,ori_sar_path,work_path,taget_path):
#.\SIMOrthoProgram\x64\Release\SIMOrthoProgram.exe 1 parameter_path dem_path ori_sar_path work_path taget_path
# SIMOrthoProgram.exe 1 in_parameter_path in_dem_path in_ori_sar_path in_work_path in_taget_path
exe_path=r".\baseTool\x64\Release\SIMOrthoProgram.exe"
exe_cmd=r"set PROJ_LIB=.\baseTool\x64\Release; & {0} {1} {2} {3} {4} {5} {6} {7}".format(exe_path,1,self.paramterFile_path,dem_path,ori_sar_path,work_path ,taget_path,"\\")
print(exe_cmd)
print(os.system(exe_cmd))
print("==========================================================================")
def getRPC_incidenceAngle(self,in_dem_path,in_rpc_rc_path,out_rpc_dem_path,out_incident_angle_path,out_local_incident_angle_path):
'''
std::cout << "mode 4: get RPC incident and local incident angle sar model:";
std::cout << "SIMOrthoProgram.exe 4 in_parameter_path in_dem_path in_rpc_rc_path out_rpc_dem_path out_incident_angle_path out_local_incident_angle_path";
'''
exe_path=r".\baseTool\x64\Release\SIMOrthoProgram.exe"
exe_cmd=r"set PROJ_LIB=.\baseTool\x64\Release; & {0} {1} {2} {3} {4} {5} {6} {7}".format(exe_path,4,self.paramterFile_path,in_dem_path,in_rpc_rc_path,out_rpc_dem_path,out_incident_angle_path,out_local_incident_angle_path)
print(exe_cmd)
print(os.system(exe_cmd))
print("==========================================================================")
def getRPC_incidenceAngle_lon_lat(self,in_dem_path,in_gec_lon_lat_path,work_path,taget_path,out_incident_angle_path,out_local_incident_angle_path,out_incangle_geo_path,out_localincangle_geo_path):
'''
std::cout << "mode 7: get RPC incident and local incident angle sar model:";
std::cout << "SIMOrthoProgram.exe 7 in_parameter_path in_dem_path in_gec_lon_lat_path work_path taget_path out_incident_angle_path out_local_incident_angle_path";
'''
cwd_path = os.getcwd()
print("cwd_path:" + cwd_path)
exe_path=r"{}\baseTool\x64\Release\SIMOrthoProgram.exe".format(cwd_path)
exe_cmd=r"set PROJ_LIB=.\baseTool\x64\Release; & {0} {1} {2} {3} {4} {5} {6} {7} {8} {9} {10}".format(exe_path,7,self.paramterFile_path,in_dem_path,in_gec_lon_lat_path,work_path,taget_path,out_incident_angle_path,out_local_incident_angle_path,out_incangle_geo_path,out_localincangle_geo_path)
print(exe_cmd)
print(os.system(exe_cmd))
print("==========================================================================")
def get_incidenceAngle(self,in_dem_path,in_rc_wgs84_path,out_incident_angle_path,out_local_incident_angle_path):
'''
std::cout << "mode 2: get incident angle and local incident angle by rc_wgs84 and dem and statellite model:\n";
std::cout << "SIMOrthoProgram.exe 2 in_parameter_path in_dem_path in_rc_wgs84_path out_incident_angle_path out_local_incident_angle_path";
'''
exe_path=r".\baseTool\x64\Release\SIMOrthoProgram.exe"
exe_cmd=r"set PROJ_LIB=.\baseTool\x64\Release; & {0} {1} {2} {3} {4} {5} {6}".format(exe_path,2,self.paramterFile_path,in_dem_path,in_rc_wgs84_path,out_incident_angle_path,out_local_incident_angle_path)
print(exe_cmd)
print(os.system(exe_cmd))
print("==========================================================================")
def get_GEC_incidenceAngle(self,in_dem_path,in_gec_lon_lat_path,out_incident_angle_path,out_local_incident_angle_path):
'''
std::cout << "mode 6: get gec incident and local incident angle sar model:";
std::cout << "SIMOrthoProgram.exe 6 in_parameter_path in_dem_path in_gec_lon_lat_path out_incident_angle_path out_local_incident_angle_path";
'''
exe_path=r".\baseTool\x64\Release\SIMOrthoProgram.exe"
exe_cmd=r"set PROJ_LIB=.\baseTool\x64\Release; & {0} {1} {2} {3} {4} {5} {6}".format(exe_path,6,self.paramterFile_path,in_dem_path,in_gec_lon_lat_path,out_incident_angle_path,out_local_incident_angle_path)
print(exe_cmd)
print(os.system(exe_cmd))
print("==========================================================================")
def get_GTC_SAR(self,in_rc_wgs84_path,in_ori_sar_path,out_orth_sar_path,modecode=3):
'''
std::cout << "mode 3: interpolation(cubic convolution) orth sar value by rc_wgs84 and ori_sar image and model:\n ";
std::cout << "SIMOrthoProgram.exe 3 in_parameter_path in_rc_wgs84_path in_ori_sar_path out_orth_sar_path";
'''
exe_path=r".\baseTool\x64\Release\SIMOrthoProgram.exe"
exe_cmd=r"set PROJ_LIB=.\baseTool\x64\Release; & {0} {1} {2} {3} {4} {5}".format(exe_path,modecode,self.paramterFile_path,in_rc_wgs84_path,in_ori_sar_path,out_orth_sar_path)
print(exe_cmd)
print(os.system(exe_cmd))
print("==========================================================================")
def inter_Range2Geo(self,lon_lat_path , data_tiff , grid_path , space):
'''
# std::cout << "mode 10";
# std::cout << "SIMOrthoProgram.exe 10 lon_lat_path data_tiff grid_path space";
'''
exe_path=r".\baseTool\x64\Release\SIMOrthoProgram.exe"
exe_cmd=r"set PROJ_LIB=.\baseTool\x64\Release; & {0} {1} {2} {3} {4} {5}".format(exe_path,10,lon_lat_path , data_tiff , grid_path , space)
print(exe_cmd)
print(os.system(exe_cmd))
print("==========================================================================")
def calInterpolation_cubic_Wgs84_rc_sar_sigma(self, parameter_path, dem_rc, in_sar, out_sar):
'''
# std::cout << "mode 10";
# std::cout << "SIMOrthoProgram.exe 9 in_parameter_path in_rc_wgs84_path in_ori_sar_path out_orth_sar_path";
'''
exe_path = r".\baseTool\x64\Release\SIMOrthoProgram.exe"
exe_cmd = r"set PROJ_LIB=.\baseTool\x64\Release; & {0} {1} {2} {3} {4} {5}".format(exe_path, 9, parameter_path,
dem_rc, in_sar, out_sar)
print(exe_cmd)
print(os.system(exe_cmd))
print("==========================================================================")
def calInterpolation_bil_Wgs84_rc_sar_sigma(self, parameter_path, dem_rc, in_sar, out_sar):
'''
# std::cout << "mode 11";
# std::cout << "SIMOrthoProgram.exe 11 in_parameter_path in_rc_wgs84_path in_ori_sar_path out_orth_sar_path";
'''
exe_path = r".\baseTool\x64\Release\SIMOrthoProgram.exe"
exe_cmd = r"set PROJ_LIB=.\baseTool\x64\Release; & {0} {1} {2} {3} {4} {5}".format(exe_path, 11, parameter_path,
dem_rc, in_sar, out_sar)
print(exe_cmd)
print(os.system(exe_cmd))
print("==========================================================================")
def lee_process_sar(self,in_sar, out_sar, win_size, noise_var):
'''
# std::cout << "mode 12"
# std::cout << "SIMOrthoProgram.exe 12 in_sar_path out_sar_path win_size noise_var"
'''
exe_path = r".\baseTool\x64\Release\SIMOrthoProgram.exe"
exe_cmd = r"set PROJ_LIB=.\baseTool\x64\Release; & {0} {1} {2} {3} {4} {5}".format(exe_path, 12, in_sar,
out_sar, win_size, noise_var)
print(exe_cmd)
print(os.system(exe_cmd))
print("==========================================================================")
def getPowerTif(self,in_ori_path,out_power_path):
'''
std::cout << "mode 5: convert ori tiff to power tiff:";
std::cout << "SIMOrthoProgram.exe 5 in_ori_path out_power_path";
'''
exe_path=r".\baseTool\x64\Release\SIMOrthoProgram.exe"
exe_cmd=r"set PROJ_LIB=.\baseTool\x64\Release; & {0} {1} {2} {3} ".format(exe_path,5,in_ori_path,out_power_path)
print(exe_cmd)
print(os.system(exe_cmd))
print("==========================================================================")
def test_PSTN(self):
landpoint=np.array([-1945072.5,5344083.0,2878316.0]).reshape(1,3)
# 间接定位法所需的参数
Doppler_d = np.array(self.header_info['ImageInformation']['DopplerCentroidCoefficients']).reshape(-1, 1)
LightSpeed = self.config['LightSpeed']
T0 = self.header_info['ImageInformation']['refRange'] * 2 / LightSpeed
lamda = self.header_info['ImageInformation']['lambda']
StartTime = self.header_info['ImageInformation']['StartTime']
PRF = self.header_info['PRF']
R0 = self.header_info['ImageInformation']['NearRange']
r,c,ti=self.PSTN_block(landpoint, Doppler_d, StartTime, lamda, T0, LightSpeed, PRF, R0)
pass
def findInitPoint(self,sim_mask,dem_gt,sim_r_tif,sim_c_tif,sampling_f):
# 根据采样点,大致计算出影像的仿射矩阵,并以此进行外扩
sampling_f=sampling_f//10
[r_ids,c_ids]=np.where(sim_mask==1)
sim_r_ids=sim_r_tif[r_ids,c_ids]
sim_c_ids=sim_c_tif[r_ids,c_ids]
X=dem_gt[0]+dem_gt[1]*c_ids+dem_gt[2]*r_ids
Y=dem_gt[3]+dem_gt[4]*c_ids+dem_gt[5]*r_ids
# 首先计算X 变换式
sim_r_ids=sim_r_ids.reshape(-1,1)
sim_c_ids=sim_c_ids.reshape(-1,1)
X=X.reshape(-1,1)
Y=Y.reshape(-1,1)
point_count=sim_c_ids.shape[0]
X_input=np.ones((point_count,3))
X_input[:,1]=sim_c_ids[:,0]
X_input[:,2]=sim_r_ids[:,0]
A_X=np.matmul(np.matmul(np.linalg.inv(np.matmul(X_input.T,X_input)), X_input.T), X).reshape(-1,1)
A_Y=np.matmul(np.matmul(np.linalg.inv(np.matmul(X_input.T,X_input)), X_input.T), Y).reshape(-1,1)
sar_gt=[A_X[0,0],A_X[1,0],A_X[2,0],A_Y[0,0],A_Y[1,0],A_Y[2,0]]
width=self.header_info['ImageInformation']['width']
height=self.header_info['ImageInformation']['height']
width_f=self.header_info['ImageInformation']['width']/width
height_f=self.header_info['ImageInformation']['height']/height
sar_gt[1]=sar_gt[1]*width_f
sar_gt[2]=sar_gt[2]*height_f
sar_gt[4]=sar_gt[4]*width_f
sar_gt[5]=sar_gt[5]*height_f
# 外扩
sar_gt[0]=sar_gt[0]+sar_gt[1]*-60+sar_gt[2]*-60
sar_gt[3]=sar_gt[3]+sar_gt[4]*-60+sar_gt[5]*-60
inv_sar_gt=gdal.InvGeoTransform(sar_gt)
for dem_height in [0,sim_mask.shape[0]-1]:
for dem_width in [0,sim_mask.shape[1]-1]:
dem_edge_x=dem_gt[0]+dem_gt[1]*dem_width+dem_gt[2]*dem_height
dem_edge_y=dem_gt[3]+dem_gt[4]*dem_width+dem_gt[5]*dem_height
c_width=inv_sar_gt[0]+inv_sar_gt[1]*dem_edge_x+inv_sar_gt[2]*dem_edge_y
r_height=inv_sar_gt[3]+inv_sar_gt[4]*dem_edge_x+inv_sar_gt[5]*dem_edge_y
if c_width<=0 or r_height<=0:
continue
width=width+120 if width+120<c_width else c_width
height=height+120 if height+120<r_height else r_height
return sar_gt,int(width),int(height)
def clipDEMForSimSAR(self,dem_merged_path,sim_out_path,dem_clip_path,sampling_f):
sim_rc_tif=gdal.Open(sim_out_path)
sim_width=sim_rc_tif.RasterXSize
sim_height=sim_rc_tif.RasterYSize
sim_r_tif=sim_rc_tif.GetRasterBand(1).ReadAsArray(0,0,sim_width,sim_height)
sim_c_tif=sim_rc_tif.GetRasterBand(2).ReadAsArray(0,0,sim_width,sim_height)
# 构建掩膜
sim_mask=(sim_r_tif>=-3000)&(sim_r_tif<self.header_info['ImageInformation']['height'])&(sim_c_tif>=0)&(sim_c_tif<self.header_info['ImageInformation']['width'])
sim_mask=sim_mask.astype(np.uint8)
dem_tif=gdal.Open(dem_merged_path)
[r_ids,c_ids]=np.where(sim_mask==1)
r_min=np.min(r_ids)
r_max=np.max(r_ids)
c_min=np.min(c_ids)
c_max=np.max(c_ids)
len_row=3#r_max-r_min
len_col=3#c_max-c_min
r_min=r_min-len_row if r_min-len_row>=0 else 0
c_min=c_min-len_col if c_min-len_col>=0 else 0
r_max=r_max+len_row if r_max+len_row<sim_height else sim_height
c_max=c_max+len_col if c_max+len_col<sim_width else sim_width
dem_gt=list(dem_tif.GetGeoTransform())
sar_gt=[i for i in dem_gt]
sar_gt[0]=dem_gt[0]+dem_gt[1]*c_min+dem_gt[2]*r_min
sar_gt[3]=dem_gt[3]+dem_gt[4]*c_min+dem_gt[5]*r_min
len_row=int(r_max-r_min)
len_col=int(c_max-c_min)
gtiff_driver = gdal.GetDriverByName('GTiff')
out_sim_dem=gtiff_driver.Create(dem_clip_path, len_col, len_row, 1,gdal.GDT_Float32 )
out_sim_dem.SetGeoTransform(sar_gt)
out_sim_dem.SetProjection(dem_tif.GetProjection())
options = gdal.WarpOptions(dem_tif.GetProjection(), dstSRS=dem_tif.GetProjection(), resampleAlg=gdalconst.GRA_Cubic)
gdal.Warp(out_sim_dem, dem_merged_path, options=options)
time.sleep(10)
out_sim_dem.SetProjection(dem_tif.GetProjection())
return dem_clip_path,sar_gt
def ConvertCoordinary(self, dem_merged_path, sim_out_path,work_temp_path, flag=1):
''' 求解坐标,
为了节省内存和处理数据方便基本所有方法都写在这一个类中后续会进行拆分保证内存的消耗
'''
# 间接定位法所需的参数
Doppler_d = np.array(self.header_info['ImageInformation']['DopplerCentroidCoefficients']).reshape(-1, 1)
LightSpeed = self.config['LightSpeed']
T0 = self.header_info['ImageInformation']['refRange'] * 2 / LightSpeed
lamda = self.header_info['ImageInformation']['lambda']
StartTime = self.header_info['ImageInformation']['StartTime']
PRF = self.header_info['PRF']
R0 = self.header_info['ImageInformation']['NearRange']
# 创建存放坐标映射文件
temp_point_refrence_path=os.path.join(work_temp_path,"temp_point_refrence")
if os.path.exists(temp_point_refrence_path):
shutil.rmtree(temp_point_refrence_path)
os.makedirs(temp_point_refrence_path)
# 读取影像
dem_clip_tiff = gdal.Open(dem_merged_path)
row_count = dem_clip_tiff.RasterYSize # 读取图像的行数
col_count = dem_clip_tiff.RasterXSize # 读取图像的列数
im_proj = dem_clip_tiff.GetProjection()
im_geotrans = list(dem_clip_tiff.GetGeoTransform())
gt = im_geotrans # 坐标变换参数
# 计算采样率
sampling_f=self.CalSamplingRateOfDEM(dem_clip_tiff)
if sampling_f%10!=0:
sampling_f=int(sampling_f/10)+1
sampling_f=int(sampling_f*10) # 保证抽样为10的倍数
#dem_resampled_path=os.path.join(work_temp_path,"TestDEM","resampled.tif")
dem_resampled_path=os.path.join(work_temp_path,"TestDEM","resampled.tif")
sim_out_rc_path=sim_out_path.replace(".tif","rc.tif")
dem_clip_path,sar_gt=self.clipDEMForSimSAR(dem_merged_path,sim_out_rc_path,dem_resampled_path,sampling_f)
#dem_resampled_path=dem_merged_path
# 参数输出计算
self.outParameter(os.path.join(work_temp_path,"sim_sar_paras.txt"),sim_out_path,work_temp_path,dem_merged_path,sampling_f)
return os.path.join(work_temp_path,"sim_sar_paras.txt"), sampling_f
def SimSARProcess(self,mask,r,c,TargetPosition,SAR_smi):
''' 模拟SAR 累加法,并返回距离整数坐标最近的点,作为匹配点,方便后期构建坐标变换模型
args:
mask: 参与计算的范围
r: 行号
c: 列号
TargetPosition:对应的地面坐标
SAR_smi: 模拟SAR 影像
return:
SAR_smi: 模拟计算计算结果
PointRefrence:nx5 r,c,x,y,z 记录核心的映射坐标时间
'''
# 根据入射角的cos 筛选出0,1
mask=mask.astype(bool)
r_int=np.round(r).astype(np.int32)
c_int=np.round(c).astype(np.int32)
# 满足条件1.入射角0,902.r(0,SAR_height) 3.(c,SAR_width)
# 满足条件为1不满足条件为0
mask=mask&(r_int>=0)&(r_int<SAR_smi.shape[0])&(c_int>=0)&(c_int<SAR_smi.shape[1])
mask=mask.astype(np.uint8)
# 获取满足条件的,行列号
[row_ids,col_ids]=np.where(mask==1)
# 利用稀疏矩阵coo_matrix同一行列号累加求和的特性
SAR_smi=SAR_smi+ss.coo_matrix((mask[row_ids,col_ids],(r_int[row_ids,col_ids],c_int[row_ids,col_ids])),
shape=SAR_smi.shape,dtype=np.uint16) # 计算 累加求和方法
SAR_smi=SAR_smi.astype(np.uint16)
# 构建累加匹配
d_r=np.abs(r[row_ids,col_ids]-r_int[row_ids,col_ids])
d_c=np.abs(c[row_ids,col_ids]-c_int[row_ids,col_ids])
# 查找最小值
t_mask=(d_r<0.01)*(d_c<0.01)
[ids_mask]=np.where(t_mask==1)
row_ids_0=row_ids[ids_mask]
col_ids_0=col_ids[ids_mask]
rcxyz=np.zeros((row_ids_0.shape[0],5))
rcxyz[:,0]=r[row_ids_0,col_ids_0]
rcxyz[:,1]=c[row_ids_0,col_ids_0]
rcxyz[:,2]=TargetPosition[row_ids_0,col_ids_0,0]
rcxyz[:,3]=TargetPosition[row_ids_0,col_ids_0,1]
rcxyz[:,4]=TargetPosition[row_ids_0,col_ids_0,2]
return SAR_smi,rcxyz.copy()
pass
def EstimationRegionOfTargetPostion(self,i,j,block_height_width,row_count,block_row_count,col_count,block_col_count):
# 确定目标区域
# 前面通过重采样方法,比目标区域多了扩展边缘,因此需要确定真实计算的目标区域
# 还原目标块的起始行列与块宽高
start_row=0
start_col=0
end_row=0
end_col=0
# 确定行的范围
if i>0: # 可以进行行前推
start_row=1 # 因为外推了一行
else: # 不可以进行行前推
start_row=0 # 此时没有外推一行
if i+block_height_width>=row_count: # 不存在行后推
if i>0: # 存在行前推,
end_row=start_row+block_row_count-1
else: # 不存在行前推
end_row=start_row+block_row_count
else: # 存在行后推
if i>0: # 存在行前推
end_row=start_row+block_row_count-2
else: # 不存在行前推
end_row=start_row+block_row_count-1
pass
# 确定列的范围
if j>0: # 存在列前推
start_col=1
else: # 不存在列前推
start_col=0
if j+block_height_width>=col_count: # 不存在列后推
if j>0: # 存在列前推
end_col=start_col+block_col_count-1
else: # 不存在列前推
end_col=start_col+block_col_count
else: # 存在列后推
if j>0: # 存在列前推
end_col=start_col+block_col_count-2
else: # 不存在列前推
end_col=start_col+block_col_count-1
pass
return [start_row,start_col,end_row,end_col]
def CalIntensityResampled(self,TargetPosition,ti,min_theta=0,max_theta=1):
'''计算入射角
agrs:
TargetPosition: 地面坐标 nxmx3
ti:对应的卫星空间位置 nxm
return:
Intensity:入射角阵-9999 不参与运算
'''
# 1
# 2 0 4
# 3
# n=(n12+n23+n34+n41)/4
# n=(n24xn31)/4
# 计算 n24=n4-n2
n24=TargetPosition[:,2:,:]-TargetPosition[:,:-2,:] # 4-2 2: 5070x5068
n24=n24[1:-1,:,:]
# 计算 n31=n1-n3
n31=TargetPosition[:-2,:,:]-TargetPosition[2:,:,:] # 1-3 5068x5070
n31=n31[:,1:-1,:]
# 计算坡度平面向量
N=np.zeros((n31.shape[0],n31.shape[1],n31.shape[2]))
# n24=[a,b,c]
# n31=[d,f,g]
N[:,:,0]=n24[:,:,1]*n31[:,:,2]-n24[:,:,2]*n31[:,:,1] # bg-cf
N[:,:,1]=n24[:,:,2]*n31[:,:,0]-n24[:,:,0]*n31[:,:,2] # cd-ag
N[:,:,2]=n24[:,:,0]*n31[:,:,1]-n24[:,:,1]*n31[:,:,0] # af-bd
N=N*0.25 # 平面坡度向量
N=N.reshape(-1,3)
del n24,n31
n=ti.shape[0]
m=ti.shape[1]
# 分块计算
theta=np.ones((n-2,m-2)).astype(bool)
ti=ti[1:-1,1:-1]
TargetPosition=TargetPosition[1:-1,1:-1]
TargetPosition=TargetPosition.reshape(-1,3)
ti=ti.reshape(-1)
theta=theta.reshape(-1)
# 分块计算
le_iter=4000
for i in range(0,theta.shape[0],le_iter):
len_ti=le_iter
if len_ti+i>theta.shape[0]:
len_ti=theta.shape[0]-i
end_i=i+len_ti
# 计算卫星空间坐标
R_sp = self.SatelliteOrbitModel.getSatelliteSpaceState(ti[i:end_i])[:, :3]-TargetPosition[i:end_i]
# 夹角=arccos((R_sp*N)/(|R_sp|*|N|))
theta_=np.sum(R_sp*N[i:end_i],axis=1)/(np.sum(R_sp**2,axis=1)*np.sum(N[i:end_i],axis=1))
theta[i:end_i]=(theta_>min_theta)&(theta_<max_theta)
result_theta_mask=np.ones((n,m),dtype=bool)
result_theta_mask[1:-1,1:-1]=theta.reshape(n-2,m-2)
return result_theta_mask
def ResamplingDEMBlock(self,dem_resampled_tiff,start_row,start_col,block_row_count,block_col_count,sampling_f,gt):
''' 根据DEM获取插值之后的规则格网块
agrs:
dem_resampled_tiff原始DEM
start_row: 起始行号
start_col终止行号
block_row_count获取块的行数
block_col_count获取块的列数
sampling_f采样率
gtdem_resampled_tiff 的仿射矩阵
return:
block_resampled:最终插值结果 经度(lon)纬度(lat)高程(ati)
'''
altii_block=dem_resampled_tiff.GetRasterBand(1).ReadAsArray(start_col,start_row , block_col_count, block_row_count) # 块 高程文件
block_resampled = LinearSampling(altii_block,sampling_f) # 双线性插值
# 直接根据仿射矩阵计算对应的X,Y
gt_resample=[gt[0]+gt[1]*start_col+gt[2]*start_row, gt[1]/sampling_f, gt[2]/sampling_f,
gt[3]+gt[4]*start_col+gt[5]*start_row, gt[4]/sampling_f, gt[5]/sampling_f]
X=gt_resample[0]+gt_resample[1]*block_resampled[:,:,1]+gt_resample[2]*block_resampled[:,:,0] # 经度 lon
Y=gt_resample[3]+gt_resample[4]*block_resampled[:,:,1]+gt_resample[5]*block_resampled[:,:,0] # 纬度 lat
block_resampled[:,:,0]=X
block_resampled[:,:,1]=Y
# 根据的情况计算最终的投影坐标系值
Land_point= OrthoAuxData.LLA2XYZM(block_resampled[:,:,0].reshape(-1,1),block_resampled[:,:,1].reshape(-1,1),block_resampled[:,:,2].reshape(-1,1))
block_resampled=np.ones((block_resampled.shape[0],block_resampled.shape[1],3))
block_resampled[:,:,0]=Land_point[0].reshape(block_resampled.shape[0],block_resampled.shape[1]).copy()
block_resampled[:,:,1]=Land_point[1].reshape(block_resampled.shape[0],block_resampled.shape[1]).copy()
block_resampled[:,:,2]=Land_point[2].reshape(block_resampled.shape[0],block_resampled.shape[1]).copy()
result=copy.deepcopy(block_resampled)
del block_resampled
return result
def EstimateDEMCoordinate(self,dem_resampled_tiff,start_row,start_col,block_row_count,block_col_count,sampling_f,gt,Doppler_d, StartTime, lamda, T0, LightSpeed, PRF, R0):
''' 粗估当前区域有无重采样的必要'''
altii=dem_resampled_tiff.GetRasterBand(1).ReadAsArray(start_col,start_row , block_col_count, block_row_count) # 块 高程文件
h=int(altii.shape[0])
w=int(altii.shape[1])
y_pixel=(np.ones((w,h))*range(h)+start_row).transpose(1,0)
x_pixel=np.ones((h,w))*range(w)+start_col
lat=gt[0]+gt[1]*x_pixel+gt[2]*y_pixel # 经度
lon=gt[3]+gt[4]*x_pixel+gt[5]*y_pixel # 纬度
#del x_pixel,y_pixel
#gc.collect()
[X, Y, Z] = OrthoAuxData.LLA2XYZM(lat.reshape(-1,1), lon.reshape(-1,1), altii.reshape(-1,1)) # 计算错误
TargetPosition = np.ones((int(h*w), 3), dtype=np.float32)
TargetPosition[:, 0] = X.reshape(-1)
TargetPosition[:, 1] = Y.reshape(-1)
TargetPosition[:, 2] = Z.reshape(-1)
r, c, ti = self.PSTN_block(TargetPosition, Doppler_d, StartTime, lamda, T0, LightSpeed, PRF, R0) # 间接定位法,核心求解代码
if np.max(r) < -1*sampling_f*2 or np.min(r) > self.header_info['ImageInformation']['height']+sampling_f*2:
return False,ti[-1,0]
if np.max(c)<-1*sampling_f*2 or np.min(c) > self.header_info['ImageInformation']['width']+sampling_f*2:
return False,ti[-1,0]
return True
def ConvertCoordinary_test(self, dem_merged_path, sim_out_path,work_temp_path, flag=1):
print("当前python程序内存占用 {}G".format(psutil.Process(os.getpid()).memory_info().rss / 1024 / 1024 / 1024))
"""
批量求解点坐标的性能改进
主要针对数据频繁开关文件读写
flag:是否想要经纬度转大地坐标系
"""
start = time.time()
# 间接定位法所需的参数
Doppler_d = np.array(self.header_info['ImageInformation']['DopplerCentroidCoefficients']).reshape(-1, 1)
LightSpeed = self.config['LightSpeed']
T0 = self.header_info['ImageInformation']['refRange'] * 2 / LightSpeed
lamda = self.header_info['ImageInformation']['lambda']
StartTime = self.header_info['ImageInformation']['StartTime']
PRF = self.header_info['PRF']
R0 = self.header_info['ImageInformation']['NearRange']
# 计算采样率
# 读取影像
dem_resampled_tiff = gdal.Open(dem_merged_path)
row_count = dem_resampled_tiff.RasterYSize # 读取图像的行数
col_count = dem_resampled_tiff.RasterXSize # 读取图像的列数
im_proj = dem_resampled_tiff.GetProjection()
im_geotrans = list(dem_resampled_tiff.GetGeoTransform())
gt = im_geotrans # 坐标变换参数
# 计算采样率
sampling_f=self.CalSamplingRateOfDEM(dem_resampled_tiff)
# 创建目标虚拟影像
SAR_width=self.header_info['ImageInformation']['width']
SAR_height=self.header_info['ImageInformation']['height']
SAR_row_col_array=np.zeros((row_count,col_count,2),np.float32)
for ii in range(0,row_count,3000):
if ii==row_count:
continue
altii=dem_resampled_tiff.GetRasterBand(1).ReadAsArray(0, ii, col_count, 3000)
if altii is None:
# 长度过长,设置行数
altii=dem_resampled_tiff.GetRasterBand(1).ReadAsArray(0, ii, col_count, int(row_count-ii))
pass
h=int(altii.shape[0])
w=int(altii.shape[1])
y_pixel=(np.ones((w,h))*range(h)+ii).transpose(1,0)
x_pixel=np.ones((h,w))*range(w)
lat=gt[0]+gt[1]*x_pixel+gt[2]*y_pixel # 经度
lon=gt[3]+gt[4]*x_pixel+gt[5]*y_pixel # 纬度
#del x_pixel,y_pixel
#gc.collect()
[X, Y, Z] = OrthoAuxData.LLA2XYZM(lat.reshape(-1,1), lon.reshape(-1,1), altii.reshape(-1,1)) # 计算错误
TargetPosition = np.ones((int(h*w), 3), dtype=np.float32)
TargetPosition[:, 0] = X.reshape(-1)
TargetPosition[:, 1] = Y.reshape(-1)
TargetPosition[:, 2] = Z.reshape(-1)
r, c, ti = self.PSTN_M(TargetPosition, Doppler_d, StartTime, lamda, T0, LightSpeed, PRF, R0) # 间接定位法,核心求解代码
SAR_row_col_array[ii:ii+h,:,0]=r.reshape(-1,col_count)
SAR_row_col_array[ii:ii+h,:,1]=c.reshape(-1,col_count)
gtiff_driver = gdal.GetDriverByName('GTiff')
SAR_row_col=gtiff_driver.Create(sim_out_path.replace(".tif","rc.tif"),col_count,row_count,2,gdal.GDT_Float32)
SAR_row_col.SetGeoTransform(im_geotrans) # 写入仿射变换参数
SAR_row_col.SetProjection(im_proj) # 写入投影
# 写入tiff
SAR_row_col.GetRasterBand(1).WriteArray(SAR_row_col_array[:,:,0])
SAR_row_col.GetRasterBand(2).WriteArray(SAR_row_col_array[:,:,1])
print(sim_out_path.replace(".tif","rc.tif"))
return sim_out_path.replace(".tif","rc.tif")
pass
def CalSamplingRateOfDEM(self,DEM_tiff):
'''计算DEM的重采样率f必须在解析头文件之后参考陈尔学 博士学位论文 《 星载合成孔径雷达影像正射校正方法研究 》
args:
DEM_tiff:tif DEM的影像
return:
f:采样率向上取整
'''
# 获取DEM_tiff的高宽、投影、仿射矩阵
Trans_array=list(DEM_tiff.GetGeoTransform()) # 仿射变换矩阵
width=DEM_tiff.RasterXSize
height=DEM_tiff.RasterYSize
# x=trans[0]+trans[1]*c+trans[2]*r
# y=trans[3]+trans[4]*c+trans[5]*r
# 获得其高宽分辨率
delta_x=Trans_array[1]+Trans_array[2] # x轴上的分辨率 经度
delta_y=Trans_array[4]+Trans_array[5] # y轴上的分辨率 纬度
# 因为单位为度,所以需要转换为 米
y_resultion=abs(111194.926644558737*delta_y)
x_resultion=abs(111194.926644*math.cos(Trans_array[3])*delta_x)
resultion=x_resultion if x_resultion>y_resultion else y_resultion
delta_R=self.delta_R # 斜距分辨率
incidenceAngle=self.header_info['ImageInformation']['incidenceAngle']["NearRange"] # 入射角
f=math.sin(incidenceAngle*math.pi/180)*1.4142135623730951*resultion/delta_R
f=math.ceil(f)
return f
def PSTN_M2(self, TargetPostion, Doppler_d, StartTime, lamda, T0, LightSpeed, PRF, R0):
"""
间接求解方法使用矩阵方法,分段计算方便加速
args:
TargetPositionnparray,nx3 地面坐标
Doppler_d:多普勒系数 -11
lamda:波长
T0:多普勒参考时间
LightSpeed:光速
return:
rc:nparray shape nx2 行列号
"""
#
n = int(TargetPostion.shape[0]) # 坐标点数据 nx3
r=np.zeros((n,1))
c=np.zeros((n,1))
ti=np.zeros((n,1),dtype=np.float64)
len_iter=2000
pool= ThreadPoolExecutor()
pool_ls=[]
SatelliteOrbitModelstarttime=self.SatelliteOrbitModel.get_starttime()
SatelliteOrbitModelParameters=self.SatelliteOrbitModel.A_arr
SatelliteOrbitModelName=self.SatelliteOrbitModel.modelName
delta_R=self.delta_R
for i in range(0, n, len_iter):
start_i=i
len_block=len_iter
if start_i+len_block>n:
len_block=n-start_i
end_i=start_i+len_block
temp_TargetPosition=TargetPostion[start_i:end_i,:]
pool_ls.append( pool.submit(PSTN_block_MuilThread,copy.deepcopy(start_i),copy.deepcopy(end_i),
temp_TargetPosition.copy(),
copy.deepcopy(Doppler_d),
copy.deepcopy(StartTime),
copy.deepcopy(lamda),
copy.deepcopy(T0), copy.deepcopy(LightSpeed),
copy.deepcopy(PRF),copy.deepcopy(R0),
copy.deepcopy(delta_R),
copy.deepcopy(SatelliteOrbitModelstarttime),
SatelliteOrbitModelParameters.copy(),
copy.deepcopy(SatelliteOrbitModelName),))
pool.close()
pool.join()
for p in pool_ls:
r_temp, c_temp, ti_temp,start_i,end_i=p.get()
r[start_i:end_i,:]=r_temp
c[start_i:end_i,:]=c_temp
ti[start_i:end_i,:]=ti_temp
return r,c,ti
def PSTN_M(self, TargetPostion, Doppler_d, StartTime, lamda, T0, LightSpeed, PRF, R0):
"""
间接求解方法使用矩阵方法,分段计算方便加速
args:
TargetPositionnparray,nx3 地面坐标
Doppler_d:多普勒系数 -11
lamda:波长
T0:多普勒参考时间
LightSpeed:光速
return:
rc:nparray shape nx2 行列号
"""
#
n = int(TargetPostion.shape[0]) # 坐标点数据 nx3
r=np.zeros((n,1))
c=np.zeros((n,1))
ti=np.zeros((n,1),dtype=np.float64)
init_size=3000
for i in range(0,n,init_size):
start_i=i
len_block=init_size
if start_i+len_block>n:
len_block=n-start_i
end_i=start_i+len_block
temp_TargetPosition=TargetPostion[start_i:end_i,:]
r_temp, c_temp, ti_temp=self.PSTN_block(temp_TargetPosition, Doppler_d, StartTime, lamda, T0, LightSpeed, PRF, R0)
r[start_i:end_i,:]=r_temp.copy()
c[start_i:end_i,:]=c_temp.copy()
ti[start_i:end_i,:]=ti_temp.copy()
return r,c,ti
def PSTN_block(self, TargetPostion, Doppler_d, StartTime, lamda, T0, LightSpeed, PRF, R0):
'''
间接求解方法使用矩阵方法
args:
TargetPositionnparray,nx3 地面坐标
Doppler_d:多普勒系数 -11
lamda:波长
T0:多普勒参考时间
LightSpeed:光速
return:
rc:nparray shape nx2 行列号
'''
n = TargetPostion.shape[0] # 坐标点数据 nx3
ti = np.ones((n, 1),dtype=np.float64) * StartTime # 初始值
delta_R = self.delta_R
delta_t = 1 / PRF
R=np.zeros((n,1))
Rs = np.zeros((n, 3))
R_sc = np.zeros((n, 3)) # 地面-卫星空间位置矢量
V_sc = np.zeros((n, 3)) # 地面-卫星空间速率矢量
FdNumerical = np.ones((n, 1)) # 多普勒公式的数值解法
FdTheory = np.ones((n, 1)) # 多普勒公式的理论解法
FdTheory_grad = np.ones((n, 1)) # 多普勒公式的导数
# 多普勒参数系数
Doppler_d = Doppler_d.reshape(-1, 1) # 5x1
TSR=np.ones((n, 1)) # nx1
TSRx = np.ones((n, Doppler_d.shape[0])) # nx5
inc_t = np.ones((n, 1)) # 计算增加的导数
dt = 0.0001 # 数值法求解多普勒距离公式的导数
dt_rec=1/dt
# 默认最高迭代100次如果还未求解出结果就将所有的未收敛的时间值记录为0 注意时间不能为0
for i in range(100):
tempT = ti + dt # 计算增加时间
# ------- 求解导数 ----------------
#del Rs,R_sc,V_sc,TSR,TSRx,satelliteSpaceState,R
satelliteSpaceState = self.SatelliteOrbitModel.getSatelliteSpaceState(tempT) # 卫星坐标与速度 nx6
Rs = satelliteSpaceState[:, :3]
R_sc = satelliteSpaceState[:, :3] - TargetPostion # 地面-卫星空间位置矢量
V_sc = satelliteSpaceState[:, 3:] # 地面-卫星空间位置矢量
R =np.sqrt(np.sum(R_sc ** 2, axis=1)).reshape(-1, 1) # nx1
#FdTheory_grad = (-2 / lamda) * (1 / R) * np.sum(R_sc * V_sc, axis=1).reshape(-1, 1) # nx1
FdTheory_grad = -2*np.reciprocal(R*lamda) * np.sum(R_sc * V_sc, axis=1).reshape(-1, 1) # nx1
# 获取卫星轨道状态信息
satelliteSpaceState = self.SatelliteOrbitModel.getSatelliteSpaceState(ti) # 卫星坐标与速度 nx6
# 卫星轨道坐标
Rs =satelliteSpaceState[:, :3]
# 卫星相对地面的位置向量、卫星速度向量
R_sc=Rs - TargetPostion # 地面-卫星空间位置矢量
V_sc =satelliteSpaceState[:, 3:] # 地面-卫星空间位置矢量
# 斜距
R = np.sqrt(np.sum(R_sc ** 2, axis=1)).reshape(-1, 1) # nx1
# 根据多普勒数值求解公式求解多普勒频移值
TSR= R * (2 / LightSpeed) - T0 # nx1
TSRx[:,0]=TSR[:,0]**0 # nx5
TSRx[:,1]=TSR[:,0]**1
TSRx[:,2]=TSR[:,0]**2
TSRx[:,3]=TSR[:,0]**3
TSRx[:,4]=TSR[:,0]**4
# 根据多普勒物理公式求解求解多普勒频移值
FdTheory=-2*np.reciprocal(lamda*R)*np.sum(R_sc * V_sc, axis=1).reshape(-1, 1) # nx1
FdNumerical= np.matmul(TSRx, Doppler_d) # nx1
FdTheory_grad = np.reciprocal((FdTheory_grad - FdTheory) * dt_rec) # nx1
inc_t = (FdTheory - FdNumerical) * FdTheory_grad #(FdTheory - FdNumerical) * (1 / FdTheory_grad) # nx1
# inc_t = inc_t - inc_t * ti_mask # 允许继续迭代 nx1
if np.max(np.abs(inc_t)) < delta_t * 0.001:
break
ti = ti - inc_t # 更新坐标
#del Rs,R_sc,V_sc,R,satelliteSpaceState,FdTheory_grad,FdNumerical,inc_t
#print("当前python程序{} step inc_t {} 求解内存占用 {}G".format(i,np.max(inc_t),psutil.Process(os.getpid()).memory_info().rss / 1024 / 1024 / 1024))
# 计算行号
ti_=copy.deepcopy(ti.copy())
r_ = (ti_ - StartTime)*PRF
delta_t_light=delta_t*LightSpeed
r=copy.deepcopy(r_.copy())
del r_
c_ = (R - R0) * (1 / delta_R)
c=copy.deepcopy(c_.copy())
del c_
ti = copy.deepcopy(ti_.copy())
del ti_
return r, c, ti
pass
def sim_intensity(self, in_tif_path, dem_resampled_path, lut_tif_path, incidence_tif_path, sim_out_path):
"""
局部入射角计算
原方法存在的问题多次文件读写
"""
dem_resampled_tiff = gdal.Open(dem_resampled_path) # 获取重采样的DEM 数据,为了减少文件读写操作,这里做了持久化
im_proj = dem_resampled_tiff.GetProjection() # 构建投影
im_geotrans = list(dem_resampled_tiff.GetGeoTransform()) # 构建投影变换对象
[a1, b1, c1, a2, b2, c2] = im_geotrans # 坐标变换参数c1=0,b2=0
start = time.time() # 度量算法
dem_resampled = dem_resampled_tiff.GetRasterBand(1).ReadAsArray(0, 0, dem_resampled_tiff.RasterXSize,
dem_resampled_tiff.RasterYSize)
del dem_resampled_tiff # 释放内存
incidence = dem_resampled * 0.0 + 1.8
# 读取时间
in_ds = gdal.Open(lut_tif_path) # 读取间接法
row_cnt = in_ds.RasterYSize
col_cnt = in_ds.RasterXSize
t_arr = in_ds.GetRasterBand(3).ReadAsArray(0, 0, col_cnt, row_cnt).astype(np.float64) # 获取时间阵列
t_arr = t_arr[1:-1, 1:-1] + self.header_info['ImageInformation']['StartTime'] # 去除最外围一圈时间数据
row_data = in_ds.GetRasterBand(1).ReadAsArray(0, 0, col_cnt, row_cnt) # 读取行号
col_data = in_ds.GetRasterBand(2).ReadAsArray(0, 0, col_cnt, row_cnt) # 读取列号
row_data = np.round(row_data)
col_data = np.round(col_data)
row_data = row_data.astype(np.int16)
col_data = col_data.astype(np.int16)
del in_ds # 释放内存
c = range(0, col_cnt)
c = np.array(c).reshape(-1, 1)
for r0 in range(1, row_cnt - 1):
T0 = np.zeros((col_cnt, 3)) # colcount-2 3
T0[:, 0] = a1 + b1 * c[:, 0] + c1 * r0
T0[:, 1] = a2 + b2 * c[:, 0] + c2 * r0
T0[:, 2] = dem_resampled[r0, :]
T0 = np.concatenate(OrthoAuxData.LLA2XYZM(T0[:, 0].reshape(-1, 1), T0[:, 1].reshape(-1, 1), T0[:, 2].reshape(-1, 1)), axis=1)
n1 = np.concatenate(OrthoAuxData.LLA2XYZM(a1 + b1 * c + c1 * (r0 - 1), a2 + b2 * c + c2 * (r0 - 1),
dem_resampled[r0 - 1, :]), axis=1)[1:-1, :] - T0[1:-1, :] # colcount-2 3
n3 = np.concatenate(OrthoAuxData.LLA2XYZM(a1 + b1 * c + c1 * (r0 + 1), a2 + b2 * c + c2 * (r0 + 1),
dem_resampled[r0 + 1, :]), axis=1)[1:-1, :] - T0[1:-1, :] # colcount-2 3
n2 = T0[:-2, :] - T0[1:-1, :]
n4 = T0[2:, :] - T0[1:-1, :]
T0 = T0[1:-1, :]
n31 = n1 - n3
n42 = n2 - n4
N = XYZOuterM2(n31, n42) / 4
ti = t_arr[r0 - 1, :].reshape(-1, 1) # rowcount-2,colcount-2
satelliteSpaceState = self.SatelliteOrbitModel.getSatelliteSpaceState(ti)
Rps = satelliteSpaceState[:, :3] - T0 # nx3
# 计算向量模之积
N_Norm = np.sqrt(np.sum(N * N, axis=1)).reshape(-1, 1)
Rps_Norm = np.sqrt(np.sum(Rps * Rps, axis=1)).reshape(-1, 1)
N_Norm = np.concatenate((N_Norm, N_Norm, N_Norm), axis=1)
Rps_Norm = np.concatenate((Rps_Norm, Rps_Norm, Rps_Norm), axis=1)
N = N / N_Norm
Rps = Rps / Rps_Norm
# 计算向量相乘
N_Rps = np.sum(N * Rps, axis=1) # col_count-2
theta = np.arccos(N_Rps) # 入射角
incidence[r0, 1:-1] = theta
incidence = np.degrees(incidence)
print('整张图入射角计算完成,耗时{}'.format(time.time() - start))
ImageHandler.write_img(incidence_tif_path, im_proj, im_geotrans, incidence)
# 读取原始影像相关信息
in_tif = gdal.Open(in_tif_path)
col_num = in_tif.RasterXSize
row_num = in_tif.RasterYSize
im_proj1 = in_tif.GetProjection() # 构建投影
im_geotrans1 = in_tif.GetGeoTransform()
out_arr = np.zeros((row_num, col_num), dtype=np.float32)
for h in range(row_cnt):
r_min = min(row_data[h])
r_max = max(row_data[h])
c_min = min(col_data[h])
c_max = max(col_data[h])
if 0 <= r_min < row_num or 0 <= r_max < row_num or (r_min < 0 and r_max >= row_num):
if 0 <= c_min < col_num or 0 <= c_max < col_num or (c_min < 0 and c_max >= col_num):
for w in range(col_cnt):
r = row_data[h, w]
c = col_data[h, w]
if 0 <= r < row_num and 0 <= c < col_num:
if 0 <= incidence[h, w] < 90:
out_arr[r, c] += 1
K = 10
out_arr = K * out_arr
max_delta = np.max(out_arr)
min_delta = np.min(out_arr)
out_arr = (out_arr - min_delta) / (max_delta - min_delta)
ImageHandler.write_img(sim_out_path, im_proj1, im_geotrans1, out_arr)
@staticmethod
def sar_intensity_synthesis(sar_in_tif, sar_out_tif):
# 获取SLC格式SAR影像的相关信息
in_ds = gdal.Open(sar_in_tif)
bands_num = in_ds.RasterCount
rows = in_ds.RasterYSize
columns = in_ds.RasterXSize
proj = in_ds.GetProjection()
geotrans = in_ds.GetGeoTransform()
datatype = gdal.GDT_Float32
# 创建输出的SAR强度图
gtiff_driver = gdal.GetDriverByName('GTiff')
out_ds = gtiff_driver.Create(sar_out_tif, columns, rows, 1, datatype)
# 输出SAR强度图
out_data=np.zeros((rows,columns))
for i in range(0,rows,10000):
for j in range(0,columns,10000):
len_row=10000
len_col=10000
if i+len_row>rows:
len_row=rows-i
if j+len_col>columns:
len_col=columns-j
end_i=i+len_row
end_j=j+len_col
in_data1 = in_ds.GetRasterBand(1).ReadAsArray(j, i, len_col, len_row).astype(np.float32)
in_data2 = in_ds.GetRasterBand(2).ReadAsArray(j, i, len_col, len_row).astype(np.float32)
out_data[i:end_i,j:end_j] = np.log10((in_data1**2 + in_data2**2)+1)*10
out_ds.GetRasterBand(1).WriteArray(out_data)
del in_ds, out_ds
@staticmethod
def img_match(sim_sar_path, ori_sar_path,work_sapce_path):
''' 影像匹配并根据配准点
args:
sim_sar_path:模拟SAR强度图
orig_sar_path: 原始SAR强度图
out_path:配准结果输出点
work_space_path: 工作目录
return:
point_correct: 点集映射结果
raise
None: 出现错误
'''
match_points_path=ImageMatchClass.ImageMatch(ori_sar_path,sim_sar_path,work_sapce_path)
match_points_path=os.path.join(work_sapce_path,"GridMatch.npy")
match_result_path=os.path.join(work_sapce_path,"match_result.npy")
match_result_image_path=os.path.join(work_sapce_path,"match_result_show.tif")
ImageMatchClass.DeNoiseMatch(match_points_path,match_result_path)
ImageMatchClass.DrawMatchResult(ori_sar_path,sim_sar_path,match_result_path,match_result_image_path)
return match_result_path
def IndireOrtho_smi(self,sim_SAR_rc_path,ori_SAR_path,tar_sar_path):
'''
测试间接定位法计算的影像坐标是否有问题
方法核心插值出间接定位法坐标处的 实部和虚部不考虑其他区域
使用插值方法等权反距离权重法
考虑实际的数据量较大为节省内存使用分块处理方法
块大小为1000
'''
sim_rc_tif=gdal.Open(sim_SAR_rc_path)
sim_width=sim_rc_tif.RasterXSize
sim_height=sim_rc_tif.RasterYSize
sim_r_tif=sim_rc_tif.GetRasterBand(1).ReadAsArray(0,0,sim_width,sim_height)
sim_c_tif=sim_rc_tif.GetRasterBand(2).ReadAsArray(0,0,sim_width,sim_height)
# 构建掩膜
sim_mask=(sim_r_tif>0)&(sim_r_tif<self.header_info['ImageInformation']['height'])&(sim_c_tif>0)&(sim_c_tif<self.header_info['ImageInformation']['width'])
sim_mask=sim_mask.astype(np.uint8)
dem_gt=list(sim_rc_tif.GetGeoTransform())
# 根据采样点,大致计算出影像的仿射矩阵,并以此进行外扩
[r_ids,c_ids]=np.where(sim_mask==1)
sim_r_ids=sim_r_tif[r_ids,c_ids]
sim_c_ids=sim_c_tif[r_ids,c_ids]
X=dem_gt[0]+dem_gt[1]*c_ids+dem_gt[2]*r_ids
Y=dem_gt[3]+dem_gt[4]*c_ids+dem_gt[5]*r_ids
# 首先计算X 变换式
sim_r_ids=sim_r_ids.reshape(-1,1)
sim_c_ids=sim_c_ids.reshape(-1,1)
X=X.reshape(-1,1)
Y=Y.reshape(-1,1)
point_count=sim_c_ids.shape[0]
X_input=np.ones((point_count,3))
X_input[:,1]=sim_c_ids[:,0]
X_input[:,2]=sim_r_ids[:,0]
A_X=np.matmul(np.matmul(np.linalg.inv(np.matmul(X_input.T,X_input)), X_input.T), X).reshape(-1,1)
A_Y=np.matmul(np.matmul(np.linalg.inv(np.matmul(X_input.T,X_input)), X_input.T), Y).reshape(-1,1)
sar_gt=[A_X[0,0],A_X[1,0],A_X[2,0],A_Y[0,0],A_Y[1,0],A_Y[2,0]]
# 根据行列号获取对应的值
ori_sar=gdal.Open(ori_SAR_path)
ori_width=ori_sar.RasterXSize
ori_height=ori_sar.RasterYSize
# 创建存储栅格
gtiff_driver = gdal.GetDriverByName('GTiff')
out_sar=gtiff_driver.Create(tar_sar_path, ori_width, ori_height, 2, gdal.GDT_Float32)
ori_sar=gdal.Open(ori_SAR_path)
ori_width=ori_sar.RasterXSize
ori_height=ori_sar.RasterYSize
out_sar.SetProjection(sim_rc_tif.GetProjection()) # 写入坐标系
out_sar.SetGeoTransform(sar_gt) # 写入仿射变换参数
out_sar.GetRasterBand(1).WriteArray(ori_sar.GetRasterBand(1).ReadAsArray(0,0,ori_width,ori_height).astype(np.float32))
out_sar.GetRasterBand(2).WriteArray(ori_sar.GetRasterBand(2).ReadAsArray(0,0,ori_width,ori_height).astype(np.float32))
# print(tar_sar_path)
pass
@staticmethod
def CoordinateTransformation(point_arr):
'''
原始->模拟
args:
point_arr:[模拟row,模拟col原始row,原始col]
'''
# 由模拟->原始
point_cnt = point_arr.shape[0] #
rs_arr = point_arr[:,2].reshape(point_cnt, 1) # 原始 行
cs_arr = point_arr[:,3].reshape(point_cnt, 1)
rm_arr = point_arr[:,0].reshape(point_cnt, 1)-3000 # 模拟 行 还原偏移
cm_arr = point_arr[:,1].reshape(point_cnt, 1)
X = np.concatenate(
[np.ones((point_cnt, 1), dtype=np.float64), rm_arr, cm_arr, rm_arr ** 2, cm_arr ** 2, rm_arr * cm_arr],
axis=1)
sim2orirc_arr=np.ones((2,6))
sim2orirc_arr[0,:] = np.matmul(np.matmul(np.linalg.inv(np.matmul(X.T, X)), X.T), rs_arr).reshape(1, 6)
sim2orirc_arr[1,:] = np.matmul(np.matmul(np.linalg.inv(np.matmul(X.T, X)), X.T), cs_arr).reshape(1, 6)
# 翻转 sim->ori
X = np.concatenate(
[np.ones((point_cnt, 1), dtype=np.float64), rs_arr, cs_arr, rs_arr ** 2, cs_arr ** 2, rs_arr * cs_arr],
axis=1)
ori2simrc_arr=np.ones((2,6))
ori2simrc_arr[0,:] = np.matmul(np.matmul(np.linalg.inv(np.matmul(X.T, X)), X.T), rm_arr).reshape(1, 6)
ori2simrc_arr[1,:] = np.matmul(np.matmul(np.linalg.inv(np.matmul(X.T, X)), X.T), cm_arr).reshape(1, 6)
return ori2simrc_arr.copy(),sim2orirc_arr.copy()
@staticmethod
def ReSamplingSAR(ori_sar_path,out_sar_path,lon_lat_point_match_path,gt):
''' 根据影像点匹配点,插值得到正射图像
args:
ori_sar_path: 输入sar地址
out_sar_path: 正射结果地址
lon_lat_point_match_path: CoordinateCorrection计算结果的路径
gt: 仿射矩阵
return:
out_sar_path
'''
ori_sar=gdal.Open(ori_sar_path)
ori_height=ori_sar.RasterYSize # 获得高度
ori_width=ori_sar.RasterXSize # 获得宽度
# 开始插值
spatialreference=osr.SpatialReference()
spatialreference.SetWellKnownGeogCS("WGS84") # 设置地理坐标,单位为度 degree # 设置投影坐标,单位为度 degree
spatialproj=spatialreference.ExportToWkt() # 导出投影结果
gtiff_driver = gdal.GetDriverByName('GTiff')
out_sar=gtiff_driver.Create(out_sar_path, ori_width, ori_height, 2, gdal.GDT_Float32)
out_sar.SetGeoTransform(gt) # 写入仿射变换参数
out_sar.SetProjection(spatialproj) # 写入投影
ab=np.array([gt[1],gt[2],gt[4],gt[5]]).reshape(2,2)
ab=np.np.matmul(np.linalg.inv(np.np.matmul(ab.T,ab)),ab.T)
# 解算仿射矩阵,为后面的插值做准备
lon_lat_file_list=os.listdir(lon_lat_point_match_path)
block_info_json=[]
for lon_lat_file_name in lon_lat_file_list:
lon_lat=np.load(os.path.join(lon_lat_point_match_path,lon_lat_file_name))
ori_r=lon_lat[:,0] # 原始影像的行坐标
ori_c=lon_lat[:,1] # 原始影像的列坐标
lon=lon_lat[:,2].copy()
lat=lon_lat[:,3].copy()
# 根据仿射矩阵阶段投影变换结果
lon=lon-gt[0]
lat=lat-gt[3]
lon_lat[:,2]=ab[0,0]*lon+ab[0,1]*lat # 行
lon_lat[:,3]=ab[1,0]*lon+ab[1,1]*lat # 列
block_info_json.append({
'ori':[np.min(lon_lat[:,0]),np.max(lon_lat[:,0]),np.min(lon_lat[:,1]),np.max(lon_lat[:,1])],# r0 r1 c0 c1
'ortho':[np.min(lon_lat[:,2]),np.max(lon_lat[:,2]),np.min(lon_lat[:,3]),np.max(lon_lat[:,3])],
'path':os.path.join(lon_lat_point_match_path,lon_lat_file_name)
})
for i in range(0,ori_height,6000):
for j in range(0,ori_width,6000):
# 判断需要检索的行列
len_row=6000
len_col=6000
if i+len_row>ori_height:
len_row=ori_height-i
if j+len_col>ori_width:
len_col=ori_width-j
end_i=i+len_row
end_j=j+len_col
select_region=[i-1000,end_i+1000,j-1000,end_i+1000]
# 根据求交原则,解出需要可以参与插值计算的 方块
inter_block=[]
for block in block_info_json:
block_ortho =block['ortho']
if block_ortho[0]>select_region[0] and block_ortho[1]<select_region[1]:
if block_ortho[2]>select_region[2] and block_ortho[3]<select_region[3]:
inter_block.append(block)
# 读取对应的块,进行全局插值
block_ori=np.zeros((1,5))
for block in inter_block:
block_ori=np.row_stack((block_ori,np.load(block['path'])))
block_ori=block_ori[1:,:]
# 计算 ori的范围
ori_r_min=np.min(block_ori[:,0])
ori_r_max=np.max(block_ori[:,0])
r_count=ori_r_max-ori_c_min+1
ori_c_min=np.min(block_ori[:,1])
ori_c_max=np.max(block_ori[:,1])
c_count=ori_c_max-ori_c_min+1
# 更新块的坐标
block_ori[:,0]=block_ori[:,0]-ori_r_min
block_ori[:,1]=block_ori[:,1]-ori_c_min
offset_i=i
offset_j=j
block_ori[:,2]=block_ori[:,2]-offset_i
block_ori[:,3]=block_ori[:,3]-offset_j
r=((np.ones((len_col,len_row))*range(len_row)).transpose(1,0)).shape(-1) # 行对应的x
c=(np.ones((len_row,len_col))*range(len_col)).shape(-1)
# 实部
sar_ab=out_sar.GetRasterBand(1).ReadAsArray(ori_c_min,ori_r_min,c_count, r_count)
resampling_result=interpolate.griddata(block_ori[:,2:],sar_ab[block_ori[:,0],block_ori[:,1]],(r,c), method='cubic').reshape(len_row,len_col)
out_sar.GetRasterBand(1).WriteRaster(offset_j, offset_i, len_col, len_row, resampling_result,len_col,len_row)
del resampling_result,sar_ab
# 虚部
sar_ab=out_sar.GetRasterBand(2).ReadAsArray(ori_c_min,ori_r_min,c_count, r_count)
resampling_result=interpolate.griddata(block_ori[:,2:],sar_ab[block_ori[:,0],block_ori[:,1]],(r,c), method='cubic').reshape(len_row,len_col)
out_sar.GetRasterBand(2).WriteRaster(offset_j, offset_i, len_col, len_row, resampling_result,len_col,len_row)
del resampling_result,sar_ab,r,c,block_ori
'''
sar_ab=ori_sar.GetRasterBand(1).ReadAsArray(0,0 , ori_width, ori_height)
resampling_result=interpolate.griddata(target_rc.reshape(-1,2),sar_ab.reshape(-1), (r.shape(-1), c.reshape(-1)), method='cubic').reshape(-1)
out_sar.GetRasterBand(1).WriteArray(resampling_result)
sar_ab=ori_sar.GetRasterBand(2).ReadAsArray(0,0, ori_width, ori_height)
resampling_result=interpolate.griddata(target_rc.reshape(-1,2),sar_ab.reshape(-1), (r.shape(-1), c.reshape(-1)), method='cubic').reshape(-1)
out_sar.GetRasterBand(2).WriteArray(resampling_result)
'''
return out_sar_path
def CoordinateCorrection(self,sim_out_path,dem_merged_path,dem_clip_path,point_match_path):
'''
构建转换矩阵以及重采样所需的坐标系变换坐标
args:
ori_sar_path原始SAR文件地址
point_arr: 影像匹配目标
work_sapce_file:文件输出目标
return
lonSAR点对应的经度
lat: SAR点对应的纬度
'''
# 计算转换模型 原始SAR->模拟SAR
# X=a0+a1*r+a2*c+a5*r*c+a3*r^2+a4*c^2
# Y=b0+b1*r+b2*c+b5*r*c+b3*r^2+b4*r^2
point_arr=np.load(point_match_path)
rcori2simrc_arr,sim2orirc_arr=IndirectOrthorectification.CoordinateTransformation(point_arr)
# 根据行列号裁剪DEM
sim_rc_tif=gdal.Open(sim_out_path)
sim_width=sim_rc_tif.RasterXSize
sim_height=sim_rc_tif.RasterYSize
sim_r_tif=sim_rc_tif.GetRasterBand(1).ReadAsArray(0,0,sim_width,sim_height)
sim_c_tif=sim_rc_tif.GetRasterBand(2).ReadAsArray(0,0,sim_width,sim_height)
# 计算实际行列号
r=sim2orirc_arr[0,0]+sim2orirc_arr[0,1]*sim_r_tif+sim2orirc_arr[0,2]*sim_c_tif+sim2orirc_arr[0,3]*sim_r_tif*sim_r_tif+sim2orirc_arr[0,4]*sim_c_tif*sim_c_tif+sim2orirc_arr[0,5]*sim_r_tif*sim_c_tif
c=sim2orirc_arr[1,0]+sim2orirc_arr[1,1]*sim_r_tif+sim2orirc_arr[1,2]*sim_c_tif+sim2orirc_arr[1,3]*sim_r_tif*sim_r_tif+sim2orirc_arr[1,4]*sim_c_tif*sim_c_tif+sim2orirc_arr[1,5]*sim_r_tif*sim_c_tif
sim_r_tif=r
sim_c_tif=c
del r,c
#
sim_mask=(sim_r_tif>=-1)&(sim_r_tif<self.header_info['ImageInformation']['height']+1)&(sim_c_tif>=-1)&(sim_c_tif<self.header_info['ImageInformation']['width']+1)
sim_mask=sim_mask.astype(np.uint8)
dem_tif=gdal.Open(dem_merged_path)
dem_gt=list(dem_tif.GetGeoTransform())
gtiff_driver = gdal.GetDriverByName('GTiff')
ori_path=sim_out_path.replace(".tif","_ori.tif")
sar_gt,len_col,len_row=self.findInitPoint(sim_mask,list(dem_tif.GetGeoTransform()),sim_r_tif,sim_c_tif,100)
out_sim_dem=gtiff_driver.Create(dem_clip_path, len_col, len_row, 1,gdal.GDT_Float32 )
out_sim_dem.SetGeoTransform(sar_gt)
out_sim_dem.SetProjection(dem_tif.GetProjection())
options = gdal.WarpOptions(dem_tif.GetProjection(), dstSRS=dem_tif.GetProjection(), resampleAlg=gdalconst.GRA_Cubic)
gdal.Warp(out_sim_dem, dem_merged_path, options=options) # 重采样结果
time.sleep(3)
return rcori2simrc_arr,sim2orirc_arr
def calxyzOFOut_sar(self,ori_xyz_path,sim_sar_x_path,sim_sar_y_path,sim_sar_z_path,r_arr_trans,c_arr_trans,distance_sim_path):
'''
根据行列号求解对应的插值情况
'''
# 首先读取distance_sim_path,获取对应的行列号
distance_dataset=gdal.Open(distance_sim_path)
distance_arr=distance_dataset.GetRasterBand(1).ReadAsArray(0,0 , distance_dataset.RasterXSize, distance_dataset.RasterYSize) # 块 高程文件
[r_ids,c_ids]=np.where(distance_arr<0.00001) # 构建插值点 模拟
width=distance_dataset.RasterXSize
height=distance_dataset.RasterYSize
del distance_arr,distance_dataset
gc.collect()
# 模拟->原始
ori_rc=np.ones((r_ids.size,2))
ori_rc[:,0]=r_arr_trans[0,0]+r_ids*r_arr_trans[0,1]+c_ids*r_arr_trans[0,2]+r_arr_trans[0,3]*r_ids ** 2+r_arr_trans[0,4]*c_ids ** 2+r_arr_trans[0,5]*r_ids * c_ids
ori_rc[:,1]=c_arr_trans[0,0]+r_ids*c_arr_trans[0,1]+c_ids*c_arr_trans[0,2]+c_arr_trans[0,3]*r_ids ** 2+c_arr_trans[0,4]*c_ids ** 2+c_arr_trans[0,5]*r_ids * c_ids
# 插值x坐标
sim_x_data=gdal.Open(sim_sar_x_path)
sim_x_arr=sim_x_data.GetRasterBand(1).ReadAsArray(0,0 , sim_x_data.RasterXSize, sim_x_data.RasterYSize) # 块 高程文件
sim_x=sim_x_arr[r_ids,c_ids]
del sim_x_arr,sim_x_data
tree=KDTree(ori_rc) # 原始sar点对应的坐标
gtiff_driver = gdal.GetDriverByName('GTiff')
SAR_row_col=gtiff_driver.Create(ori_xyz_path,width,height,3,gdal.GDT_Float32)
# 准备插值--分块插值
blocksize=5000
SAR_ori=np.zeros((height,width))
for i in range(0,height,blocksize):
for j in range(0,width,blocksize):
start_row=i
start_col=j
len_row=blocksize
len_col=blocksize
if(start_row+len_row>height):
len_row=height-start_row
if(start_col+len_col>width):
len_col=width-start_col
end_row=start_row+len_row
end_col=start_col+len_col
grid_xy= np.mgrid[start_row:end_row:1, start_col:end_col:1]
grid_xy=grid_xy.reshape(2,-1).transpose(1,0)
distance_weight,ori_select=tree.query(grid_xy,k=10)
distance_weight=np.reciprocal(distance_weight)
distance_weight=np.multiply(distance_weight.transpose(1,0),np.reciprocal(np.sum(distance_weight,axis=1)))
distance_weight=distance_weight.transpose(1,0)
SAR_ori[start_row:end_row,start_col:end_col]=np.sum( np.multiply(distance_weight,sim_x[ori_select]),axis=1).reshape(len_row,len_col)
SAR_row_col.GetRasterBand(1).WriteArray(SAR_ori)
# 插值y坐标
sim_y_data=gdal.Open(sim_sar_y_path)
sim_y_arr=sim_y_data.GetRasterBand(1).ReadAsArray(0,0 , sim_y_data.RasterXSize, sim_y_data.RasterYSize) # 块 高程文件
sim_y=sim_y_arr[r_ids,c_ids]
del sim_y_arr,sim_y_data,sim_x
# 准备插值--分块插值
blocksize=5000
SAR_ori=np.zeros((height,width))
for i in range(0,height,blocksize):
for j in range(0,width,blocksize):
start_row=i
start_col=j
len_row=blocksize
len_col=blocksize
if(start_row+len_row>height):
len_row=height-start_row
if(start_col+len_col>width):
len_col=width-start_col
end_row=start_row+len_row
end_col=start_col+len_col
grid_xy= np.mgrid[start_row:end_row:1, start_col:end_col:1]
grid_xy=grid_xy.reshape(2,-1).transpose(1,0)
distance_weight,ori_select=tree.query(grid_xy,k=10)
distance_weight=np.reciprocal(distance_weight)
distance_weight=np.multiply(distance_weight.transpose(1,0),np.reciprocal(np.sum(distance_weight,axis=1)))
distance_weight=distance_weight.transpose(1,0)
SAR_ori[start_row:end_row,start_col:end_col]=np.sum(np.multiply(distance_weight,sim_y[ori_select]),axis=1).reshape(len_row,len_col)
SAR_row_col.GetRasterBand(2).WriteArray(SAR_ori)
# 插值z坐标
sim_z_data=gdal.Open(sim_sar_z_path)
sim_z_arr=sim_z_data.GetRasterBand(1).ReadAsArray(0,0 , sim_z_data.RasterXSize, sim_z_data.RasterYSize) # 块 高程文件
sim_z=sim_z_arr[r_ids,c_ids]
del sim_z_arr,sim_z_data,sim_y
# 准备插值--分块插值
blocksize=5000
SAR_ori=np.zeros((height,width))
for i in range(0,height,blocksize):
for j in range(0,width,blocksize):
start_row=i
start_col=j
len_row=blocksize
len_col=blocksize
if(start_row+len_row>height):
len_row=height-start_row
if(start_col+len_col>width):
len_col=width-start_col
end_row=start_row+len_row
end_col=start_col+len_col
grid_xy= np.mgrid[start_row:end_row:1, start_col:end_col:1]
grid_xy=grid_xy.reshape(2,-1).transpose(1,0)
distance_weight,ori_select=tree.query(grid_xy,k=10)
distance_weight=np.reciprocal(distance_weight)
distance_weight=np.multiply(distance_weight.transpose(1,0),np.reciprocal(np.sum(distance_weight,axis=1)))
distance_weight=distance_weight.transpose(1,0)
SAR_ori[start_row:end_row,start_col:end_col]=np.sum(np.multiply(distance_weight,sim_z[ori_select]),axis=1).reshape(len_row,len_col)
SAR_row_col.GetRasterBand(3).WriteArray(SAR_ori)
return ori_xyz_path
def outResamplingParas(self,work_space_file,ortho_sar_xyz_pow_path,sar_xyz_path,sar_incidence_path,ortho_sar_xyz_path,ortho_sar_incidence_path,out_sar_file_list,dem_clip_path,ori2sim,sim2ori):
'''
sar_xyz_path:xyz插值结果
sar_incidence_path: 入射角
ortho_sar_xyz_path 重采样结果文件夹
out_sar_file_list需要重采样的文件
rc_trans_arr变换结果
'''
with open(os.path.join(work_space_file,"resample_para.txt"),'w',encoding='utf-8') as fp:
fp.write("{}\n".format(dem_clip_path))
fp.write("{}\n".format(os.path.join(work_space_file,"ori_sim.tif")))
fp.write("{}\n".format(sar_xyz_path))
fp.write("{}\n".format(sar_incidence_path))
fp.write("{}\n".format(ortho_sar_incidence_path))
fp.write("{}\n".format(ortho_sar_incidence_path.replace("orth_sar_incidence.tif","orth_sar_local_incidence.tif")))
fp.write("{}\n".format(ortho_sar_xyz_path))
fp.write("{}\n".format(len(out_sar_file_list)))
for i in range(len(out_sar_file_list)):
file_name=os.path.split(out_sar_file_list[i])[1]
fp.write("{}\n".format(out_sar_file_list[i]))
fp.write("{}\n".format(os.path.join(ortho_sar_xyz_path,file_name)))
fp.write("{}\n".format(os.path.join(ortho_sar_xyz_pow_path,file_name)))
#os.path.split(in_tif_path)[1]
fp.write("{}\n".format(12))
for i in range(6):
fp.write("{}\n".format(ori2sim[0,i]))
for i in range(6):
fp.write("{}\n".format(ori2sim[1,i]))
fp.write("{}\n".format(12))
for i in range(6):
fp.write("{}\n".format(sim2ori[0,i]))
for i in range(6):
fp.write("{}\n".format(sim2ori[1,i]))
return os.path.join(work_space_file,"resample_para.txt")
def Resampling(self,out_sar_xyz_path,inv_gt,gt,ori_resampling_file_path):
out_xyz=gdal.Open(out_sar_xyz_path)
ori_height=out_xyz.RasterYSize # 获得高度
ori_width=out_xyz.RasterXSize # 获得宽度
out_xyz_x=out_xyz.GetRasterBand(1).ReadAsArray(0,0 , ori_width, ori_height)
out_xyz_y=out_xyz.GetRasterBand(2).ReadAsArray(0,0 , ori_width, ori_height)
# 计算对应的行列号
out_xyz_rc=np.ones((ori_height,ori_width,2))
out_xyz_rc[:,:,1]=inv_gt[0]+inv_gt[1]*out_xyz_x+inv_gt[2]*out_xyz_y
out_xyz_rc[:,:,0]=inv_gt[3]+inv_gt[4]*out_xyz_x+inv_gt[5]*out_xyz_y
del out_xyz_x,out_xyz_y,out_xyz
out_xyz_rc=out_xyz_rc.reshape(-1,2)
blocksize=2000
ori_data=gdal.Open(ori_resampling_file_path[0][0][0])
width=ori_data.RasterXSize
height=ori_data.RasterYSize
SAR_ori=np.ones((width,height))
sim_x=ori_data.GetRasterBand(1).ReadAsArray(0,0 , width, height).reshape(-1)
tree=KDTree(out_xyz_rc)
for i in range(0,height,blocksize):
for j in range(0,width,blocksize):
start_row=i
start_col=j
len_row=blocksize
len_col=blocksize
if(start_row+len_row>height):
len_row=height-start_row
if(start_col+len_col>width):
len_col=width-start_col
end_row=start_row+len_row
end_col=start_col+len_col
grid_xy= np.mgrid[start_row:end_row:1, start_col:end_col:1]
grid_xy=grid_xy.reshape(2,-1).transpose(1,0)
distance_weight,ori_select=tree.query(grid_xy,k=4)
distance_weight=np.reciprocal(distance_weight)
distance_weight=np.multiply(distance_weight.transpose(1,0),np.reciprocal(np.sum(distance_weight,axis=1)))
distance_weight=distance_weight.transpose(1,0)
SAR_ori[start_row:end_row,start_col:end_col]=np.sum( np.multiply(distance_weight,sim_x[ori_select]),axis=1).reshape(len_row,len_col)
pass
'''
# 获得所有点集
del point_arr
# 构建查询表
ori_sar=gdal.Open(ori_sar_path)
ori_height=ori_sar.RasterYSize # 获得高度
ori_width=ori_sar.RasterXSize # 获得宽度
point_arr_path=[os.path.join(work_space_file,"point_refrence.npy")]
for point_match_arr_filename in os.listdir(os.path.join(work_space_file,'temp_point_refrence')):
point_arr_path.append(os.path.join(work_space_file,'temp_point_refrence',point_match_arr_filename))
point_arr=np.ones((1,5))
for point_path in point_arr_path:
point_temp_arr=np.load(point_path)
point_arr=np.row_stack((point_arr,point_temp_arr))
point_arr=point_arr[1:,:]
ori_points=np.zeros((point_arr.shape[0],2))
# 求解对应的行列号
for i in range(r_arr_trans.shape[1]):
ori_points[:,0]=ori_points[:,0]+r_arr_trans[0,i]*point_arr[:,1]**i
ori_points[:,1]=ori_points[:,1]+c_arr_trans[0,i]*point_arr[:,1]**i
point_arr[:,0]=ori_points[:,0].copy()
point_arr[:,1]=ori_points[:,1].copy()
del ori_points
gc.collect()
# 根据此进行散点插值,确定
lon_lat_point_match_path=os.path.join(work_space_file,"lon_lat_point_match")
if os.path.exists(lon_lat_point_match_path):
shutil.rmtree(lon_lat_point_match_path)
os.makedirs(lon_lat_point_match_path)
lon_lat=np.zeros((4,2))
block_info_json={"ori_rc":[]}
#
block_size=5000
for i in range(0,ori_height,block_size):
for j in range(0,ori_width,block_size):
len_row=block_size
len_col=block_size
if i+len_row>ori_height:
len_row=ori_height-i
if j+len_col>ori_width:
len_col=ori_width-j
end_i=i+len_row
end_j=j+len_col
r=(np.ones((len_col,len_row))*range(len_row)).transpose(1,0)+i
c=np.ones((len_row,len_col))*range(len_col)+j
# 格网插值
# scipy 规则格网插值
lon_lat_r_c=np.ones((len_col*len_row,5))
lon_lat_r_c[:,0]=r.reshape(-1)
lon_lat_r_c[:,1]=c.reshape(-1)
SAR_ori_X=interpolate.griddata(point_arr[:,:2], point_arr[:,2], (lon_lat_r_c[:,0], lon_lat_r_c[:,1]), method='linear').reshape(-1)
SAR_ori_Y=interpolate.griddata(point_arr[:,:2], point_arr[:,3], (lon_lat_r_c[:,0], lon_lat_r_c[:,1]), method='linear').reshape(-1)
SAR_ori_Z=interpolate.griddata(point_arr[:,:2], point_arr[:,4], (lon_lat_r_c[:,0], lon_lat_r_c[:,1]), method='linear').reshape(-1)
[lon_lat_r_c[:,2],lon_lat_r_c[:,3],lon_lat_r_c[:,4]]=OrthoAuxData.XYZ2LLAM(SAR_ori_X,SAR_ori_Y,SAR_ori_Z)
temp_path=os.path.join(lon_lat_point_match_path,"r_c_{}_{}.npy".format(i,j))
np.save(temp_path,lon_lat_r_c)
block_info_json['ori_rc'].append({'ori':[i,j,end_i,end_j],"path":temp_path})
if i==0 and j==0:
lon_lat[0,0]=lon_lat_r_c[:,2].reshape(len_row,len_col)[0,0] # 经度
lon_lat[0,1]=lon_lat_r_c[:,3].reshape(len_row,len_col)[0,0] # 纬度
if i+len_row==ori_height and j==0:
lon_lat[1,0]=lon_lat_r_c[:,2].reshape(len_row,len_col)[-1,0]
lon_lat[1,1]=lon_lat_r_c[:,3].reshape(len_row,len_col)[-1,0]
if j+len_col==ori_width and i==0:
lon_lat[2,0]=lon_lat_r_c[:,2].reshape(len_row,len_col)[0,-1]
lon_lat[2,1]=lon_lat_r_c[:,3].reshape(len_row,len_col)[0,-1]
if j+len_col==ori_width and i+len_row==ori_height:
lon_lat[3,0]=lon_lat_r_c[:,2].reshape(len_row,len_col)[-1,-1]
lon_lat[3,1]=lon_lat_r_c[:,3].reshape(len_row,len_col)[-1,-1]
# 1 3
# 2 4
gt=[0,1,2,3,4,5]
# 计算 经度
gt[0]= lon_lat[0,0]
gt[1]=(lon_lat[2,0]-gt[0])/(ori_width-1)
gt[2]=(lon_lat[3,0]-gt[0]-gt[1]*(ori_width-1))/(ori_height-1)
# 计算 纬度
gt[3]= lon_lat[0,1]
gt[5]=(lon_lat[1,1]-gt[3])/(ori_height-1)
gt[4]=(lon_lat[3,1]-gt[3]-gt[5]*(ori_height-1))/(ori_width-1)
return lon_lat_point_match_path,gt
#return lon_lat_point_match_path
return None
pass
'''