https://github.com/Dongvdong/v1_1_slam_tool
链接:https://pan.baidu.com/s/1ntXJch2t3GcLJhFBXFrBdw?pwd=kles
提取码:kles
注意事项
R的行列式算出来如果是-1 需要给R的第三列取符号,不然会导致两个平面(RTK采集数据厘米级别精度平面飞行, 非三维空间上下而是退化到二维平面计算srt)计算的t是反着的
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67 68 69 70 71 72 73 74 75 76 77 78 79 80 81 82 83 84 85 86 87 88 89 90 91 92 93 94 95 96 97 98 99 100 101 102 103 104 105 106 107 108 109 110 111 112 113 114 115 116 117 118 119 120 121 122 123 124 125 126 127 128 129 130 131 132 133 134 135 136 137 138 139 140 141 142 143 144 145 146 147 148 149 150 151 152 153 154 155 156 157 158 159 160 161 162 163 164 165 166 167 168 169 170 171 172 173 174 175 176 177 178 179 180 181 182 183 184 185 186 187 188 189 190 191 192 193 194 195 196 197 198 199 200 201 202 203 204 205 206 207 208 209 210 211 212 213 214 215 216 217 218 219 220 221 222 223 224 225 226 227 228 229 230 231 232 233 234 235 236 237 238 239 240 241 242 243 244 245 246 247 248 249 250 251 252 253 254 255 256 257 258 | import random import math import numpy as np import os def API_pose_estimation_3dTo3d_ransac(points_src, points_dst): #NED -> slam p = np.array(points_src, dtype= float ) q = np.array(points_dst, dtype= float ) print( "匹配点数: " , len(points_src), " " , len(points_dst)) # 1.计算s并去质心 mean_p = np.mean(p, axis=0) mean_q = np.mean(q, axis=0) p_norm = p - mean_p q_norm = q - mean_q # 计算距离比 iter_num = 0 _s = 0 inliner_num = 0 ransac_time=2000 # ransac随机抽取验证次数 while iter_num < ransac_time: # 随机挑选两个元素 _list = [] # print("len(points_src): ",len(points_src)) # if len(points_src) < 2: # break inx_1, inx_2 = random.sample(range(len(points_src)), 2) #print("inx_1: ",inx_1,"inx_2: ",inx_2) # print("inx_2: ",inx_2) p_r = np.array([points_src[inx_1], points_src[inx_2]], dtype= float ) q_r = np.array([points_dst[inx_1], points_dst[inx_2]], dtype= float ) _list.append(inx_1) _list.append(inx_2) # 计算s p_norm_r = p_r - mean_p q_norm_r = q_r - mean_q # 所有点的xyz平方求和 d1_list = [] d2_list = [] for i in range(len(q_norm_r)): d1 = q_norm_r[i] d2 = p_norm_r[i] dist1 = math. sqrt (np.sum(d1**2)) dist2 = math. sqrt (np.sum(d2**2)) d1_list.append(dist1) d2_list.append(dist2) s_r = np.sum(d1_list) / np.sum(d2_list) # 计算其他点s的误差值 inliner_p = [points_src[inx_1], points_src[inx_2]] inliner_q = [points_dst[inx_1], points_dst[inx_2]] for inx in range(len(points_src)): # 计算点不参与验证 if inx == inx_1 or inx == inx_2: continue p_src = np.array(points_src[inx]) q_dst = np.array(points_dst[inx]) # 分别计算到质心距离 p_src_norm = p_src - mean_p q_dst_norm = q_dst - mean_q p_src_norm_dist = math. sqrt (np.sum(p_src_norm**2)) q_dst_norm_dist = math. sqrt (np.sum(q_dst_norm**2)) # 计算误差 cal_dist = p_src_norm_dist * s_r error = cal_dist - q_dst_norm_dist if abs (error) < 3: inliner_p.append(points_src[inx]) inliner_q.append(points_dst[inx]) _list.append(inx) # 利用所有内点计算新的s p_r = np.array(inliner_p) q_r = np.array(inliner_q) p_norm_f = p_r - mean_p q_norm_f = q_r - mean_q d1_list = [] d2_list = [] for i in range(len(q_norm_f)): d1 = q_norm_f[i] d2 = p_norm_f[i] dist1 = math. sqrt (np.sum(d1**2)) dist2 = math. sqrt (np.sum(d2**2)) d1_list.append(dist1) d2_list.append(dist2) s_final = np.sum(d1_list) / np.sum(d2_list) # 记录内点数最高的模型 if inliner_num < len(inliner_p): _s = s_final inliner_num = len(inliner_p) inx_list = _list iter_num += 1 s = _s # 2.用s缩放src到dst尺度下 p = s * p mean_p = np.mean(p, axis=0) p_norm = p - mean_p # 2.计算q1*q2^T(注意顺序:q2->q1,x是dst,y是src) N = len(p) W = np.zeros((3, 3)) for i in range(N): x = q_norm[i, :] # 每一行数据 x = x.reshape(3, 1) # 3行1列格式 一维数组借助reshape转置 y = p_norm[i, :] y = y.reshape(1, 3) W += np.matmul(x, y) # 3.SVD分解W # python 线性代数库中svd求出的V与C++ Eigen库中求的V是转置关系 U, sigma, VT = np.linalg.svd(W, full_matrices=True) # 旋转矩阵R R = np.matmul(U, VT) # 这里无需再对V转置 # 在寻找旋转矩阵时,有一种特殊情况需要注意。有时SVD会返回一个“反射”矩阵,这在数值上是正确的,但在现实生活中实际上是无意义的。 # 通过检查R的行列式(来自上面的SVD)并查看它是否为负(-1)来解决。如果是,则V的第三列乘以-1。 # 验证R行列式是否为负数 参考链接:https://blog.csdn.net/sinat_29886521/article/details/77506426 # R为-1 会导致两个平面计算方向相反 导致T方向相反 所以要吧R取符号 # 方案1 R=SD的逆=UV的逆 V第三列取负号 # 方案2 按照SLam14讲解R的第三行给负1 if np.linalg.det(R) < 0: R_temp=np.matmul(U, VT) # R=SD=UV的转置 R_temp_det = np.linalg.det(R_temp) #其实就是-1 # VT 第三列给负号 VT_3col_to_fu1 = np.array([[1, 0, 0], [0, 1, 0], [0, 0, R_temp_det]]) VT_new= np.matmul(VT, VT_3col_to_fu1) # 重新计算 R 等同于R的第三列直接取负号 R = np.matmul(U, VT_new) # 平移向量 T = mean_q - np.matmul(R, mean_p) # dst - src T = T.reshape(3, 1) sR = s*R RT_34 = np.c_[sR, T] # 4.计算误差值 p = np.array(points_src) error_sum = 0 inx_list2 = [] error_ENU = [] for i in range(N): src = p[i, :] dst = q[i, :] src = src.reshape(3, 1) dst = dst.reshape(3, 1) test_dst = np.matmul(sR, src) + T error_Mat = test_dst - dst error_Mat2 = error_Mat**2 error = math. sqrt (np.sum(error_Mat2)) error_ENU.append(error) if error < 3: inx_list2.append(i) error_sum += error print( "mean error:" , error_sum/N) print( "max error:" , max(error_ENU)) print( "RT_34:\n" , RT_34) print( "缩放系数s:\n" , s) print( "旋转矩阵R:\n" , R) print( "通尺度下的T:\n" , T) return RT_34, sR, T # 根据 srt 将单个目标点云变换到指定坐标系下 def API_src3D_sRt_dis3D_one(points_src,SR,T): points_src_ = [[points_src[0]], [points_src[1]], [points_src[2]]] points_dis_ = np.matmul(SR,points_src_) + T #points_dis_ = SR @ points_src_ + T points_dis_t=[points_dis_[0][0],points_dis_[1][0],points_dis_[2][0]] return points_dis_t # 将1组3d点 根据 srt变换到另一个坐标系下 def API_src3D_sRt_dis3D_list(points_src,points_dst,SR,T): points_dis_t_list=[] error_sum=0 # 误差计算 for p_i in range(0,len(points_src)): # 根据srt计算便函后的x y z平移点 points_dis_t=API_src3D_sRt_dis3D_one(points_src[p_i],SR,T) print( "原始点" ,points_src[p_i], "变换后的点" ,points_dis_t, "真值" ,points_dst[p_i]) points_dis_t_list.append(points_dis_t) # =========整体转换后的计算误差=============== points_dis_t = np.array(points_dis_t) points_dst[p_i] = np.array(points_dst[p_i]) error_Mat = points_dis_t - points_dst[p_i] error_Mat2 = error_Mat**2 error = np.sum(error_Mat2) error_sum += error error_sum=math. sqrt (error_sum)/len(points_src) print( "平均误差:" ,error_sum) return points_dis_t_list '' ' if __name__ == "__main__" : # points_src=[[1,1,1],[2,2,2],[3,3,3]] # points_dst=[[11,11,11],[21,21,21],[31,31,31]] # RT_34, SR, T = API_pose_estimation_3dTo3d_ransac(points_src, points_dst) # # points_dis_t_list=API_src3D_sRt_dis3D_list(points_src,points_dst,SR, T) # print("变换后的列表",points_dis_t_list) '' ' '' ' # # 4 数据转化 为3D-3D计算相似变换准备 colmap enu 变换到 gnss enu坐标系上 # #ENU_List :名字 e n u 转化为: e n u # 4-1 读取gnss enu # 取出前400个数据计算 ENU_GNSS_List_4= API_read2txt( "data/test/2ENU_from_GNSS.txt" ) ENU_GNSS_List_4_400=[] for i in range(160 , len(ENU_GNSS_List_4)): ENU_GNSS_List_4_400.append(ENU_GNSS_List_4[i]) ENU_GNSS_List_3_400=API_data0123_to_data123(ENU_GNSS_List_4_400) # 去掉第一列名字 # 4-2 读取colmap enu ENU_colmap_list_4= API_read2txt( "data/test/colmap_images_t.txt" ) ENU_colmap_list_3=API_data0123_to_data123(ENU_colmap_list_4) # 去掉第一列名字 # 4-4 计算变换关系 points_src 到 points_dst points_src=ENU_colmap_list_3 points_dst=ENU_GNSS_List_3_400 #ENU_GNSS_List_3_400 RT_34, SR, T = API_pose_estimation_3dTo3d_ransac(points_src, points_dst) # colmapenu_in_gnssenu_3=API_src3D_sRt_dis3D_list(points_src,points_dst,SR, T) # 4-5 保存计算结果 colmap enu变换到gnss enu坐标系下的新坐标 colmapenu_in_gnssenu_4=[] for i in range(0,len(ENU_GNSS_List_4_400)): name=ENU_GNSS_List_4[i][0] #保存数据 名字 e n u li=[name,colmapenu_in_gnssenu_3[i][0],colmapenu_in_gnssenu_3[i][1],colmapenu_in_gnssenu_3[i][2]] colmapenu_in_gnssenu_4.append(li) # 保存数据 colmapeEnu_from_GnssEnu_txt_name= "data/test/3colmapeEnu_from_GnssEnu.txt" API_Save2txt(colmapeEnu_from_GnssEnu_txt_name,colmapenu_in_gnssenu_4) '' ' |
分类:
1_1_0SLAM工具集合
【推荐】国内首个AI IDE,深度理解中文开发场景,立即下载体验Trae
【推荐】编程新体验,更懂你的AI,立即体验豆包MarsCode编程助手
【推荐】抖音旗下AI助手豆包,你的智能百科全书,全免费不限次数
【推荐】轻量又高性能的 SSH 工具 IShell:AI 加持,快人一步
· winform 绘制太阳,地球,月球 运作规律
· 震惊!C++程序真的从main开始吗?99%的程序员都答错了
· AI与.NET技术实操系列(五):向量存储与相似性搜索在 .NET 中的实现
· 超详细:普通电脑也行Windows部署deepseek R1训练数据并当服务器共享给他人
· 【硬核科普】Trae如何「偷看」你的代码?零基础破解AI编程运行原理
2019-06-17 项目(二) esp32-cam 网页图像人脸
2019-06-17 开发(一) ardunio环境配置 针对esp32-cam 更多例程
2019-06-17 centos7.2(一)vultr服务器购买和开通端口