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 RosUkfPassThrough : public RosUkf
00008 {
00009 public:
00010 RosUkfPassThrough(std::vector<double> args) : RosUkf(args)
00011 {
00012 }
00013
00014 Ukf &getFilter()
00015 {
00016 return filter_;
00017 }
00018 };
00019
00020 TEST (UkfTest, Measurements)
00021 {
00022 std::vector<double> args;
00023 args.push_back(0.001);
00024 args.push_back(0);
00025 args.push_back(2);
00026
00027 RosUkfPassThrough ukf(args);
00028
00029 Eigen::MatrixXd initialCovar(15, 15);
00030 initialCovar.setIdentity();
00031 initialCovar *= 0.5;
00032 ukf.getFilter().setEstimateErrorCovariance(initialCovar);
00033
00034 Eigen::VectorXd measurement(STATE_SIZE);
00035 for(size_t i = 0; i < STATE_SIZE; ++i)
00036 {
00037 measurement[i] = i * 0.01 * STATE_SIZE;
00038 }
00039
00040 Eigen::MatrixXd measurementCovariance(STATE_SIZE, STATE_SIZE);
00041 for(size_t i = 0; i < STATE_SIZE; ++i)
00042 {
00043 measurementCovariance(i, i) = 1e-9;
00044 }
00045
00046 std::vector<int> updateVector(STATE_SIZE, true);
00047
00048
00049 ros::Time time;
00050 time.fromSec(1000);
00051 ukf.enqueueMeasurement("odom0",
00052 measurement,
00053 measurementCovariance,
00054 updateVector,
00055 std::numeric_limits<double>::max(),
00056 time);
00057
00058 ukf.integrateMeasurements(1001);
00059
00060 EXPECT_EQ(ukf.getFilter().getState(), measurement);
00061 EXPECT_EQ(ukf.getFilter().getEstimateErrorCovariance(), measurementCovariance);
00062
00063 ukf.getFilter().setEstimateErrorCovariance(initialCovar);
00064
00065
00066
00067
00068
00069 Eigen::VectorXd measurement2 = measurement;
00070
00071 measurement2 *= 2.0;
00072
00073 for(size_t i = 0; i < STATE_SIZE; ++i)
00074 {
00075 measurementCovariance(i, i) = 1e-9;
00076 }
00077
00078 time.fromSec(1002);
00079 ukf.enqueueMeasurement("odom0",
00080 measurement2,
00081 measurementCovariance,
00082 updateVector,
00083 std::numeric_limits<double>::max(),
00084 time);
00085
00086 ukf.integrateMeasurements(1003);
00087
00088 measurement = measurement2.eval() - ukf.getFilter().getState();
00089 for(size_t i = 0; i < STATE_SIZE; ++i)
00090 {
00091 EXPECT_LT(::fabs(measurement[i]), 0.001);
00092 }
00093 }
00094
00095 int main(int argc, char **argv)
00096 {
00097 ros::init(argc, argv, "ukf");
00098
00099 testing::InitGoogleTest(&argc, argv);
00100 return RUN_ALL_TESTS();
00101 }