28 using namespace std::placeholders;
 
   29 using namespace gtsam;
 
   48   Pose3 init_pose(Rot3::Ypr(0.0, 0.0, 0.0), 
Point3(0.0, 0.0, 0.0));
 
   50   sigmas << 0.001, 0.001, 0.001, 0.001, 0.001, 0.001;
 
   54   Vector3 sigmas3 {0.1, 0.1, 0.1};
 
   55   Vector4 measurement0 {-1.0, 0.0, 0.0, 3.0};
 
   57       measurement0, noiseModel::Diagonal::Sigmas(sigmas3), 
X(0), 
P(0));
 
  135   Pose3 poseLin(rotationLin, pointLin);
 
  144     return factor.evaluateError(
p, o);
 
  146   Matrix numericalH1 = numericalDerivative21<Vector, Pose3, OrientedPlane3>(
f, poseLin, pLin);
 
  147   Matrix numericalH2 = numericalDerivative22<Vector, Pose3, OrientedPlane3>(
f, poseLin, pLin);
 
  150   Matrix actualH1, actualH2;
 
  151   factor.evaluateError(poseLin, pLin, actualH1, actualH2);
 
  165   Vector4 planeOrientation = (
Vector(4) << 0.0, 0.0, -1.0, 10.0).finished(); 
 
  173   Vector4 theta1 {0.0, 0.02, -1.2, 10.0};
 
  174   Vector4 theta2 {0.0, 0.1, -0.8, 10.0};
 
  175   Vector4 theta3 {0.0, 0.2, -0.9, 10.0};
 
  182   Matrix expectedH1 = numericalDerivative11<Vector, OrientedPlane3>(
 
  185   Matrix expectedH2 = numericalDerivative11<Vector, OrientedPlane3>(
 
  188   Matrix expectedH3 = numericalDerivative11<Vector, OrientedPlane3>(
 
  192   Matrix actualH1, actualH2, actualH3;
 
  214   auto x0_noise = noiseModel::Isotropic::Sigma(6, 0.01);
 
  218   const Plane 
p1(0,0,1,1), 
p2(0,0,1,2);
 
  219   auto p1_noise = noiseModel::Diagonal::Sigmas(
Vector3{1, 1, 5});
 
  220   auto p2_noise = noiseModel::Diagonal::Sigmas(
Vector3{1, 1, 5});
 
  225   auto p1_measured_from_x0 = 
p1.transform(
x0); 
 
  226   auto p2_measured_from_x0 = 
p2.transform(
x0); 
 
  227   const auto x0_p1_noise = noiseModel::Isotropic::Sigma(3, 0.05);
 
  228   const auto x0_p2_noise = noiseModel::Isotropic::Sigma(3, 0.05);
 
  230       p1_measured_from_x0.planeCoefficients(), x0_p1_noise, 
X(0), 
P(1));
 
  232       p2_measured_from_x0.planeCoefficients(), x0_p2_noise, 
X(0), 
P(2));
 
  238   initialEstimate.insert(
P(1), 
p1);
 
  239   initialEstimate.insert(
P(2), 
p2);
 
  240   initialEstimate.insert(
X(0), x0_initial);
 
  251     std::cerr << 
"CAPTURED THE EXCEPTION: " << 
DefaultKeyFormatter(
e.nearbyVariable()) << std::endl;
 
  258   srand(
time(
nullptr));