|
NASA Astrobee Robot Software
0.19.1
Flight software for the Astrobee robots operating inside the International Space Station.
|
Go to the documentation of this file.
19 #ifndef GRAPH_FACTORS_POINT_TO_LINE_FACTOR_H_
20 #define GRAPH_FACTORS_POINT_TO_LINE_FACTOR_H_
24 #include <gtsam/geometry/Pose3.h>
25 #include <gtsam/geometry/Point3.h>
38 const SharedNoiseModel& model, Key pose_key,
const bool use_silu =
false)
41 void print(
const std::string& s =
"",
const KeyFormatter& keyFormatter = DefaultKeyFormatter)
const override {
42 std::cout << s <<
"PointToLineFactor, z = ";
46 bool equals(
const NonlinearFactor& p,
double tol = 1e-9)
const override {
return Base::equals(p, tol); }
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);
52 *H = H->topRows(2).eval();
54 return line_t_point.head<2>();
59 template <
class ARCHIVE>
60 void serialize(ARCHIVE& ar,
const unsigned int ) {
61 ar& BOOST_SERIALIZATION_BASE_OBJECT_NVP(
Base);
66 #endif // GRAPH_FACTORS_POINT_TO_LINE_FACTOR_H_
Vector error(const Pose3 &world_T_body, boost::optional< Matrix & > H=boost::none) const
Definition: point_to_line_factor_base.h:62
const Point3 & sensor_t_point() const
Definition: point_to_line_factor_base.h:87
PointToLineFactor()
Definition: point_to_line_factor.h:35
Definition: point_to_line_factor_base.h:29
bool equals(const NonlinearFactor &p, double tol=1e-9) const override
Definition: point_to_line_factor_base.h:55
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
Definition: point_to_line_factor_base.h:47
Vector evaluateError(const Pose3 &world_T_body, boost::optional< Matrix & > H=boost::none) const override
Definition: point_to_line_factor.h:48
const Pose3 & world_T_line() const
Definition: point_to_line_factor_base.h:88
friend class boost::serialization::access
Definition: point_to_line_factor.h:58
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
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
Definition: point_to_line_factor.h:41
Definition: cumulative_factor.h:26
bool equals(const NonlinearFactor &p, double tol=1e-9) const override
Definition: point_to_line_factor.h:46
Definition: point_to_line_factor.h:30
const Pose3 & body_T_sensor() const
Definition: point_to_line_factor_base.h:89