18#include <px4_msgs/msg/vehicle_status.hpp>
19#include <rclcpp/rclcpp.hpp>
44 void onStatusMessage(
const px4_msgs::msg::VehicleStatus::SharedPtr msg);
46 rclcpp::Subscription<px4_msgs::msg::VehicleStatus>::SharedPtr
subscriber_;
smacc2::SmaccSignal< void()> onModeChanged_
uint8_t getNavState() const
rclcpp::Subscription< px4_msgs::msg::VehicleStatus >::SharedPtr subscriber_
void onStatusMessage(const px4_msgs::msg::VehicleStatus::SharedPtr msg)
smacc2::SmaccSignal< void()> onDisarmed_
virtual ~CpVehicleStatus()
uint8_t getArmingState() const
void onInitialize() override
smacc2::SmaccSignal< void()> onArmed_
smacc2::SmaccSignal< void()> onLanded_