19 #ifndef GRAPH_FACTORS_POINT_TO_POINT_BETWEEN_FACTOR_H_
20 #define GRAPH_FACTORS_POINT_TO_POINT_BETWEEN_FACTOR_H_
22 #include <gtsam/geometry/Pose3.h>
23 #include <gtsam/geometry/Point3.h>
24 #include <gtsam/nonlinear/NonlinearFactor.h>
30 typedef NoiseModelFactor2<Pose3, Pose3> Base;
37 const Pose3&
body_T_sensor,
const SharedNoiseModel& model, Key source_pose_key,
39 : Base(model, source_pose_key, target_pose_key),
44 void print(
const std::string& s =
"",
const KeyFormatter& keyFormatter = DefaultKeyFormatter)
const override {
45 std::cout << s <<
"PointToPointBetweenFactor, z = ";
49 Base::print(
"", keyFormatter);
52 bool equals(
const NonlinearFactor& p,
double tol = 1e-9)
const override {
53 const This* e =
dynamic_cast<const This*
>(&p);
54 return e && Base::equals(p, tol) &&
60 Vector
evaluateError(
const Pose3& world_T_body_source,
const Pose3& world_T_body_target,
61 boost::optional<Matrix&> H1 = boost::none,
62 boost::optional<Matrix&> H2 = boost::none)
const override {
63 const auto world_t_point_source = world_T_body_source.transformFrom(body_T_sensor_ * sensor_t_point_source_, H1);
64 const auto world_t_point_target = world_T_body_target.transformFrom(body_T_sensor_ * sensor_t_point_target_, H2);
65 if (H2) *H2 = -1.0 * (*H2);
66 return world_t_point_source - world_t_point_target;
75 template <
class ARCHIVE>
76 void serialize(ARCHIVE& ar,
const unsigned int ) {
77 ar& BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
78 ar& BOOST_SERIALIZATION_NVP(sensor_t_point_source_);
79 ar& BOOST_SERIALIZATION_NVP(sensor_t_point_target_);
80 ar& BOOST_SERIALIZATION_NVP(body_T_sensor_);
83 Point3 sensor_t_point_source_;
84 Point3 sensor_t_point_target_;
88 GTSAM_MAKE_ALIGNED_OPERATOR_NEW
92 #endif // GRAPH_FACTORS_POINT_TO_POINT_BETWEEN_FACTOR_H_