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 #include <stdexcept>
21 
22 namespace mavros {
23 namespace ftf {
24 namespace detail {
30 static const auto NED_ENU_Q = quaternion_from_rpy(M_PI, 0.0, M_PI_2);
31 
37 static const auto AIRCRAFT_BASELINK_Q = quaternion_from_rpy(M_PI, 0.0, 0.0);
38 
45 static const Eigen::Affine3d NED_ENU_AFFINE(NED_ENU_Q);
46 
52 static const Eigen::Affine3d AIRCRAFT_BASELINK_AFFINE(AIRCRAFT_BASELINK_Q);
53 
57 static const auto NED_ENU_R = NED_ENU_Q.normalized().toRotationMatrix();
58 static const auto AIRCRAFT_BASELINK_R = AIRCRAFT_BASELINK_Q.normalized().toRotationMatrix();
59 
65 static const Eigen::PermutationMatrix<3> NED_ENU_REFLECTION_XY(Eigen::Vector3i(1,0,2));
66 static const Eigen::DiagonalMatrix<double,3> NED_ENU_REFLECTION_Z(1,1,-1);
67 
71 using Matrix6d = Eigen::Matrix<double, 6, 6>;
72 using Matrix9d = Eigen::Matrix<double, 9, 9>;
73 
74 
75 Eigen::Quaterniond transform_orientation(const Eigen::Quaterniond &q, const StaticTF transform)
76 {
77  // Transform the attitude representation from frame to frame.
78  // The proof for this transform can be seen
79  // http://www.euclideanspace.com/maths/algebra/realNormedAlgebra/quaternions/transforms/
80  switch (transform) {
83  return NED_ENU_Q * q;
84 
87  return q * AIRCRAFT_BASELINK_Q;
88 
91  return AIRCRAFT_BASELINK_Q * q;
92  }
93 }
94 
95 
96 Eigen::Vector3d transform_static_frame(const Eigen::Vector3d &vec, const StaticTF transform)
97 {
98  switch (transform) {
102 
105  return AIRCRAFT_BASELINK_AFFINE * vec;
106  }
107 }
108 
110 {
111  Covariance3d cov_out_;
112  EigenMapConstCovariance3d cov_in(cov.data());
113  EigenMapCovariance3d cov_out(cov_out_.data());
114 
115  switch (transform) {
119  NED_ENU_REFLECTION_XY.transpose();
120  return cov_out_;
121 
124  cov_out = cov_in * AIRCRAFT_BASELINK_Q;
125  return cov_out_;
126  }
127 }
128 
130 {
131  Covariance6d cov_out_;
132  Matrix6d R = Matrix6d::Zero(); // not `auto` because Zero ret is const
133 
134  EigenMapConstCovariance6d cov_in(cov.data());
135  EigenMapCovariance6d cov_out(cov_out_.data());
136 
137  switch (transform) {
140  {
141  Eigen::PermutationMatrix<6> NED_ENU_REFLECTION_XY_6 (NED_ENU_REFLECTION_XY.indices().replicate<2,1>());
142  NED_ENU_REFLECTION_XY_6.indices().middleRows<3>(3).array() += 3;
143  Eigen::DiagonalMatrix<double,6> NED_ENU_REFLECTION_Z_6(NED_ENU_REFLECTION_Z.diagonal().replicate<2,1>());
144 
145  cov_out = NED_ENU_REFLECTION_XY_6 * (NED_ENU_REFLECTION_Z_6 * cov_in * NED_ENU_REFLECTION_Z_6) *
146  NED_ENU_REFLECTION_XY_6.transpose();
147 
148  return cov_out_;
149  }
152  R.block<3, 3>(0, 0) =
153  R.block<3, 3>(3, 3) = AIRCRAFT_BASELINK_R;
154 
155  cov_out = R * cov_in * R.transpose();
156  return cov_out_;
157  }
158 }
159 
161 {
162  Covariance9d cov_out_;
163  Matrix9d R = Matrix9d::Zero();
164 
165  EigenMapConstCovariance9d cov_in(cov.data());
166  EigenMapCovariance9d cov_out(cov_out_.data());
167 
168  switch (transform) {
171  {
172  Eigen::PermutationMatrix<9> NED_ENU_REFLECTION_XY_9 (NED_ENU_REFLECTION_XY.indices().replicate<3,1>());
173  NED_ENU_REFLECTION_XY_9.indices().middleRows<3>(3).array() += 3;
174  NED_ENU_REFLECTION_XY_9.indices().middleRows<3>(6).array() += 6;
175  Eigen::DiagonalMatrix<double,9> NED_ENU_REFLECTION_Z_9(NED_ENU_REFLECTION_Z.diagonal().replicate<3,1>());
176 
177  cov_out = NED_ENU_REFLECTION_XY_9 * (NED_ENU_REFLECTION_Z_9 * cov_in * NED_ENU_REFLECTION_Z_9) *
178  NED_ENU_REFLECTION_XY_9.transpose();
179 
180  return cov_out_;
181  }
184  R.block<3, 3>(0, 0) =
185  R.block<3, 3>(3, 3) =
186  R.block<3, 3>(6, 6) = AIRCRAFT_BASELINK_R;
187 
188  cov_out = R * cov_in * R.transpose();
189  return cov_out_;
190  }
191 }
192 
193 Eigen::Vector3d transform_static_frame(const Eigen::Vector3d &vec, const Eigen::Vector3d &map_origin, const StaticEcefTF transform)
194 {
196  static constexpr double DEG_TO_RAD = (M_PI / 180.0);
197 
198  // Don't forget to convert from degrees to radians
199  const double sin_lat = std::sin(map_origin.x() * DEG_TO_RAD);
200  const double sin_lon = std::sin(map_origin.y() * DEG_TO_RAD);
201  const double cos_lat = std::cos(map_origin.x() * DEG_TO_RAD);
202  const double cos_lon = std::cos(map_origin.y() * DEG_TO_RAD);
203 
218  Eigen::Matrix3d R;
219  R << -sin_lon, cos_lon, 0.0,
220  -cos_lon * sin_lat, -sin_lon * sin_lat, cos_lat,
221  cos_lon * cos_lat, sin_lon * cos_lat, sin_lat;
222 
223  switch (transform) {
225  return R * vec;
226 
228  // ENU to ECEF rotation is just an inverse rotation from ECEF to ENU, which means transpose.
229  R.transposeInPlace();
230  return R * vec;
231  }
232 }
233 
234 Eigen::Vector3d transform_frame(const Eigen::Vector3d &vec, const Eigen::Quaterniond &q)
235 {
236  Eigen::Affine3d transformation(q);
237  return transformation * vec;
238 }
239 
240 Covariance3d transform_frame(const Covariance3d &cov, const Eigen::Quaterniond &q)
241 {
242  Covariance3d cov_out_;
243  EigenMapConstCovariance3d cov_in(cov.data());
244  EigenMapCovariance3d cov_out(cov_out_.data());
245 
246  cov_out = cov_in * q;
247  return cov_out_;
248 }
249 
250 Covariance6d transform_frame(const Covariance6d &cov, const Eigen::Quaterniond &q)
251 {
252  Covariance6d cov_out_;
253  Matrix6d R = Matrix6d::Zero();
254 
255  EigenMapConstCovariance6d cov_in(cov.data());
256  EigenMapCovariance6d cov_out(cov_out_.data());
257 
258  R.block<3, 3>(0, 0) =
259  R.block<3, 3>(3, 3) = q.normalized().toRotationMatrix();
260 
261  cov_out = R * cov_in * R.transpose();
262  return cov_out_;
263 }
264 
265 Covariance9d transform_frame(const Covariance9d &cov, const Eigen::Quaterniond &q)
266 {
267  Covariance9d cov_out_;
268  Matrix9d R = Matrix9d::Zero();
269 
270  EigenMapConstCovariance9d cov_in(cov.data());
271  EigenMapCovariance9d cov_out(cov_out_.data());
272 
273  R.block<3, 3>(0, 0) =
274  R.block<3, 3>(3, 3) =
275  R.block<3, 3>(6, 6) = q.normalized().toRotationMatrix();
276 
277  cov_out = R * cov_in * R.transpose();
278  return cov_out_;
279 }
280 
281 } // namespace detail
282 } // namespace ftf
283 } // namespace mavros
change orientation from being expressed in baselink frame to aircraft frame in an absolute frame of r...
change from expressed WRT ENU frame to WRT ECEF frame
will change orientation from being expressed WRT NED frame to WRT ENU frame
StaticEcefTF
Orientation transform options when applying rotations to data, for ECEF.
Definition: frame_tf.h:72
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
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 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
change orientation from being expressed in aircraft frame to baselink frame in an absolute frame of r...
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...
change from expressed WRT ECEF frame to WRT ENU frame
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 Tue Jun 1 2021 02:36:26