NASA Astrobee Robot Software  0.19.1
Flight software for the Astrobee robots operating inside the International Space Station.
point_to_line_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_LINE_FACTOR_H_
20 #define GRAPH_FACTORS_POINT_TO_LINE_FACTOR_H_
21 
23 
24 #include <gtsam/geometry/Pose3.h>
25 #include <gtsam/geometry/Point3.h>
26 
27 #include <string>
28 
29 namespace gtsam {
32  typedef PointToLineFactor This;
33 
34  public:
36 
37  PointToLineFactor(const Point3& sensor_t_point, const Pose3& world_T_line, const Pose3& body_T_sensor,
38  const SharedNoiseModel& model, Key pose_key, const bool use_silu = false)
39  : Base(sensor_t_point, world_T_line, body_T_sensor, model, pose_key) {}
40 
41  void print(const std::string& s = "", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const override {
42  std::cout << s << "PointToLineFactor, z = ";
43  Base::print("", keyFormatter);
44  }
45 
46  bool equals(const NonlinearFactor& p, double tol = 1e-9) const override { return Base::equals(p, tol); }
47 
48  Vector evaluateError(const Pose3& world_T_body, boost::optional<Matrix&> H = boost::none) const override {
49  const auto line_t_point = Base::error(world_T_body, H);
50  if (H) {
51  // Remove last row as error does not account for z value in line_t_point
52  *H = H->topRows(2).eval();
53  }
54  return line_t_point.head<2>();
55  }
56 
57  private:
59  template <class ARCHIVE>
60  void serialize(ARCHIVE& ar, const unsigned int /*version*/) {
61  ar& BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
62  }
63 };
64 } // namespace gtsam
65 
66 #endif // GRAPH_FACTORS_POINT_TO_LINE_FACTOR_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::PointToLineFactor::PointToLineFactor
PointToLineFactor()
Definition: point_to_line_factor.h:35
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::PointToLineFactor::evaluateError
Vector evaluateError(const Pose3 &world_T_body, boost::optional< Matrix & > H=boost::none) const override
Definition: point_to_line_factor.h:48
gtsam::PointToLineFactorBase::world_T_line
const Pose3 & world_T_line() const
Definition: point_to_line_factor_base.h:88
gtsam::PointToLineFactor::access
friend class boost::serialization::access
Definition: point_to_line_factor.h:58
gtsam::PointToLineFactor::PointToLineFactor
PointToLineFactor(const Point3 &sensor_t_point, const Pose3 &world_T_line, const Pose3 &body_T_sensor, const SharedNoiseModel &model, Key pose_key, const bool use_silu=false)
Definition: point_to_line_factor.h:37
gtsam::PointToLineFactor::print
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
Definition: point_to_line_factor.h:41
gtsam
Definition: cumulative_factor.h:26
point_to_line_factor_base.h
gtsam::PointToLineFactor::equals
bool equals(const NonlinearFactor &p, double tol=1e-9) const override
Definition: point_to_line_factor.h:46
gtsam::PointToLineFactor
Definition: point_to_line_factor.h:30
gtsam::PointToLineFactorBase::body_T_sensor
const Pose3 & body_T_sensor() const
Definition: point_to_line_factor_base.h:89