9 #include <px4_msgs/msg/vehicle_global_position.hpp>
10 #include <px4_ros2/common/context.hpp>
11 #include <px4_ros2/utils/subscription.hpp>
42 const px4_msgs::msg::VehicleGlobalPosition & pos =
last();
43 return {pos.lat, pos.lon, pos.alt};
Definition: context.hpp:20
Provides access to the vehicle's global position estimate.
Definition: global_position.hpp:23
Eigen::Vector3d position() const
Get the vehicle's global position.
Definition: global_position.hpp:40
bool positionValid() const
Definition: global_position.hpp:30
Provides a subscription to arbitrary ROS topics.
Definition: subscription.hpp:23
bool lastValid(const std::chrono::duration< int64_t, DurationT > max_delay=500ms) const
Check whether the last message is still valid. To be valid, the message must have been received withi...
Definition: subscription.hpp:84
const px4_msgs::msg::VehicleGlobalPosition & last() const
Get the last-received message.
Definition: subscription.hpp:58