gravity相关
gtsam users group discussion
姿态的先验
在body frame的重力方向
reference是navigation frame中的重力方向
可是一般会进行设置body frame与navigation frame进行重合
如果nRb * bF == nG 因子将会输出零误差
nG==nRb * bF (body frame 转到navigation frame)
/*** Base class for prior on attitude* Example:* - measurement is direction of gravity in body frame bF* - reference is direction of gravity in navigation frame nG* This factor will give zero error if nRb * bF == nG* @addtogroup Navigation*/class AttitudeFactor {};
都是protected作用域
protected:Unit3 nZ_, bRef_; ///< Position measurement in
nZ ->是在导航系中的测量
bRef ->body frame的参考方向
/** default constructor - only use for serialization */AttitudeFactor() {}/*** @brief Constructor* @param nZ measured direction in navigation frame* @param bRef reference direction in body frame (default Z-axis in NED frame, i.e., [0; 0; 1])*/AttitudeFactor(const Unit3& nZ, const Unit3& bRef = Unit3(0, 0, 1)) :nZ_(nZ), bRef_(bRef) {}
/** vector of errors */Vector attitudeError(const Rot3& p,OptionalJacobian<2,3> H = boost::none) const;
重要的一个函数
//rotate 3D direction from rotated coordinate frame to world frame
gtsam::Unit3 gtsam::Rot3::rotate(const gtsam::Unit3 &p, gtsam::OptionalJacobian<2, 3> HR = boost::none, gtsam::OptionalJacobian<2, 2> Hp = boost::none) const
//nRb是body和navigation的变换关系
Vector AttitudeFactor::attitudeError(const Rot3& nRb,OptionalJacobian<2, 3> H) const {if (H) {Matrix23 D_nRef_R;Matrix22 D_e_nRef;Unit3 nRef = nRb.rotate(bRef_, D_nRef_R);//b -> worldVector e = nZ_.error(nRef, D_e_nRef);//nZ_测量,nRef计算得到,由于是单位向量所以D_e_nRef是2x2的矩阵(*H) = D_e_nRef * D_nRef_R;//链式求导//对变换关系的导数return e;} else {Unit3 nRef = nRb * bRef_;return nZ_.error(nRef);}
}
const Unit3& nZ() const {return nZ_;}const Unit3& bRef() const {return bRef_;}/** Serialization function */friend class boost::serialization::access;templatevoid serialize(ARCHIVE & ar, const unsigned int /*version*/) {ar & boost::serialization::make_nvp("nZ_", nZ_);ar & boost::serialization::make_nvp("bRef_", bRef_);}
/*** Version of AttitudeFactor for Rot3* @addtogroup Navigation*/
class GTSAM_EXPORT Rot3AttitudeFactor: public NoiseModelFactor1, public AttitudeFactor
{};
typedef NoiseModelFactor1 Base;public:/// shorthand for a smart pointer to a factortypedef boost::shared_ptr shared_ptr;/// Typedef to this classtypedef Rot3AttitudeFactor This;
key ->value的key
nZ ->navigation frame中的测量方向
bRef ->body frame下的参考方向
/*** @brief Constructor* @param key of the Rot3 variable that will be constrained* @param nZ measured direction in navigation frame* @param model Gaussian noise model* @param bRef reference direction in body frame (default Z-axis)*/Rot3AttitudeFactor(Key key, const Unit3& nZ, const SharedNoiseModel& model,const Unit3& bRef = Unit3(0, 0, 1)) :Base(model, key), AttitudeFactor(nZ, bRef) {}
见attitudeError
/** vector of errors */Vector evaluateError(const Rot3& nRb, //boost::optional H = boost::none) const override {return attitudeError(nRb, H);}
class GTSAM_EXPORT Pose3AttitudeFactor: public NoiseModelFactor1, public AttitudeFactor
{};
typedef NoiseModelFactor1 Base;public:/// shorthand for a smart pointer to a factortypedef boost::shared_ptr shared_ptr;/// Typedef to this classtypedef Pose3AttitudeFactor This;
key ->value的key
nZ ->navigation frame中的测量方向
bRef ->body frame下的参考方向
/*** @brief Constructor* @param key of the Pose3 variable that will be constrained* @param nZ measured direction in navigation frame* @param model Gaussian noise model* @param bRef reference direction in body frame (default Z-axis)*/Pose3AttitudeFactor(Key key, const Unit3& nZ, const SharedNoiseModel& model,const Unit3& bRef = Unit3(0, 0, 1)) :Base(model, key), AttitudeFactor(nZ, bRef) {}
对Pose3的求导
对平移导数为0,只保留旋转的
/** vector of errors */Vector evaluateError(const Pose3& nTb, //boost::optional H = boost::none) const override {Vector e = attitudeError(nTb.rotation(), H);//对旋转求导if (H) {Matrix H23 = *H;*H = Matrix::Zero(2,6);H->block<2,3>(0,0) = H23;//对平移导数为0,只保留旋转的}return e;}