PX4 ROS 2 Interface Library
Library to interface with PX4 from a companion computer using ROS 2
px4_ros2::GlobalPositionMeasurement Struct Reference

Represents a global position measurement to be passed to GlobalPositionMeasurementInterface::update. More...

#include <px4_ros2/navigation/experimental/global_position_measurement_interface.hpp>

Public Attributes

rclcpp::Time timestamp_sample {}
 Timestamp of the sample.
 
std::optional< Eigen::Vector2d > lat_lon {std::nullopt}
 Latitude and longitude.
 
std::optional< float > horizontal_variance {std::nullopt}
 Variance of horizontal position error (meters).
 
std::optional< float > altitude_msl {std::nullopt}
 Altitude in the MSL frame.
 
std::optional< float > vertical_variance {std::nullopt}
 Variance of vertical position error (meters).
 

Detailed Description

Represents a global position measurement to be passed to GlobalPositionMeasurementInterface::update.

This struct holds information about the global position measurement, including: the timestamp of the sample, latitude and longitude, altitude in the MSL frame, and their associated variances.

See also
GlobalPositionMeasurementInterface::update

The documentation for this struct was generated from the following file: