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 #include "imu_compass/imu_compass.h"
00026
00027 double magn(tf::Vector3 a) {
00028 return sqrt(a.x()*a.x() + a.y()*a.y() + a.z()*a.z());
00029 }
00030
00031 IMUCompass::IMUCompass(ros::NodeHandle &n) :
00032 node_(n), curr_imu_reading_(new sensor_msgs::Imu()) {
00033
00034 ros::param::param("~mag_bias/x", mag_zero_x_, 0.0);
00035 ros::param::param("~mag_bias/y", mag_zero_y_, 0.0);
00036 ros::param::param("~mag_bias/z", mag_zero_z_, 0.0);
00037
00038
00039 ROS_INFO("Using magnetometer bias (x,y):%f,%f", mag_zero_x_, mag_zero_y_);
00040
00041 ros::param::param("~compass/sensor_timeout", sensor_timeout_, 0.5);
00042 ros::param::param("~compass/yaw_meas_variance", yaw_meas_variance_, 10.0);
00043 ros::param::param("~compass/gyro_meas_variance", heading_prediction_variance_, 0.01);
00044 ROS_INFO("Using variance %f", yaw_meas_variance_);
00045
00046 ros::param::param("~compass/mag_declination", mag_declination_, 0.0);
00047 ROS_INFO("Using magnetic declination %f (%f degrees)", mag_declination_, mag_declination_ * 180 / M_PI);
00048
00049
00050 imu_sub_ = node_.subscribe("imu/data", 1000, &IMUCompass::imuCallback, this);
00051 mag_sub_ = node_.subscribe("imu/mag", 1000, &IMUCompass::magCallback, this);
00052 decl_sub_ = node_.subscribe("imu/declination", 1000, &IMUCompass::declCallback, this);
00053 imu_pub_ = node_.advertise<sensor_msgs::Imu>("imu/data_compass", 1);
00054 compass_pub_ = node_.advertise<std_msgs::Float32>("imu/compass_heading", 1);
00055 mag_pub_ = node_.advertise<geometry_msgs::Vector3Stamped>("imu/mag_calib", 1);
00056
00057 raw_compass_pub_ = node_.advertise<std_msgs::Float32>("imu/raw_compass_heading", 1);
00058
00059 first_mag_reading_ = false;
00060 first_gyro_reading_ = false;
00061 gyro_update_complete_ = false;
00062 last_motion_update_time_ = ros::Time::now().toSec();
00063 debug_timer_ = node_.createTimer(ros::Duration(1), &IMUCompass::debugCallback, this);
00064
00065 ROS_INFO("Compass Estimator Started");
00066 }
00067
00068 void IMUCompass::debugCallback(const ros::TimerEvent&) {
00069 if (!first_gyro_reading_)
00070 ROS_WARN("Waiting for IMU data, no gyroscope data available)");
00071 if (!first_mag_reading_)
00072 ROS_WARN("Waiting for mag data, no magnetometer data available, Filter not initialized");
00073
00074 if ((ros::Time::now().toSec() - last_motion_update_time_ > sensor_timeout_) && first_gyro_reading_) {
00075
00076 ROS_WARN("Gyroscope data being receieved too slow or not at all");
00077 first_gyro_reading_ = false;
00078 }
00079
00080 if ((ros::Time::now().toSec() - last_measurement_update_time_ > sensor_timeout_) && first_mag_reading_) {
00081
00082 ROS_WARN("Magnetometer data being receieved too slow or not at all");
00083 filter_initialized_ = false;
00084 first_mag_reading_ = false;
00085 }
00086 }
00087
00088 void IMUCompass::imuCallback(const sensor_msgs::ImuPtr data) {
00089
00090 geometry_msgs::Vector3 gyro_vector;
00091 geometry_msgs::Vector3 gyro_vector_transformed;
00092 gyro_vector = data->angular_velocity;
00093
00094 if(!first_gyro_reading_)
00095 first_gyro_reading_ = true;
00096
00097 double dt = ros::Time::now().toSec() - last_motion_update_time_;
00098 last_motion_update_time_ = ros::Time::now().toSec();
00099 tf::StampedTransform transform;
00100
00101 try {
00102 listener_.lookupTransform("base_link", data->header.frame_id, ros::Time(0), transform);
00103 } catch (tf::TransformException &ex) {
00104 ROS_WARN("Missed transform between base_link and %s", data->header.frame_id.c_str());
00105 return;
00106 }
00107
00108 tf::Vector3 orig_bt;
00109 tf::Matrix3x3 transform_mat(transform.getRotation());
00110 tf::vector3MsgToTF(gyro_vector, orig_bt);
00111 tf::vector3TFToMsg(orig_bt * transform_mat, gyro_vector_transformed);
00112 double yaw_gyro_reading = gyro_vector_transformed.z;
00113
00114
00115 if (filter_initialized_) {
00116 heading_prediction_ = curr_heading_ + yaw_gyro_reading * dt;
00117 heading_variance_prediction_ = curr_heading_variance_ + heading_prediction_variance_;
00118
00119 if (heading_prediction_ > 3.14159)
00120 heading_prediction_ -= 2 * 3.14159;
00121 else if(heading_prediction_ < -3.14159)
00122 heading_prediction_ += 2 * 3.14159;
00123 gyro_update_complete_ = true;
00124 }
00125 curr_imu_reading_ = data;
00126 }
00127
00128 void IMUCompass::declCallback(const std_msgs::Float32& data) {
00129 mag_declination_ = data.data;
00130 ROS_INFO("Using magnetic declination %f (%f degrees)", mag_declination_, mag_declination_ * 180 / M_PI);
00131 }
00132
00133 void IMUCompass::magCallback(const geometry_msgs::Vector3StampedConstPtr& data) {
00134 geometry_msgs::Vector3 imu_mag = data->vector;
00135 geometry_msgs::Vector3 imu_mag_transformed;
00136
00137 imu_mag.x = data->vector.x;
00138 imu_mag.y = data->vector.y;
00139 imu_mag.z = data->vector.z;
00140
00141 last_measurement_update_time_ = ros::Time::now().toSec();
00142 tf::StampedTransform transform;
00143 try {
00144 listener_.lookupTransform("base_link", data->header.frame_id, ros::Time(0), transform);
00145 } catch (tf::TransformException &ex) {
00146 ROS_WARN("Missed transform between base_link and %s", data->header.frame_id.c_str());
00147 return;
00148 }
00149
00150 tf::Vector3 orig_bt;
00151 tf::Matrix3x3 transform_mat(transform.getRotation());
00152 tf::vector3MsgToTF(imu_mag, orig_bt);
00153 tf::vector3TFToMsg(orig_bt * transform_mat, imu_mag_transformed);
00154
00155
00156 double mag_x = imu_mag_transformed.x - mag_zero_x_;
00157 double mag_y = imu_mag_transformed.y - mag_zero_y_;
00158 double mag_z = imu_mag_transformed.z;
00159
00160
00161 tf::Vector3 calib_mag(mag_x, mag_y, mag_z);
00162 calib_mag = calib_mag / magn(calib_mag);
00163 mag_x = calib_mag.x();
00164 mag_y = calib_mag.y();
00165 mag_z = calib_mag.z();
00166
00167 geometry_msgs::Vector3Stamped calibrated_mag;
00168 calibrated_mag.header.stamp = ros::Time::now();
00169 calibrated_mag.header.frame_id = "imu_link";
00170
00171 calibrated_mag.vector.x = calib_mag.x();
00172 calibrated_mag.vector.y = calib_mag.y();
00173 calibrated_mag.vector.z = calib_mag.z();
00174
00175 mag_pub_.publish(calibrated_mag);
00176
00177 tf::Quaternion q;
00178 tf::quaternionMsgToTF(curr_imu_reading_->orientation, q);
00179 tf::Transform curr_imu_meas;
00180 curr_imu_meas = tf::Transform(q, tf::Vector3(0, 0, 0));
00181 curr_imu_meas = curr_imu_meas * transform;
00182 tf::Quaternion orig (transform.getRotation());
00183
00184
00185 tf::Matrix3x3 temp(curr_imu_meas.getRotation());
00186
00187 double c_r, c_p, c_y;
00188 temp.getRPY(c_r, c_p, c_y);
00189 double cos_pitch = cos(c_p);
00190 double sin_pitch = sin(c_p);
00191 double cos_roll = cos(c_r);
00192 double sin_roll = sin(c_r);
00193 double t_mag_x = mag_x * cos_pitch + mag_z * sin_pitch;
00194 double t_mag_y = mag_x * sin_roll * sin_pitch + mag_y * cos_roll - mag_z * sin_roll * cos_pitch;
00195 double head_x = t_mag_x;
00196 double head_y = t_mag_y;
00197
00198
00199 double heading_meas = atan2(head_x, head_y);
00200
00201
00202 if (!first_mag_reading_) {
00203
00204 initFilter(heading_meas);
00205 first_mag_reading_ = true;
00206 return;
00207 }
00208
00209 if (gyro_update_complete_) {
00210
00211 double kalman_gain = heading_variance_prediction_ * (1 / (heading_variance_prediction_ + yaw_meas_variance_));
00212 double innovation = heading_meas - heading_prediction_;
00213 if (abs(innovation) > M_PI)
00214 curr_heading_ = heading_meas;
00215 else
00216 curr_heading_ = heading_prediction_ + kalman_gain * (innovation);
00217
00218 curr_heading_variance_ = (1 - kalman_gain) * heading_variance_prediction_;
00219
00220 std_msgs::Float32 raw_heading_float;
00221 raw_heading_float.data = heading_meas;
00222 raw_compass_pub_.publish(raw_heading_float);
00223
00224 repackageImuPublish(transform);
00225 gyro_update_complete_ = false;
00226 }
00227 }
00228
00229 void IMUCompass::repackageImuPublish(tf::StampedTransform transform) {
00230
00231 tf::Quaternion imu_reading;
00232 tf::quaternionMsgToTF(curr_imu_reading_->orientation, imu_reading);
00233 double compass_heading = curr_heading_ - mag_declination_;
00234
00235
00236 tf::Transform o_imu_reading;
00237 o_imu_reading = tf::Transform(imu_reading, tf::Vector3(0, 0, 0));
00238 o_imu_reading = o_imu_reading * transform;
00239 imu_reading = o_imu_reading.getRotation();
00240
00241
00242 tf::Quaternion compass_yaw = tf::createQuaternionFromRPY(0.0, 0.0, compass_heading);
00243 tf::Quaternion diff_yaw = tf::createQuaternionFromRPY(0.0, 0.0, compass_heading - tf::getYaw(imu_reading));
00244
00245
00246 tf::Quaternion new_quaternion = diff_yaw * imu_reading;
00247
00248
00249 sensor_msgs::Imu publish_imu;
00250 o_imu_reading = tf::Transform(new_quaternion, tf::Vector3(0, 0, 0));
00251 o_imu_reading = o_imu_reading * (transform.inverse());
00252 tf::quaternionTFToMsg(o_imu_reading.getRotation(), curr_imu_reading_->orientation);
00253
00254
00255 std_msgs::Float32 curr_heading_float;
00256 curr_heading_float.data = compass_heading;
00257 compass_pub_.publish(curr_heading_float);
00258 imu_pub_.publish(curr_imu_reading_);
00259 }
00260
00261 void IMUCompass::initFilter(double heading_meas) {
00262 curr_heading_ = heading_meas;
00263 curr_heading_variance_ = 1;
00264 filter_initialized_ = true;
00265 ROS_INFO("Magnetometer data received. Compass estimator initialized");
00266 }
00267
00268 int main(int argc, char **argv) {
00269 ros::init(argc, argv, "imu_compass");
00270 ros::NodeHandle node;
00271 IMUCompass imu_heading_estimator(node);
00272 ros::spin();
00273 return 0;
00274 }