ftf_frame_conversions.cpp
Go to the documentation of this file.
1 
10 /*
11  * Copyright 2015 Nuno Marques.
12  * Copyright 2016 Vladimir Ermakov
13  *
14  * This file is part of the mavros package and subject to the license terms
15  * in the top-level LICENSE file of the mavros repository.
16  * https://github.com/mavlink/mavros/tree/master/LICENSE.md
17  */
18 
19 #include <mavros/frame_tf.h>
20 
21 namespace mavros {
22 namespace ftf {
23 namespace detail {
29 static const auto NED_ENU_Q = quaternion_from_rpy(M_PI, 0.0, M_PI_2);
30 
36 static const auto AIRCRAFT_BASELINK_Q = quaternion_from_rpy(M_PI, 0.0, 0.0);
37 
44 static const Eigen::Affine3d NED_ENU_AFFINE(NED_ENU_Q);
45 
51 static const Eigen::Affine3d AIRCRAFT_BASELINK_AFFINE(AIRCRAFT_BASELINK_Q);
52 
56 static const auto NED_ENU_R = NED_ENU_Q.normalized().toRotationMatrix();
57 static const auto AIRCRAFT_BASELINK_R = AIRCRAFT_BASELINK_Q.normalized().toRotationMatrix();
58 
64 static const Eigen::PermutationMatrix<3> NED_ENU_REFLECTION_XY(Eigen::Vector3i(1,0,2));
65 static const Eigen::DiagonalMatrix<double,3> NED_ENU_REFLECTION_Z(1,1,-1);
66 
70 using Matrix6d = Eigen::Matrix<double, 6, 6>;
71 using Matrix9d = Eigen::Matrix<double, 9, 9>;
72 
73 
74 Eigen::Quaterniond transform_orientation(const Eigen::Quaterniond &q, const StaticTF transform)
75 {
76  // Transform the attitude representation from frame to frame.
77  // The proof for this transform can be seen
78  // http://www.euclideanspace.com/maths/algebra/realNormedAlgebra/quaternions/transforms/
79  switch (transform) {
82  return NED_ENU_Q * q;
83 
86  return q * AIRCRAFT_BASELINK_Q;
87  }
88 }
89 
90 
91 Eigen::Vector3d transform_static_frame(const Eigen::Vector3d &vec, const StaticTF transform)
92 {
93  switch (transform) {
97 
100  return AIRCRAFT_BASELINK_AFFINE * vec;
101  }
102 }
103 
105 {
106  Covariance3d cov_out_;
107  EigenMapConstCovariance3d cov_in(cov.data());
108  EigenMapCovariance3d cov_out(cov_out_.data());
109 
110  switch (transform) {
114  NED_ENU_REFLECTION_XY.transpose();
115  return cov_out_;
116 
119  cov_out = cov_in * AIRCRAFT_BASELINK_Q;
120  return cov_out_;
121  }
122 }
123 
125 {
126  Covariance6d cov_out_;
127  Matrix6d R = Matrix6d::Zero(); // not `auto` because Zero ret is const
128 
129  EigenMapConstCovariance6d cov_in(cov.data());
130  EigenMapCovariance6d cov_out(cov_out_.data());
131 
132  switch (transform) {
135  {
136  Eigen::PermutationMatrix<6> NED_ENU_REFLECTION_XY_6 (NED_ENU_REFLECTION_XY.indices().replicate<2,1>());
137  NED_ENU_REFLECTION_XY_6.indices().middleRows<3>(3).array() += 3;
138  Eigen::DiagonalMatrix<double,6> NED_ENU_REFLECTION_Z_6(NED_ENU_REFLECTION_Z.diagonal().replicate<2,1>());
139 
140  cov_out = NED_ENU_REFLECTION_XY_6 * (NED_ENU_REFLECTION_Z_6 * cov_in * NED_ENU_REFLECTION_Z_6) *
141  NED_ENU_REFLECTION_XY_6.transpose();
142 
143  return cov_out_;
144  }
147  R.block<3, 3>(0, 0) =
148  R.block<3, 3>(3, 3) = AIRCRAFT_BASELINK_R;
149 
150  cov_out = R * cov_in * R.transpose();
151  return cov_out_;
152  }
153 }
154 
156 {
157  Covariance9d cov_out_;
158  Matrix9d R = Matrix9d::Zero();
159 
160  EigenMapConstCovariance9d cov_in(cov.data());
161  EigenMapCovariance9d cov_out(cov_out_.data());
162 
163  switch (transform) {
166  {
167  Eigen::PermutationMatrix<9> NED_ENU_REFLECTION_XY_9 (NED_ENU_REFLECTION_XY.indices().replicate<3,1>());
168  NED_ENU_REFLECTION_XY_9.indices().middleRows<3>(3).array() += 3;
169  NED_ENU_REFLECTION_XY_9.indices().middleRows<3>(6).array() += 6;
170  Eigen::DiagonalMatrix<double,9> NED_ENU_REFLECTION_Z_9(NED_ENU_REFLECTION_Z.diagonal().replicate<3,1>());
171 
172  cov_out = NED_ENU_REFLECTION_XY_9 * (NED_ENU_REFLECTION_Z_9 * cov_in * NED_ENU_REFLECTION_Z_9) *
173  NED_ENU_REFLECTION_XY_9.transpose();
174 
175  return cov_out_;
176  }
179  R.block<3, 3>(0, 0) =
180  R.block<3, 3>(3, 3) =
181  R.block<3, 3>(6, 6) = AIRCRAFT_BASELINK_R;
182 
183  cov_out = R * cov_in * R.transpose();
184  return cov_out_;
185  }
186 }
187 
188 Eigen::Vector3d transform_static_frame(const Eigen::Vector3d &vec, const Eigen::Vector3d &map_origin, const StaticTF transform)
189 {
191  static constexpr double DEG_TO_RAD = (M_PI / 180.0);
192 
193  // Don't forget to convert from degrees to radians
194  const double sin_lat = std::sin(map_origin.x() * DEG_TO_RAD);
195  const double sin_lon = std::sin(map_origin.y() * DEG_TO_RAD);
196  const double cos_lat = std::cos(map_origin.x() * DEG_TO_RAD);
197  const double cos_lon = std::cos(map_origin.y() * DEG_TO_RAD);
198 
213  Eigen::Matrix3d R;
214  R << -sin_lon, cos_lon, 0.0,
215  -cos_lon * sin_lat, -sin_lon * sin_lat, cos_lat,
216  cos_lon * cos_lat, sin_lon * cos_lat, sin_lat;
217 
218  switch (transform) {
220  return R * vec;
221 
223  // ENU to ECEF rotation is just an inverse rotation from ECEF to ENU, which means transpose.
224  R.transposeInPlace();
225  return R * vec;
226  }
227 }
228 
229 Eigen::Vector3d transform_frame(const Eigen::Vector3d &vec, const Eigen::Quaterniond &q)
230 {
231  Eigen::Affine3d transformation(q);
232  return transformation * vec;
233 }
234 
235 Covariance3d transform_frame(const Covariance3d &cov, const Eigen::Quaterniond &q)
236 {
237  Covariance3d cov_out_;
238  EigenMapConstCovariance3d cov_in(cov.data());
239  EigenMapCovariance3d cov_out(cov_out_.data());
240 
241  cov_out = cov_in * q;
242  return cov_out_;
243 }
244 
245 Covariance6d transform_frame(const Covariance6d &cov, const Eigen::Quaterniond &q)
246 {
247  Covariance6d cov_out_;
248  Matrix6d R = Matrix6d::Zero();
249 
250  EigenMapConstCovariance6d cov_in(cov.data());
251  EigenMapCovariance6d cov_out(cov_out_.data());
252 
253  R.block<3, 3>(0, 0) =
254  R.block<3, 3>(3, 3) = q.normalized().toRotationMatrix();
255 
256  cov_out = R * cov_in * R.transpose();
257  return cov_out_;
258 }
259 
260 Covariance9d transform_frame(const Covariance9d &cov, const Eigen::Quaterniond &q)
261 {
262  Covariance9d cov_out_;
263  Matrix9d R = Matrix9d::Zero();
264 
265  EigenMapConstCovariance9d cov_in(cov.data());
266  EigenMapCovariance9d cov_out(cov_out_.data());
267 
268  R.block<3, 3>(0, 0) =
269  R.block<3, 3>(3, 3) =
270  R.block<3, 3>(6, 6) = q.normalized().toRotationMatrix();
271 
272  cov_out = R * cov_in * R.transpose();
273  return cov_out_;
274 }
275 
276 } // namespace detail
277 } // namespace ftf
278 } // namespace mavros
will change orientation from being expressed WRT NED frame to WRT ENU frame
static const auto NED_ENU_Q
Static quaternion needed for rotating between ENU and NED frames NED to ENU: +PI/2 rotation about Z (...
static const Eigen::Affine3d NED_ENU_AFFINE(NED_ENU_Q)
Static vector needed for rotating between ENU and NED frames +PI rotation around X (North) axis follw...
StaticTF
Orientation transform options when applying rotations to data.
Definition: frame_tf.h:60
Eigen::Map< Eigen::Matrix< double, 6, 6, Eigen::RowMajor > > EigenMapCovariance6d
Eigen::Map for Covariance6d.
Definition: frame_tf.h:50
change from expressed WRT ENU frame to WRT ECEF frame
Eigen::Map< const Eigen::Matrix< double, 3, 3, Eigen::RowMajor > > EigenMapConstCovariance3d
Definition: frame_tf.h:47
Eigen::Quaterniond transform_orientation(const Eigen::Quaterniond &q, const StaticTF transform)
Transform representation of attitude from 1 frame to another (e.g. transfrom attitude from representi...
static const Eigen::DiagonalMatrix< double, 3 > NED_ENU_REFLECTION_Z(1, 1,-1)
Eigen::Vector3d transform_static_frame(const Eigen::Vector3d &vec, const StaticTF transform)
Transform data expressed in one frame to another frame.
Eigen::Matrix< double, 9, 9 > Matrix9d
static const Eigen::PermutationMatrix< 3 > NED_ENU_REFLECTION_XY(Eigen::Vector3i(1, 0, 2))
Use reflections instead of rotations for NED <-> ENU transformation to avoid NaN/Inf floating point p...
Eigen::Vector3d transform_frame(const Eigen::Vector3d &vec, const Eigen::Quaterniond &q)
Transform data expressed in one frame to another frame.
change from expressed WRT ECEF frame to WRT ENU frame
change from expressed WRT aircraft frame to WRT to baselink frame
static const auto AIRCRAFT_BASELINK_R
static const Eigen::Affine3d AIRCRAFT_BASELINK_AFFINE(AIRCRAFT_BASELINK_Q)
Static vector needed for rotating between aircraft and base_link frames +PI rotation around X (Forwar...
Eigen::Map< Eigen::Matrix< double, 9, 9, Eigen::RowMajor > > EigenMapCovariance9d
Eigen::Map for Covariance9d.
Definition: frame_tf.h:54
geometry_msgs::PoseWithCovariance::_covariance_type Covariance6d
Type matching rosmsg for 6x6 covariance matrix.
Definition: frame_tf.h:40
boost::array< double, 81 > Covariance9d
Type matching rosmsg for 9x9 covariance matrix.
Definition: frame_tf.h:43
Eigen::Map< Eigen::Matrix< double, 3, 3, Eigen::RowMajor > > EigenMapCovariance3d
Eigen::Map for Covariance3d.
Definition: frame_tf.h:46
Eigen::Matrix< double, 6, 6 > Matrix6d
Auxiliar matrices to Covariance transforms.
sensor_msgs::Imu::_angular_velocity_covariance_type Covariance3d
Type matching rosmsg for 3x3 covariance matrix.
Definition: frame_tf.h:37
Eigen::Quaterniond quaternion_from_rpy(const Eigen::Vector3d &rpy)
Convert euler angles to quaternion.
change from expressed WRT baselnk to WRT aircraft
static const auto AIRCRAFT_BASELINK_Q
Static quaternion needed for rotating between aircraft and base_link frames +PI rotation around X (Fo...
static const auto NED_ENU_R
3-D matrices to fill 6-D rotation matrix applied to change covariance matrices coordinate frames ...
Eigen::Map< const Eigen::Matrix< double, 9, 9, Eigen::RowMajor > > EigenMapConstCovariance9d
Definition: frame_tf.h:55
Frame transformation utilities.
Eigen::Map< const Eigen::Matrix< double, 6, 6, Eigen::RowMajor > > EigenMapConstCovariance6d
Definition: frame_tf.h:51
change from expressed WRT ENU frame to WRT NED frame


mavros
Author(s): Vladimir Ermakov
autogenerated on Mon Jul 8 2019 03:20:10