Go to the documentation of this file.
153 Eigen::PermutationMatrix<6> NED_ENU_REFLECTION_XY_6 (
NED_ENU_REFLECTION_XY.indices().replicate<2,1>());
154 NED_ENU_REFLECTION_XY_6.indices().middleRows<3>(3).array() += 3;
155 Eigen::DiagonalMatrix<double,6> NED_ENU_REFLECTION_Z_6(
NED_ENU_REFLECTION_Z.diagonal().replicate<2,1>());
157 cov_out = NED_ENU_REFLECTION_XY_6 * (NED_ENU_REFLECTION_Z_6 * cov_in * NED_ENU_REFLECTION_Z_6) *
158 NED_ENU_REFLECTION_XY_6.transpose();
164 R.block<3, 3>(0, 0) =
167 cov_out = R * cov_in * R.transpose();
188 Eigen::PermutationMatrix<9> NED_ENU_REFLECTION_XY_9 (
NED_ENU_REFLECTION_XY.indices().replicate<3,1>());
189 NED_ENU_REFLECTION_XY_9.indices().middleRows<3>(3).array() += 3;
190 NED_ENU_REFLECTION_XY_9.indices().middleRows<3>(6).array() += 6;
191 Eigen::DiagonalMatrix<double,9> NED_ENU_REFLECTION_Z_9(
NED_ENU_REFLECTION_Z.diagonal().replicate<3,1>());
193 cov_out = NED_ENU_REFLECTION_XY_9 * (NED_ENU_REFLECTION_Z_9 * cov_in * NED_ENU_REFLECTION_Z_9) *
194 NED_ENU_REFLECTION_XY_9.transpose();
200 R.block<3, 3>(0, 0) =
201 R.block<3, 3>(3, 3) =
204 cov_out = R * cov_in * R.transpose();
216 static constexpr
double DEG_TO_RAD = (M_PI / 180.0);
219 const double sin_lat = std::sin(map_origin.x() * DEG_TO_RAD);
220 const double sin_lon = std::sin(map_origin.y() * DEG_TO_RAD);
221 const double cos_lat = std::cos(map_origin.x() * DEG_TO_RAD);
222 const double cos_lon = std::cos(map_origin.y() * DEG_TO_RAD);
239 R << -sin_lon, cos_lon, 0.0,
240 -cos_lon * sin_lat, -sin_lon * sin_lat, cos_lat,
241 cos_lon * cos_lat, sin_lon * cos_lat, sin_lat;
249 R.transposeInPlace();
258 Eigen::Vector3d
transform_frame(
const Eigen::Vector3d &vec,
const Eigen::Quaterniond &q)
260 Eigen::Affine3d transformation(q);
261 return transformation * vec;
270 cov_out = cov_in * q;
282 R.block<3, 3>(0, 0) =
283 R.block<3, 3>(3, 3) = q.normalized().toRotationMatrix();
285 cov_out = R * cov_in * R.transpose();
297 R.block<3, 3>(0, 0) =
298 R.block<3, 3>(3, 3) =
299 R.block<3, 3>(6, 6) = q.normalized().toRotationMatrix();
301 cov_out = R * cov_in * R.transpose();
sensor_msgs::Imu::_angular_velocity_covariance_type Covariance3d
Type matching rosmsg for 3x3 covariance matrix.
Eigen::Vector3d transform_frame(const Eigen::Vector3d &vec, const Eigen::Quaterniond &q)
Transform data expressed in one frame to another frame.
Eigen::Map< const Eigen::Matrix< double, 3, 3, Eigen::RowMajor > > EigenMapConstCovariance3d
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...
static const auto AIRCRAFT_BASELINK_Q
Static quaternion needed for rotating between aircraft and base_link frames +PI rotation around X (Fo...
Eigen::Quaterniond quaternion_from_rpy(const Eigen::Vector3d &rpy)
Convert euler angles to quaternion.
Eigen::Matrix< double, 9, 9 > Matrix9d
static const Eigen::DiagonalMatrix< double, 3 > NED_ENU_REFLECTION_Z(1, 1,-1)
@ AIRCRAFT_TO_BASELINK
change from expressed WRT aircraft frame to WRT to baselink frame
static const auto AIRCRAFT_BASELINK_R
Eigen::Map< const Eigen::Matrix< double, 9, 9, Eigen::RowMajor > > EigenMapConstCovariance9d
Eigen::Map< const Eigen::Matrix< double, 6, 6, Eigen::RowMajor > > EigenMapConstCovariance6d
@ ECEF_TO_ENU
change from expressed WRT ECEF frame to WRT ENU frame
Eigen::Map< Eigen::Matrix< double, 9, 9, Eigen::RowMajor > > EigenMapCovariance9d
Eigen::Map for Covariance9d.
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...
@ ENU_TO_ECEF
change from expressed WRT ENU frame to WRT ECEF frame
@ BASELINK_TO_AIRCRAFT
change from expressed WRT baselnk to WRT aircraft
@ NED_TO_ENU
will change orientation from being expressed WRT NED frame to WRT ENU frame
@ ABSOLUTE_FRAME_BASELINK_TO_AIRCRAFT
change orientation from being expressed in baselink frame to aircraft frame in an absolute frame of r...
Eigen::Matrix< double, 6, 6 > Matrix6d
Auxiliar matrices to Covariance transforms.
static const auto NED_ENU_R
3-D matrices to fill 6-D rotation matrix applied to change covariance matrices coordinate frames
Eigen::Vector3d transform_static_frame(const Eigen::Vector3d &vec, const StaticTF transform)
Transform data expressed in one frame to another frame.
@ ENU_TO_NED
change from expressed WRT ENU frame to WRT NED frame
Eigen::Map< Eigen::Matrix< double, 6, 6, Eigen::RowMajor > > EigenMapCovariance6d
Eigen::Map for Covariance6d.
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...
StaticEcefTF
Orientation transform options when applying rotations to data, for ECEF.
Frame transformation utilities.
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...
@ ABSOLUTE_FRAME_AIRCRAFT_TO_BASELINK
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.
boost::array< double, 81 > Covariance9d
Type matching rosmsg for 9x9 covariance matrix.
static const auto NED_ENU_Q
Static quaternion needed for rotating between ENU and NED frames NED to ENU: +PI/2 rotation about Z (...
StaticTF
Orientation transform options when applying rotations to data.
geometry_msgs::PoseWithCovariance::_covariance_type Covariance6d
Type matching rosmsg for 6x6 covariance matrix.
mavros
Author(s): Vladimir Ermakov
autogenerated on Tue May 6 2025 02:34:03