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
00035
00036 #ifndef __ODOM_ESTIMATION_NODE__
00037 #define __ODOM_ESTIMATION_NODE__
00038
00039
00040 #include <ros/ros.h>
00041 #include <tf/tf.h>
00042 #include <tf/transform_listener.h>
00043 #include <tf/transform_broadcaster.h>
00044 #include "odom_estimation.h"
00045 #include <robot_pose_ekf/GetStatus.h>
00046
00047
00048 #include "nav_msgs/Odometry.h"
00049 #include "geometry_msgs/Twist.h"
00050 #include "sensor_msgs/Imu.h"
00051 #include "geometry_msgs/PoseStamped.h"
00052 #include "geometry_msgs/PoseWithCovarianceStamped.h"
00053
00054 #include <boost/thread/mutex.hpp>
00055
00056
00057 #include <fstream>
00058
00059 namespace estimation
00060 {
00061
00071 typedef boost::shared_ptr<nav_msgs::Odometry const> OdomConstPtr;
00072 typedef boost::shared_ptr<sensor_msgs::Imu const> ImuConstPtr;
00073 typedef boost::shared_ptr<nav_msgs::Odometry const> VoConstPtr;
00074 typedef boost::shared_ptr<geometry_msgs::Twist const> VelConstPtr;
00075
00076 class OdomEstimationNode
00077 {
00078 public:
00080 OdomEstimationNode();
00081
00083 virtual ~OdomEstimationNode();
00084
00085 private:
00087 void spin(const ros::TimerEvent& e);
00088
00090 void odomCallback(const OdomConstPtr& odom);
00091
00093 void imuCallback(const ImuConstPtr& imu);
00094
00096 void voCallback(const VoConstPtr& vo);
00097
00099 bool getStatus(robot_pose_ekf::GetStatus::Request& req, robot_pose_ekf::GetStatus::Response& resp);
00100
00101 ros::NodeHandle node_;
00102 ros::Timer timer_;
00103 ros::Publisher pose_pub_;
00104 ros::Subscriber odom_sub_, imu_sub_, vo_sub_;
00105 ros::ServiceServer state_srv_;
00106
00107
00108 OdomEstimation my_filter_;
00109
00110
00111 geometry_msgs::PoseWithCovarianceStamped output_;
00112
00113
00114 tf::TransformListener robot_state_;
00115 tf::TransformBroadcaster odom_broadcaster_;
00116
00117
00118 tf::Transform odom_meas_, imu_meas_, vo_meas_;
00119 tf::Transform base_vo_init_;
00120 tf::StampedTransform camera_base_;
00121 ros::Time odom_time_, imu_time_, vo_time_;
00122 ros::Time odom_stamp_, imu_stamp_, vo_stamp_, filter_stamp_;
00123 ros::Time odom_init_stamp_, imu_init_stamp_, vo_init_stamp_;
00124 bool odom_active_, imu_active_, vo_active_;
00125 bool odom_used_, imu_used_, vo_used_;
00126 bool odom_initializing_, imu_initializing_, vo_initializing_;
00127 double timeout_;
00128 MatrixWrapper::SymmetricMatrix odom_covariance_, imu_covariance_, vo_covariance_;
00129 bool debug_, self_diagnose_;
00130 std::string output_frame_;
00131
00132
00133 std::ofstream odom_file_, imu_file_, vo_file_, corr_file_, time_file_, extra_file_;
00134
00135
00136 unsigned int odom_callback_counter_, imu_callback_counter_, vo_callback_counter_, ekf_sent_counter_;
00137
00138 };
00139
00140 };
00141
00142 #endif