imu_bias_remover.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2013, Willow Garage, Inc.
00003  * All rights reserved.
00004  *
00005  * Redistribution and use in source and binary forms, with or without
00006  * modification, are permitted provided that the following conditions are met:
00007  *
00008  *     * Redistributions of source code must retain the above copyright
00009  *       notice, this list of conditions and the following disclaimer.
00010  *     * Redistributions in binary form must reproduce the above copyright
00011  *       notice, this list of conditions and the following disclaimer in the
00012  *       documentation and/or other materials provided with the distribution.
00013  *     * Neither the name of the Willow Garage, Inc. nor the names of its
00014  *       contributors may be used to endorse or promote products derived from
00015  *       this software without specific prior written permission.
00016  *
00017  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00018  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00019  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00020  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00021  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00022  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00023  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00024  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00025  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00026  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00027  * POSSIBILITY OF SUCH DAMAGE.
00028  */
00029 
00030 /* 
00031  * Author: Chad Rockey
00032  */
00033 
00034 #include <ros/ros.h>
00035 
00036 #include <sensor_msgs/Imu.h>
00037 #include <geometry_msgs/Twist.h>
00038 #include <nav_msgs/Odometry.h>
00039 #include <geometry_msgs/Vector3Stamped.h>
00040 
00041 ros::Publisher pub_;
00042 ros::Publisher bias_pub_;
00043 
00044 bool use_cmd_vel_;
00045 bool use_odom_;
00046 
00047 bool twist_is_zero_;
00048 bool odom_is_zero_;
00049 
00050 double cmd_vel_threshold_;
00051 double odom_threshold_;
00052 
00053 // Implement an exponentially weighted moving average to calculate bias
00054 double accumulator_alpha_;
00055 geometry_msgs::Vector3 angular_velocity_accumulator;
00056 
00057 // Returns true if |val1| < val2
00058 bool abslt(const double& val1, const double& val2){
00059   return std::abs(val1) < val2;
00060 }
00061 
00062 double accumulator_update(const double& alpha, const double& avg, const double& meas){
00063   return alpha * meas + (1.0 - alpha) * avg;
00064 }
00065 
00066 void cmd_vel_callback(const geometry_msgs::TwistConstPtr& msg){
00067   if(use_cmd_vel_){
00068     if(abslt(msg->linear.x, cmd_vel_threshold_) &&
00069        abslt(msg->linear.y, cmd_vel_threshold_) &&
00070        abslt(msg->linear.z, cmd_vel_threshold_) &&
00071        abslt(msg->angular.x, cmd_vel_threshold_) &&
00072        abslt(msg->angular.y, cmd_vel_threshold_) &&
00073        abslt(msg->angular.z, cmd_vel_threshold_)){
00074       twist_is_zero_ = true;
00075       return;
00076     }
00077   }
00078   twist_is_zero_ = false;
00079 }
00080 
00081 void odom_callback(const nav_msgs::OdometryConstPtr& msg){
00082   if(use_odom_){
00083     if(abslt(msg->twist.twist.linear.x, odom_threshold_) &&
00084        abslt(msg->twist.twist.linear.y, odom_threshold_) &&
00085        abslt(msg->twist.twist.linear.z, odom_threshold_) &&
00086        abslt(msg->twist.twist.angular.x, odom_threshold_) &&
00087        abslt(msg->twist.twist.angular.y, odom_threshold_) &&
00088        abslt(msg->twist.twist.angular.z, odom_threshold_)){
00089       odom_is_zero_ = true;
00090       return;
00091     }
00092   }
00093   odom_is_zero_ = false;
00094 }
00095 
00096 void imu_callback(const sensor_msgs::ImuConstPtr& msg){
00097   sensor_msgs::ImuPtr imu(new sensor_msgs::Imu(*msg));
00098 
00099   if(twist_is_zero_ || odom_is_zero_){ // Update bias, set outputs to 0
00100     angular_velocity_accumulator.x = accumulator_update(accumulator_alpha_, angular_velocity_accumulator.x, msg->angular_velocity.x);
00101     angular_velocity_accumulator.y = accumulator_update(accumulator_alpha_, angular_velocity_accumulator.y, msg->angular_velocity.y);
00102     angular_velocity_accumulator.z = accumulator_update(accumulator_alpha_, angular_velocity_accumulator.z, msg->angular_velocity.z);
00103     imu->angular_velocity.x = 0.0;
00104     imu->angular_velocity.y = 0.0;
00105     imu->angular_velocity.z = 0.0;
00106   } else { // Modify outputs by bias
00107     imu->angular_velocity.x -= angular_velocity_accumulator.x;
00108     imu->angular_velocity.y -= angular_velocity_accumulator.y;
00109     imu->angular_velocity.z -= angular_velocity_accumulator.z;
00110   }
00111 
00112   // Publish transformed message
00113         pub_.publish(imu);
00114 
00115   // Publish bias information
00116   geometry_msgs::Vector3StampedPtr bias(new geometry_msgs::Vector3Stamped());
00117   bias->header = imu->header;
00118   bias->vector = angular_velocity_accumulator;
00119   bias_pub_.publish(bias);
00120 }
00121 
00122 
00123 int main(int argc, char **argv){
00124   ros::init(argc, argv, "imu_bias_remover");
00125   ros::NodeHandle n;
00126   ros::NodeHandle pnh("~");
00127 
00128   // Initialize
00129   twist_is_zero_ = false;
00130   odom_is_zero_ = false;
00131   angular_velocity_accumulator.x = 0.0;
00132   angular_velocity_accumulator.y = 0.0;
00133   angular_velocity_accumulator.z = 0.0;
00134 
00135   // Get parameters
00136   pnh.param<bool>("use_cmd_vel", use_cmd_vel_, false);
00137   pnh.param<bool>("use_odom", use_odom_, false);
00138   pnh.param<double>("accumulator_alpha", accumulator_alpha_, 0.01);
00139   
00140   ros::Subscriber cmd_sub;
00141   if(use_cmd_vel_){
00142     cmd_sub = n.subscribe("cmd_vel", 10, cmd_vel_callback);
00143   }
00144   ros::Subscriber odom_sub;
00145   if(use_odom_){
00146     odom_sub = n.subscribe("odom", 10, odom_callback);
00147   }
00148 
00149   pnh.param<double>("cmd_vel_threshold", cmd_vel_threshold_, 0.001);
00150   pnh.param<double>("odom_threshold", odom_threshold_, 0.001);
00151   
00152   // Create publisher
00153   pub_ = n.advertise<sensor_msgs::Imu>("imu_biased", 10);
00154   bias_pub_ = n.advertise<geometry_msgs::Vector3Stamped>("bias", 10);
00155 
00156   // Imu Subscriber
00157   ros::Subscriber sub = n.subscribe("imu", 100, imu_callback);  
00158   
00159   ros::spin();
00160 
00161   return 0;
00162 }


imu_processors
Author(s): Chad Rockey
autogenerated on Thu Jan 26 2017 03:49:24