|
SMACC2
|
#include <cp_vehicle_status.hpp>


Public Member Functions | |
| CpVehicleStatus () | |
| virtual | ~CpVehicleStatus () |
| void | onInitialize () override |
| bool | isArmed () const |
| bool | isLanded () const |
| uint8_t | getNavState () const |
| uint8_t | getArmingState () const |
Public Member Functions inherited from smacc2::ISmaccComponent | |
| ISmaccComponent () | |
| virtual | ~ISmaccComponent () |
| virtual std::string | getName () const |
Public Attributes | |
| smacc2::SmaccSignal< void()> | onArmed_ |
| smacc2::SmaccSignal< void()> | onDisarmed_ |
| smacc2::SmaccSignal< void()> | onModeChanged_ |
| smacc2::SmaccSignal< void()> | onLanded_ |
Private Member Functions | |
| void | onStatusMessage (const px4_msgs::msg::VehicleStatus::SharedPtr msg) |
Private Attributes | |
| rclcpp::Subscription< px4_msgs::msg::VehicleStatus >::SharedPtr | subscriber_ |
| uint8_t | armingState_ = 0 |
| uint8_t | navState_ = 0 |
| uint8_t | prevArmingState_ = 0 |
| uint8_t | prevNavState_ = 0 |
| std::mutex | mutex_ |
Additional Inherited Members | |
Protected Member Functions inherited from smacc2::ISmaccComponent | |
| template<typename TOrthogonal , typename TClient > | |
| void | onComponentInitialization () |
| template<typename EventType > | |
| void | postEvent (const EventType &ev) |
| template<typename EventType > | |
| void | postEvent () |
| template<typename TOrthogonal , typename TSourceObject > | |
| void | onStateOrthogonalAllocation () |
| template<typename TComponent > | |
| void | requiresComponent (TComponent *&requiredComponentStorage, ComponentRequirement requirementType=ComponentRequirement::SOFT) |
| template<typename TComponent > | |
| void | requiresComponent (std::string name, TComponent *&requiredComponentStorage, ComponentRequirement requirementType=ComponentRequirement::SOFT) |
| template<typename TClient > | |
| void | requiresClient (TClient *&requiredClientStorage) |
| template<typename SmaccComponentType , typename TOrthogonal , typename TClient , typename... TArgs> | |
| SmaccComponentType * | createSiblingComponent (TArgs... targs) |
| template<typename SmaccComponentType , typename TOrthogonal , typename TClient , typename... TArgs> | |
| SmaccComponentType * | createSiblingNamedComponent (std::string name, TArgs... targs) |
| rclcpp::Node::SharedPtr | getNode () |
| rclcpp::Logger | getLogger () const |
| ISmaccStateMachine * | getStateMachine () |
Protected Attributes inherited from smacc2::ISmaccComponent | |
| ISmaccStateMachine * | stateMachine_ |
| ISmaccClient * | owner_ |
Definition at line 25 of file cp_vehicle_status.hpp.
| cl_px4_mr::CpVehicleStatus::CpVehicleStatus | ( | ) |
Definition at line 20 of file cp_vehicle_status.cpp.
|
virtual |
Definition at line 22 of file cp_vehicle_status.cpp.
| uint8_t cl_px4_mr::CpVehicleStatus::getArmingState | ( | ) | const |
Definition at line 83 of file cp_vehicle_status.cpp.
References armingState_, and mutex_.
| uint8_t cl_px4_mr::CpVehicleStatus::getNavState | ( | ) | const |
Definition at line 77 of file cp_vehicle_status.cpp.
| bool cl_px4_mr::CpVehicleStatus::isArmed | ( | ) | const |
Definition at line 65 of file cp_vehicle_status.cpp.
References armingState_, and mutex_.
| bool cl_px4_mr::CpVehicleStatus::isLanded | ( | ) | const |
Definition at line 71 of file cp_vehicle_status.cpp.
References armingState_, and mutex_.
|
overridevirtual |
Reimplemented from smacc2::ISmaccComponent.
Definition at line 24 of file cp_vehicle_status.cpp.
References smacc2::ISmaccComponent::getLogger(), smacc2::ISmaccComponent::getNode(), onStatusMessage(), and subscriber_.

|
private |
Definition at line 33 of file cp_vehicle_status.cpp.
References armingState_, smacc2::ISmaccComponent::getLogger(), mutex_, navState_, onArmed_, onDisarmed_, onModeChanged_, prevArmingState_, and prevNavState_.
Referenced by onInitialize().


|
private |
Definition at line 47 of file cp_vehicle_status.hpp.
Referenced by getArmingState(), isArmed(), isLanded(), and onStatusMessage().
|
mutableprivate |
Definition at line 51 of file cp_vehicle_status.hpp.
Referenced by getArmingState(), getNavState(), isArmed(), isLanded(), and onStatusMessage().
|
private |
Definition at line 48 of file cp_vehicle_status.hpp.
Referenced by getNavState(), and onStatusMessage().
| smacc2::SmaccSignal<void()> cl_px4_mr::CpVehicleStatus::onArmed_ |
Definition at line 38 of file cp_vehicle_status.hpp.
Referenced by cl_px4_mr::CbArmPX4::onEntry(), and onStatusMessage().
| smacc2::SmaccSignal<void()> cl_px4_mr::CpVehicleStatus::onDisarmed_ |
Definition at line 39 of file cp_vehicle_status.hpp.
Referenced by cl_px4_mr::CbDisarmPX4::onEntry(), cl_px4_mr::CbLand::onEntry(), and onStatusMessage().
| smacc2::SmaccSignal<void()> cl_px4_mr::CpVehicleStatus::onLanded_ |
Definition at line 41 of file cp_vehicle_status.hpp.
| smacc2::SmaccSignal<void()> cl_px4_mr::CpVehicleStatus::onModeChanged_ |
Definition at line 40 of file cp_vehicle_status.hpp.
Referenced by onStatusMessage().
|
private |
Definition at line 49 of file cp_vehicle_status.hpp.
Referenced by onStatusMessage().
|
private |
Definition at line 50 of file cp_vehicle_status.hpp.
Referenced by onStatusMessage().
|
private |
Definition at line 46 of file cp_vehicle_status.hpp.
Referenced by onInitialize().