9 #include <px4_msgs/msg/vehicle_local_position.hpp>
10 #include <px4_ros2/common/context.hpp>
11 #include <px4_ros2/utils/subscription.hpp>
27 bool positionXYValid()
const
32 bool positionZValid()
const
37 Eigen::Vector3f positionNed()
const
39 const px4_msgs::msg::VehicleLocalPosition & pos =
last();
40 return {pos.x, pos.y, pos.z};
43 bool velocityXYValid()
const
48 bool velocityZValid()
const
52 Eigen::Vector3f velocityNed()
const
54 const px4_msgs::msg::VehicleLocalPosition & pos =
last();
55 return {pos.vx, pos.vy, pos.vz};
58 Eigen::Vector3f accelerationNed()
const
60 const px4_msgs::msg::VehicleLocalPosition & pos =
last();
61 return {pos.ax, pos.ay, pos.az};
71 const px4_msgs::msg::VehicleLocalPosition & pos =
last();
75 float distanceGround()
const
77 const px4_msgs::msg::VehicleLocalPosition & pos =
last();
78 return pos.dist_bottom;
Definition: context.hpp:20
Provides access to the vehicle's local position estimate.
Definition: local_position.hpp:23
float heading() const
Get the vehicle's heading relative to NED earth-fixed frame.
Definition: local_position.hpp:69
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::VehicleLocalPosition & last() const
Get the last-received message.
Definition: subscription.hpp:58