imu_integrator.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 
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   // Fill in quaternion
00065   imu_->orientation.z = sin(theta/2.0);
00066   imu_->orientation.w = cos(theta/2.0);
00067 
00068   // Publish transformed message
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   // Get parameters
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   // Create publisher
00085   pub_ = n.advertise<sensor_msgs::Imu>("imu_integrated", 10);
00086 
00087   // Subscriber
00088   ros::Subscriber sub = n.subscribe("imu", 100, imu_callback);  
00089   
00090   ros::spin();
00091 
00092   return 0;
00093 }


imu_pipeline
Author(s): Chad Rockey
autogenerated on Fri Aug 28 2015 11:10:26