$search
#include <ros/ros.h>
#include <tf/tf.h>
#include <tf/transform_listener.h>
#include <tf/transform_broadcaster.h>
#include "odom_estimation.h"
#include <filter/extendedkalmanfilter.h>
#include <wrappers/matrix/matrix_wrapper.h>
#include <model/linearanalyticsystemmodel_gaussianuncertainty.h>
#include <model/linearanalyticmeasurementmodel_gaussianuncertainty.h>
#include <pdf/analyticconditionalgaussian.h>
#include <pdf/linearanalyticconditionalgaussian.h>
#include "nonlinearanalyticconditionalgaussianodo.h"
#include <geometry_msgs/PoseWithCovarianceStamped.h>
#include <fstream>
#include <robot_pose_ekf/GetStatus.h>
#include "nav_msgs/Odometry.h"
#include "geometry_msgs/Twist.h"
#include "sensor_msgs/Imu.h"
#include "geometry_msgs/PoseStamped.h"
#include <boost/thread/mutex.hpp>
Go to the source code of this file.
Classes | |
class | estimation::OdomEstimationNode |
Namespaces | |
namespace | estimation |
Typedefs | |
typedef boost::shared_ptr < sensor_msgs::Imu const > | estimation::ImuConstPtr |
typedef boost::shared_ptr < nav_msgs::Odometry const > | estimation::OdomConstPtr |
typedef boost::shared_ptr < geometry_msgs::Twist const > | estimation::VelConstPtr |
typedef boost::shared_ptr < nav_msgs::Odometry const > | estimation::VoConstPtr |