|
| using | Covariance3d = sensor_msgs::Imu::_angular_velocity_covariance_type |
| | Type matching rosmsg for 3x3 covariance matrix. More...
|
| |
| using | Covariance6d = geometry_msgs::PoseWithCovariance::_covariance_type |
| | Type matching rosmsg for 6x6 covariance matrix. More...
|
| |
| using | Covariance9d = boost::array< double, 81 > |
| | Type matching rosmsg for 9x9 covariance matrix. More...
|
| |
| using | EigenMapConstCovariance3d = Eigen::Map< const Eigen::Matrix< double, 3, 3, Eigen::RowMajor > > |
| |
| using | EigenMapConstCovariance6d = Eigen::Map< const Eigen::Matrix< double, 6, 6, Eigen::RowMajor > > |
| |
| using | EigenMapConstCovariance9d = Eigen::Map< const Eigen::Matrix< double, 9, 9, Eigen::RowMajor > > |
| |
| using | EigenMapCovariance3d = Eigen::Map< Eigen::Matrix< double, 3, 3, Eigen::RowMajor > > |
| | Eigen::Map for Covariance3d. More...
|
| |
| using | EigenMapCovariance6d = Eigen::Map< Eigen::Matrix< double, 6, 6, Eigen::RowMajor > > |
| | Eigen::Map for Covariance6d. More...
|
| |
| using | EigenMapCovariance9d = Eigen::Map< Eigen::Matrix< double, 9, 9, Eigen::RowMajor > > |
| | Eigen::Map for Covariance9d. More...
|
| |
|
| template<class T , std::size_t SIZE> |
| void | covariance_to_mavlink (const T &cov, std::array< float, SIZE > &covmsg) |
| | Convert covariance matrix to MAVLink float[n] format. More...
|
| |
| template<class T , std::size_t ARR_SIZE> |
| void | covariance_urt_to_mavlink (const T &covmap, std::array< float, ARR_SIZE > &covmsg) |
| | Convert upper right triangular of a covariance matrix to MAVLink float[n] format. More...
|
| |
| Eigen::Quaterniond | mavlink_to_quaternion (const std::array< float, 4 > &q) |
| | Convert Mavlink float[4] quaternion to Eigen. More...
|
| |
| template<class T , std::size_t ARR_SIZE> |
| void | mavlink_urt_to_covariance_matrix (const std::array< float, ARR_SIZE > &covmsg, T &covmat) |
| | Convert MAVLink float[n] format (upper right triangular of a covariance matrix) to Eigen::MatrixXd<n,n> full covariance matrix. More...
|
| |
| Eigen::Quaterniond | quaternion_from_rpy (const Eigen::Vector3d &rpy) |
| | Convert euler angles to quaternion. More...
|
| |
| Eigen::Quaterniond | quaternion_from_rpy (const double roll, const double pitch, const double yaw) |
| | Convert euler angles to quaternion. More...
|
| |
| double | quaternion_get_yaw (const Eigen::Quaterniond &q) |
| | Get Yaw angle from quaternion. More...
|
| |
| void | quaternion_to_mavlink (const Eigen::Quaterniond &q, std::array< float, 4 > &qmsg) |
| | Store Quaternion to MAVLink float[4] format. More...
|
| |
| Eigen::Vector3d | quaternion_to_rpy (const Eigen::Quaterniond &q) |
| | Convert quaternion to euler angles. More...
|
| |
| void | quaternion_to_rpy (const Eigen::Quaterniond &q, double &roll, double &pitch, double &yaw) |
| | Convert quaternion to euler angles. More...
|
| |
| Eigen::Vector3d | to_eigen (const geometry_msgs::Point r) |
| | Helper to convert common ROS geometry_msgs::Point to Eigen::Vector3d. More...
|
| |
| Eigen::Vector3d | to_eigen (const geometry_msgs::Vector3 r) |
| | Helper to convert common ROS geometry_msgs::Vector3 to Eigen::Vector3d. More...
|
| |
| Eigen::Quaterniond | to_eigen (const geometry_msgs::Quaternion r) |
| | Helper to convert common ROS geometry_msgs::Quaternion to Eigen::Quaterniond. More...
|
| |
| template<class T > |
| T | transform_frame_aircraft_baselink (const T &in) |
| | Transform data expressed in Aircraft frame to Baselink frame. More...
|
| |
| template<class T > |
| T | transform_frame_aircraft_enu (const T &in, const Eigen::Quaterniond &q) |
| | Transform data expressed in aircraft frame to ENU frame. Assumes quaternion represents rotation from aircraft frame to ENU frame. More...
|
| |
| template<class T > |
| T | transform_frame_aircraft_ned (const T &in, const Eigen::Quaterniond &q) |
| | Transform data expressed in aircraft frame to NED frame. Assumes quaternion represents rotation from aircraft frame to NED frame. More...
|
| |
| template<class T > |
| T | transform_frame_baselink_aircraft (const T &in) |
| | Transform data expressed in Baselink frame to Aircraft frame. More...
|
| |
| template<class T > |
| T | transform_frame_baselink_enu (const T &in, const Eigen::Quaterniond &q) |
| | Transform data expressed in baselink to ENU frame. Assumes quaternion represents rotation from basel_link to ENU frame. More...
|
| |
| template<class T > |
| T | transform_frame_ecef_enu (const T &in, const T &map_origin) |
| | Transform data expressed in ECEF frame to ENU frame. More...
|
| |
| template<class T > |
| T | transform_frame_enu_aircraft (const T &in, const Eigen::Quaterniond &q) |
| | Transform data expressed in ENU to aircraft frame. Assumes quaternion represents rotation from ENU to aircraft frame. More...
|
| |
| template<class T > |
| T | transform_frame_enu_baselink (const T &in, const Eigen::Quaterniond &q) |
| | Transform data expressed in ENU to base_link frame. Assumes quaternion represents rotation from ENU to base_link frame. More...
|
| |
| template<class T > |
| T | transform_frame_enu_ecef (const T &in, const T &map_origin) |
| | Transform data expressed in ENU frame to ECEF frame. More...
|
| |
| template<class T > |
| T | transform_frame_enu_ned (const T &in) |
| | Transform data expressed in ENU to NED frame. More...
|
| |
| template<class T > |
| T | transform_frame_ned_aircraft (const T &in, const Eigen::Quaterniond &q) |
| | Transform data expressed in NED to aircraft frame. Assumes quaternion represents rotation from NED to aircraft frame. More...
|
| |
| template<class T > |
| T | transform_frame_ned_enu (const T &in) |
| | Transform data expressed in NED to ENU frame. More...
|
| |
| template<class T > |
| T | transform_orientation_aircraft_baselink (const T &in) |
| | Transform from attitude represented WRT aircraft frame to attitude represented WRT base_link frame. More...
|
| |
| template<class T > |
| T | transform_orientation_baselink_aircraft (const T &in) |
| | Transform from attitude represented WRT baselink frame to attitude represented WRT body frame. More...
|
| |
| template<class T > |
| T | transform_orientation_enu_ned (const T &in) |
| | Transform from attitude represented WRT ENU frame to attitude represented WRT NED frame. More...
|
| |
| template<class T > |
| T | transform_orientation_ned_enu (const T &in) |
| | Transform from attitude represented WRT NED frame to attitude represented WRT ENU frame. More...
|
| |