34 RCLCPP_INFO(
getLogger(),
"CbConnectMicroRosAgent: launching micro_ros_agent...");
40 getLogger(),
"CbConnectMicroRosAgent: waiting for node '%s' (timeout %.1fs)",
43 auto startTime = std::chrono::steady_clock::now();
49 auto elapsed = std::chrono::steady_clock::now() - startTime;
50 double elapsedSec = std::chrono::duration<double>(elapsed).count();
55 targetNodeName.c_str());
62 auto nodeNames =
getNode()->get_node_names();
64 for (
const auto & n : nodeNames)
66 ss <<
" - " << n << std::endl;
68 if (n == targetNodeName)
75 getLogger(),
"[" <<
getName() <<
"] listing nodes (" << nodeNames.size() <<
")" << std::endl
83 RCLCPP_WARN(
getLogger(),
"CbConnectMicroRosAgent: shutdown requested before node found");
89 getLogger(),
"CbConnectMicroRosAgent: node '%s' detected - starting failsafe health check",
90 targetNodeName.c_str());
99 "/fmu/out/failsafe_flags", rclcpp::SensorDataQoS(),
100 [
this](
const px4_msgs::msg::FailsafeFlags::SharedPtr msg)
106 !msg->attitude_invalid && !msg->local_altitude_invalid && !msg->local_position_invalid);
109 rclcpp::Rate healthRate(2.0);
112 auto elapsed = std::chrono::steady_clock::now() - startTime;
113 double elapsedSec = std::chrono::duration<double>(elapsed).count();
118 "CbConnectMicroRosAgent: timeout (%.1fs) waiting for health check. "
119 "attitude_invalid=%d, local_altitude_invalid=%d, local_position_invalid=%d",
128 "CbConnectMicroRosAgent: health check: attitude_invalid=%d, "
129 "local_altitude_invalid=%d, local_position_invalid=%d",
137 RCLCPP_INFO(
getLogger(),
"CbConnectMicroRosAgent: health check passed - posting success");
143 getLogger(),
"CbConnectMicroRosAgent: shutdown requested before health check passed");