imu_compass.h
Go to the documentation of this file.
1 /*imu_compass.cpp
2 Authors: Prasenjit (pmukherj@clearpathrobotics.com)
3 Copyright (c) 2013, Clearpath Robotics, Inc., All rights reserved.
4 Redistribution and use in source and binary forms, with or without modification, are permitted provided that the
5 following conditions are met:
6  * Redistributions of source code must retain the above copyright notice, this list of conditions and the following
7  disclaimer.
8  * Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following
9  disclaimer in the documentation and/or other materials provided with the distribution.
10  * Neither the name of Clearpath Robotics nor the names of its contributors may be used to endorse or promote products
11  derived from this software without specific prior written permission.
12 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES,
13 INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
14 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
15 SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
16 SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY,
17 WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
18 OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
19 
20 Description:
21 Header file for IMU Compass Class that combines gyroscope and magnetometer data to get a clean estimate of yaw.
22 */
23 
24 #include "ros/ros.h"
25 #include "tf/tf.h"
26 #include "tf/transform_listener.h"
27 
28 #include "sensor_msgs/Imu.h"
29 #include "geometry_msgs/Vector3Stamped.h"
30 #include "std_msgs/Float32.h"
31 
32 //typedef boost::shared_ptr<sensor_msgs::Imu const> ImuConstPtr;
33 
34 class IMUCompass {
35 
36 private:
45 
48 
49  void imuCallback(sensor_msgs::ImuPtr data);
50  void declCallback(const std_msgs::Float32& data);
51  void magCallback(const geometry_msgs::Vector3StampedConstPtr& data);
52  void debugCallback(const ros::TimerEvent&);
54 
55  //Heading Filter functions
56  void initFilter(double heading_meas); //initialize heading fiter
57  bool first_mag_reading_; //signifies receiving the first magnetometer message
58  bool first_gyro_reading_; //signifies receiving the first gyroscope message
59  bool filter_initialized_; //after receiving the first measurement, make sure the filter is initialized
60  bool gyro_update_complete_; //sigfnifies that a gyro update (motion model update) has gone through
61 
63 
64  sensor_msgs::ImuPtr curr_imu_reading_;
65 
66  //Heading Filter Variables
67  //State and Variance
68  double curr_heading_;
71 
72  //Motion Update Variables
79 
80  //Measurement Update Variables
82 
83 public:
86  }
87 };
88 
double heading_variance_prediction_
Definition: imu_compass.h:74
ros::Publisher raw_compass_pub_
Definition: imu_compass.h:44
double mag_zero_z_
Definition: imu_compass.h:62
void declCallback(const std_msgs::Float32 &data)
ros::Timer debug_timer_
Definition: imu_compass.h:47
bool gyro_update_complete_
Definition: imu_compass.h:60
ros::Publisher mag_pub_
Definition: imu_compass.h:42
ros::Subscriber mag_sub_
Definition: imu_compass.h:39
double curr_heading_variance_
Definition: imu_compass.h:69
double heading_prediction_
Definition: imu_compass.h:73
double mag_declination_
Definition: imu_compass.h:76
bool first_mag_reading_
Definition: imu_compass.h:57
void debugCallback(const ros::TimerEvent &)
Definition: imu_compass.cpp:68
void imuCallback(sensor_msgs::ImuPtr data)
Definition: imu_compass.cpp:88
sensor_msgs::ImuPtr curr_imu_reading_
Definition: imu_compass.h:64
double mag_zero_x_
Definition: imu_compass.h:62
ros::Publisher compass_pub_
Definition: imu_compass.h:43
double mag_zero_y_
Definition: imu_compass.h:62
ros::Subscriber imu_sub_
Definition: imu_compass.h:38
tf::TransformListener listener_
Definition: imu_compass.h:46
bool filter_initialized_
Definition: imu_compass.h:59
double yaw_meas_variance_
Definition: imu_compass.h:81
ros::NodeHandle node_
Definition: imu_compass.h:37
bool first_gyro_reading_
Definition: imu_compass.h:58
void repackageImuPublish(tf::StampedTransform)
IMUCompass(ros::NodeHandle &n)
Definition: imu_compass.cpp:31
double last_measurement_update_time_
Definition: imu_compass.h:78
void initFilter(double heading_meas)
double last_motion_update_time_
Definition: imu_compass.h:77
double sensor_timeout_
Definition: imu_compass.h:70
void magCallback(const geometry_msgs::Vector3StampedConstPtr &data)
double heading_prediction_variance_
Definition: imu_compass.h:75
double curr_heading_
Definition: imu_compass.h:68
ros::Publisher imu_pub_
Definition: imu_compass.h:41
ros::Subscriber decl_sub_
Definition: imu_compass.h:40


imu_compass
Author(s):
autogenerated on Mon Jun 10 2019 13:35:52