19 #ifndef GRAPH_FACTORS_POINT_TO_PLANE_FACTOR_H_
20 #define GRAPH_FACTORS_POINT_TO_PLANE_FACTOR_H_
24 #include <gtsam/geometry/Pose3.h>
25 #include <gtsam/geometry/Point3.h>
26 #include <gtsam/nonlinear/NonlinearFactor.h>
32 typedef NoiseModelFactor1<Pose3> Base;
39 const Pose3&
body_T_sensor,
const SharedNoiseModel& model, Key pose_key)
40 : Base(model, pose_key),
45 void print(
const std::string& s =
"",
const KeyFormatter& keyFormatter = DefaultKeyFormatter)
const override {
46 std::cout << s <<
"PointToPlaneFactor, z = ";
50 Base::print(
"", keyFormatter);
53 bool equals(
const NonlinearFactor& p,
double tol = 1e-9)
const override {
54 const This* e =
dynamic_cast<const This*
>(&p);
60 Vector
evaluateError(
const Pose3& world_T_body, boost::optional<Matrix&> H = boost::none)
const override {
62 Matrix66 d_world_T_sensor_d_world_T_body;
63 Matrix36 d_world_t_point_d_world_T_sensor;
64 Matrix13 d_distance_d_world_t_point;
65 const auto error =
getError(world_T_body, d_world_T_sensor_d_world_T_body, d_world_t_point_d_world_T_sensor,
66 d_distance_d_world_t_point);
67 *H = d_distance_d_world_t_point * d_world_t_point_d_world_T_sensor * d_world_T_sensor_d_world_T_body;
73 Vector
getError(
const Pose3& world_T_body, OptionalJacobian<6, 6> d_world_T_sensor_d_world_T_body = boost::none,
74 OptionalJacobian<3, 6> d_world_t_point_d_world_T_sensor = boost::none,
75 OptionalJacobian<1, 3> d_distance_d_world_t_point = boost::none)
const {
76 const Pose3 world_T_sensor = world_T_body.transformPoseFrom(body_T_sensor_, d_world_T_sensor_d_world_T_body);
77 const Point3 world_t_point = world_T_sensor.transformFrom(sensor_t_point_, d_world_t_point_d_world_T_sensor);
78 const double distance = world_T_plane_.
Distance(world_t_point, d_distance_d_world_t_point);
90 template <
class ARCHIVE>
91 void serialize(ARCHIVE& ar,
const unsigned int ) {
92 ar& BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
93 ar& BOOST_SERIALIZATION_NVP(sensor_t_point_);
94 ar& BOOST_SERIALIZATION_NVP(world_T_plane_);
95 ar& BOOST_SERIALIZATION_NVP(body_T_sensor_);
98 Point3 sensor_t_point_;
100 Pose3 body_T_sensor_;
103 GTSAM_MAKE_ALIGNED_OPERATOR_NEW
107 #endif // GRAPH_FACTORS_POINT_TO_PLANE_FACTOR_H_