36 #include <sensor_msgs/Imu.h>
37 #include <geometry_msgs/Twist.h>
38 #include <nav_msgs/Odometry.h>
39 #include <geometry_msgs/Vector3Stamped.h>
58 bool abslt(
const double& val1,
const double& val2){
59 return std::abs(val1) < val2;
63 return alpha * meas + (1.0 - alpha) * avg;
97 sensor_msgs::ImuPtr imu(
new sensor_msgs::Imu(*msg));
103 imu->angular_velocity.x = 0.0;
104 imu->angular_velocity.y = 0.0;
105 imu->angular_velocity.z = 0.0;
116 geometry_msgs::Vector3StampedPtr bias(
new geometry_msgs::Vector3Stamped());
117 bias->header = imu->header;
123 int main(
int argc,
char **argv){
124 ros::init(argc, argv,
"imu_bias_remover");