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
00026
00027
00028
00029
00030
00031
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
00054 double accumulator_alpha_;
00055 geometry_msgs::Vector3 angular_velocity_accumulator;
00056
00057
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_){
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 {
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
00113 pub_.publish(imu);
00114
00115
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
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
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
00153 pub_ = n.advertise<sensor_msgs::Imu>("imu_biased", 10);
00154 bias_pub_ = n.advertise<geometry_msgs::Vector3Stamped>("bias", 10);
00155
00156
00157 ros::Subscriber sub = n.subscribe("imu", 100, imu_callback);
00158
00159 ros::spin();
00160
00161 return 0;
00162 }