AttitudeFactor.h/AttitudeFactor.cpp
创始人
2024-01-28 12:05:33
0

AttitudeFactor.h/AttitudeFactor.cpp

  • 一、AttitudeFactor类
    • 1.1 成员函数
    • 1.2 构造函数
    • 1.3 计算误差的
    • 1.4 其他
  • 二、基于SO(3)的派生类
    • 2.1 一些定义
    • 2.2 有参构造
    • 2.3 计算误差
    • 2.4 traits
    • 三、基于SE(3)的派生类
    • 3.1 一些定义
    • 3.2 有参构造
    • 3.3 误差函数
    • 3.4 traits

gravity相关
gtsam users group discussion

一、AttitudeFactor类

姿态的先验
在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 {};

1.1 成员函数

都是protected作用域

protected:Unit3 nZ_, bRef_; ///< Position measurement in

1.2 构造函数

nZ是navigation frame的测量方向 bRef是在body frame中的参考方向 由系的转换的到旋转矩阵

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) {}

1.3 计算误差的

  /** 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);}
}

1.4 其他

  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_);}

二、基于SO(3)的派生类

/*** Version of AttitudeFactor for Rot3* @addtogroup Navigation*/
class GTSAM_EXPORT Rot3AttitudeFactor: public NoiseModelFactor1, public AttitudeFactor 
{};

2.1 一些定义

  typedef NoiseModelFactor1 Base;public:/// shorthand for a smart pointer to a factortypedef boost::shared_ptr shared_ptr;/// Typedef to this classtypedef Rot3AttitudeFactor This;

2.2 有参构造

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) {}

2.3 计算误差

见attitudeError

  /** vector of errors */Vector evaluateError(const Rot3& nRb, //boost::optional H = boost::none) const override {return attitudeError(nRb, H);}

2.4 traits

三、基于SE(3)的派生类

class GTSAM_EXPORT Pose3AttitudeFactor: public NoiseModelFactor1, public AttitudeFactor 
{};

3.1 一些定义

  typedef NoiseModelFactor1 Base;public:/// shorthand for a smart pointer to a factortypedef boost::shared_ptr shared_ptr;/// Typedef to this classtypedef Pose3AttitudeFactor This;

3.2 有参构造

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) {}

3.3 误差函数

对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;}

3.4 traits

相关内容

热门资讯

喜欢穿一身黑的男生性格(喜欢穿... 今天百科达人给各位分享喜欢穿一身黑的男生性格的知识,其中也会对喜欢穿一身黑衣服的男人人好相处吗进行解...
发春是什么意思(思春和发春是什... 本篇文章极速百科给大家谈谈发春是什么意思,以及思春和发春是什么意思对应的知识点,希望对各位有所帮助,...
网络用语zl是什么意思(zl是... 今天给各位分享网络用语zl是什么意思的知识,其中也会对zl是啥意思是什么网络用语进行解释,如果能碰巧...
为什么酷狗音乐自己唱的歌不能下... 本篇文章极速百科小编给大家谈谈为什么酷狗音乐自己唱的歌不能下载到本地?,以及为什么酷狗下载的歌曲不是...
华为下载未安装的文件去哪找(华... 今天百科达人给各位分享华为下载未安装的文件去哪找的知识,其中也会对华为下载未安装的文件去哪找到进行解...
怎么往应用助手里添加应用(应用... 今天百科达人给各位分享怎么往应用助手里添加应用的知识,其中也会对应用助手怎么添加微信进行解释,如果能...
家里可以做假山养金鱼吗(假山能... 今天百科达人给各位分享家里可以做假山养金鱼吗的知识,其中也会对假山能放鱼缸里吗进行解释,如果能碰巧解...
四分五裂是什么生肖什么动物(四... 本篇文章极速百科小编给大家谈谈四分五裂是什么生肖什么动物,以及四分五裂打一生肖是什么对应的知识点,希...
一帆风顺二龙腾飞三阳开泰祝福语... 本篇文章极速百科给大家谈谈一帆风顺二龙腾飞三阳开泰祝福语,以及一帆风顺二龙腾飞三阳开泰祝福语结婚对应...
美团联名卡审核成功待激活(美团... 今天百科达人给各位分享美团联名卡审核成功待激活的知识,其中也会对美团联名卡审核未通过进行解释,如果能...