imu_integrator.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2013, Willow Garage, Inc.
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the Willow Garage, Inc. nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
30 /*
31  * Author: Chad Rockey
32  */
33 
34 #include <ros/ros.h>
35 
36 #include <sensor_msgs/Imu.h>
37 
39 sensor_msgs::ImuPtr imu_;
41 double static_dt_;
42 
43 void imu_callback(const sensor_msgs::ImuConstPtr& msg){
44  double dt = msg->header.stamp.toSec() - imu_->header.stamp.toSec();
45  if(imu_->header.stamp.sec == 0){
46  dt = 0.0;
47  }
48  if(static_dt_ > 0.0001){
49  dt = static_dt_;
50  }
51  imu_->header = msg->header;
52  imu_->angular_velocity = msg->angular_velocity;
53  imu_->angular_velocity_covariance = msg->angular_velocity_covariance;
54  imu_->linear_acceleration = msg->linear_acceleration;
55  imu_->linear_acceleration_covariance = msg->linear_acceleration_covariance;
56 
57  double diff = pow(imu_->orientation.w, 2.0)-pow(imu_->orientation.z, 2.0);
58  double mult = 2.0*imu_->orientation.w*imu_->orientation.z;
59  double theta = atan2(mult, diff);
60  if(std::abs(imu_->angular_velocity.z) > min_angular_velocity_){
61  theta = theta + imu_->angular_velocity.z*dt;
62  }
63 
64  // Fill in quaternion
65  imu_->orientation.z = sin(theta/2.0);
66  imu_->orientation.w = cos(theta/2.0);
67 
68  // Publish transformed message
69  pub_.publish(imu_);
70 }
71 
72 
73 int main(int argc, char **argv){
74  ros::init(argc, argv, "imu_integrator");
76  ros::NodeHandle pnh("~");
77 
78  // Get parameters
79  pnh.param<double>("min_angular_velocity", min_angular_velocity_, 0.0);
80  pnh.param<double>("static_dt", static_dt_, 0.0);
81  imu_.reset(new sensor_msgs::Imu());
82  imu_->orientation.w = 1.0;
83 
84  // Create publisher
85  pub_ = n.advertise<sensor_msgs::Imu>("imu_integrated", 10);
86 
87  // Subscriber
88  ros::Subscriber sub = n.subscribe("imu", 100, imu_callback);
89 
90  ros::spin();
91 
92  return 0;
93 }
void publish(const boost::shared_ptr< M > &message) const
int main(int argc, char **argv)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
ros::Publisher pub_
ROSCPP_DECL void spin(Spinner &spinner)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
double static_dt_
void imu_callback(const sensor_msgs::ImuConstPtr &msg)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
double min_angular_velocity_
sensor_msgs::ImuPtr imu_


imu_processors
Author(s): Chad Rockey
autogenerated on Thu Jun 4 2020 03:22:59