19 #ifndef GRAPH_FACTORS_POINT_TO_LINE_FACTOR_BASE_H_ 
   20 #define GRAPH_FACTORS_POINT_TO_LINE_FACTOR_BASE_H_ 
   22 #include <gtsam/geometry/Pose3.h> 
   23 #include <gtsam/geometry/Point3.h> 
   24 #include <gtsam/nonlinear/NonlinearFactor.h> 
   30   typedef NoiseModelFactor1<Pose3> Base;
 
   39                         const SharedNoiseModel& model, Key pose_key)
 
   40       : Base(model, pose_key),
 
   45         body_t_sensor_(body_T_sensor_.translation()) {}
 
   47   void print(
const std::string& s = 
"", 
const KeyFormatter& keyFormatter = DefaultKeyFormatter)
 const override {
 
   48     std::cout << s << 
"PointToLineFactorBase, z = ";
 
   52     Base::print(
"", keyFormatter);
 
   55   bool equals(
const NonlinearFactor& p, 
double tol = 1e-9)
 const override {
 
   56     const This* e = 
dynamic_cast<const This*
>(&p);
 
   62   Vector 
error(
const Pose3& world_T_body, boost::optional<Matrix&> H = boost::none)
 const {
 
   63     const Pose3 world_T_sensor = world_T_body * body_T_sensor_;
 
   64     const Pose3 line_T_sensor = world_T_line_.inverse() * world_T_sensor;
 
   75       const Matrix3 line_R_sensor = line_T_sensor.rotation().matrix();
 
   76       const Matrix A = -1.0 * line_R_sensor *
 
   77                        (skewSymmetric(sensor_t_point_) + skewSymmetric(sensor_R_body_ * body_t_sensor_)) *
 
   79       const Matrix B = line_R_sensor * sensor_R_body_;
 
   81       *H = Eigen::Matrix<double, 3, 6>::Zero();
 
   84     return line_T_sensor * sensor_t_point_;
 
   93   template <
class ARCHIVE>
 
   94   void serialize(ARCHIVE& ar, 
const unsigned int ) {
 
   95     ar& BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
 
   96     ar& BOOST_SERIALIZATION_NVP(sensor_t_point_);
 
   97     ar& BOOST_SERIALIZATION_NVP(world_T_line_);
 
   98     ar& BOOST_SERIALIZATION_NVP(body_T_sensor_);
 
   99     ar& BOOST_SERIALIZATION_NVP(sensor_R_body_);
 
  100     ar& BOOST_SERIALIZATION_NVP(body_t_sensor_);
 
  103   Point3 sensor_t_point_;
 
  105   Pose3 body_T_sensor_;
 
  107   Matrix sensor_R_body_;
 
  108   Point3 body_t_sensor_;
 
  111   GTSAM_MAKE_ALIGNED_OPERATOR_NEW
 
  115 #endif  // GRAPH_FACTORS_POINT_TO_LINE_FACTOR_BASE_H_