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
00038 ros::Publisher pub_;
00039 sensor_msgs::ImuPtr imu_;
00040 double min_angular_velocity_;
00041 double static_dt_;
00042
00043 void imu_callback(const sensor_msgs::ImuConstPtr& msg){
00044 double dt = msg->header.stamp.toSec() - imu_->header.stamp.toSec();
00045 if(imu_->header.stamp.sec == 0){
00046 dt = 0.0;
00047 }
00048 if(static_dt_ > 0.0001){
00049 dt = static_dt_;
00050 }
00051 imu_->header = msg->header;
00052 imu_->angular_velocity = msg->angular_velocity;
00053 imu_->angular_velocity_covariance = msg->angular_velocity_covariance;
00054 imu_->linear_acceleration = msg->linear_acceleration;
00055 imu_->linear_acceleration_covariance = msg->linear_acceleration_covariance;
00056
00057 double diff = pow(imu_->orientation.w, 2.0)-pow(imu_->orientation.z, 2.0);
00058 double mult = 2.0*imu_->orientation.w*imu_->orientation.z;
00059 double theta = atan2(mult, diff);
00060 if(std::abs(imu_->angular_velocity.z) > min_angular_velocity_){
00061 theta = theta + imu_->angular_velocity.z*dt;
00062 }
00063
00064
00065 imu_->orientation.z = sin(theta/2.0);
00066 imu_->orientation.w = cos(theta/2.0);
00067
00068
00069 pub_.publish(imu_);
00070 }
00071
00072
00073 int main(int argc, char **argv){
00074 ros::init(argc, argv, "imu_integrator");
00075 ros::NodeHandle n;
00076 ros::NodeHandle pnh("~");
00077
00078
00079 pnh.param<double>("min_angular_velocity", min_angular_velocity_, 0.0);
00080 pnh.param<double>("static_dt", static_dt_, 0.0);
00081 imu_.reset(new sensor_msgs::Imu());
00082 imu_->orientation.w = 1.0;
00083
00084
00085 pub_ = n.advertise<sensor_msgs::Imu>("imu_integrated", 10);
00086
00087
00088 ros::Subscriber sub = n.subscribe("imu", 100, imu_callback);
00089
00090 ros::spin();
00091
00092 return 0;
00093 }