|
PX4 ROS 2 Interface Library
Library to interface with PX4 from a companion computer using ROS 2
|
Represents a local position measurement to be passed to LocalPositionMeasurementInterface::update.
More...
#include <px4_ros2/navigation/experimental/local_position_measurement_interface.hpp>
Public Attributes | |
| rclcpp::Time | timestamp_sample {} |
| Timestamp of the sample. | |
| std::optional< Eigen::Vector2f > | position_xy {std::nullopt} |
| Position in the xy-plane. | |
| std::optional< Eigen::Vector2f > | position_xy_variance {std::nullopt} |
| Variance of position error in the xy-plane. | |
| std::optional< float > | position_z {std::nullopt} |
| Position in the z-axis. | |
| std::optional< float > | position_z_variance {std::nullopt} |
| Variance of position error in the z-axis. | |
| std::optional< Eigen::Vector2f > | velocity_xy {std::nullopt} |
| Velocity in the xy-plane. | |
| std::optional< Eigen::Vector2f > | velocity_xy_variance {std::nullopt} |
| Variance of velocity error in the xy-plane. | |
| std::optional< float > | velocity_z {std::nullopt} |
| Velocity in the z-axis. | |
| std::optional< float > | velocity_z_variance {std::nullopt} |
| Variance of velocity error in the z-axis. | |
| std::optional< Eigen::Quaternionf > | attitude_quaternion {std::nullopt} |
| Attitude quaternion [w, x, y, z], Hamiltonian convention. | |
| std::optional< Eigen::Vector3f > | attitude_variance {std::nullopt} |
| Variance of attitude error in body frame. | |
Represents a local position measurement to be passed to LocalPositionMeasurementInterface::update.
This struct holds information about the local position measurement, including: the timestamp of the sample, vertical and horizontal postion and velocity, attitude, and their associated variances.