SMACC2
Loading...
Searching...
No Matches
cl_px4_mr::CpVehicleStatus Class Reference

#include <cp_vehicle_status.hpp>

Inheritance diagram for cl_px4_mr::CpVehicleStatus:
Inheritance graph
Collaboration diagram for cl_px4_mr::CpVehicleStatus:
Collaboration graph

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
 
ISmaccStateMachinegetStateMachine ()
 
- Protected Attributes inherited from smacc2::ISmaccComponent
ISmaccStateMachinestateMachine_
 
ISmaccClientowner_
 

Detailed Description

Definition at line 25 of file cp_vehicle_status.hpp.

Constructor & Destructor Documentation

◆ CpVehicleStatus()

cl_px4_mr::CpVehicleStatus::CpVehicleStatus ( )

Definition at line 20 of file cp_vehicle_status.cpp.

20{}

◆ ~CpVehicleStatus()

cl_px4_mr::CpVehicleStatus::~CpVehicleStatus ( )
virtual

Definition at line 22 of file cp_vehicle_status.cpp.

22{}

Member Function Documentation

◆ getArmingState()

uint8_t cl_px4_mr::CpVehicleStatus::getArmingState ( ) const

Definition at line 83 of file cp_vehicle_status.cpp.

84{
85 std::lock_guard<std::mutex> lock(mutex_);
86 return armingState_;
87}

References armingState_, and mutex_.

◆ getNavState()

uint8_t cl_px4_mr::CpVehicleStatus::getNavState ( ) const

Definition at line 77 of file cp_vehicle_status.cpp.

78{
79 std::lock_guard<std::mutex> lock(mutex_);
80 return navState_;
81}

References mutex_, and navState_.

◆ isArmed()

bool cl_px4_mr::CpVehicleStatus::isArmed ( ) const

Definition at line 65 of file cp_vehicle_status.cpp.

66{
67 std::lock_guard<std::mutex> lock(mutex_);
68 return armingState_ == px4_msgs::msg::VehicleStatus::ARMING_STATE_ARMED;
69}

References armingState_, and mutex_.

◆ isLanded()

bool cl_px4_mr::CpVehicleStatus::isLanded ( ) const

Definition at line 71 of file cp_vehicle_status.cpp.

72{
73 std::lock_guard<std::mutex> lock(mutex_);
74 return armingState_ == px4_msgs::msg::VehicleStatus::ARMING_STATE_DISARMED;
75}

References armingState_, and mutex_.

◆ onInitialize()

void cl_px4_mr::CpVehicleStatus::onInitialize ( )
overridevirtual

Reimplemented from smacc2::ISmaccComponent.

Definition at line 24 of file cp_vehicle_status.cpp.

25{
26 auto node = this->getNode();
27 subscriber_ = node->create_subscription<px4_msgs::msg::VehicleStatus>(
28 "/fmu/out/vehicle_status_v1", rclcpp::SensorDataQoS(),
29 std::bind(&CpVehicleStatus::onStatusMessage, this, std::placeholders::_1));
30 RCLCPP_INFO(getLogger(), "CpVehicleStatus: subscribed to /fmu/out/vehicle_status");
31}
rclcpp::Subscription< px4_msgs::msg::VehicleStatus >::SharedPtr subscriber_
void onStatusMessage(const px4_msgs::msg::VehicleStatus::SharedPtr msg)
rclcpp::Logger getLogger() const
rclcpp::Node::SharedPtr getNode()

References smacc2::ISmaccComponent::getLogger(), smacc2::ISmaccComponent::getNode(), onStatusMessage(), and subscriber_.

Here is the call graph for this function:

◆ onStatusMessage()

void cl_px4_mr::CpVehicleStatus::onStatusMessage ( const px4_msgs::msg::VehicleStatus::SharedPtr msg)
private

Definition at line 33 of file cp_vehicle_status.cpp.

34{
35 std::lock_guard<std::mutex> lock(mutex_);
38 armingState_ = msg->arming_state;
39 navState_ = msg->nav_state;
40
41 // Detect arming state changes
43 {
44 if (armingState_ == px4_msgs::msg::VehicleStatus::ARMING_STATE_ARMED)
45 {
46 RCLCPP_INFO(getLogger(), "CpVehicleStatus: ARMED");
47 onArmed_();
48 }
49 else if (armingState_ == px4_msgs::msg::VehicleStatus::ARMING_STATE_DISARMED)
50 {
51 RCLCPP_INFO(getLogger(), "CpVehicleStatus: DISARMED");
53 }
54 }
55
56 // Detect nav state changes
58 {
59 RCLCPP_INFO(
60 getLogger(), "CpVehicleStatus: nav_state changed %u -> %u", prevNavState_, navState_);
62 }
63}
smacc2::SmaccSignal< void()> onModeChanged_
smacc2::SmaccSignal< void()> onDisarmed_
smacc2::SmaccSignal< void()> onArmed_

References armingState_, smacc2::ISmaccComponent::getLogger(), mutex_, navState_, onArmed_, onDisarmed_, onModeChanged_, prevArmingState_, and prevNavState_.

Referenced by onInitialize().

Here is the call graph for this function:
Here is the caller graph for this function:

Member Data Documentation

◆ armingState_

uint8_t cl_px4_mr::CpVehicleStatus::armingState_ = 0
private

Definition at line 47 of file cp_vehicle_status.hpp.

Referenced by getArmingState(), isArmed(), isLanded(), and onStatusMessage().

◆ mutex_

std::mutex cl_px4_mr::CpVehicleStatus::mutex_
mutableprivate

Definition at line 51 of file cp_vehicle_status.hpp.

Referenced by getArmingState(), getNavState(), isArmed(), isLanded(), and onStatusMessage().

◆ navState_

uint8_t cl_px4_mr::CpVehicleStatus::navState_ = 0
private

Definition at line 48 of file cp_vehicle_status.hpp.

Referenced by getNavState(), and onStatusMessage().

◆ onArmed_

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().

◆ onDisarmed_

smacc2::SmaccSignal<void()> cl_px4_mr::CpVehicleStatus::onDisarmed_

◆ onLanded_

smacc2::SmaccSignal<void()> cl_px4_mr::CpVehicleStatus::onLanded_

Definition at line 41 of file cp_vehicle_status.hpp.

◆ onModeChanged_

smacc2::SmaccSignal<void()> cl_px4_mr::CpVehicleStatus::onModeChanged_

Definition at line 40 of file cp_vehicle_status.hpp.

Referenced by onStatusMessage().

◆ prevArmingState_

uint8_t cl_px4_mr::CpVehicleStatus::prevArmingState_ = 0
private

Definition at line 49 of file cp_vehicle_status.hpp.

Referenced by onStatusMessage().

◆ prevNavState_

uint8_t cl_px4_mr::CpVehicleStatus::prevNavState_ = 0
private

Definition at line 50 of file cp_vehicle_status.hpp.

Referenced by onStatusMessage().

◆ subscriber_

rclcpp::Subscription<px4_msgs::msg::VehicleStatus>::SharedPtr cl_px4_mr::CpVehicleStatus::subscriber_
private

Definition at line 46 of file cp_vehicle_status.hpp.

Referenced by onInitialize().


The documentation for this class was generated from the following files: