imu_filter.h
Go to the documentation of this file.
00001 /*
00002  *  Copyright (C) 2010, CCNY Robotics Lab
00003  *  Ivan Dryanovski <ivan.dryanovski@gmail.com>
00004  *
00005  *  http://robotics.ccny.cuny.edu
00006  *
00007  *  Based on implementation of Madgwick's IMU and AHRS algorithms.
00008  *  http://www.x-io.co.uk/node/8#open_source_ahrs_and_imu_algorithms
00009  *
00010  *
00011  *  This program is free software: you can redistribute it and/or modify
00012  *  it under the terms of the GNU General Public License as published by
00013  *  the Free Software Foundation, either version 3 of the License, or
00014  *  (at your option) any later version.
00015  *
00016  *  This program is distributed in the hope that it will be useful,
00017  *  but WITHOUT ANY WARRANTY; without even the implied warranty of
00018  *  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
00019  *  GNU General Public License for more details.
00020  *
00021  *  You should have received a copy of the GNU General Public License
00022  *  along with this program.  If not, see <http://www.gnu.org/licenses/>.
00023  */
00024 
00025 #ifndef IMU_FILTER_MADWICK_IMU_FILTER_H
00026 #define IMU_FILTER_MADWICK_IMU_FILTER_H
00027 
00028 #include <math.h>
00029 
00030 #include <ros/ros.h>
00031 #include <sensor_msgs/Imu.h>
00032 #include <geometry_msgs/Vector3Stamped.h>
00033 #include <tf/transform_datatypes.h>
00034 #include <tf/transform_broadcaster.h>
00035 #include <message_filters/subscriber.h>
00036 #include <message_filters/synchronizer.h>
00037 #include <message_filters/sync_policies/approximate_time.h>
00038 #include <dynamic_reconfigure/server.h>
00039 
00040 #include "imu_filter_madgwick/ImuFilterMadgwickConfig.h"
00041 
00042 class ImuFilter
00043 {
00044   typedef sensor_msgs::Imu              ImuMsg;
00045   typedef geometry_msgs::Vector3Stamped MagMsg;
00046 
00047   typedef message_filters::sync_policies::ApproximateTime<ImuMsg, MagMsg> SyncPolicy;
00048   typedef message_filters::Synchronizer<SyncPolicy> Synchronizer;
00049   typedef message_filters::Subscriber<ImuMsg> ImuSubscriber; 
00050   typedef message_filters::Subscriber<MagMsg> MagSubscriber;
00051   
00052   typedef imu_filter_madgwick::ImuFilterMadgwickConfig   FilterConfig;
00053   typedef dynamic_reconfigure::Server<FilterConfig>   FilterConfigServer;
00054 
00055   public:
00056 
00057     ImuFilter(ros::NodeHandle nh, ros::NodeHandle nh_private);
00058     virtual ~ImuFilter();
00059 
00060   private:
00061 
00062     // **** ROS-related
00063 
00064     ros::NodeHandle nh_;
00065     ros::NodeHandle nh_private_;
00066     
00067     boost::shared_ptr<Synchronizer> sync_;
00068     boost::shared_ptr<ImuSubscriber> imu_subscriber_;
00069     boost::shared_ptr<MagSubscriber> mag_subscriber_;
00070 
00071     ros::Publisher imu_publisher_;
00072     tf::TransformBroadcaster tf_broadcaster_;
00073 
00074     FilterConfigServer config_server_;
00075     
00076     // **** paramaters
00077 
00078     double gain_;     // algorithm gain
00079     double zeta_;         // gyro drift bias gain
00080     bool use_mag_;
00081     bool publish_tf_;
00082     std::string fixed_frame_;
00083     std::string imu_frame_;
00084     double constant_dt_;
00085 
00086     // **** state variables
00087   
00088     boost::mutex mutex_;
00089     bool initialized_;
00090     double q0, q1, q2, q3;  // quaternion
00091     ros::Time last_time_;
00092     float w_bx_, w_by_, w_bz_; // 
00093 
00094     // **** member functions
00095 
00096     void imuMagCallback(const ImuMsg::ConstPtr& imu_msg_raw,
00097                         const MagMsg::ConstPtr& mav_msg);
00098 
00099     void imuCallback(const ImuMsg::ConstPtr& imu_msg_raw);
00100 
00101     void publishFilteredMsg(const ImuMsg::ConstPtr& imu_msg_raw);
00102     void publishTransform(const ImuMsg::ConstPtr& imu_msg_raw);
00103 
00104     void madgwickAHRSupdate(float gx, float gy, float gz, 
00105                             float ax, float ay, float az, 
00106                             float mx, float my, float mz,
00107                             float dt);
00108 
00109     void madgwickAHRSupdateIMU(float gx, float gy, float gz, 
00110                                float ax, float ay, float az,
00111                                float dt);
00112 
00113     void reconfigCallback(FilterConfig& config, uint32_t level);
00114     
00115     // Fast inverse square-root
00116     // See: http://en.wikipedia.org/wiki/Methods_of_computing_square_roots#Reciprocal_of_the_square_root
00117     static float invSqrt(float x)
00118     {
00119       float xhalf = 0.5f * x;
00120       union
00121       {
00122         float x;
00123         int i;
00124       } u;
00125       u.x = x;
00126       u.i = 0x5f3759df - (u.i >> 1);
00127       /* The next line can be repeated any number of times to increase accuracy */
00128       u.x = u.x * (1.5f - xhalf * u.x * u.x);
00129       return u.x;
00130     }
00131 };
00132 
00133 #endif // IMU_FILTER_IMU_MADWICK_FILTER_H


imu_filter_madgwick
Author(s): Ivan Dryanovski
autogenerated on Mon Oct 6 2014 00:49:04