123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266 |
- #ifndef IMUTYPES_H
- #define IMUTYPES_H
- #include <vector>
- #include <utility>
- #include <opencv2/core/core.hpp>
- #include <Eigen/Core>
- #include <Eigen/Geometry>
- #include <Eigen/Dense>
- #include <sophus/se3.hpp>
- #include <mutex>
- #include "SerializationUtils.h"
- #include <boost/serialization/serialization.hpp>
- #include <boost/serialization/vector.hpp>
- namespace ORB_SLAM3
- {
- namespace IMU
- {
- const float GRAVITY_VALUE=9.81;
- class Point
- {
- public:
- Point(const float &acc_x, const float &acc_y, const float &acc_z,
- const float &ang_vel_x, const float &ang_vel_y, const float &ang_vel_z,
- const double ×tamp): a(acc_x,acc_y,acc_z), w(ang_vel_x,ang_vel_y,ang_vel_z), t(timestamp){}
- Point(const cv::Point3f Acc, const cv::Point3f Gyro, const double ×tamp):
- a(Acc.x,Acc.y,Acc.z), w(Gyro.x,Gyro.y,Gyro.z), t(timestamp){}
- public:
- Eigen::Vector3f a;
- Eigen::Vector3f w;
- double t;
- EIGEN_MAKE_ALIGNED_OPERATOR_NEW
- };
- class Bias
- {
- friend class boost::serialization::access;
- template<class Archive>
- void serialize(Archive & ar, const unsigned int version)
- {
- ar & bax;
- ar & bay;
- ar & baz;
- ar & bwx;
- ar & bwy;
- ar & bwz;
- }
- public:
- Bias():bax(0),bay(0),baz(0),bwx(0),bwy(0),bwz(0){}
- Bias(const float &b_acc_x, const float &b_acc_y, const float &b_acc_z,
- const float &b_ang_vel_x, const float &b_ang_vel_y, const float &b_ang_vel_z):
- bax(b_acc_x), bay(b_acc_y), baz(b_acc_z), bwx(b_ang_vel_x), bwy(b_ang_vel_y), bwz(b_ang_vel_z){}
- void CopyFrom(Bias &b);
- friend std::ostream& operator<< (std::ostream &out, const Bias &b);
- public:
- float bax, bay, baz;
- float bwx, bwy, bwz;
- EIGEN_MAKE_ALIGNED_OPERATOR_NEW
- };
- //IMU calibration (Tbc, Tcb, noise)
- class Calib
- {
- friend class boost::serialization::access;
- template<class Archive>
- void serialize(Archive & ar, const unsigned int version)
- {
- serializeSophusSE3(ar,mTcb,version);
- serializeSophusSE3(ar,mTbc,version);
- ar & boost::serialization::make_array(Cov.diagonal().data(), Cov.diagonal().size());
- ar & boost::serialization::make_array(CovWalk.diagonal().data(), CovWalk.diagonal().size());
- ar & mbIsSet;
- }
- public:
- Calib(const Sophus::SE3<float> &Tbc, const float &ng, const float &na, const float &ngw, const float &naw)
- {
- Set(Tbc,ng,na,ngw,naw);
- }
- Calib(const Calib &calib);
- Calib(){mbIsSet = false;}
-
- void Set(const Sophus::SE3<float> &sophTbc, const float &ng, const float &na, const float &ngw, const float &naw);
- public:
-
- Sophus::SE3<float> mTcb;
- Sophus::SE3<float> mTbc;
- Eigen::DiagonalMatrix<float,6> Cov, CovWalk;
- bool mbIsSet;
- };
- class IntegratedRotation
- {
- public:
- IntegratedRotation(){}
- IntegratedRotation(const Eigen::Vector3f &angVel, const Bias &imuBias, const float &time);
- public:
- float deltaT;
- Eigen::Matrix3f deltaR;
- Eigen::Matrix3f rightJ;
- EIGEN_MAKE_ALIGNED_OPERATOR_NEW
- };
- class Preintegrated
- {
- friend class boost::serialization::access;
- template<class Archive>
- void serialize(Archive & ar, const unsigned int version)
- {
- ar & dT;
- ar & boost::serialization::make_array(C.data(), C.size());
- ar & boost::serialization::make_array(Info.data(), Info.size());
- ar & boost::serialization::make_array(Nga.diagonal().data(), Nga.diagonal().size());
- ar & boost::serialization::make_array(NgaWalk.diagonal().data(), NgaWalk.diagonal().size());
- ar & b;
- ar & boost::serialization::make_array(dR.data(), dR.size());
- ar & boost::serialization::make_array(dV.data(), dV.size());
- ar & boost::serialization::make_array(dP.data(), dP.size());
- ar & boost::serialization::make_array(JRg.data(), JRg.size());
- ar & boost::serialization::make_array(JVg.data(), JVg.size());
- ar & boost::serialization::make_array(JVa.data(), JVa.size());
- ar & boost::serialization::make_array(JPg.data(), JPg.size());
- ar & boost::serialization::make_array(JPa.data(), JPa.size());
- ar & boost::serialization::make_array(avgA.data(), avgA.size());
- ar & boost::serialization::make_array(avgW.data(), avgW.size());
- ar & bu;
- ar & boost::serialization::make_array(db.data(), db.size());
- ar & mvMeasurements;
- }
- public:
- EIGEN_MAKE_ALIGNED_OPERATOR_NEW
- Preintegrated(const Bias &b_, const Calib &calib);
- Preintegrated(Preintegrated* pImuPre);
- Preintegrated() {}
- ~Preintegrated() {}
- void CopyFrom(Preintegrated* pImuPre);
- void Initialize(const Bias &b_);
- void IntegrateNewMeasurement(const Eigen::Vector3f &acceleration, const Eigen::Vector3f &angVel, const float &dt);
- void Reintegrate();
- void MergePrevious(Preintegrated* pPrev);
- void SetNewBias(const Bias &bu_);
- IMU::Bias GetDeltaBias(const Bias &b_);
- Eigen::Matrix3f GetDeltaRotation(const Bias &b_);
- Eigen::Vector3f GetDeltaVelocity(const Bias &b_);
- Eigen::Vector3f GetDeltaPosition(const Bias &b_);
- Eigen::Matrix3f GetUpdatedDeltaRotation();
- Eigen::Vector3f GetUpdatedDeltaVelocity();
- Eigen::Vector3f GetUpdatedDeltaPosition();
- Eigen::Matrix3f GetOriginalDeltaRotation();
- Eigen::Vector3f GetOriginalDeltaVelocity();
- Eigen::Vector3f GetOriginalDeltaPosition();
- Eigen::Matrix<float,6,1> GetDeltaBias();
- Bias GetOriginalBias();
- Bias GetUpdatedBias();
- void printMeasurements() const {
- std::cout << "pint meas:\n";
- for(int i=0; i<mvMeasurements.size(); i++){
- std::cout << "meas " << mvMeasurements[i].t << std::endl;
- }
- std::cout << "end pint meas:\n";
- }
- public:
- float dT;
- Eigen::Matrix<float,15,15> C;
- Eigen::Matrix<float,15,15> Info;
- Eigen::DiagonalMatrix<float,6> Nga, NgaWalk;
-
- Bias b;
- Eigen::Matrix3f dR;
- Eigen::Vector3f dV, dP;
- Eigen::Matrix3f JRg, JVg, JVa, JPg, JPa;
- Eigen::Vector3f avgA, avgW;
- private:
-
- Bias bu;
-
-
- Eigen::Matrix<float,6,1> db;
- struct integrable
- {
- template<class Archive>
- void serialize(Archive & ar, const unsigned int version)
- {
- ar & boost::serialization::make_array(a.data(), a.size());
- ar & boost::serialization::make_array(w.data(), w.size());
- ar & t;
- }
- EIGEN_MAKE_ALIGNED_OPERATOR_NEW
- integrable(){}
- integrable(const Eigen::Vector3f &a_, const Eigen::Vector3f &w_ , const float &t_):a(a_),w(w_),t(t_){}
- Eigen::Vector3f a, w;
- float t;
- };
- std::vector<integrable> mvMeasurements;
- std::mutex mMutex;
- };
- Eigen::Matrix3f RightJacobianSO3(const float &x, const float &y, const float &z);
- Eigen::Matrix3f RightJacobianSO3(const Eigen::Vector3f &v);
- Eigen::Matrix3f InverseRightJacobianSO3(const float &x, const float &y, const float &z);
- Eigen::Matrix3f InverseRightJacobianSO3(const Eigen::Vector3f &v);
- Eigen::Matrix3f NormalizeRotation(const Eigen::Matrix3f &R);
- }
- }
- #endif
|