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
00033
00034 #ifndef GRAFT_UKFABSOLUTE_H
00035 #define GRAFT_UKFABSOLUTE_H
00036
00037 #include <Eigen/Dense>
00038 #include <Eigen/Cholesky>
00039
00040 #include <graft/GraftState.h>
00041 #include <nav_msgs/Odometry.h>
00042 #include <geometry_msgs/QuaternionStamped.h>
00043 #include <sensor_msgs/Imu.h>
00044 #include <tf/transform_datatypes.h>
00045 #include <graft/GraftSensor.h>
00046
00047 #define SIZE 13 // State size: x, y, z, qw, qx, qy, qz, vx, vy, vz, wx, wy, wz
00048
00049 using namespace Eigen;
00050
00051 class GraftUKFAbsolute{
00052 public:
00053 GraftUKFAbsolute();
00054 ~GraftUKFAbsolute();
00055
00056 MatrixXd f(MatrixXd x, double dt);
00057
00058 std::vector<MatrixXd > predict_sigma_points(std::vector<MatrixXd >& sigma_points, double dt);
00059
00060 graft::GraftStatePtr getMessageFromState();
00061
00062 graft::GraftStatePtr getMessageFromState(Matrix<double, SIZE, 1>& state, Matrix<double, SIZE, SIZE>& covariance);
00063
00064 double predictAndUpdate();
00065
00066 void setTopics(std::vector<boost::shared_ptr<GraftSensor> >& topics);
00067
00068 void setInitialCovariance(std::vector<double>& P);
00069
00070 void setProcessNoise(std::vector<double>& Q);
00071
00072 void setAlpha(const double alpha);
00073
00074 void setKappa(const double kappa);
00075
00076 void setBeta(const double beta);
00077
00078 private:
00079
00080 Matrix<double, SIZE, 1> graft_state_;
00081 Matrix<double, SIZE, 1> graft_control_;
00082 Matrix<double, SIZE, SIZE> graft_covariance_;
00083
00084 Matrix<double, SIZE, SIZE> Q_;
00085
00086 ros::Time last_update_time_;
00087 ros::Time last_imu_time_;
00088
00089 double alpha_;
00090 double beta_;
00091 double kappa_;
00092
00093 std::vector<boost::shared_ptr<GraftSensor> > topics_;
00094 };
00095
00096 #endif