SMACC2
Loading...
Searching...
No Matches
cb_connect_micro_ros_agent.cpp
Go to the documentation of this file.
1// Copyright 2025 Robosoft Inc.
2//
3// Licensed under the Apache License, Version 2.0 (the "License");
4// you may not use this file except in compliance with the License.
5// You may obtain a copy of the License at
6//
7// http://www.apache.org/licenses/LICENSE-2.0
8//
9// Unless required by applicable law or agreed to in writing, software
10// distributed under the License is distributed on an "AS IS" BASIS,
11// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12// See the License for the specific language governing permissions and
13// limitations under the License.
14
17
18#include <chrono>
19
20namespace cl_px4_mr
21{
22
24: timeoutSec_(timeoutSec), rate_(5)
25{
26}
27
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}
147
149
150} // namespace cl_px4_mr
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...