Go to the documentation of this file.00001 #include "robot_localization/ros_filter_types.h"
00002 #include <limits>
00003 #include <gtest/gtest.h>
00004
00005 using namespace RobotLocalization;
00006
00007 class RosEkfPassThrough : public RosEkf
00008 {
00009 public:
00010 RosEkfPassThrough()
00011 {
00012 }
00013
00014 Ekf &getFilter()
00015 {
00016 return filter_;
00017 }
00018 };
00019
00020 TEST (EkfTest, Measurements)
00021 {
00022 RosEkfPassThrough ekf;
00023
00024 Eigen::MatrixXd initialCovar(15, 15);
00025 initialCovar.setIdentity();
00026 initialCovar *= 0.5;
00027 ekf.getFilter().setEstimateErrorCovariance(initialCovar);
00028
00029 Eigen::VectorXd measurement(STATE_SIZE);
00030 for(size_t i = 0; i < STATE_SIZE; ++i)
00031 {
00032 measurement[i] = i * 0.01 * STATE_SIZE;
00033 }
00034
00035 Eigen::MatrixXd measurementCovariance(STATE_SIZE, STATE_SIZE);
00036 for(size_t i = 0; i < STATE_SIZE; ++i)
00037 {
00038 measurementCovariance(i, i) = 1e-9;
00039 }
00040
00041 std::vector<int> updateVector(STATE_SIZE, true);
00042
00043
00044 ros::Time time;
00045 time.fromSec(1000);
00046 ekf.enqueueMeasurement("odom0",
00047 measurement,
00048 measurementCovariance,
00049 updateVector,
00050 std::numeric_limits<double>::max(),
00051 time);
00052
00053 ekf.integrateMeasurements(1001);
00054
00055 EXPECT_EQ(ekf.getFilter().getState(), measurement);
00056 EXPECT_EQ(ekf.getFilter().getEstimateErrorCovariance(), measurementCovariance);
00057
00058 ekf.getFilter().setEstimateErrorCovariance(initialCovar);
00059
00060
00061
00062
00063
00064 Eigen::VectorXd measurement2 = measurement;
00065
00066 measurement2 *= 2.0;
00067
00068 for(size_t i = 0; i < STATE_SIZE; ++i)
00069 {
00070 measurementCovariance(i, i) = 1e-9;
00071 }
00072
00073 time.fromSec(1002);
00074 ekf.enqueueMeasurement("odom0",
00075 measurement2,
00076 measurementCovariance,
00077 updateVector,
00078 std::numeric_limits<double>::max(),
00079 time);
00080
00081 ekf.integrateMeasurements(1003);
00082
00083 measurement = measurement2.eval() - ekf.getFilter().getState();
00084 for(size_t i = 0; i < STATE_SIZE; ++i)
00085 {
00086 EXPECT_LT(::fabs(measurement[i]), 0.001);
00087 }
00088 }
00089
00090 int main(int argc, char **argv)
00091 {
00092 ros::init(argc, argv, "ekf");
00093
00094 testing::InitGoogleTest(&argc, argv);
00095 return RUN_ALL_TESTS();
00096 }