|
PX4 ROS 2 Interface Library
Library to interface with PX4 from a companion computer using ROS 2
|
Provides access to the vehicle's local position estimate. More...
#include <px4_ros2/odometry/local_position.hpp>
Public Member Functions | |
| OdometryLocalPosition (Context &context, bool local_position_is_optional=false) | |
| bool | positionXYValid () const |
| bool | positionZValid () const |
| Eigen::Vector3f | positionNed () const |
| bool | velocityXYValid () const |
| bool | velocityZValid () const |
| Eigen::Vector3f | velocityNed () const |
| Eigen::Vector3f | accelerationNed () const |
| float | heading () const |
| Get the vehicle's heading relative to NED earth-fixed frame. More... | |
| float | distanceGround () const |
Public Member Functions inherited from px4_ros2::Subscription< px4_msgs::msg::VehicleLocalPosition > | |
| Subscription (Context &context, const std::string &topic) | |
| void | onUpdate (const UpdateCallback &callback) |
| Add a callback to execute when receiving a new message. More... | |
| const px4_msgs::msg::VehicleLocalPosition & | last () const |
| Get the last-received message. More... | |
| const rclcpp::Time & | lastTime () const |
| Get the receive-time of the last message. More... | |
| 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 within a given time of the current time. More... | |
Additional Inherited Members | |
Protected Attributes inherited from px4_ros2::Subscription< px4_msgs::msg::VehicleLocalPosition > | |
| rclcpp::Node & | _node |
Provides access to the vehicle's local position estimate.
|
explicit |
setting local_position_is_optional to true allows to create a mode that uses local position data but doesn't necessarly require local position to be available (for instance if the mode reads altitude data from vehicle_local_position). Reading XY position without a correct source of positional data is not recommended
|
inline |
Get the vehicle's heading relative to NED earth-fixed frame.