NASA Astrobee Robot Software  0.19.1
Flight software for the Astrobee robots operating inside the International Space Station.
point_to_plane_factor.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_PLANE_FACTOR_H_
20 #define GRAPH_FACTORS_POINT_TO_PLANE_FACTOR_H_
21 
23 
24 #include <gtsam/geometry/Pose3.h>
25 #include <gtsam/geometry/Point3.h>
26 #include <gtsam/nonlinear/NonlinearFactor.h>
27 
28 #include <string>
29 
30 namespace gtsam {
31 class PointToPlaneFactor : public NoiseModelFactor1<Pose3> {
32  typedef NoiseModelFactor1<Pose3> Base;
33  typedef PointToPlaneFactor This;
34 
35  public:
37 
39  const Pose3& body_T_sensor, const SharedNoiseModel& model, Key pose_key)
40  : Base(model, pose_key),
41  sensor_t_point_(sensor_t_point),
42  world_T_plane_(world_T_plane),
43  body_T_sensor_(body_T_sensor) {}
44 
45  void print(const std::string& s = "", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const override {
46  std::cout << s << "PointToPlaneFactor, z = ";
47  traits<Point3>::Print(sensor_t_point_);
49  traits<Pose3>::Print(body_T_sensor_);
50  Base::print("", keyFormatter);
51  }
52 
53  bool equals(const NonlinearFactor& p, double tol = 1e-9) const override {
54  const This* e = dynamic_cast<const This*>(&p);
55  return e && Base::equals(p, tol) && traits<Point3>::Equals(this->sensor_t_point(), e->sensor_t_point(), tol) &&
56  traits<localization_measurements::Plane>::Equals(this->world_T_plane(), e->world_T_plane(), tol) &&
57  traits<Pose3>::Equals(this->body_T_sensor(), e->body_T_sensor(), tol);
58  }
59 
60  Vector evaluateError(const Pose3& world_T_body, boost::optional<Matrix&> H = boost::none) const override {
61  if (H) {
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;
68  return error;
69  }
70  return getError(world_T_body);
71  }
72 
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);
79  Vector error(1);
80  error << distance;
81  return error;
82  }
83 
84  const Point3& sensor_t_point() const { return sensor_t_point_; }
85  const localization_measurements::Plane& world_T_plane() const { return world_T_plane_; }
86  const Pose3& body_T_sensor() const { return body_T_sensor_; }
87 
88  private:
90  template <class ARCHIVE>
91  void serialize(ARCHIVE& ar, const unsigned int /*version*/) {
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_);
96  }
97 
98  Point3 sensor_t_point_;
99  localization_measurements::Plane world_T_plane_;
100  Pose3 body_T_sensor_;
101 
102  public:
103  GTSAM_MAKE_ALIGNED_OPERATOR_NEW
104 };
105 } // namespace gtsam
106 
107 #endif // GRAPH_FACTORS_POINT_TO_PLANE_FACTOR_H_
gtsam::PointToPlaneFactor::getError
Vector getError(const Pose3 &world_T_body, OptionalJacobian< 6, 6 > d_world_T_sensor_d_world_T_body=boost::none, OptionalJacobian< 3, 6 > d_world_t_point_d_world_T_sensor=boost::none, OptionalJacobian< 1, 3 > d_distance_d_world_t_point=boost::none) const
Definition: point_to_plane_factor.h:73
gtsam::PointToPlaneFactor::body_T_sensor
const Pose3 & body_T_sensor() const
Definition: point_to_plane_factor.h:86
plane.h
gtsam::PointToPlaneFactor::print
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
Definition: point_to_plane_factor.h:45
gtsam::PointToPlaneFactor::PointToPlaneFactor
PointToPlaneFactor()
Definition: point_to_plane_factor.h:36
gtsam::PointToPlaneFactor::sensor_t_point
const Point3 & sensor_t_point() const
Definition: point_to_plane_factor.h:84
Print
int Print(std::string const &msg)
Definition: eps_driver_tool.cc:86
gtsam::PointToPlaneFactor::access
friend class boost::serialization::access
Definition: point_to_plane_factor.h:89
gtsam::PointToPlaneFactor::PointToPlaneFactor
PointToPlaneFactor(const Point3 &sensor_t_point, const localization_measurements::Plane &world_T_plane, const Pose3 &body_T_sensor, const SharedNoiseModel &model, Key pose_key)
Definition: point_to_plane_factor.h:38
gtsam::PointToPlaneFactor::world_T_plane
const localization_measurements::Plane & world_T_plane() const
Definition: point_to_plane_factor.h:85
gtsam::PointToPlaneFactor
Definition: point_to_plane_factor.h:31
gtsam
Definition: cumulative_factor.h:26
localization_measurements::Plane::Distance
double Distance(const gtsam::Point3 &point, gtsam::OptionalJacobian< 1, 3 > d_distance_d_point=boost::none) const
Definition: plane.h:94
error
uint8_t error
Definition: signal_lights.h:89
gtsam::PointToPlaneFactor::evaluateError
Vector evaluateError(const Pose3 &world_T_body, boost::optional< Matrix & > H=boost::none) const override
Definition: point_to_plane_factor.h:60
localization_measurements::Plane
Definition: plane.h:87
gtsam::PointToPlaneFactor::equals
bool equals(const NonlinearFactor &p, double tol=1e-9) const override
Definition: point_to_plane_factor.h:53