diff --git a/common/autoware_control_center/src/include/control_center_node.hpp b/common/autoware_control_center/src/include/control_center_node.hpp index 48aeea52..fe0ca278 100644 --- a/common/autoware_control_center/src/include/control_center_node.hpp +++ b/common/autoware_control_center/src/include/control_center_node.hpp @@ -29,6 +29,7 @@ #include #include #include +#include #include #include diff --git a/common/autoware_control_center/test/test_cc_heartbeat.cpp b/common/autoware_control_center/test/test_cc_heartbeat.cpp index 3ca2d75a..8a93cf87 100644 --- a/common/autoware_control_center/test/test_cc_heartbeat.cpp +++ b/common/autoware_control_center/test/test_cc_heartbeat.cpp @@ -67,13 +67,10 @@ TEST_F(ControlCenterHeartbeatTest, HeartbeatHandling) const auto [uuid, node] = test::register_node(node_name, ns); // Send a heartbeat and verify node status is updated - autoware_control_center_msgs::msg::NodeStatusActivity status_activity; - status_activity.status = autoware_control_center_msgs::msg::NodeStatusActivity::PROCESSING; - autoware_control_center_msgs::msg::NodeStatusOperational status_operational; - status_operational.status = autoware_control_center_msgs::msg::NodeStatusOperational::NORMAL; + auto hb_healthy_init = test::generate_hb_healthy(); RCLCPP_INFO(rclcpp::get_logger("test"), "Sending heartbeat"); - auto pub_hb = test::send_first_heartbeat(node, deadline_ms_, test::generate_hb_healthy()); + auto pub_hb = test::send_first_heartbeat(node, deadline_ms_, hb_healthy_init); RCLCPP_INFO(rclcpp::get_logger("test"), "Sent heartbeat"); test::send_heartbeat(node, pub_hb, test::generate_hb_healthy()); RCLCPP_INFO(rclcpp::get_logger("test"), "Sent 2nd heartbeat"); @@ -84,8 +81,8 @@ TEST_F(ControlCenterHeartbeatTest, HeartbeatHandling) autoware_control_center_msgs::msg::NodeReport report; ASSERT_TRUE(test::wait_for_node_report(node->get_fully_qualified_name(), report)); - ASSERT_EQ(report.status_activity.status, status_activity.status); - ASSERT_EQ(report.status_operational.status, status_operational.status); + ASSERT_EQ(report.status_activity.status, hb_healthy_init->status_activity.status); + ASSERT_EQ(report.status_operational.status, hb_healthy_init->status_operational.status); } TEST_F(ControlCenterHeartbeatTest, HeartbeatMissedDeadline) diff --git a/common/autoware_control_center/test/test_utility.hpp b/common/autoware_control_center/test/test_utility.hpp index aa6b279b..4ef345d7 100644 --- a/common/autoware_control_center/test/test_utility.hpp +++ b/common/autoware_control_center/test/test_utility.hpp @@ -26,6 +26,8 @@ #include #include +#include + namespace autoware::control_center::test {