NASA Astrobee Robot Software  0.19.1
Flight software for the Astrobee robots operating inside the International Space Station.
point_to_point_between_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_POINT_BETWEEN_FACTOR_H_
20 #define GRAPH_FACTORS_POINT_TO_POINT_BETWEEN_FACTOR_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 PointToPointBetweenFactor : public NoiseModelFactor2<Pose3, Pose3> {
30  typedef NoiseModelFactor2<Pose3, Pose3> Base;
32 
33  public:
35 
37  const Pose3& body_T_sensor, const SharedNoiseModel& model, Key source_pose_key,
38  Key target_pose_key)
39  : Base(model, source_pose_key, target_pose_key),
40  sensor_t_point_source_(sensor_t_point_source),
41  sensor_t_point_target_(sensor_t_point_target),
42  body_T_sensor_(body_T_sensor) {}
43 
44  void print(const std::string& s = "", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const override {
45  std::cout << s << "PointToPointBetweenFactor, z = ";
46  traits<Point3>::Print(sensor_t_point_source_);
47  traits<Point3>::Print(sensor_t_point_target_);
48  traits<Pose3>::Print(body_T_sensor_);
49  Base::print("", keyFormatter);
50  }
51 
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) &&
55  traits<Point3>::Equals(this->sensor_t_point_source(), e->sensor_t_point_source(), tol) &&
56  traits<Point3>::Equals(this->sensor_t_point_target(), e->sensor_t_point_target(), tol) &&
57  traits<Pose3>::Equals(this->body_T_sensor(), e->body_T_sensor(), tol);
58  }
59 
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;
67  }
68 
69  const Point3& sensor_t_point_source() const { return sensor_t_point_source_; }
70  const Point3& sensor_t_point_target() const { return sensor_t_point_target_; }
71  const Pose3& body_T_sensor() const { return body_T_sensor_; }
72 
73  private:
75  template <class ARCHIVE>
76  void serialize(ARCHIVE& ar, const unsigned int /*version*/) {
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_);
81  }
82 
83  Point3 sensor_t_point_source_;
84  Point3 sensor_t_point_target_;
85  Pose3 body_T_sensor_;
86 
87  public:
88  GTSAM_MAKE_ALIGNED_OPERATOR_NEW
89 };
90 } // namespace gtsam
91 
92 #endif // GRAPH_FACTORS_POINT_TO_POINT_BETWEEN_FACTOR_H_
gtsam::PointToPointBetweenFactor
Definition: point_to_point_between_factor.h:29
gtsam::PointToPointBetweenFactor::print
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
Definition: point_to_point_between_factor.h:44
gtsam::PointToPointBetweenFactor::equals
bool equals(const NonlinearFactor &p, double tol=1e-9) const override
Definition: point_to_point_between_factor.h:52
gtsam::PointToPointBetweenFactor::PointToPointBetweenFactor
PointToPointBetweenFactor(const Point3 &sensor_t_point_source, const Point3 &sensor_t_point_target, const Pose3 &body_T_sensor, const SharedNoiseModel &model, Key source_pose_key, Key target_pose_key)
Definition: point_to_point_between_factor.h:36
gtsam::PointToPointBetweenFactor::sensor_t_point_target
const Point3 & sensor_t_point_target() const
Definition: point_to_point_between_factor.h:70
gtsam::PointToPointBetweenFactor::PointToPointBetweenFactor
PointToPointBetweenFactor()
Definition: point_to_point_between_factor.h:34
Print
int Print(std::string const &msg)
Definition: eps_driver_tool.cc:86
gtsam::PointToPointBetweenFactor::sensor_t_point_source
const Point3 & sensor_t_point_source() const
Definition: point_to_point_between_factor.h:69
gtsam
Definition: cumulative_factor.h:26
gtsam::PointToPointBetweenFactor::evaluateError
Vector evaluateError(const Pose3 &world_T_body_source, const Pose3 &world_T_body_target, boost::optional< Matrix & > H1=boost::none, boost::optional< Matrix & > H2=boost::none) const override
Definition: point_to_point_between_factor.h:60
gtsam::PointToPointBetweenFactor::access
friend class boost::serialization::access
Definition: point_to_point_between_factor.h:74
gtsam::PointToPointBetweenFactor::body_T_sensor
const Pose3 & body_T_sensor() const
Definition: point_to_point_between_factor.h:71