PX4 ROS 2 Interface Library
Library to interface with PX4 from a companion computer using ROS 2
|
Provides access to the vehicle's status. More...
#include <px4_ros2/vehicle_state/land_detected.hpp>
Public Member Functions | |
LandDetected (Context &context) | |
bool | landed () const |
Check if vehicle is landed on the ground. More... | |
Public Member Functions inherited from px4_ros2::Subscription< px4_msgs::msg::VehicleLandDetected > | |
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::VehicleLandDetected & | 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::VehicleLandDetected > | |
rclcpp::Node & | _node |
Provides access to the vehicle's status.
|
inline |
Check if vehicle is landed on the ground.