Typedefs | Functions | Variables
mavros::ftf::detail Namespace Reference

Typedefs

using Matrix6d = Eigen::Matrix< double, 6, 6 >
 Auxiliar matrices to Covariance transforms. More...
 
using Matrix9d = Eigen::Matrix< double, 9, 9 >
 

Functions

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 (Forward) axis transforms from Forward, Right, Down (aircraft) Fto Forward, Left, Up (base_link) frames. More...
 
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 follwed by +PI/2 rotation about Z (Down) gives the ENU frame. Similarly, a +PI rotation about X (East) followed by a +PI/2 roation about Z (Up) gives the NED frame. More...
 
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 pollution across different axes since in NED <-> ENU the axes are perfectly aligned. More...
 
static const Eigen::DiagonalMatrix< double, 3 > NED_ENU_REFLECTION_Z (1, 1,-1)
 
Eigen::Vector3d transform_frame (const Eigen::Vector3d &vec, const Eigen::Quaterniond &q)
 Transform data expressed in one frame to another frame. More...
 
Covariance3d transform_frame (const Covariance3d &cov, const Eigen::Quaterniond &q)
 Transform 3x3 convariance expressed in one frame to another. More...
 
Covariance6d transform_frame (const Covariance6d &cov, const Eigen::Quaterniond &q)
 Transform 6x6 convariance expressed in one frame to another. More...
 
Covariance9d transform_frame (const Covariance9d &cov, const Eigen::Quaterniond &q)
 Transform 9x9 convariance expressed in one frame to another. More...
 
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 representing from base_link -> NED to representing base_link -> ENU) More...
 
Eigen::Vector3d transform_static_frame (const Eigen::Vector3d &vec, const StaticTF transform)
 Transform data expressed in one frame to another frame. More...
 
Covariance3d transform_static_frame (const Covariance3d &cov, const StaticTF transform)
 Transform 3d convariance expressed in one frame to another. More...
 
Covariance6d transform_static_frame (const Covariance6d &cov, const StaticTF transform)
 Transform 6d convariance expressed in one frame to another. More...
 
Covariance9d transform_static_frame (const Covariance9d &cov, const StaticTF transform)
 Transform 9d convariance expressed in one frame to another. More...
 
Eigen::Vector3d transform_static_frame (const Eigen::Vector3d &vec, const Eigen::Vector3d &map_origin, const StaticEcefTF transform)
 Transform data expressed in one frame to another frame with additional map origin parameter. More...
 

Variables

static const auto AIRCRAFT_BASELINK_Q = quaternion_from_rpy(M_PI, 0.0, 0.0)
 Static quaternion needed for rotating between aircraft and base_link frames +PI rotation around X (Forward) axis transforms from Forward, Right, Down (aircraft) Fto Forward, Left, Up (base_link) frames. More...
 
static const auto AIRCRAFT_BASELINK_R = AIRCRAFT_BASELINK_Q.normalized().toRotationMatrix()
 
static const auto NED_ENU_Q = quaternion_from_rpy(M_PI, 0.0, M_PI_2)
 Static quaternion needed for rotating between ENU and NED frames NED to ENU: +PI/2 rotation about Z (Down) followed by a +PI rotation around X (old North/new East) ENU to NED: +PI/2 rotation about Z (Up) followed by a +PI rotation about X (old East/new North) More...
 
static const auto NED_ENU_R = NED_ENU_Q.normalized().toRotationMatrix()
 3-D matrices to fill 6-D rotation matrix applied to change covariance matrices coordinate frames More...
 


mavros
Author(s): Vladimir Ermakov
autogenerated on Tue Jun 1 2021 02:36:27