imu_filter_ros.h
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2010, CCNY Robotics Lab
3  * Ivan Dryanovski <ivan.dryanovski@gmail.com>
4  *
5  * http://robotics.ccny.cuny.edu
6  *
7  * Based on implementation of Madgwick's IMU and AHRS algorithms.
8  * http://www.x-io.co.uk/node/8#open_source_ahrs_and_imu_algorithms
9  *
10  *
11  * This program is free software: you can redistribute it and/or modify
12  * it under the terms of the GNU General Public License as published by
13  * the Free Software Foundation, either version 3 of the License, or
14  * (at your option) any later version.
15  *
16  * This program is distributed in the hope that it will be useful,
17  * but WITHOUT ANY WARRANTY; without even the implied warranty of
18  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
19  * GNU General Public License for more details.
20  *
21  * You should have received a copy of the GNU General Public License
22  * along with this program. If not, see <http://www.gnu.org/licenses/>.
23  */
24 
25 #ifndef IMU_FILTER_MADWICK_IMU_FILTER_ROS_H
26 #define IMU_FILTER_MADWICK_IMU_FILTER_ROS_H
27 
28 #include <ros/ros.h>
29 #include <sensor_msgs/Imu.h>
30 #include <sensor_msgs/MagneticField.h>
31 #include <geometry_msgs/Vector3Stamped.h>
36 #include <dynamic_reconfigure/server.h>
37 
39 #include "imu_filter_madgwick/ImuFilterMadgwickConfig.h"
40 
42 {
43  typedef sensor_msgs::Imu ImuMsg;
44  typedef sensor_msgs::MagneticField MagMsg;
45 
50 
51  typedef imu_filter_madgwick::ImuFilterMadgwickConfig FilterConfig;
52  typedef dynamic_reconfigure::Server<FilterConfig> FilterConfigServer;
53 
54  public:
55 
57  virtual ~ImuFilterRos();
58 
59  private:
60 
61  // **** ROS-related
62 
65 
69 
74 
77 
78  // **** paramaters
80  bool use_mag_;
81  bool stateless_;
84  std::string fixed_frame_;
85  std::string imu_frame_;
86  double constant_dt_;
88  geometry_msgs::Vector3 mag_bias_;
90 
91  // **** state variables
92  boost::mutex mutex_;
95 
96  // **** filter implementation
98 
99  // **** member functions
100  void imuMagCallback(const ImuMsg::ConstPtr& imu_msg_raw,
101  const MagMsg::ConstPtr& mav_msg);
102 
103  void imuCallback(const ImuMsg::ConstPtr& imu_msg_raw);
104 
105  void publishFilteredMsg(const ImuMsg::ConstPtr& imu_msg_raw);
106  void publishTransform(const ImuMsg::ConstPtr& imu_msg_raw);
107 
108  void publishRawMsg(const ros::Time& t,
109  float roll, float pitch, float yaw);
110 
111  void reconfigCallback(FilterConfig& config, uint32_t level);
113 };
114 
115 #endif // IMU_FILTER_IMU_MADWICK_FILTER_ROS_H
message_filters::Subscriber< ImuMsg > ImuSubscriber
message_filters::sync_policies::ApproximateTime< ImuMsg, MagMsg > SyncPolicy
bool publish_debug_topics_
boost::shared_ptr< Synchronizer > sync_
double orientation_variance_
void publishRawMsg(const ros::Time &t, float roll, float pitch, float yaw)
void imuMagCallback(const ImuMsg::ConstPtr &imu_msg_raw, const MagMsg::ConstPtr &mav_msg)
ros::Publisher rpy_raw_debug_publisher_
imu_filter_madgwick::ImuFilterMadgwickConfig FilterConfig
sensor_msgs::Imu ImuMsg
double constant_dt_
message_filters::Synchronizer< SyncPolicy > Synchronizer
std::string imu_frame_
message_filters::Subscriber< MagMsg > MagSubscriber
ros::Time last_time_
void checkTopicsTimerCallback(const ros::TimerEvent &)
boost::shared_ptr< FilterConfigServer > config_server_
std::string fixed_frame_
ImuFilterRos(ros::NodeHandle nh, ros::NodeHandle nh_private)
ros::NodeHandle nh_private_
boost::shared_ptr< ImuSubscriber > imu_subscriber_
sensor_msgs::MagneticField MagMsg
ros::Publisher imu_publisher_
dynamic_reconfigure::Server< FilterConfig > FilterConfigServer
boost::mutex mutex_
virtual ~ImuFilterRos()
void publishTransform(const ImuMsg::ConstPtr &imu_msg_raw)
ros::NodeHandle nh_
ImuFilter filter_
ros::Timer check_topics_timer_
void reconfigCallback(FilterConfig &config, uint32_t level)
void publishFilteredMsg(const ImuMsg::ConstPtr &imu_msg_raw)
WorldFrame::WorldFrame world_frame_
tf2_ros::TransformBroadcaster tf_broadcaster_
void imuCallback(const ImuMsg::ConstPtr &imu_msg_raw)
boost::shared_ptr< MagSubscriber > mag_subscriber_
ros::Publisher rpy_filtered_debug_publisher_
geometry_msgs::Vector3 mag_bias_


imu_filter_madgwick
Author(s): Ivan Dryanovski
autogenerated on Tue May 7 2019 03:16:55