34 Point2 reprojectionError(
camera.project(point, Hprj, H3, {}) -
36 if (H1) *H1 = Hprj * HbodySensor * (*H1);
37 if (H2) *H2 = Hprj * HbodySensor * (*H2);
38 return reprojectionError;
45 Point2 reprojectionError(camera.
project(point, Hprj, H3, {}) -
47 if (H1) *H1 = Hprj * (*H1);
48 if (H2) *H2 = Hprj * (*H2);
49 return reprojectionError;
52 if (H1) *H1 = Matrix::Zero(2, 6);
53 if (H2) *H2 = Matrix::Zero(2, 6);
54 if (H3) *H3 = Matrix::Zero(2, 3);
56 std::cout << e.
what() <<
": Landmark " 61 return Vector2::Constant(2.0 *
K_->fx());
static const KeyFormatter DefaultKeyFormatter
Basic projection factor for rolling shutter cameras.
Point2 project(const Point3 &pw, OptionalJacobian< 2, 6 > Dpose={}, OptionalJacobian< 2, 3 > Dpoint={}, OptionalJacobian< 2, DimK > Dcal={}) const
project a 3D point from world coordinates into the image
Matrix * OptionalMatrixType
Array< double, 1, 3 > e(1./3., 0.5, 2.)
Class compose(const Class &g) const
Point2 measured_
2D measurement
static const Pose3 pose(Rot3(Vector3(1, -1, -1).asDiagonal()), Point3(0, 0, 0.5))
std::optional< Pose3 > body_P_sensor_
The pose of the sensor in the body frame.
Vector evaluateError(const Pose3 &pose_a, const Pose3 &pose_b, const Point3 &point, OptionalMatrixType H1, OptionalMatrixType H2, OptionalMatrixType H3) const override
Evaluate error h(x)-z and optionally derivatives.
static const CalibratedCamera camera(kDefaultPose)
std::shared_ptr< Cal3_S2 > K_
shared pointer to calibration object
const char * what() const noexcept override