Go to the documentation of this file.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 #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
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
00077
00078 double gain_;
00079 double zeta_;
00080 bool use_mag_;
00081 bool publish_tf_;
00082 std::string fixed_frame_;
00083 std::string imu_frame_;
00084 double constant_dt_;
00085
00086
00087
00088 boost::mutex mutex_;
00089 bool initialized_;
00090 double q0, q1, q2, q3;
00091 ros::Time last_time_;
00092 float w_bx_, w_by_, w_bz_;
00093
00094
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
00116
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
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