27 #include <gtsam/nonlinear/NonlinearFactor.h> 28 #include <gtsam/geometry/Pose3.h> 29 #include <gtsam/geometry/Unit3.h> 31 using namespace gtsam;
47 const Unit3
nZ_, bRef_;
61 nZ_(nZ), bRef_(bRef) {
65 Vector attitudeError(
const Rot3& p,
66 OptionalJacobian<2,3> H = boost::none)
const;
69 friend class boost::serialization::access;
70 template<
class ARCHIVE>
72 ar & boost::serialization::make_nvp(
"nZ_", const_cast<Unit3&>(nZ_));
73 ar & boost::serialization::make_nvp(
"bRef_", const_cast<Unit3&>(bRef_));
83 typedef NoiseModelFactor1<Rot3>
Base;
108 const Unit3& bRef = Unit3(0, 0, 1)) :
113 virtual gtsam::NonlinearFactor::shared_ptr
clone()
const {
114 return boost::static_pointer_cast<gtsam::NonlinearFactor>(
115 gtsam::NonlinearFactor::shared_ptr(
new This(*
this)));
119 virtual void print(
const std::string& s,
const KeyFormatter& keyFormatter =
120 DefaultKeyFormatter)
const;
123 virtual bool equals(
const NonlinearFactor& expected,
double tol = 1
e-9)
const;
127 boost::optional<Matrix&> H = boost::none)
const {
128 return attitudeError(nRb, H);
140 friend class boost::serialization::access;
141 template<
class ARCHIVE>
143 ar & boost::serialization::make_nvp(
"NoiseModelFactor1",
144 boost::serialization::base_object<Base>(*
this));
145 ar & boost::serialization::make_nvp(
"GravityFactor",
146 boost::serialization::base_object<GravityFactor>(*
this));
150 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
161 typedef NoiseModelFactor1<Pose3>
Base;
186 const Unit3& bRef = Unit3(0, 0, 1)) :
191 virtual gtsam::NonlinearFactor::shared_ptr
clone()
const {
192 return boost::static_pointer_cast<gtsam::NonlinearFactor>(
193 gtsam::NonlinearFactor::shared_ptr(
new This(*
this)));
197 virtual void print(
const std::string& s,
const KeyFormatter& keyFormatter =
198 DefaultKeyFormatter)
const;
201 virtual bool equals(
const NonlinearFactor& expected,
double tol = 1
e-9)
const;
205 boost::optional<Matrix&> H = boost::none)
const {
206 Vector
e = attitudeError(nTb.rotation(), H);
209 *H = Matrix::Zero(2,6);
210 H->block<2,3>(0,0) = H23;
224 friend class boost::serialization::access;
225 template<
class ARCHIVE>
227 ar & boost::serialization::make_nvp(
"NoiseModelFactor1",
228 boost::serialization::base_object<Base>(*
this));
229 ar & boost::serialization::make_nvp(
"GravityFactor",
230 boost::serialization::base_object<GravityFactor>(*
this));
234 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
virtual ~Rot3GravityFactor()
boost::shared_ptr< Rot3GravityFactor > shared_ptr
shorthand for a smart pointer to a factor
void serialize(ARCHIVE &ar, const unsigned int)
virtual Vector evaluateError(const Rot3 &nRb, boost::optional< Matrix & > H=boost::none) const
GLM_FUNC_DECL genType e()
NoiseModelFactor1< Pose3 > Base
Pose3GravityFactor This
Typedef to this class.
void serialize(ARCHIVE &ar, const unsigned int)
virtual ~Pose3GravityFactor()
ROSCONSOLE_DECL void print(FilterBase *filter, void *logger, Level level, const char *file, int line, const char *function, const char *fmt,...) ROSCONSOLE_PRINTF_ATTRIBUTE(7
virtual gtsam::NonlinearFactor::shared_ptr clone() const
virtual gtsam::NonlinearFactor::shared_ptr clone() const
virtual Vector evaluateError(const Pose3 &nTb, boost::optional< Matrix & > H=boost::none) const
NoiseModelFactor1< Rot3 > Base
boost::shared_ptr< Pose3GravityFactor > shared_ptr
shorthand for a smart pointer to a factor
void serialize(ARCHIVE &ar, const unsigned int)
Rot3GravityFactor This
Typedef to this class.
Rot3GravityFactor(Key key, const Unit3 &nZ, const SharedNoiseModel &model, const Unit3 &bRef=Unit3(0, 0, 1))
Constructor.
Pose3GravityFactor(Key key, const Unit3 &nZ, const SharedNoiseModel &model, const Unit3 &bRef=Unit3(0, 0, 1))
Constructor.
GravityFactor(const Unit3 &nZ, const Unit3 &bRef=Unit3(0, 0, 1))
Constructor.