9#include <px4_msgs/msg/vehicle_local_position.hpp>
10#include <px4_ros2/common/context.hpp>
11#include <px4_ros2/utils/subscription.hpp>
33 bool positionXYValid()
const
38 bool positionZValid()
const
43 Eigen::Vector3f positionNed()
const
45 const px4_msgs::msg::VehicleLocalPosition & pos =
last();
46 return {pos.x, pos.y, pos.z};
49 bool velocityXYValid()
const
54 bool velocityZValid()
const
58 Eigen::Vector3f velocityNed()
const
60 const px4_msgs::msg::VehicleLocalPosition & pos =
last();
61 return {pos.vx, pos.vy, pos.vz};
64 Eigen::Vector3f accelerationNed()
const
66 const px4_msgs::msg::VehicleLocalPosition & pos =
last();
67 return {pos.ax, pos.ay, pos.az};
77 const px4_msgs::msg::VehicleLocalPosition & pos =
last();
81 float distanceGround()
const
83 const px4_msgs::msg::VehicleLocalPosition & pos =
last();
84 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:75
OdometryLocalPosition(Context &context, bool local_position_is_optional=false)
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