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 KFMODELLOADER_HPP_
00035 #define KFMODELLOADER_HPP_
00036 #include <labust/navigation/KFBase.hpp>
00037 #include <labust/tools/MatrixLoader.hpp>
00038 #include <ros/ros.h>
00039
00040 namespace labust
00041 {
00042 namespace navigation
00043 {
00044 template <class ModelType>
00045 void kfModelLoader(ModelType& model, const ros::NodeHandle& nh, const std::string& group = "")
00046 {
00047 std::string ns(group);
00048 if (!ns.empty() && (ns.at(ns.length()-1) != '/')) ns+="/";
00049
00050 labust::tools::getMatrixParam(nh, ns+"Q", model.Q);
00051 model.W = ModelType::matrix::Identity(model.Q.rows(), model.Q.cols());
00052 labust::tools::getMatrixParam(nh, ns+"R", model.R0);
00053 model.V0 = ModelType::matrix::Identity(model.R0.rows(), model.R0.cols());
00054 model.H0 = ModelType::matrix::Identity(model.R0.rows(), model.Q.cols());
00055
00056
00057 if (nh.hasParam(ns+"W")) labust::tools::getMatrixParam(nh, ns+"W", model.W);
00058 if (nh.hasParam(ns+"V")) labust::tools::getMatrixParam(nh, ns+"V", model.V0);
00059 if (nh.hasParam(ns+"H")) labust::tools::getMatrixParam(nh, ns+"H", model.H0);
00060 if (nh.hasParam(ns+"P"))
00061 {
00062 typename ModelType::matrix P;
00063 labust::tools::getMatrixParam(nh, ns+"P", P);
00064 model.setStateCovariance(P);
00065 }
00066 if (nh.hasParam(ns+"x0"))
00067 {
00068 typename ModelType::vector x0;
00069 labust::tools::getMatrixParam(nh, ns+"x0", x0);
00070 model.setState(x0);
00071 }
00072
00073
00074 model.R = model.R0;
00075 model.V = model.V0;
00076 model.H = model.H0;
00077
00078 nh.param("sampling_time",model.Ts,0.1);
00079 }
00080 };
00081 }
00082
00083 #endif