tf2_sensor_msgs.h
Go to the documentation of this file.
1 //Remove this header when https://github.com/ros/geometry_experimental/pull/78 is released
2 
3 /*
4  * Copyright (c) 2008, Willow Garage, Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions are met:
9  *
10  * * Redistributions of source code must retain the above copyright
11  * notice, this list of conditions and the following disclaimer.
12  * * Redistributions in binary form must reproduce the above copyright
13  * notice, this list of conditions and the following disclaimer in the
14  * documentation and/or other materials provided with the distribution.
15  * * Neither the name of the Willow Garage, Inc. nor the names of its
16  * contributors may be used to endorse or promote products derived from
17  * this software without specific prior written permission.
18  *
19  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
20  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
21  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
22  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
23  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
24  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
25  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
26  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
27  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
28  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
29  * POSSIBILITY OF SUCH DAMAGE.
30  */
31 
32 #ifndef TF2_SENSOR_MSGS_H
33 #define TF2_SENSOR_MSGS_H
34 
35 #include <tf2/convert.h>
36 #include <sensor_msgs/PointCloud2.h>
37 #include <sensor_msgs/Imu.h>
38 #include <sensor_msgs/MagneticField.h>
40 #include <Eigen/Eigen>
41 #include <Eigen/Geometry>
42 
43 namespace tf2
44 {
45 
46 /**********/
48 /**********/
49 
53  template <>
54  inline
55  const ros::Time& getTimestamp(const sensor_msgs::Imu& p) {return p.header.stamp;}
56 
60  template <>
61  inline
62  const std::string& getFrameId(const sensor_msgs::Imu &p) {return p.header.frame_id;}
63 
64 
68  inline
69  void transformCovariance(const boost::array<double, 9>& in, boost::array<double, 9>& out, Eigen::Quaternion<double> r){
70 
71  Eigen::Map<const Eigen::Matrix<double, 3, 3, Eigen::RowMajor> > cov_in(in.data());
72  Eigen::Map<Eigen::Matrix<double, 3, 3, Eigen::RowMajor> > cov_out(out.data());
73  cov_out = r * cov_in * r.inverse();
74 
75  }
76 
80  template <>
81  inline
82  void doTransform(const sensor_msgs::Imu &imu_in, sensor_msgs::Imu &imu_out, const geometry_msgs::TransformStamped& t_in)
83  {
84 
85  imu_out.header = t_in.header;
86 
87  // Discard translation, only use orientation for IMU transform
88  Eigen::Quaternion<double> r(
89  t_in.transform.rotation.w, t_in.transform.rotation.x, t_in.transform.rotation.y, t_in.transform.rotation.z);
90  Eigen::Transform<double,3,Eigen::Affine> t(r);
91 
92  Eigen::Vector3d vel = t * Eigen::Vector3d(
93  imu_in.angular_velocity.x, imu_in.angular_velocity.y, imu_in.angular_velocity.z);
94 
95  imu_out.angular_velocity.x = vel.x();
96  imu_out.angular_velocity.y = vel.y();
97  imu_out.angular_velocity.z = vel.z();
98 
99  transformCovariance(imu_in.angular_velocity_covariance, imu_out.angular_velocity_covariance, r);
100 
101  Eigen::Vector3d accel = t * Eigen::Vector3d(
102  imu_in.linear_acceleration.x, imu_in.linear_acceleration.y, imu_in.linear_acceleration.z);
103 
104 
105  imu_out.linear_acceleration.x = accel.x();
106  imu_out.linear_acceleration.y = accel.y();
107  imu_out.linear_acceleration.z = accel.z();
108 
109  transformCovariance(imu_in.linear_acceleration_covariance, imu_out.linear_acceleration_covariance, r);
110 
111  // Orientation expresses attitude of the new frame_id in a fixed world frame. This is why the transform here applies
112  // in the opposite direction.
113  Eigen::Quaternion<double> orientation = Eigen::Quaternion<double>(
114  imu_in.orientation.w, imu_in.orientation.x, imu_in.orientation.y, imu_in.orientation.z) * r.inverse();
115 
116  imu_out.orientation.w = orientation.w();
117  imu_out.orientation.x = orientation.x();
118  imu_out.orientation.y = orientation.y();
119  imu_out.orientation.z = orientation.z();
120 
121  // Orientation is measured relative to the fixed world frame, so it doesn't change when applying a static
122  // transform to the sensor frame.
123  imu_out.orientation_covariance = imu_in.orientation_covariance;
124 
125  }
126 
127  inline
128  sensor_msgs::Imu toMsg(const sensor_msgs::Imu &in)
129  {
130  return in;
131  }
132 
133  inline
134  void fromMsg(const sensor_msgs::Imu &msg, sensor_msgs::Imu &out)
135  {
136  out = msg;
137  }
138 
139 /*********************/
141 /*********************/
142 
146  template <>
147  inline
148  const ros::Time& getTimestamp(const sensor_msgs::MagneticField& p) {return p.header.stamp;}
149 
153  template <>
154  inline
155  const std::string& getFrameId(const sensor_msgs::MagneticField &p) {return p.header.frame_id;}
156 
160  template <>
161  inline
162  void doTransform(const sensor_msgs::MagneticField &mag_in, sensor_msgs::MagneticField &mag_out, const geometry_msgs::TransformStamped& t_in)
163  {
164 
165  mag_out.header = t_in.header;
166 
167  // Discard translation, only use orientation for Magnetic Field transform
168  Eigen::Quaternion<double> r(
169  t_in.transform.rotation.w, t_in.transform.rotation.x, t_in.transform.rotation.y, t_in.transform.rotation.z);
170  Eigen::Transform<double,3,Eigen::Affine> t(r);
171 
172  Eigen::Vector3d mag = t * Eigen::Vector3d(
173  mag_in.magnetic_field.x, mag_in.magnetic_field.y, mag_in.magnetic_field.z);
174 
175  mag_out.magnetic_field.x = mag.x();
176  mag_out.magnetic_field.y = mag.y();
177  mag_out.magnetic_field.z = mag.z();
178 
179  transformCovariance(mag_in.magnetic_field_covariance, mag_out.magnetic_field_covariance, r);
180 
181  }
182 
183  inline
184  sensor_msgs::MagneticField toMsg(const sensor_msgs::MagneticField &in)
185  {
186  return in;
187  }
188 
189  inline
190  void fromMsg(const sensor_msgs::MagneticField &msg, sensor_msgs::MagneticField &out)
191  {
192  out = msg;
193  }
194 
195 } // namespace
196 
197 #endif // TF2_SENSOR_MSGS_IMU_H
const std::string & getFrameId(const T &t)
void transformCovariance(const boost::array< double, 9 > &in, boost::array< double, 9 > &out, Eigen::Quaternion< double > r)
void doTransform(const T &data_in, T &data_out, const geometry_msgs::TransformStamped &transform)
void fromMsg(const A &, B &b)
B toMsg(const A &a)
const ros::Time & getTimestamp(const T &t)


imu_transformer
Author(s): Paul Bovbel
autogenerated on Fri Nov 25 2022 03:51:09