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

#include <cb_connect_micro_ros_agent.hpp>

Inheritance diagram for cl_px4_mr::CbConnectMicroRosAgent:
Inheritance graph
Collaboration diagram for cl_px4_mr::CbConnectMicroRosAgent:
Collaboration graph

Public Member Functions

 CbConnectMicroRosAgent (double timeoutSec=30.0)
 
void onEntry () override
 
void onExit () override
 
- Public Member Functions inherited from smacc2::SmaccAsyncClientBehavior
template<typename TOrthogonal , typename TSourceObject >
void onStateOrthogonalAllocation ()
 
virtual ~SmaccAsyncClientBehavior ()
 
template<typename TCallback , typename T >
smacc2::SmaccSignalConnection onSuccess (TCallback callback, T *object)
 
template<typename TCallback , typename T >
smacc2::SmaccSignalConnection onFinished (TCallback callback, T *object)
 
template<typename TCallback , typename T >
smacc2::SmaccSignalConnection onFailure (TCallback callback, T *object)
 
void requestForceFinish ()
 
void executeOnEntry () override
 
void executeOnExit () override
 
void waitOnEntryThread (bool requestFinish)
 
template<typename TCallbackMethod , typename T >
smacc2::SmaccSignalConnection onSuccess (TCallbackMethod callback, T *object)
 
template<typename TCallbackMethod , typename T >
smacc2::SmaccSignalConnection onFinished (TCallbackMethod callback, T *object)
 
template<typename TCallbackMethod , typename T >
smacc2::SmaccSignalConnection onFailure (TCallbackMethod callback, T *object)
 
- Public Member Functions inherited from smacc2::ISmaccClientBehavior
 ISmaccClientBehavior ()
 
virtual ~ISmaccClientBehavior ()
 
ISmaccStateMachinegetStateMachine ()
 
std::string getName () const
 
template<typename SmaccClientType >
void requiresClient (SmaccClientType *&storage)
 
template<typename SmaccComponentType >
void requiresComponent (SmaccComponentType *&storage, ComponentRequirement requirementType=ComponentRequirement::SOFT)
 

Private Attributes

CpMicroRosAgentmicroRosAgent_ = nullptr
 
double timeoutSec_
 
rclcpp::Rate rate_
 
rclcpp::Subscription< px4_msgs::msg::FailsafeFlags >::SharedPtr failsafeSub_
 
std::atomic< boolhealthOk_ {false}
 
std::atomic< boolattitudeInvalid_ {true}
 
std::atomic< boollocalAltitudeInvalid_ {true}
 
std::atomic< boollocalPositionInvalid_ {true}
 

Additional Inherited Members

- Protected Member Functions inherited from smacc2::SmaccAsyncClientBehavior
void postSuccessEvent ()
 
void postFailureEvent ()
 
virtual void dispose () override
 
bool isShutdownRequested ()
 onEntry is executed in a new thread. However the current state cannot be left until the onEntry thread finishes. This flag can be checked from the onEntry thread to force finishing the thread.
 
- Protected Member Functions inherited from smacc2::ISmaccClientBehavior
virtual void runtimeConfigure ()
 
template<typename EventType >
void postEvent (const EventType &ev)
 
template<typename EventType >
void postEvent ()
 
ISmaccStategetCurrentState ()
 
virtual rclcpp::Node::SharedPtr getNode () const
 
virtual rclcpp::Logger getLogger () const
 

Detailed Description

Definition at line 28 of file cb_connect_micro_ros_agent.hpp.

Constructor & Destructor Documentation

◆ CbConnectMicroRosAgent()

cl_px4_mr::CbConnectMicroRosAgent::CbConnectMicroRosAgent ( double timeoutSec = 30.0)

Member Function Documentation

◆ onEntry()

void cl_px4_mr::CbConnectMicroRosAgent::onEntry ( )
overridevirtual

Reimplemented from smacc2::ISmaccClientBehavior.

Definition at line 28 of file cb_connect_micro_ros_agent.cpp.

29{
31
33 {
34 RCLCPP_INFO(getLogger(), "CbConnectMicroRosAgent: launching micro_ros_agent...");
36 }
37
38 std::string targetNodeName = microRosAgent_->getNodeName();
39 RCLCPP_INFO(
40 getLogger(), "CbConnectMicroRosAgent: waiting for node '%s' (timeout %.1fs)",
41 targetNodeName.c_str(), timeoutSec_);
42
43 auto startTime = std::chrono::steady_clock::now();
44 bool found = false;
45
46 while (!this->isShutdownRequested() && !found)
47 {
48 // Check timeout
49 auto elapsed = std::chrono::steady_clock::now() - startTime;
50 double elapsedSec = std::chrono::duration<double>(elapsed).count();
51 if (elapsedSec > timeoutSec_)
52 {
53 RCLCPP_ERROR(
54 getLogger(), "CbConnectMicroRosAgent: timeout (%.1fs) waiting for '%s'", timeoutSec_,
55 targetNodeName.c_str());
56 this->postFailureEvent();
57 return;
58 }
59
60 // Poll for node
61 std::stringstream ss;
62 auto nodeNames = getNode()->get_node_names();
63
64 for (const auto & n : nodeNames)
65 {
66 ss << " - " << n << std::endl;
67
68 if (n == targetNodeName)
69 {
70 found = true;
71 }
72 }
73
74 RCLCPP_INFO_STREAM(
75 getLogger(), "[" << getName() << "] listing nodes (" << nodeNames.size() << ")" << std::endl
76 << ss.str());
77
78 rate_.sleep();
79 }
80
81 if (!found)
82 {
83 RCLCPP_WARN(getLogger(), "CbConnectMicroRosAgent: shutdown requested before node found");
84 this->postFailureEvent();
85 return;
86 }
87
88 RCLCPP_INFO(
89 getLogger(), "CbConnectMicroRosAgent: node '%s' detected - starting failsafe health check",
90 targetNodeName.c_str());
91
92 // Phase 2: Wait for PX4 failsafe health flags to clear
93 healthOk_.store(false);
94 attitudeInvalid_.store(true);
95 localAltitudeInvalid_.store(true);
96 localPositionInvalid_.store(true);
97
98 failsafeSub_ = getNode()->create_subscription<px4_msgs::msg::FailsafeFlags>(
99 "/fmu/out/failsafe_flags", rclcpp::SensorDataQoS(),
100 [this](const px4_msgs::msg::FailsafeFlags::SharedPtr msg)
101 {
102 attitudeInvalid_.store(msg->attitude_invalid);
103 localAltitudeInvalid_.store(msg->local_altitude_invalid);
104 localPositionInvalid_.store(msg->local_position_invalid);
105 healthOk_.store(
106 !msg->attitude_invalid && !msg->local_altitude_invalid && !msg->local_position_invalid);
107 });
108
109 rclcpp::Rate healthRate(2.0);
110 while (!this->isShutdownRequested() && !healthOk_.load())
111 {
112 auto elapsed = std::chrono::steady_clock::now() - startTime;
113 double elapsedSec = std::chrono::duration<double>(elapsed).count();
114 if (elapsedSec > timeoutSec_)
115 {
116 RCLCPP_ERROR(
117 getLogger(),
118 "CbConnectMicroRosAgent: timeout (%.1fs) waiting for health check. "
119 "attitude_invalid=%d, local_altitude_invalid=%d, local_position_invalid=%d",
121 localPositionInvalid_.load());
122 this->postFailureEvent();
123 return;
124 }
125
126 RCLCPP_INFO(
127 getLogger(),
128 "CbConnectMicroRosAgent: health check: attitude_invalid=%d, "
129 "local_altitude_invalid=%d, local_position_invalid=%d",
131
132 healthRate.sleep();
133 }
134
135 if (healthOk_.load())
136 {
137 RCLCPP_INFO(getLogger(), "CbConnectMicroRosAgent: health check passed - posting success");
138 this->postSuccessEvent();
139 }
140 else
141 {
142 RCLCPP_WARN(
143 getLogger(), "CbConnectMicroRosAgent: shutdown requested before health check passed");
144 this->postFailureEvent();
145 }
146}
rclcpp::Subscription< px4_msgs::msg::FailsafeFlags >::SharedPtr failsafeSub_
virtual rclcpp::Logger getLogger() const
virtual rclcpp::Node::SharedPtr getNode() const
void requiresComponent(SmaccComponentType *&storage, ComponentRequirement requirementType=ComponentRequirement::SOFT)
bool isShutdownRequested()
onEntry is executed in a new thread. However the current state cannot be left until the onEntry threa...

References attitudeInvalid_, failsafeSub_, smacc2::ISmaccClientBehavior::getLogger(), smacc2::ISmaccClientBehavior::getName(), smacc2::ISmaccClientBehavior::getNode(), cl_px4_mr::CpMicroRosAgent::getNodeName(), healthOk_, cl_px4_mr::CpMicroRosAgent::isLaunched(), smacc2::SmaccAsyncClientBehavior::isShutdownRequested(), cl_px4_mr::CpMicroRosAgent::launch(), localAltitudeInvalid_, localPositionInvalid_, microRosAgent_, smacc2::SmaccAsyncClientBehavior::postFailureEvent(), smacc2::SmaccAsyncClientBehavior::postSuccessEvent(), rate_, smacc2::ISmaccClientBehavior::requiresComponent(), and timeoutSec_.

Here is the call graph for this function:

◆ onExit()

void cl_px4_mr::CbConnectMicroRosAgent::onExit ( )
overridevirtual

Reimplemented from smacc2::ISmaccClientBehavior.

Definition at line 148 of file cb_connect_micro_ros_agent.cpp.

148{ failsafeSub_.reset(); }

References failsafeSub_.

Member Data Documentation

◆ attitudeInvalid_

std::atomic<bool> cl_px4_mr::CbConnectMicroRosAgent::attitudeInvalid_ {true}
private

Definition at line 43 of file cb_connect_micro_ros_agent.hpp.

43{true};

Referenced by onEntry().

◆ failsafeSub_

rclcpp::Subscription<px4_msgs::msg::FailsafeFlags>::SharedPtr cl_px4_mr::CbConnectMicroRosAgent::failsafeSub_
private

Definition at line 41 of file cb_connect_micro_ros_agent.hpp.

Referenced by onEntry(), and onExit().

◆ healthOk_

std::atomic<bool> cl_px4_mr::CbConnectMicroRosAgent::healthOk_ {false}
private

Definition at line 42 of file cb_connect_micro_ros_agent.hpp.

42{false};

Referenced by onEntry().

◆ localAltitudeInvalid_

std::atomic<bool> cl_px4_mr::CbConnectMicroRosAgent::localAltitudeInvalid_ {true}
private

Definition at line 44 of file cb_connect_micro_ros_agent.hpp.

44{true};

Referenced by onEntry().

◆ localPositionInvalid_

std::atomic<bool> cl_px4_mr::CbConnectMicroRosAgent::localPositionInvalid_ {true}
private

Definition at line 45 of file cb_connect_micro_ros_agent.hpp.

45{true};

Referenced by onEntry().

◆ microRosAgent_

CpMicroRosAgent* cl_px4_mr::CbConnectMicroRosAgent::microRosAgent_ = nullptr
private

Definition at line 37 of file cb_connect_micro_ros_agent.hpp.

Referenced by onEntry().

◆ rate_

rclcpp::Rate cl_px4_mr::CbConnectMicroRosAgent::rate_
private

Definition at line 39 of file cb_connect_micro_ros_agent.hpp.

Referenced by onEntry().

◆ timeoutSec_

double cl_px4_mr::CbConnectMicroRosAgent::timeoutSec_
private

Definition at line 38 of file cb_connect_micro_ros_agent.hpp.

Referenced by onEntry().


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