00001 /* 00002 * eigen_test.cpp 00003 * 00004 * Created on: Oct 16, 2013 00005 * Author: dnad 00006 */ 00007 #include <labust/navigation/KinematicModel.hpp> 00008 #include <labust/navigation/KFCore.hpp> 00009 #include <labust/navigation/KFModelLoader.hpp> 00010 00011 #include <ros/ros.h> 00012 00013 int main(int argc, char* argv[]) 00014 { 00015 ros::init(argc, argv, "eigen_test"); 00016 ros::NodeHandle nh; 00017 using namespace labust::navigation; 00018 KFCore<KinematicModel> nav; 00019 00020 kfModelLoader(nav,nh); 00021 00022 ros::Rate rate(10); 00023 00024 while (ros::ok()) 00025 { 00026 nav.predict(); 00027 KinematicModel::vector meas = KinematicModel::vector::Zero(KinematicModel::inputSize); 00028 nav.correct(meas); 00029 rate.sleep(); 00030 } 00031 00032 return 0; 00033 } 00034 00035 00036 00037 00038