Class Data
Defined in File mavros_uas.hpp
Class Documentation
-
class Data
UAS Node data.
This class stores some useful data;
Currently it stores:
IMU data (mavplugin::IMUPubPlugin)
GPS data (mavplugin::GPSPlugin)
Public Functions
-
EIGEN_MAKE_ALIGNED_OPERATOR_NEW Data()
-
~Data() = default
-
void update_attitude_imu_enu(const sensor_msgs::msg::Imu &imu)
Store IMU data [ENU].
-
void update_attitude_imu_ned(const sensor_msgs::msg::Imu &imu)
Store IMU data [NED].
-
sensor_msgs::msg::Imu get_attitude_imu_enu()
Get IMU data [ENU].
-
sensor_msgs::msg::Imu get_attitude_imu_ned()
Get IMU data [NED].
-
geometry_msgs::msg::Quaternion get_attitude_orientation_enu()
Get Attitude orientation quaternion.
- Returns:
orientation quaternion [ENU]
-
geometry_msgs::msg::Quaternion get_attitude_orientation_ned()
Get Attitude orientation quaternion.
- Returns:
orientation quaternion [NED]
-
geometry_msgs::msg::Vector3 get_attitude_angular_velocity_enu()
Get angular velocity from IMU data.
- Returns:
vector3 [ENU]
-
geometry_msgs::msg::Vector3 get_attitude_angular_velocity_ned()
Get angular velocity from IMU data.
- Returns:
vector3 [NED]
Store GPS RAW data.
-
void get_gps_epts(float &eph, float &epv, int &fix_type, int &satellites_visible)
Returns EPH, EPV, Fix type and satellites visible.
-
sensor_msgs::msg::NavSatFix get_gps_fix()
Retunrs last GPS RAW message.
-
template<class T, std::enable_if_t<std::is_pointer<T>::value, bool> = true>
inline double geoid_to_ellipsoid_height(const T lla) Conversion from height above geoid (AMSL) to height above ellipsoid (WGS-84)
-
template<class T, std::enable_if_t<std::is_class<T>::value, bool> = true>
inline double geoid_to_ellipsoid_height(const T &lla)
Public Static Attributes
-
static std::shared_ptr<GeographicLib::Geoid> egm96_5
Geoid dataset used to convert between AMSL and WGS-84.
That class loads egm96_5 dataset to RAM, it is about 24 MiB.