odometry_publisher.h
Go to the documentation of this file.
00001 #ifndef ODOMETRY_PUBLISHER_H_
00002 #define ODOMETRY_PUBLISHER_H_
00003 
00004 #include <ros/ros.h>
00005 #include <message_filters/subscriber.h>
00006 //#include <message_filters/time_synchronizer.h>
00007 #include <message_filters/sync_policies/approximate_time.h>
00008 
00009 #include <nav_msgs/Odometry.h>
00010 #include <sensor_msgs/Imu.h>
00011 
00012 namespace combine_dr_measurements{
00013 
00014     class OdometryPublisher{
00015     public:
00016         OdometryPublisher(ros::NodeHandle &nh);
00017         void syncMsgsCB(const nav_msgs::OdometryConstPtr &odom, const sensor_msgs::ImuConstPtr &imu);
00018         void run();
00019 
00020     private:
00021         typedef message_filters::sync_policies::ApproximateTime<nav_msgs::Odometry, sensor_msgs::Imu> SyncPolicy;
00022         ros::Publisher odom_pub_;
00023 
00024         nav_msgs::Odometry received_odom_;
00025         sensor_msgs::Imu received_imu_;
00026         message_filters::Subscriber<nav_msgs::Odometry> odom_sub_;
00027         message_filters::Subscriber<sensor_msgs::Imu> imu_sub_;
00028         message_filters::Synchronizer<SyncPolicy> sync_;
00029         //message_filters::TimeSynchronizer<nav_msgs::Odometry, sensor_msgs::Imu> sync_msgs_;
00030         ros::NodeHandle &nh_;
00031         double max_update_rate_;
00032     };
00033 
00034 };
00035 
00036 #endif //ODOMETRY_PUBLISHER_H_


combine_dr_measurements
Author(s): Daiki Maekawa
autogenerated on Fri Oct 16 2015 10:27:52