AttitudeFactor.h/AttitudeFactor.cpp

  • 0、误差计算以SO3为例
  • 一、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

0、误差计算以SO3为例

  /** vector of errors */
Vector evaluateError(const Rot3& nRb, //nRb是优化初值boost::optional<Matrix&> H = boost::none) const override {return attitudeError(nRb, H);
Vector AttitudeFactor::attitudeError(const Rot3& nRb,OptionalJacobian<2, 3> H) const {if (H) {Matrix23 D_nRef_R;Matrix22 D_e_nRef;//bRef_是参考有defalt值(是一个vector,通常是重力方向默认(0,0,1))//下面是将bRef_通过nRb转到导航系下(world)(nRb是优化变量)Unit3 nRef = nRb.rotate(bRef_, D_nRef_R);//nz_是在导航系下的测量值//下面是测量值nZ_和上一步优化变量()计算误差,算JacobianVector e = nZ_.error(nRef, D_e_nRef);(*H) = D_e_nRef * D_nRef_R;return e;} else {Unit3 nRef = nRb * bRef_;return nZ_.error(nRef);}
}

一、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;template<class ARCHIVE>void 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<Rot3>, public AttitudeFactor
{};

2.1 一些定义

  typedef NoiseModelFactor1<Rot3> Base;public:/// shorthand for a smart pointer to a factortypedef boost::shared_ptr<Rot3AttitudeFactor> 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<Matrix&> H = boost::none) const override {return attitudeError(nRb, H);}

2.4 traits

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

class GTSAM_EXPORT Pose3AttitudeFactor: public NoiseModelFactor1<Pose3>, public AttitudeFactor
{};

3.1 一些定义

  typedef NoiseModelFactor1<Pose3> Base;public:/// shorthand for a smart pointer to a factortypedef boost::shared_ptr<Pose3AttitudeFactor> 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<Matrix&> 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

AttitudeFactor.h/AttitudeFactor.cpp相关推荐

  1. 把Qt的界面文件(.ui文件)生成源文件(.h或.cpp)封装成链接库

    前言 在用Qt做开发时,为了方便快速,一般都使用Qt设计师界面类来做界面相关的布局,这个类在当前工程中是没有.cpp或.h文件的,但主类又有引入了这个头文件,点开转到定义或声明时,是打不开的,如下图: ...

  2. c++ *.h和*.cpp在编译中的作用

    首先,我们可以将所有东西都放在一个.cpp文件内.然后编译器就将这个.cpp编译成.obj,obj是什么东西?就是编译单元了. 一个程序,可以由一个编译单元组成,也可以有多个编译单元组成. 如果你不想 ...

  3. 在类模板的声明和定义中把.h与.cpp分离

    看了几位大吓的回复,深深地感觉到了这篇附笔中可能存在错误,于是把最初遇到此问题时的环境再模拟了一下,现在可以确认这篇附笔中的确存在问题,现在就修正一下,并对各位表示歉意. 6月初的一个项目中需要写一个 ...

  4. C++中的 .h 和 .cpp 区别详解

    2019独角兽企业重金招聘Python工程师标准>>> 在C++编程过程中,随着项目的越来越大,代码也会越来越多,并且难以管理和分析.于是,在C++中就要分出了头(.h)文件和实现( ...

  5. 如何将Arduino的ino文件分解成多个.h和.cpp工程文件

    如何将Arduino的ino文件分解成多个.h和.cpp工程文件 当用Arduino做复杂工程项目时,程序难免会变得很大.这时候要修改个别参数或函数的时候会变得麻烦,简而言之,项目程序管理难度增高了, ...

  6. NonlinearFactorGraph.h/NonlinearFactorGraph.cpp

    NonlinearFactorGraph.h/NonlinearFactorGraph.cpp 一.预先定义 二.NonlinearFactorGraph类 2.1 构造与析构函数 2.2 一些输出 ...

  7. 【GNSS】GREAT多频多系统GREAT-UPD开源代码-第4.1章 代码解读之gnss.h/gnss.cpp

    GREAT多频多系统GREAT-UPD开源代码-第4.1章 代码解读之gnss.h/gnss.cpp 第4.1章 代码解读之gnss.h/gnss.cpp 1. GNSS系统设定 ///< GN ...

  8. C++中的 .h 和 .cpp 详解

    通俗解释:.h和.cpp差不多就像书和目录的关系吧,目录中对书中的章节和内容进行简单表示,真正的实现是在书里面的. 一般的数据,数据结构,接口,还有类的定义放在.h文件中,可以叫他们头文件,可以#in ...

  9. ISAM2.h/ISAM2.cpp

    ISAM2.h/ISAM2.cpp 0.成员变量 0.1 theta_ 0.2 variableIndex_ 0.3 delta_ 0.4 deltaNewton_ 0.5 RgProd_ 0.6 d ...

最新文章

  1. 如何搭建并使用便携式 4G/LTE 伪基站研究移动安全
  2. [BZOJ 1441]Min(裴蜀定理)
  3. VTK:几何对象之Dodecahedron
  4. VC++ 删除当前读取行 代码
  5. 工程和模块的关系以及继承和依赖的概念
  6. 面试官系统精讲Java源码及大厂真题 - 25 整体设计:队列设计思想、工作中使用场景
  7. 美的集团:董事长减持两千万股套现13亿属个人资产配置需要
  8. 可逆矩阵的特征值和原来矩阵_线性代数——相似矩阵的可逆变换矩阵P是否唯一...
  9. 偏最小二乘法(NIPALS经典实现--未简化)
  10. 无线桥接怎么设置网关和dns服务器,两个无线路由器进行桥接的设置方法
  11. 计算机软件专利安全期刊论文,安全与环境学报
  12. source insight 4.0 闪退问题
  13. ZZULIOJ:1134: 字符串转换
  14. 城乡规划资质怎么办?
  15. 浙江大学 计算机学院的博士,通知 | 浙江大学第377期博士生创新论坛 暨计算机学院第十六届博士生创新论坛(秋冬)报名通知...
  16. 工程量计算稿1.55安装步骤 v1.55pjb
  17. [LnOI2019]东京夏日相会
  18. 华米在自主芯片和OS研发上取得突破,将成为又一个华为
  19. [c]设计程序,输入一个圆柱体的半径r和高h,求圆柱体的底周长c、底面积s、侧面积s1、表面积s2和体积v。
  20. C# 报表(report)和LocalReport类如何实现打印?

热门文章

  1. c++给所有数组元素赋初值0
  2. Ajax--请求的基本操作 设置请求参数
  3. Anaconda详细安装使用教程
  4. css中的auto属性
  5. 【新手向】C语言中“=”与“==”的区别及使用方法
  6. bzoj 3055 礼物运送
  7. mac 两种视频转音频方法
  8. XMind Zen 2020 10.3.1注册使用
  9. qq同步android 2.2,QQ同步助手旧版本2.3
  10. 买房后为何有装修公司找你?个人信息就卖5毛钱