NASA Astrobee Robot Software  0.19.1
Flight software for the Astrobee robots operating inside the International Space Station.
point_to_line_factor_base.h
Go to the documentation of this file.
1 /* Copyright (c) 2017, United States Government, as represented by the
2  * Administrator of the National Aeronautics and Space Administration.
3  *
4  * All rights reserved.
5  *
6  * The Astrobee platform is licensed under the Apache License, Version 2.0
7  * (the "License"); you may not use this file except in compliance with the
8  * License. You may obtain a copy of the License at
9  *
10  * http://www.apache.org/licenses/LICENSE-2.0
11  *
12  * Unless required by applicable law or agreed to in writing, software
13  * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
14  * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
15  * License for the specific language governing permissions and limitations
16  * under the License.
17  */
18 
19 #ifndef GRAPH_FACTORS_POINT_TO_LINE_FACTOR_BASE_H_
20 #define GRAPH_FACTORS_POINT_TO_LINE_FACTOR_BASE_H_
21 
22 #include <gtsam/geometry/Pose3.h>
23 #include <gtsam/geometry/Point3.h>
24 #include <gtsam/nonlinear/NonlinearFactor.h>
25 
26 #include <string>
27 
28 namespace gtsam {
29 class PointToLineFactorBase : public NoiseModelFactor1<gtsam::Pose3> {
30  typedef NoiseModelFactor1<Pose3> Base;
32 
33  public:
35 
36  // The line in world_T_line is oriented such that the z axis is along the line and is initialized with an arbitrary
37  // orientation about the z axis. body_T_sensor is the sensor extrinsics and assumed to be static.
38  PointToLineFactorBase(const Point3& sensor_t_point, const Pose3& world_T_line, const Pose3& body_T_sensor,
39  const SharedNoiseModel& model, Key pose_key)
40  : Base(model, pose_key),
41  sensor_t_point_(sensor_t_point),
42  world_T_line_(world_T_line),
43  body_T_sensor_(body_T_sensor),
44  sensor_R_body_(body_T_sensor.inverse().rotation().matrix()),
45  body_t_sensor_(body_T_sensor_.translation()) {}
46 
47  void print(const std::string& s = "", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const override {
48  std::cout << s << "PointToLineFactorBase, z = ";
49  traits<Point3>::Print(sensor_t_point_);
50  traits<Pose3>::Print(world_T_line_);
51  traits<Pose3>::Print(body_T_sensor_);
52  Base::print("", keyFormatter);
53  }
54 
55  bool equals(const NonlinearFactor& p, double tol = 1e-9) const override {
56  const This* e = dynamic_cast<const This*>(&p);
57  return e && Base::equals(p, tol) && traits<Point3>::Equals(this->sensor_t_point(), e->sensor_t_point(), tol) &&
58  traits<Pose3>::Equals(this->world_T_line(), e->world_T_line(), tol) &&
59  traits<Pose3>::Equals(this->body_T_sensor(), e->body_T_sensor(), tol);
60  }
61 
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;
65  if (H) {
66  // GTSAM equivalent:
67  /* gtsam::Matrix H_a;
68  const auto world_T_sensor = world_T_body.transformPoseFrom(body_T_sensor_, H_a);
69  gtsam::Matrix H_b;
70  const auto line_T_sensor = world_T_line_.inverse().transformPoseFrom(world_T_sensor, boost::none, H_b);
71  gtsam::Matrix H_c;
72  const auto line_t_point = line_T_sensor.transformFrom(sensor_t_point_, H_c);
73  H = H_c *H_b* H_a;
74  */
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_)) *
78  sensor_R_body_;
79  const Matrix B = line_R_sensor * sensor_R_body_;
80  // TODO(rsoussan): avoid zero initialization
81  *H = Eigen::Matrix<double, 3, 6>::Zero();
82  *H << A, B;
83  }
84  return line_T_sensor * sensor_t_point_;
85  }
86 
87  const Point3& sensor_t_point() const { return sensor_t_point_; }
88  const Pose3& world_T_line() const { return world_T_line_; }
89  const Pose3& body_T_sensor() const { return body_T_sensor_; }
90 
91  private:
93  template <class ARCHIVE>
94  void serialize(ARCHIVE& ar, const unsigned int /*version*/) {
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_);
101  }
102 
103  Point3 sensor_t_point_;
104  Pose3 world_T_line_;
105  Pose3 body_T_sensor_;
106  // Cached for faster Jacobian calculations
107  Matrix sensor_R_body_;
108  Point3 body_t_sensor_;
109 
110  public:
111  GTSAM_MAKE_ALIGNED_OPERATOR_NEW
112 };
113 } // namespace gtsam
114 
115 #endif // GRAPH_FACTORS_POINT_TO_LINE_FACTOR_BASE_H_
gtsam::PointToLineFactorBase::error
Vector error(const Pose3 &world_T_body, boost::optional< Matrix & > H=boost::none) const
Definition: point_to_line_factor_base.h:62
gtsam::PointToLineFactorBase::sensor_t_point
const Point3 & sensor_t_point() const
Definition: point_to_line_factor_base.h:87
gtsam::PointToLineFactorBase
Definition: point_to_line_factor_base.h:29
gtsam::PointToLineFactorBase::equals
bool equals(const NonlinearFactor &p, double tol=1e-9) const override
Definition: point_to_line_factor_base.h:55
gtsam::PointToLineFactorBase::print
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
Definition: point_to_line_factor_base.h:47
gtsam::PointToLineFactorBase::world_T_line
const Pose3 & world_T_line() const
Definition: point_to_line_factor_base.h:88
Print
int Print(std::string const &msg)
Definition: eps_driver_tool.cc:86
gtsam::PointToLineFactorBase::access
friend class boost::serialization::access
Definition: point_to_line_factor_base.h:92
gtsam
Definition: cumulative_factor.h:26
gtsam::PointToLineFactorBase::PointToLineFactorBase
PointToLineFactorBase()
Definition: point_to_line_factor_base.h:34
gtsam::PointToLineFactorBase::body_T_sensor
const Pose3 & body_T_sensor() const
Definition: point_to_line_factor_base.h:89
gtsam::PointToLineFactorBase::PointToLineFactorBase
PointToLineFactorBase(const Point3 &sensor_t_point, const Pose3 &world_T_line, const Pose3 &body_T_sensor, const SharedNoiseModel &model, Key pose_key)
Definition: point_to_line_factor_base.h:38