• AttitudeFactor.h/AttitudeFactor.cpp


    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_和上一步优化变量()计算误差,算Jacobian
        Vector 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);
      }
    }
    
    
    • 1
    • 2
    • 3
    • 4
    • 5
    • 6
    • 7
    • 8
    • 9
    • 10
    • 11
    • 12
    • 13
    • 14
    • 15
    • 16
    • 17
    • 18
    • 19
    • 20
    • 21
    • 22
    • 23
    • 24

    一、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
    • 2
    • 3
    • 4
    • 5
    • 6
    • 7
    • 8
    • 9
    • 10

    1.1 成员函数

    都是protected作用域

    protected:
    
      Unit3 nZ_, bRef_; ///< Position measurement in
    
    • 1
    • 2
    • 3

    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
    • 2
    • 3
    • 4
    • 5
    • 6
    • 7
    • 8
    • 9
    • 10
    • 11
    • 12

    1.3 计算误差的

      /** vector of errors */
      Vector attitudeError(const Rot3& p,
          OptionalJacobian<2,3> H = boost::none) const;
    
    • 1
    • 2
    • 3
    重要的一个函数
    //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
    
    • 1
    • 2
    //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 -> world
        Vector 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
    • 2
    • 3
    • 4
    • 5
    • 6
    • 7
    • 8
    • 9
    • 10
    • 11
    • 12
    • 13
    • 14
    • 15
    • 16

    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_);
      }
    
    • 1
    • 2
    • 3
    • 4
    • 5
    • 6
    • 7
    • 8
    • 9
    • 10
    • 11
    • 12
    • 13
    • 14

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

    /**
     * Version of AttitudeFactor for Rot3
     * @addtogroup Navigation
     */
    class GTSAM_EXPORT Rot3AttitudeFactor: public NoiseModelFactor1<Rot3>, public AttitudeFactor 
    {};
    
    • 1
    • 2
    • 3
    • 4
    • 5
    • 6

    2.1 一些定义

      typedef NoiseModelFactor1<Rot3> Base;
    
    public:
    
      /// shorthand for a smart pointer to a factor
      typedef boost::shared_ptr<Rot3AttitudeFactor> shared_ptr;
    
      /// Typedef to this class
      typedef Rot3AttitudeFactor This;
    
    • 1
    • 2
    • 3
    • 4
    • 5
    • 6
    • 7
    • 8
    • 9

    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) {
      }
    
    • 1
    • 2
    • 3
    • 4
    • 5
    • 6
    • 7
    • 8
    • 9
    • 10
    • 11

    2.3 计算误差

    见attitudeError

      /** vector of errors */
      Vector evaluateError(const Rot3& nRb, //
          boost::optional<Matrix&> H = boost::none) const override {
        return attitudeError(nRb, H);
      }
    
    • 1
    • 2
    • 3
    • 4
    • 5

    2.4 traits

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

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

    3.1 一些定义

      typedef NoiseModelFactor1<Pose3> Base;
    
    public:
    
      /// shorthand for a smart pointer to a factor
      typedef boost::shared_ptr<Pose3AttitudeFactor> shared_ptr;
    
      /// Typedef to this class
      typedef Pose3AttitudeFactor This;
    
    • 1
    • 2
    • 3
    • 4
    • 5
    • 6
    • 7
    • 8
    • 9

    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) {
      }
    
    • 1
    • 2
    • 3
    • 4
    • 5
    • 6
    • 7
    • 8
    • 9
    • 10
    • 11

    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;
      }
    
    • 1
    • 2
    • 3
    • 4
    • 5
    • 6
    • 7
    • 8
    • 9
    • 10
    • 11

    3.4 traits

  • 相关阅读:
    echarts设置竖向不同区间范围颜色,并且x轴自定义轴线刻度范围
    浅谈继承之默认成员函数
    线框图软件:Balsamiq Wireframes mac中文介绍
    677. 键值映射-字符树算法应用
    ThreadGroup
    长风破浪会有时,直挂云帆济沧海!(工作室年会总结)
    Python Asyncio 之网络编程方法详解
    携创教育:最新!2022年10月自考报名时间已全部公布
    3分钟火速手写一个二叉查找树,搞快点。
    Tengine编译安装
  • 原文地址:https://blog.csdn.net/weixin_43848456/article/details/127898664