34 #ifndef GRAFT_UKFVELOCITY_H
35 #define GRAFT_UKFVELOCITY_H
37 #include <Eigen/Dense>
38 #include <Eigen/Cholesky>
40 #include <graft/GraftState.h>
41 #include <nav_msgs/Odometry.h>
42 #include <geometry_msgs/QuaternionStamped.h>
43 #include <sensor_msgs/Imu.h>
47 #define SIZE 3 // State size: vx, vy, wz
49 using namespace Eigen;
56 MatrixXd
f(MatrixXd x,
double dt);
58 std::vector<MatrixXd > predict_sigma_points(std::vector<MatrixXd >& sigma_points,
double dt);
60 graft::GraftStatePtr getMessageFromState();
62 graft::GraftStatePtr getMessageFromState(Matrix<double, SIZE, 1>& state, Matrix<double, SIZE, SIZE>& covariance);
64 double predictAndUpdate();
68 void setInitialCovariance(std::vector<double>& P);
70 void setProcessNoise(std::vector<double>& Q);
72 void setAlpha(
const double alpha);
74 void setKappa(
const double kappa);
76 void setBeta(
const double beta);
84 Matrix<double, SIZE, SIZE>
Q_;
93 std::vector<boost::shared_ptr<GraftSensor> >
topics_;