1.定义残差类
基于自动求导的核心是定义残差类。
说到要定义一个类,感觉是要实现很复杂的功能,而实际上该类就实现一个功能,即实现残差模型。
必须在残差类中重截operator()实现残差模型,很多时候,残差类也就这么一个成员,无需再添加其它成员,就能实现残差模型。
如何实现残差类取决于残差模型,反映在代码实现上,就是如何实现operator(),operator()的形式如下:
template <typename tp> bool operator()(const tp * const param1,…, const tp * const param9, tp *residual) const {…}
(1)以上给出的是十个参数的operator(),可根据实际情况选择参数个数,最少两个,最多十个。
(2)最后一个参数residual是必须的,它用于保存计算的残差值,其维度等于残差项的个数。
(3)前九个参数可根据实际需求裁剪,但至少一个。当被优化的所有参数可以归为一组时,就只需要一个;当被优化的参数需要被分为多组时,则需要多个。
定义多少个残差类取决于具体业务模型,但不外乎也就以下几种情况:
(1)定义一个残差类,这个残差类实现所有残差模型,耦合性强,不推荐。
(2)定义多个残差类,某些残差类实现多个残差模型,耦合性强,不推荐。
(3)定义多个残差类,每个残差类实现一个残差模型,每个残差模型实现所有时刻采集的数据,扩展性差,不推荐。
(4)定义多个残差类,每个残差类实现一个残差模型,每个残差模型实现单个时刻采集的数据,扩展性好,最实用。
这里之所以还区分每个时刻,是因为对于某些业务,尽管残差模型一样,但在不同时刻采集数据,部分模型参数值(真值)不一样,所以给定的初值和被优化后的最优值不一样,如VSLAM中基于不同位置的观察数据来计算每次观察时的位姿和相机内参。
2.使用残差类
在决定了operator()的形式后,也就决定了微分类CostFunction和Problem::AddResidualBlock的使用形式。
以AutoDiffCostFunction为例,其形式如下:
AutoDiffCostFunction<Functor, int M, int N0=0, int N1=0, int N2=0, int N3=0, int N4=0, int N5=0, …, int N9=0>
(1)第一个模板参数Functor就是定义好的残差类。
(2)第二个模板参数表示残差项的个数,若运行时才能确定则用ceres::DYNMIC。
(3)第三个及之后的模板参数,表示被优化的每组参数中包含的参数个数,即与operator()中参数对应,假设param2包含k个参数,则N2=k。
Problem::AddResidualBlock的形式如下:
Problem::AddResidualBlock(costfunction, lossfunction, param1,…param9)
Problem::AddResidualBlock(costfunction, lossfunction, vectorparam)
(1)前两个参数分别是微分模型和损失函数模型。
(2)之后的九个参数具体要多少个,与operator()对应,也可以用std::vector合为一个参数后传进去。
3.使用样例
提供两个使用样例,封装为两个类:
OptimizeRt:基于单次观察,优化此次观察的外参,定义了ProjectionModelRt类。
OptimizeKDRt:基于多次观察,优化相机内参和所有观察的外参,定义了ProjectionModelKDRt类。
其中类MotionSim用于生成仿真数据,使用说明参见《CV学习日志:CV开发之三维仿真器》。
存在可能不收敛的测试结果,属于正常现象,可修改初值精度来增加收敛性。
以下是详细代码,依赖于C++14、OpenCV4.x、Ceres和Spdlog。
1 #include <opencv2/opencv.hpp> 2 #include <opencv2/viz.hpp> 3 #include <spdlog/spdlog.h> 4 #include <ceres/ceres.h> 5 using namespace std; 6 using namespace cv; 7 8 class MotionSim 9 { 10 public: 11 static void TestMe(int argc, char** argv) 12 { 13 MotionSim motionSim(false); 14 motionSim.camFovX = 45; 15 motionSim.camFovY = 30; 16 motionSim.camRand = 10; 17 motionSim.enableVerbose = false; 18 motionSim.runMotion(false, false, 7); 19 motionSim.visMotion(); 20 } 21 22 public: 23 struct MotionView 24 { 25 Mat_<double> r = Mat_<double>(3, 1); 26 Mat_<double> t = Mat_<double>(3, 1); 27 Mat_<double> q = Mat_<double>(4, 1); 28 Mat_<double> rt = Mat_<double>(6, 1); 29 Mat_<double> radian = Mat_<double>(3, 1); 30 Mat_<double> degree = Mat_<double>(3, 1); 31 Mat_<double> R = Mat_<double>(3, 3); 32 Mat_<double> T = Mat_<double>(3, 4); 33 Mat_<double> K; 34 Mat_<double> D; 35 Mat_<Vec3d> point3D; 36 Mat_<Vec2d> point2D; 37 Mat_<int> point3DIds; 38 string print(string savePath = "") 39 { 40 string str; 41 str += fmt::format("r: {}\n", cvarr2str(r.t())); 42 str += fmt::format("t: {}\n", cvarr2str(t.t())); 43 str += fmt::format("q: {}\n", cvarr2str(q.t())); 44 str += fmt::format("rt: {}\n", cvarr2str(rt.t())); 45 str += fmt::format("radian: {}\n", cvarr2str(radian.t())); 46 str += fmt::format("degree: {}\n", cvarr2str(degree.t())); 47 str += fmt::format("R: {}\n", cvarr2str(R)); 48 str += fmt::format("T: {}\n", cvarr2str(T)); 49 str += fmt::format("K: {}\n", cvarr2str(K)); 50 str += fmt::format("D: {}\n", cvarr2str(D.t())); 51 if (savePath.empty() == false) { FILE* out = fopen(savePath.c_str(), "w"); fprintf(out, str.c_str()); fclose(out); } 52 return str; 53 } 54 }; 55 static string cvarr2str(InputArray v) 56 { 57 Ptr<Formatted> fmtd = cv::format(v, Formatter::FMT_DEFAULT); 58 string dst; fmtd->reset(); 59 for (const char* str = fmtd->next(); str; str = fmtd->next()) dst += string(str); 60 return dst; 61 } 62 static void euler2matrix(double e[3], double R[9], bool forward = true, int argc = 0, char** argv = 0) 63 { 64 if (argc > 0) 65 { 66 int N = 999; 67 for (int k = 0; k < N; ++k)//OpenCV not better than DIY 68 { 69 //1.GenerateData 70 Matx31d radian0 = radian0.randu(-3.14159265358979323846, 3.14159265358979323846); 71 Matx33d R; euler2matrix(radian0.val, R.val, true); 72 const double deg2rad = 3.14159265358979323846 * 0.0055555555555555556; 73 const double rad2deg = 180 * 0.3183098861837906715; 74 75 //2.CalcByOpenCV 76 Matx31d radian1 = cv::RQDecomp3x3(R, Matx33d(), Matx33d()) * deg2rad; 77 78 //3.CalcByDIY 79 Matx31d radian2; euler2matrix(R.val, radian2.val, false); 80 81 //4.AnalyzeError 82 double infRadian0Radian1 = norm(radian0, radian1, NORM_INF); 83 double infRadian1Radian2 = norm(radian1, radian2, NORM_INF); 84 85 //5.PrintError 86 cout << endl << "LoopCount: " << k << endl; 87 if (infRadian0Radian1 > 0 || infRadian1Radian2 > 0) 88 { 89 cout << endl << "5.1PrintError" << endl; 90 cout << endl << "infRadian0Radian1: " << infRadian0Radian1 << endl; 91 cout << endl << "infRadian1Radian2: " << infRadian1Radian2 << endl; 92 if (0) 93 { 94 cout << endl << "5.2PrintDiff" << endl; 95 cout << endl << "radian0-degree0:" << endl << radian0.t() << endl << radian0.t() * rad2deg << endl; 96 cout << endl << "radian1-degree1:" << endl << radian1.t() << endl << radian1.t() * rad2deg << endl; 97 cout << endl << "radian2-degree2:" << endl << radian2.t() << endl << radian2.t() * rad2deg << endl; 98 cout << endl << "5.3PrintOthers" << endl; 99 cout << endl << "R:" << endl << R << endl; 100 } 101 cout << endl << "Press any key to continue" << endl; std::getchar(); 102 } 103 } 104 return; 105 } 106 if (forward)//check with 3D Rotation Converter 107 { 108 double sinR = std::sin(e[0]); 109 double sinP = std::sin(e[1]); 110 double sinY = std::sin(e[2]); 111 double cosR = std::cos(e[0]); 112 double cosP = std::cos(e[1]); 113 double cosY = std::cos(e[2]); 114 115 //RPY indicates: first Yaw aroundZ, second Pitch aroundY, third Roll aroundX 116 R[0] = cosY * cosP; R[1] = cosY * sinP * sinR - sinY * cosR; R[2] = cosY * sinP * cosR + sinY * sinR; 117 R[3] = sinY * cosP; R[4] = sinY * sinP * sinR + cosY * cosR; R[5] = sinY * sinP * cosR - cosY * sinR; 118 R[6] = -sinP; R[7] = cosP * sinR; R[8] = cosP * cosR; 119 } 120 else 121 { 122 double vs1 = std::abs(R[6] - 1.); 123 double vs_1 = std::abs(R[6] + 1.); 124 if (vs1 > 1E-9 && vs_1 > 1E-9) 125 { 126 e[2] = std::atan2(R[3], R[0]); //Yaw aroundZ 127 e[1] = std::asin(-R[6]);//Pitch aroundY 128 e[0] = std::atan2(R[7], R[8]); //Roll aroundX 129 } 130 else if (vs_1 <= 1E-9) 131 { 132 e[2] = 0; //Yaw aroundZ 133 e[1] = 3.14159265358979323846 * 0.5;//Pitch aroundY 134 e[0] = e[2] + atan2(R[1], R[2]); //Roll aroundX 135 } 136 else 137 { 138 e[2] = 0; //Yaw aroundZ 139 e[1] = -3.14159265358979323846 * 0.5;//Pitch aroundY 140 e[0] = -e[2] + atan2(-R[1], -R[2]); //Roll aroundX 141 } 142 } 143 }; 144 static void quat2matrix(double q[4], double R[9], bool forward = true) 145 { 146 if (forward)//refer to qglviwer 147 { 148 double L1 = std::sqrt(q[0] * q[0] + q[1] * q[1] + q[2] * q[2] + q[3] * q[3]); 149 if (std::abs(L1 - 1) > 1E-9) { std::printf("Not uint quaternion: NormQ=%.9f\n", L1); abort(); } 150 151 double xx = 2.0 * q[1] * q[1]; 152 double yy = 2.0 * q[2] * q[2]; 153 double zz = 2.0 * q[3] * q[3]; 154 155 double xy = 2.0 * q[1] * q[2]; 156 double xz = 2.0 * q[1] * q[3]; 157 double wx = 2.0 * q[1] * q[0]; 158 159 double yz = 2.0 * q[2] * q[3]; 160 double wy = 2.0 * q[2] * q[0]; 161 162 double wz = 2.0 * q[3] * q[0]; 163 164 R[0] = 1.0 - yy - zz; 165 R[4] = 1.0 - xx - zz; 166 R[8] = 1.0 - xx - yy; 167 168 R[1] = xy - wz; 169 R[3] = xy + wz; 170 171 R[2] = xz + wy; 172 R[6] = xz - wy; 173 174 R[5] = yz - wx; 175 R[7] = yz + wx; 176 } 177 else 178 { 179 double onePlusTrace = 1.0 + R[0] + R[4] + R[8];// Compute one plus the trace of the matrix 180 if (onePlusTrace > 1E-9) 181 { 182 double s = sqrt(onePlusTrace) * 2.0; 183 double is = 1 / s; 184 q[0] = 0.25 * s; 185 q[1] = (R[7] - R[5]) * is; 186 q[2] = (R[2] - R[6]) * is; 187 q[3] = (R[3] - R[1]) * is; 188 } 189 else 190 { 191 std::printf("1+trace(R)=%.9f is too small and (R11,R22,R33)=(%.9f,%.9f,%.9f)\n", onePlusTrace, R[0], R[4], R[8]); 192 if ((R[0] > R[4]) && (R[0] > R[8]))//max(R00, R11, R22)=R00 193 { 194 double s = sqrt(1.0 + R[0] - R[4] - R[8]) * 2.0; 195 double is = 1 / s; 196 q[0] = (R[5] - R[7]) * is; 197 q[1] = 0.25 * s; 198 q[2] = (R[1] + R[3]) * is; 199 q[3] = (R[2] + R[6]) * is; 200 } 201 else if (R[4] > R[8])//max(R00, R11, R22)=R11 202 { 203 double s = sqrt(1.0 - R[0] + R[4] - R[8]) * 2.0; 204 double is = 1 / s; 205 q[0] = (R[2] - R[6]) * is; 206 q[1] = (R[1] + R[3]) * is; 207 q[2] = 0.25 * s; 208 q[3] = (R[5] + R[7]) * is; 209 } 210 else//max(R00, R11, R22)=R22 211 { 212 double s = sqrt(1.0 - R[0] - R[4] + R[8]) * 2.0; 213 double is = 1 / s; 214 q[0] = (R[1] - R[3]) * is; 215 q[1] = (R[2] + R[6]) * is; 216 q[2] = (R[5] + R[7]) * is; 217 q[3] = 0.25 * s; 218 } 219 } 220 double L1 = std::sqrt(q[0] * q[0] + q[1] * q[1] + q[2] * q[2] + q[3] * q[3]); 221 if (L1 < 1e-9) { std::printf("Wrong rotation matrix: NormQ=%.9f\n", L1); abort(); } 222 else { L1 = 1 / L1; q[0] *= L1; q[1] *= L1; q[2] *= L1; q[3] *= L1; } 223 } 224 } 225 static void vec2quat(double r[3], double q[4], bool forward = true) 226 { 227 if (forward)//refer to qglviwer 228 { 229 double theta = std::sqrt(r[0] * r[0] + r[1] * r[1] + r[2] * r[2]); 230 if (std::abs(theta) < 1E-9) 231 { 232 q[0] = 1; q[1] = q[2] = q[3] = 0; 233 std::printf("Rotation approximates zero: Theta=%.9f\n", theta); 234 }; 235 236 q[0] = std::cos(theta * 0.5); 237 double ss = std::sin(theta * 0.5) / theta; 238 q[1] = r[0] * ss; 239 q[2] = r[1] * ss; 240 q[3] = r[2] * ss; 241 } 242 else 243 { 244 double L1 = std::sqrt(q[0] * q[0] + q[1] * q[1] + q[2] * q[2] + q[3] * q[3]); 245 if (std::abs(L1 - 1) > 1E-9) { std::printf("Not uint quaternion: NormQ=%.9f\n", L1); abort(); } 246 247 double theta = 2 * acos(q[0]); 248 if (theta > 3.14159265358979323846) theta = 2 * 3.14159265358979323846 - theta; 249 double thetaEx = theta / std::sin(theta * 0.5); 250 r[0] = q[1] * thetaEx; 251 r[1] = q[2] * thetaEx; 252 r[2] = q[3] * thetaEx; 253 } 254 } 255 static void vec2matrix(double r[3], double R[9], bool forward = true, int argc = 0, char** argv = 0) 256 { 257 if (argc > 0) 258 { 259 int N = 999; 260 for (int k = 0; k < N; ++k) //refer to the subsequent article for more details 261 { 262 //1.GenerateData 263 Matx31d r0 = r0.randu(-999, 999); 264 Matx33d R0; cv::Rodrigues(r0, R0); 265 266 //2.CalcByOpenCV 267 Matx33d R1; 268 Matx31d r1; 269 cv::Rodrigues(r0, R1); 270 cv::Rodrigues(R0, r1); 271 272 //3.CalcByDIY 273 Matx33d R2; 274 Matx31d r2; 275 vec2matrix(r0.val, R2.val, true); 276 vec2matrix(r2.val, R0.val, false); 277 278 //4.AnalyzeError 279 double infR1R2 = norm(R1, R2, NORM_INF); 280 double infr1r2 = norm(r1, r2, NORM_INF); 281 282 //5.PrintError 283 cout << endl << "LoopCount: " << k << endl; 284 if (infR1R2 > 1E-12 || infr1r2 > 1E-12) 285 { 286 cout << endl << "5.1PrintError" << endl; 287 cout << endl << "infR1R2: " << infR1R2 << endl; 288 cout << endl << "infr1r2: " << infr1r2 << endl; 289 if (0) 290 { 291 cout << endl << "5.2PrintDiff" << endl; 292 cout << endl << "R1: " << endl << R1 << endl; 293 cout << endl << "R2: " << endl << R2 << endl; 294 cout << endl; 295 cout << endl << "r1: " << endl << r1.t() << endl; 296 cout << endl << "r2: " << endl << r2.t() << endl; 297 cout << endl << "5.3PrintOthers" << endl; 298 } 299 cout << endl << "Press any key to continue" << endl; std::getchar(); 300 } 301 } 302 return; 303 } 304 305 if (forward) 306 { 307 double theta = std::sqrt(r[0] * r[0] + r[1] * r[1] + r[2] * r[2]); 308 if (theta < 1E-9) 309 { 310 R[0] = R[4] = R[8] = 1.0; 311 R[1] = R[2] = R[3] = R[5] = R[6] = R[7] = 0.0; 312 std::printf("Rotation approximates zero: Theta=%.9f\n", theta); 313 return; 314 } 315 double cs = cos(theta); 316 double sn = sin(theta); 317 double itheta = 1. / theta; 318 double cs1 = 1 - cs; 319 double nx = r[0] * itheta; 320 double ny = r[1] * itheta; 321 double nz = r[2] * itheta; 322 323 double nxnx = nx * nx, nyny = ny * ny, nznz = nz * nz; 324 double nxny = nx * ny, nxnz = nx * nz, nynz = ny * nz; 325 double nxsn = nx * sn, nysn = ny * sn, nzsn = nz * sn; 326 327 R[0] = nxnx * cs1 + cs; 328 R[3] = nxny * cs1 + nzsn; 329 R[6] = nxnz * cs1 - nysn; 330 331 R[1] = nxny * cs1 - nzsn; 332 R[4] = nyny * cs1 + cs; 333 R[7] = nynz * cs1 + nxsn; 334 335 R[2] = nxnz * cs1 + nysn; 336 R[5] = nynz * cs1 - nxsn; 337 R[8] = nznz * cs1 + cs; 338 339 if (0) 340 { 341 Mat_<double> dRdu({ 9, 4 }, { 342 2 * nx * cs1, 0, 0, (nxnx - 1) * sn, 343 ny * cs1, nx * cs1, -sn, nxny * sn - nz * cs, 344 nz * cs1, sn, nx * cs1, nxnz * sn + ny * cs, 345 ny * cs1, nx * cs1, sn, nxny * sn + nz * cs, 346 0, 2 * ny * cs1, 0, (nyny - 1) * sn, 347 -sn, nz * cs1, ny * cs1, nynz * sn - nx * cs, 348 nz * cs1, -sn, nx * cs1, nxnz * sn - ny * cs, 349 sn, nz * cs1, ny * cs1, nynz * sn + nx * cs, 350 0, 0, 2 * nz * cs1, (nznz - 1) * sn }); 351 352 Mat_<double> dudv({ 4, 4 }, { 353 itheta, 0, 0, -nx * itheta, 354 0, itheta, 0, -ny * itheta, 355 0, 0, itheta, -nz * itheta, 356 0, 0, 0, 1 }); 357 358 Mat_<double> dvdr({ 4, 3 }, { 359 1, 0, 0, 360 0, 1, 0, 361 0, 0, 1, 362 nx, ny, nz }); 363 364 Mat_<double> Jacobian = dRdu * dudv * dvdr;//rows=9 cols=3 365 } 366 } 367 else 368 { 369 double sx = R[7] - R[5]; 370 double sy = R[2] - R[6]; 371 double sz = R[3] - R[1]; 372 double sn = sqrt(sx * sx + sy * sy + sz * sz) * 0.5; 373 double cs = (R[0] + R[4] + R[8] - 1) * 0.5; 374 double theta = acos(cs); 375 double ss = 2 * sn; 376 double iss = 1. / ss; 377 double tss = theta * iss; 378 r[0] = tss * sx; 379 r[1] = tss * sy; 380 r[2] = tss * sz; 381 382 if (0) 383 { 384 Mat_<double> drdu({ 3, 4 }, { 385 tss, 0, 0, (sn - theta * cs) * iss * iss * sx * 2, 386 0, tss, 0, (sn - theta * cs) * iss * iss * sy * 2, 387 0, 0, tss, (sn - theta * cs) * iss * iss * sz * 2 }); 388 389 Mat_<double> dudR({ 4, 9 }, { 390 0, 0, 0, 0, 0, -1, 0, 1, 0, 391 0, 0, 1, 0, 0, 0, -1, 0, 0, 392 0, -1, 0, 1, 0, 0, 0, 0, 0, 393 -iss, 0, 0, 0, -iss, 0, 0, 0, -iss }); 394 395 Mat_<double> Jacobian = drdu * dudR;//rows=3 cols=9 396 } 397 } 398 } 399 400 private: 401 const int nHorPoint3D = 100; 402 const int nVerPoint3D = 100; 403 const double varPoint3DXY = 10.; 404 const double minPoint3DZ = 1.; 405 const double maxPoint3DZ = 99.; 406 const double minCamZ = 101.; 407 const double maxCamZ = 150.; 408 const double varCamDegree = 10.; 409 Mat_<Vec3d> allPoint3D = Mat_<Vec3d>(nVerPoint3D * nHorPoint3D, 1); 410 Mat_<double> allPoint3DZ = Mat_<double>(nVerPoint3D * nHorPoint3D, 1); 411 Mat_<double> K; 412 Mat_<double> D; 413 const double deg2rad = 3.14159265358979323846 * 0.0055555555555555556; 414 const double rad2deg = 180 * 0.3183098861837906715; 415 416 public: 417 int camRows = 480; 418 int camCols = 640; 419 int camFovY = 90; 420 int camFovX = 90; 421 int camRand = 10;//append random[0,camRand] to camera intrinsics 422 int nCamDist = 5;//refer to opencv for value domain 423 int nMinMotion = 32; // no less than X motion views 424 int nMaxMotion = INT_MAX; // no more than X motion views 425 int nPoint2DThenExit = 32;//exit when less than X pixies 426 int rotMode = 1 + 2 + 4;//0=noRot 1=xAxis 2=yAxis 4=zAxis 427 bool noTrans = false;//translate or not while motion 428 bool world2D = false;//planar world or not 429 bool rndSeek = true;//use random seek or not 430 bool enableVerbose = false;//check motions one by one or not 431 vector<MotionView> motionViews;//World Information: RightX, FrontY, DownZ 432 MotionSim(bool run = true, bool world2D0 = false, bool noTrans0 = false, int rotMode0 = 7) { if (run) runMotion(world2D0, noTrans0, rotMode0); } 433 434 public: 435 void runMotion(bool world2D0 = false, bool noTrans0 = false, int rotMode0 = 7) 436 { 437 world2D = world2D0; 438 noTrans = noTrans0; 439 rotMode = rotMode0; 440 motionViews.clear(); 441 if (rndSeek) cv::setRNGSeed(clock()); 442 while (motionViews.size() < nMinMotion) 443 { 444 //1.GetAllPoint3D 445 if (world2D) allPoint3DZ = 0.; 446 else cv::randu(allPoint3DZ, -maxPoint3DZ, -minPoint3DZ);//DownZ 447 for (int i = 0, k = 0; i < nVerPoint3D; ++i) 448 for (int j = 0; j < nHorPoint3D; ++j, ++k) 449 allPoint3D(k) = Vec3d((j + cv::randu<double>()) * varPoint3DXY, (i + cv::randu<double>()) * varPoint3DXY, allPoint3DZ(i, j)); 450 451 //2.GetCamParams 452 double camFx = camCols / 2. / std::tan(camFovX / 2. * deg2rad) + cv::randu<double>() * camRand; 453 double camFy = camRows / 2. / std::tan(camFovY / 2. * deg2rad) + cv::randu<double>() * camRand; 454 double camCx = camCols / 2. + cv::randu<double>() * camRand; 455 double camCy = camRows / 2. + cv::randu<double>() * camRand; 456 K.create(3, 3); K << camFx, 0, camCx, 0, camFy, camCy, 0, 0, 1; 457 D.create(nCamDist, 1); cv::randu(D, -1.0, 1.0); 458 459 //3.GetAllMotionView 460 motionViews.clear(); 461 for (int64 k = 0; ; ++k) 462 { 463 //3.1 JoinCamParams 464 MotionView view; 465 view.K = K.clone(); 466 view.D = D.clone(); 467 468 //3.2 GetCamTrans 469 if (k == 0) view.t(0) = view.t(1) = 0; 470 else 471 { 472 view.t(0) = motionViews[k - 1].t(0) + cv::randu<double>() * varPoint3DXY; 473 view.t(1) = motionViews[k - 1].t(1) + cv::randu<double>() * varPoint3DXY; 474 } 475 view.t(2) = minCamZ + cv::randu<double>() * (maxCamZ - minCamZ); 476 view.t(2) = -view.t(2);//DownZ 477 if (noTrans && k != 0) { view.t(0) = motionViews[0].t(0); view.t(1) = motionViews[0].t(1); view.t(2) = motionViews[0].t(2); } 478 479 //3.3 GetCamRot: degree-->radian-->matrix-->vector&quaternion 480 view.degree = 0.; 481 if (rotMode & 1) view.degree(0) = cv::randu<double>() * varCamDegree; 482 if (rotMode & 2) view.degree(1) = cv::randu<double>() * varCamDegree; 483 if (rotMode & 4) view.degree(2) = cv::randu<double>() * varCamDegree; 484 view.radian = view.degree * deg2rad; 485 euler2matrix(view.radian.ptr<double>(), view.R.ptr<double>()); 486 cv::Rodrigues(view.R, view.r); 487 quat2matrix(view.q.ptr<double>(), view.R.ptr<double>(), false); 488 cv::hconcat(view.R, view.t, view.T); 489 cv::vconcat(view.r, view.t, view.rt); 490 491 //3.4 GetPoint3DAndPoint2D 492 Mat_<Vec2d> allPoint2D; 493 cv::projectPoints(allPoint3D, -view.r, -view.R.t() * view.t, view.K, view.D, allPoint2D); 494 for (int k = 0; k < allPoint2D.total(); ++k) 495 if (allPoint2D(k)[0] > 0 && allPoint2D(k)[0] < camCols && allPoint2D(k)[1] > 0 && allPoint2D(k)[1] < camRows) 496 { 497 view.point2D.push_back(allPoint2D(k)); 498 view.point3D.push_back(allPoint3D(k)); 499 view.point3DIds.push_back(k); 500 } 501 502 //3.5 PrintDetails 503 motionViews.push_back(view); 504 if (enableVerbose) 505 { 506 cout << endl << view.print(); 507 cout << fmt::format("view={} features={}\n", k, view.point2D.rows); 508 double minV = 0, maxV = 0;//Distortion makes some minV next to maxV 509 int minId = 0, maxId = 0; 510 cv::minMaxIdx(allPoint2D.reshape(1, int(allPoint2D.total()) * allPoint2D.channels()), &minV, &maxV, &minId, &maxId); 511 cout << fmt::format("minInfo:({}, {})", minId, minV) << allPoint3D(minId / 2) << allPoint2D(minId / 2) << endl; 512 cout << fmt::format("maxInfo:({}, {})", maxId, maxV) << allPoint3D(maxId / 2) << allPoint2D(maxId / 2) << endl; 513 cout << "Press any key to continue" << endl; std::getchar(); 514 } 515 if (view.point2D.rows < nPoint2DThenExit || motionViews.size() > nMaxMotion) break; 516 } 517 } 518 } 519 void visMotion() 520 { 521 //1.CreateWidgets 522 Size2d validSize(nHorPoint3D * varPoint3DXY, nVerPoint3D * varPoint3DXY); 523 Mat_<cv::Affine3d> camPoses(int(motionViews.size()), 1); for (int k = 0; k < camPoses.rows; ++k) camPoses(k) = cv::Affine3d(motionViews[k].T); 524 viz::WText worldInfo(fmt::format("nMotionView: {}\nK: {}\nD: {}", motionViews.size(), cvarr2str(K), cvarr2str(D)), Point(10, 240), 10); 525 viz::WCoordinateSystem worldCSys(1000); 526 viz::WPlane worldGround(Point3d(validSize.width / 2, validSize.height / 2, 0), Vec3d(0, 0, 1), Vec3d(0, 1, 0), validSize); 527 viz::WCloud worldPoints(allPoint3D, Mat_<Vec3b>(allPoint3D.size(), Vec3b(0, 255, 0))); 528 viz::WTrajectory camTraj1(camPoses, viz::WTrajectory::FRAMES, 8); 529 viz::WTrajectorySpheres camTraj2(camPoses, 100, 2); 530 viz::WTrajectoryFrustums camTraj3(camPoses, Matx33d(K), 4., viz::Color::yellow()); 531 worldCSys.setRenderingProperty(viz::OPACITY, 0.1); 532 worldGround.setRenderingProperty(viz::OPACITY, 0.1); 533 camTraj2.setRenderingProperty(viz::OPACITY, 0.6); 534 535 //2.ShowWidgets 536 static viz::Viz3d viz3d(__FUNCTION__); 537 viz3d.showWidget("worldInfo", worldInfo); 538 viz3d.showWidget("worldCSys", worldCSys); 539 viz3d.showWidget("worldGround", worldGround); 540 viz3d.showWidget("worldPoints", worldPoints); 541 viz3d.showWidget("camTraj1", camTraj1); 542 viz3d.showWidget("camTraj2", camTraj2); 543 viz3d.showWidget("camTraj3", camTraj3); 544 545 //3.UpdateWidghts 546 static const vector<MotionView>& views = motionViews; 547 viz3d.registerKeyboardCallback([](const viz::KeyboardEvent& keyboarEvent, void* pVizBorad)->void 548 { 549 if (keyboarEvent.action != viz::KeyboardEvent::KEY_DOWN) return; 550 static int pos = 0; 551 if (keyboarEvent.code == ' ') 552 { 553 size_t num = views.size(); 554 size_t ind = pos % num; 555 double xmin3D = DBL_MAX, ymin3D = DBL_MAX, xmin2D = DBL_MAX, ymin2D = DBL_MAX; 556 double xmax3D = -DBL_MAX, ymax3D = -DBL_MAX, xmax2D = -DBL_MAX, ymax2D = -DBL_MAX; 557 for (size_t k = 0; k < views[ind].point3D.rows; ++k) 558 { 559 Vec3d pt3 = views[ind].point3D(int(k)); 560 Vec2d pt2 = views[ind].point2D(int(k)); 561 if (pt3[0] < xmin3D) xmin3D = pt3[0]; 562 if (pt3[0] > xmax3D) xmax3D = pt3[0]; 563 if (pt3[1] < ymin3D) ymin3D = pt3[1]; 564 if (pt3[1] > ymax3D) ymax3D = pt3[1]; 565 if (pt2[0] < xmin2D) xmin2D = pt2[0]; 566 if (pt2[0] > xmax2D) xmax2D = pt2[0]; 567 if (pt2[1] < ymin2D) ymin2D = pt2[1]; 568 if (pt2[1] > ymax2D) ymax2D = pt2[1]; 569 } 570 if (pos != 0) 571 { 572 for (int k = 0; k < views[ind == 0 ? num - 1 : ind - 1].point3D.rows; ++k) viz3d.removeWidget("active" + std::to_string(k)); 573 viz3d.removeWidget("viewInfo"); 574 viz3d.removeWidget("camSolid"); 575 } 576 for (int k = 0; k < views[ind].point3D.rows; ++k) viz3d.showWidget("active" + std::to_string(k), viz::WSphere(views[ind].point3D(k), 5, 10)); 577 viz3d.showWidget("viewInfo", viz::WText(fmt::format("CurrentMotion: {}\nValidPoints: {}\nMin3DXY_Min2DXY: {}, {}, {}, {}\nMax3DXY_Max2DXY: {}, {}, {}, {}\nRot_Trans_Euler: {}\n", 578 ind, views[ind].point3D.rows, xmin3D, ymin3D, xmin2D, ymin2D, xmax3D, ymax3D, xmax2D, ymax2D, 579 cvarr2str(views[ind].r.t()) + cvarr2str(views[ind].t.t()) + cvarr2str(views[ind].degree.t())), Point(10, 10), 10)); 580 viz3d.showWidget("camSolid", viz::WCameraPosition(Matx33d(views[ind].K), 10, viz::Color::yellow()), cv::Affine3d(views[ind].T)); 581 ++pos; 582 } 583 }, 0); 584 viz3d.spin(); 585 } 586 }; 587 588 class OptimizeRt 589 { 590 public: 591 using MotionView = MotionSim::MotionView; 592 static void TestMe(int argc = 0, char** argv = 0) 593 { 594 int N = 99; 595 for (int k = 0; k < N; ++k) 596 { 597 //1.GenerateData 598 bool world2D = k % 2; 599 int rotMode = k % 7 + 1; 600 MotionSim motionSim(false); 601 motionSim.camFovX = 90; 602 motionSim.camFovY = 90; 603 motionSim.camRand = 10; 604 motionSim.nMinMotion = 16;//2 605 motionSim.nMaxMotion = 32;//4 606 motionSim.rndSeek = false; 607 motionSim.nCamDist = 5; 608 motionSim.runMotion(world2D, false, rotMode); 609 //motionSim.visMotion(); 610 int rndInd = int(motionSim.motionViews.size() * cv::randu<double>()); 611 Mat_<double> r0 = -motionSim.motionViews[rndInd].r; 612 Mat_<double> t0 = -motionSim.motionViews[rndInd].R.t() * motionSim.motionViews[rndInd].t; 613 const MotionView& motionView = motionSim.motionViews[rndInd]; 614 double errRatio = 0.9; 615 616 //2.CalcByCeres 617 Mat_<double> r1 = r0 * errRatio; 618 Mat_<double> t1 = t0 * errRatio; 619 ceres::Problem problem; 620 problem.AddResidualBlock(new ceres::AutoDiffCostFunction<ProjectionModelRt, ceres::DYNAMIC, 3, 3>( 621 new ProjectionModelRt(motionView, motionSim.nCamDist), motionView.point3D.rows * 2), NULL, r1.ptr<double>(), t1.ptr<double>()); 622 ceres::Solver::Options options; 623 ceres::Solver::Summary summary; 624 ceres::Solve(options, &problem, &summary); 625 int nIter1 = (int)summary.iterations.size(); 626 627 //3.AnalyzeError 628 double infr0r0 = norm(r0, r0 * errRatio, NORM_INF); 629 double infr0r1 = norm(r0, r1, NORM_INF); 630 double inft0t0 = norm(t0, t0 * errRatio, NORM_INF); 631 double inft0t1 = norm(t0, t1, NORM_INF); 632 633 //4.PrintError 634 cout << fmt::format("LoopCount: {} CeresSolver.iters: {}\n", k, nIter1); 635 if (infr0r1 > 1e-8 || inft0t1 > 1e-8) 636 { 637 cout << fmt::format("infr0r1: {:<15.9}\t\t{:<15.9}\n", infr0r1, infr0r0); 638 cout << fmt::format("inft0t1: {:<15.9}\t\t{:<15.9}\n", inft0t1, inft0t0); 639 cout << "Press any key to continue" << endl; std::getchar(); 640 } 641 } 642 } 643 644 public: 645 struct ProjectionModelRt 646 { 647 const int nDist; 648 double K[4]; 649 const double* D; 650 Mat_<Vec2d> point2D; 651 Mat_<Vec3d> point3D; 652 ProjectionModelRt(const MotionView& motionView0, const int nDist0) : nDist(nDist0) 653 { 654 K[0] = motionView0.K(0, 0); 655 K[1] = motionView0.K(1, 1); 656 K[2] = motionView0.K(0, 2); 657 K[3] = motionView0.K(1, 2); 658 D = motionView0.D.ptr<double>(); 659 point2D = motionView0.point2D; 660 point3D = motionView0.point3D; 661 } 662 template <typename tp> bool operator()(const tp* const rot, const tp* const t, tp* errPoint2D) const 663 { 664 //1.Projection params 665 double fx = K[0]; 666 double fy = K[1]; 667 double cx = K[2]; 668 double cy = K[3]; 669 670 //2.Distortion params 671 double k1 = D[0]; 672 double k2 = D[1]; 673 double p1 = D[2]; 674 double p2 = D[3]; 675 double k3, k4, k5, k6; 676 double s1, s2, s3, s4; 677 if (nDist > 4) k3 = D[4]; 678 if (nDist > 5) { k4 = D[5]; k5 = D[6]; k6 = D[7]; } 679 if (nDist > 8) { s1 = D[8]; s2 = D[9]; s3 = D[10]; s4 = D[11]; } 680 681 //3.Translation params 682 tp tx = t[0]; 683 tp ty = t[1]; 684 tp tz = t[2]; 685 686 //4.Rotation params 687 tp R11, R12, R13, R21, R22, R23, R31, R32, R33; 688 { 689 tp theta = sqrt(rot[0] * rot[0] + rot[1] * rot[1] + rot[2] * rot[2]); 690 tp cs = cos(theta); 691 tp sn = sin(theta); 692 tp itheta = 1. / theta;//if denominator==0 693 tp cs1 = 1. - cs; 694 tp nx = rot[0] * itheta; 695 tp ny = rot[1] * itheta; 696 tp nz = rot[2] * itheta; 697 698 tp nxnx = nx * nx, nyny = ny * ny, nznz = nz * nz; 699 tp nxny = nx * ny, nxnz = nx * nz, nynz = ny * nz; 700 tp nxsn = nx * sn, nysn = ny * sn, nzsn = nz * sn; 701 702 R11 = nxnx * cs1 + cs; 703 R21 = nxny * cs1 + nzsn; 704 R31 = nxnz * cs1 - nysn; 705 706 R12 = nxny * cs1 - nzsn; 707 R22 = nyny * cs1 + cs; 708 R32 = nynz * cs1 + nxsn; 709 710 R13 = nxnz * cs1 + nysn; 711 R23 = nynz * cs1 - nxsn; 712 R33 = nznz * cs1 + cs; 713 } 714 715 //5.ReProjection 716 const Vec2d* data2D = point2D.ptr<Vec2d>(); 717 const Vec3d* data3D = point3D.ptr<Vec3d>(); 718 Vec<tp, 2>* err2D = (Vec<tp, 2>*)errPoint2D; 719 for (int k = 0; k < point3D.rows; ++k) 720 { 721 //5.1 WorldCoordinate 722 double X = data3D[k][0]; 723 double Y = data3D[k][1]; 724 double Z = data3D[k][2]; 725 726 //5.2 CameraCoordinate 727 tp x = R11 * X + R12 * Y + R13 * Z + tx; 728 tp y = R21 * X + R22 * Y + R23 * Z + ty; 729 tp z = R31 * X + R32 * Y + R33 * Z + tz; 730 731 //5.3 StandardPhysicsCoordinate 732 tp iz = 1. / z; //if denominator==0 733 tp xc = x * iz; 734 tp yc = y * iz; 735 736 //5.4 DistortionPhysicsCoordinate 737 tp xc2 = xc * xc; 738 tp yc2 = yc * yc; 739 tp d2 = xc2 + yc2; 740 tp xcyc = 2. * xc * yc; 741 tp d4 = d2 * d2; 742 tp d6 = d2 * d4; 743 tp d2xc2 = d2 + 2. * xc2; 744 tp d2yc2 = d2 + 2. * yc2; 745 tp nu, de, xd, yd; 746 if (nDist < 5) 747 { 748 nu = 1. + k1 * d2 + k2 * d4; 749 xd = xc * nu + p1 * xcyc + p2 * d2xc2; 750 yd = yc * nu + p2 * xcyc + p1 * d2yc2; 751 } 752 else if (nDist < 8) 753 { 754 nu = 1. + k1 * d2 + k2 * d4 + k3 * d6; 755 xd = xc * nu + p1 * xcyc + p2 * d2xc2; 756 yd = yc * nu + p2 * xcyc + p1 * d2yc2; 757 } 758 else if (nDist < 12) 759 { 760 nu = 1. + k1 * d2 + k2 * d4 + k3 * d6; 761 de = 1. / (1. + k4 * d2 + k5 * d4 + k6 * d6);//if denominator==0 762 xd = xc * nu * de + p1 * xcyc + p2 * d2xc2; 763 yd = yc * nu * de + p2 * xcyc + p1 * d2yc2; 764 } 765 else if (nDist < 14) 766 { 767 nu = 1. + k1 * d2 + k2 * d4 + k3 * d6; 768 de = 1. / (1. + k4 * d2 + k5 * d4 + k6 * d6);//if denominator==0 769 xd = xc * nu * de + p1 * xcyc + p2 * d2xc2 + s1 * d2 + s2 * d4; 770 yd = yc * nu * de + p2 * xcyc + p1 * d2yc2 + s3 * d2 + s4 * d4; 771 } 772 err2D[k][0] = xd * fx + cx - data2D[k][0]; 773 err2D[k][1] = yd * fy + cy - data2D[k][1]; 774 } 775 return true; 776 } 777 }; 778 }; 779 780 class OptimizeKDRt 781 { 782 public: 783 using MotionView = MotionSim::MotionView; 784 static void TestMe(int argc = 0, char** argv = 0) 785 { 786 int N = 99; 787 for (int k = 0; k < N; ++k) 788 { 789 //1.GenerateData 790 bool world2D = k % 2; 791 int rotMode = k % 7 + 1; 792 MotionSim motionSim(false); 793 motionSim.camFovX = 90; 794 motionSim.camFovY = 90; 795 motionSim.camRand = 10; 796 motionSim.nMinMotion = 16;//2 797 motionSim.nMaxMotion = 32;//4 798 motionSim.rndSeek = false; 799 static const int nDist = 5; 800 motionSim.nCamDist = nDist; 801 motionSim.runMotion(world2D, false, rotMode); 802 //motionSim.visMotion(); 803 Mat_<double> rs0; for (size_t k = 0; k < motionSim.motionViews.size(); ++k) rs0.push_back(-motionSim.motionViews[k].r); 804 Mat_<double> ts0; for (size_t k = 0; k < motionSim.motionViews.size(); ++k) ts0.push_back(-motionSim.motionViews[k].R.t() * motionSim.motionViews[k].t); 805 Mat_<double> K0({ 4, 1 }, { motionSim.motionViews[0].K(0, 0), motionSim.motionViews[0].K(1, 1), motionSim.motionViews[0].K(0, 2), motionSim.motionViews[0].K(1, 2) }); 806 Mat_<double> D0 = motionSim.motionViews[0].D.clone(); 807 double errRatio = 0.9; 808 double errRatioTrans = 0.99; 809 810 //2.CalcByCeres 811 Mat_<double> rs1 = rs0 * errRatio; 812 Mat_<double> ts1 = ts0 * errRatioTrans; 813 Mat_<double> K1 = K0 * errRatio; 814 Mat_<double> D1 = D0 * errRatio; 815 ceres::Problem problem; 816 for (int k = 0; k < motionSim.motionViews.size(); ++k) 817 problem.AddResidualBlock(new ceres::AutoDiffCostFunction<ProjectionModelKDRt, ceres::DYNAMIC, 3, 3, 4, nDist>( 818 new ProjectionModelKDRt(motionSim.motionViews[k], motionSim.nCamDist), motionSim.motionViews[k].point3D.rows * 2), NULL, 819 rs1.ptr<double>(k * 3), ts1.ptr<double>(k * 3), 820 K1.ptr<double>(), D1.ptr<double>()); 821 ceres::Solver::Options options; 822 ceres::Solver::Summary summary; 823 ceres::Solve(options, &problem, &summary); 824 int nIter1 = (int)summary.iterations.size(); 825 826 //3.AnalyzeError 827 double infrs0rs0 = norm(rs0, rs0 * errRatio, NORM_INF); 828 double infrs0rs1 = norm(rs0, rs1, NORM_INF); 829 double infts0ts0 = norm(ts0, ts0 * errRatioTrans, NORM_INF); 830 double infts0ts1 = norm(ts0, ts1, NORM_INF); 831 double infK0K0 = norm(K0, K0 * errRatio, NORM_INF); 832 double infK0K1 = norm(K0, K1, NORM_INF); 833 double infD0D0 = norm(D0, D0 * errRatio, NORM_INF); 834 double infD0D1 = norm(D0, D1, NORM_INF); 835 836 //4.PrintError 837 cout << fmt::format("LoopCount: {} CeresSolver.iters: {}\n", k, nIter1); 838 if (infrs0rs1 > 1e-8 || infts0ts1 > 1e-8 || infK0K1 > 1e-8 || infD0D1 > 1e-8) 839 { 840 cout << fmt::format("infrs0rs1: {:<15.9}\t\t{:<15.9}\n", infrs0rs1, infrs0rs0); 841 cout << fmt::format("infts0ts1: {:<15.9}\t\t{:<15.9}\n", infts0ts1, infts0ts0); 842 cout << fmt::format("infK0K1 : {:<15.9}\t\t{:<15.9}\n", infK0K1, infK0K0); 843 cout << fmt::format("infD0D1 : {:<15.9}\t\t{:<15.9}\n", infD0D1, infD0D0); 844 cout << "Press any key to continue" << endl; std::getchar(); 845 } 846 } 847 } 848 849 public: 850 struct ProjectionModelKDRt 851 { 852 const int nDist; 853 Mat_<Vec2d> point2D; 854 Mat_<Vec3d> point3D; 855 ProjectionModelKDRt(const MotionView& motionView0, const int nDist0) : nDist(nDist0) 856 { 857 point2D = motionView0.point2D; 858 point3D = motionView0.point3D; 859 } 860 template <typename tp> bool operator()(const tp* const rot, const tp* const t, const tp* const K, const tp* const D, tp* errPoint2D) const 861 { 862 //1.Projection params 863 tp fx = K[0]; 864 tp fy = K[1]; 865 tp cx = K[2]; 866 tp cy = K[3]; 867 868 //2.Distortion params 869 tp k1 = D[0]; 870 tp k2 = D[1]; 871 tp p1 = D[2]; 872 tp p2 = D[3]; 873 tp k3, k4, k5, k6; 874 tp s1, s2, s3, s4; 875 if (nDist > 4) k3 = D[4]; 876 if (nDist > 5) { k4 = D[5]; k5 = D[6]; k6 = D[7]; } 877 if (nDist > 8) { s1 = D[8]; s2 = D[9]; s3 = D[10]; s4 = D[11]; } 878 879 //3.Translation params 880 tp tx = t[0]; 881 tp ty = t[1]; 882 tp tz = t[2]; 883 884 //4. 885 tp R11, R12, R13, R21, R22, R23, R31, R32, R33; 886 { 887 tp theta = sqrt(rot[0] * rot[0] + rot[1] * rot[1] + rot[2] * rot[2]); 888 tp cs = cos(theta); 889 tp sn = sin(theta); 890 tp itheta = 1. / theta;//if denominator==0 891 tp cs1 = 1. - cs; 892 tp nx = rot[0] * itheta; 893 tp ny = rot[1] * itheta; 894 tp nz = rot[2] * itheta; 895 896 tp nxnx = nx * nx, nyny = ny * ny, nznz = nz * nz; 897 tp nxny = nx * ny, nxnz = nx * nz, nynz = ny * nz; 898 tp nxsn = nx * sn, nysn = ny * sn, nzsn = nz * sn; 899 900 R11 = nxnx * cs1 + cs; 901 R21 = nxny * cs1 + nzsn; 902 R31 = nxnz * cs1 - nysn; 903 904 R12 = nxny * cs1 - nzsn; 905 R22 = nyny * cs1 + cs; 906 R32 = nynz * cs1 + nxsn; 907 908 R13 = nxnz * cs1 + nysn; 909 R23 = nynz * cs1 - nxsn; 910 R33 = nznz * cs1 + cs; 911 } 912 913 //5.ReProjection 914 const Vec2d* data2D = point2D.ptr<Vec2d>(); 915 const Vec3d* data3D = point3D.ptr<Vec3d>(); 916 Vec<tp, 2>* err2D = (Vec<tp, 2>*)errPoint2D; 917 for (int k = 0; k < point3D.rows; ++k) 918 { 919 //5.1 WorldCoordinate 920 double X = data3D[k][0]; 921 double Y = data3D[k][1]; 922 double Z = data3D[k][2]; 923 924 //5.2 CameraCoordinate 925 tp x = R11 * X + R12 * Y + R13 * Z + tx; 926 tp y = R21 * X + R22 * Y + R23 * Z + ty; 927 tp z = R31 * X + R32 * Y + R33 * Z + tz; 928 929 //5.3 StandardPhysicsCoordinate 930 tp iz = 1. / z; //if denominator==0 931 tp xc = x * iz; 932 tp yc = y * iz; 933 934 //5.4 DistortionPhysicsCoordinate 935 tp xc2 = xc * xc; 936 tp yc2 = yc * yc; 937 tp d2 = xc2 + yc2; 938 tp xcyc = 2. * xc * yc; 939 tp d4 = d2 * d2; 940 tp d6 = d2 * d4; 941 tp d2xc2 = d2 + 2. * xc2; 942 tp d2yc2 = d2 + 2. * yc2; 943 tp nu, de, xd, yd; 944 if (nDist < 5) 945 { 946 nu = 1. + k1 * d2 + k2 * d4; 947 xd = xc * nu + p1 * xcyc + p2 * d2xc2; 948 yd = yc * nu + p2 * xcyc + p1 * d2yc2; 949 } 950 else if (nDist < 8) 951 { 952 nu = 1. + k1 * d2 + k2 * d4 + k3 * d6; 953 xd = xc * nu + p1 * xcyc + p2 * d2xc2; 954 yd = yc * nu + p2 * xcyc + p1 * d2yc2; 955 } 956 else if (nDist < 12) 957 { 958 nu = 1. + k1 * d2 + k2 * d4 + k3 * d6; 959 de = 1. / (1. + k4 * d2 + k5 * d4 + k6 * d6);//if denominator==0 960 xd = xc * nu * de + p1 * xcyc + p2 * d2xc2; 961 yd = yc * nu * de + p2 * xcyc + p1 * d2yc2; 962 } 963 else if (nDist < 14) 964 { 965 nu = 1. + k1 * d2 + k2 * d4 + k3 * d6; 966 de = 1. / (1. + k4 * d2 + k5 * d4 + k6 * d6);//if denominator==0 967 xd = xc * nu * de + p1 * xcyc + p2 * d2xc2 + s1 * d2 + s2 * d4; 968 yd = yc * nu * de + p2 * xcyc + p1 * d2yc2 + s3 * d2 + s4 * d4; 969 } 970 err2D[k][0] = xd * fx + cx - data2D[k][0]; 971 err2D[k][1] = yd * fy + cy - data2D[k][1]; 972 } 973 return true; 974 } 975 }; 976 }; 977 978 int main(int argc, char** argv) { OptimizeKDRt::TestMe(argc, argv); return 0; } 979 int main1(int argc, char** argv) { OptimizeRt::TestMe(argc, argv); return 0; } 980 int main2(int argc, char** argv) { OptimizeKDRt::TestMe(argc, argv); return 0; }