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>());
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();
147 R.block<3, 3>(0, 0) =
150 cov_out = R * cov_in * R.transpose();
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>());
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();
179 R.block<3, 3>(0, 0) =
180 R.block<3, 3>(3, 3) =
183 cov_out = R * cov_in * R.transpose();
191 static constexpr
double DEG_TO_RAD = (M_PI / 180.0);
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);
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;
224 R.transposeInPlace();
229 Eigen::Vector3d
transform_frame(
const Eigen::Vector3d &vec,
const Eigen::Quaterniond &q)
231 Eigen::Affine3d transformation(q);
232 return transformation * vec;
241 cov_out = cov_in * q;
253 R.block<3, 3>(0, 0) =
254 R.block<3, 3>(3, 3) = q.normalized().toRotationMatrix();
256 cov_out = R * cov_in * R.transpose();
268 R.block<3, 3>(0, 0) =
269 R.block<3, 3>(3, 3) =
270 R.block<3, 3>(6, 6) = q.normalized().toRotationMatrix();
272 cov_out = R * cov_in * R.transpose();
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.
Eigen::Map< Eigen::Matrix< double, 6, 6, Eigen::RowMajor > > EigenMapCovariance6d
Eigen::Map for Covariance6d.
change from expressed WRT ENU frame to WRT ECEF frame
Eigen::Map< const Eigen::Matrix< double, 3, 3, Eigen::RowMajor > > EigenMapConstCovariance3d
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.
geometry_msgs::PoseWithCovariance::_covariance_type Covariance6d
Type matching rosmsg for 6x6 covariance matrix.
boost::array< double, 81 > Covariance9d
Type matching rosmsg for 9x9 covariance matrix.
Eigen::Map< Eigen::Matrix< double, 3, 3, Eigen::RowMajor > > EigenMapCovariance3d
Eigen::Map for Covariance3d.
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.
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
Frame transformation utilities.
Eigen::Map< const Eigen::Matrix< double, 6, 6, Eigen::RowMajor > > EigenMapConstCovariance6d
change from expressed WRT ENU frame to WRT NED frame