Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032 #ifndef STATE_H_
00033 #define STATE_H_
00034
00035 #include <Eigen/Dense>
00036 #include <Eigen/Geometry>
00037 #include <vector>
00038 #include <ssf_core/eigen_conversions.h>
00039 #include <sensor_fusion_comm/ExtState.h>
00040 #include <sensor_fusion_comm/DoubleArrayStamped.h>
00041 #include <geometry_msgs/PoseWithCovarianceStamped.h>
00042
00043 #define N_STATE 25 /// error state size
00044
00045 namespace ssf_core
00046 {
00052 class State
00053 {
00054 public:
00055
00056 Eigen::Matrix<double, 3, 1> p_;
00057 Eigen::Matrix<double, 3, 1> v_;
00058 Eigen::Quaternion<double> q_;
00059 Eigen::Matrix<double, 3, 1> b_w_;
00060 Eigen::Matrix<double, 3, 1> b_a_;
00061
00062
00063 double L_;
00064 Eigen::Quaternion<double> q_wv_;
00065 Eigen::Quaternion<double> q_ci_;
00066 Eigen::Matrix<double, 3, 1> p_ci_;
00067
00068
00069 Eigen::Matrix<double,3,1> w_m_;
00070 Eigen::Matrix<double,3,1> a_m_;
00071
00072 Eigen::Quaternion<double> q_int_;
00073
00074 Eigen::Matrix<double, N_STATE, N_STATE> P_;
00075
00076 double time_;
00077
00079
00082 void reset();
00083
00085 void getPoseCovariance(geometry_msgs::PoseWithCovariance::_covariance_type & cov);
00086
00088
00089 void toPoseMsg(geometry_msgs::PoseWithCovarianceStamped & pose);
00090
00092
00093 void toExtStateMsg(sensor_fusion_comm::ExtState & state);
00094
00096
00097 void toStateMsg(sensor_fusion_comm::DoubleArrayStamped & state);
00098
00099
00100
00101 };
00102
00103 }
00104
00105 #endif