29{
31
33 {
34 RCLCPP_INFO(
getLogger(),
"CbConnectMicroRosAgent: launching micro_ros_agent...");
36 }
37
39 RCLCPP_INFO(
40 getLogger(),
"CbConnectMicroRosAgent: waiting for node '%s' (timeout %.1fs)",
42
43 auto startTime = std::chrono::steady_clock::now();
44 bool found = false;
45
47 {
48
49 auto elapsed = std::chrono::steady_clock::now() - startTime;
50 double elapsedSec = std::chrono::duration<double>(elapsed).count();
52 {
53 RCLCPP_ERROR(
55 targetNodeName.c_str());
57 return;
58 }
59
60
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
79 }
80
81 if (!found)
82 {
83 RCLCPP_WARN(
getLogger(),
"CbConnectMicroRosAgent: shutdown requested before node found");
85 return;
86 }
87
88 RCLCPP_INFO(
89 getLogger(),
"CbConnectMicroRosAgent: node '%s' detected - starting failsafe health check",
90 targetNodeName.c_str());
91
92
97
99 "/fmu/out/failsafe_flags", rclcpp::SensorDataQoS(),
100 [this](const px4_msgs::msg::FailsafeFlags::SharedPtr msg)
101 {
106 !msg->attitude_invalid && !msg->local_altitude_invalid && !msg->local_position_invalid);
107 });
108
109 rclcpp::Rate healthRate(2.0);
111 {
112 auto elapsed = std::chrono::steady_clock::now() - startTime;
113 double elapsedSec = std::chrono::duration<double>(elapsed).count();
115 {
116 RCLCPP_ERROR(
118 "CbConnectMicroRosAgent: timeout (%.1fs) waiting for health check. "
119 "attitude_invalid=%d, local_altitude_invalid=%d, local_position_invalid=%d",
123 return;
124 }
125
126 RCLCPP_INFO(
128 "CbConnectMicroRosAgent: health check: attitude_invalid=%d, "
129 "local_altitude_invalid=%d, local_position_invalid=%d",
131
132 healthRate.sleep();
133 }
134
136 {
137 RCLCPP_INFO(
getLogger(),
"CbConnectMicroRosAgent: health check passed - posting success");
139 }
140 else
141 {
142 RCLCPP_WARN(
143 getLogger(),
"CbConnectMicroRosAgent: shutdown requested before health check passed");
145 }
146}
std::atomic< bool > localAltitudeInvalid_
std::atomic< bool > localPositionInvalid_
CpMicroRosAgent * microRosAgent_
rclcpp::Subscription< px4_msgs::msg::FailsafeFlags >::SharedPtr failsafeSub_
std::atomic< bool > healthOk_
std::atomic< bool > attitudeInvalid_
std::string getNodeName() const
std::string getName() const
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...