Skip to content

Commit

Permalink
tests
Browse files Browse the repository at this point in the history
Signed-off-by: M. Fatih Cırıt <[email protected]>
  • Loading branch information
M. Fatih Cırıt committed May 23, 2024
1 parent 8a9d6ee commit b832706
Show file tree
Hide file tree
Showing 6 changed files with 118 additions and 95 deletions.
27 changes: 17 additions & 10 deletions common/autoware_control_center/src/control_center_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -72,6 +72,16 @@ ControlCenter::register_node(const std::string & node_name)
node_info->uuid = autoware_utils::generate_uuid();
node_info->time_registered = rclcpp::Clock().now();
node_info->count_registered++;
node_info->is_alive = true;

auto init_heartbeat = std::make_shared<autoware_control_center_msgs::msg::Heartbeat>();
init_heartbeat->status.operational_status =
autoware_control_center_msgs::msg::NodeStatus::OPERATIONAL_WARNING;
init_heartbeat->status.activity_status =
autoware_control_center_msgs::msg::NodeStatus::ACTIVITY_INITIALIZING;
init_heartbeat->stamp = rclcpp::Clock().now();

node_info->last_heartbeat = init_heartbeat;
node_name_to_uuid_[node_name] = node_info->uuid;
uuid_to_info_[node_info->uuid.uuid] = node_info;

Expand Down Expand Up @@ -164,31 +174,28 @@ void ControlCenter::on_deadline_missed(
return;
}

const auto node_name = uuid_to_info_.at(uuid.uuid)->name;
const auto node_info = uuid_to_info_.at(uuid.uuid);
node_info->is_alive = false;
const auto node_name = node_info->name;
RCLCPP_WARN(
this->get_logger(), "Deadline missed for node %s: total_count=%d, total_count_change=%d",
node_name.c_str(), event.total_count, event.total_count_change);
deregister_node(uuid);
}

void ControlCenter::publish_node_reports()
{
RCLCPP_INFO(this->get_logger(), "Publishing node reports");
NodeReports node_reports_msg;
node_reports_msg.stamp = rclcpp::Clock().now();
node_reports_msg.reports.reserve(uuid_to_info_.size());
for (const auto & entry : uuid_to_info_) {
const auto & node_info = entry.second;
NodeReport report;
report.uuid = node_info->uuid;
report.name = node_info->name;
if (node_info->last_heartbeat) {
report.last_heartbeat.status = node_info->last_heartbeat->status;
} else {
report.last_heartbeat.status.activity_status =
autoware_control_center_msgs::msg::NodeStatus::ACTIVITY_UNKNOWN;
report.last_heartbeat.status.operational_status =
autoware_control_center_msgs::msg::NodeStatus::OPERATIONAL_UNKNOWN;
}
report.count_registered = node_info->count_registered;
report.is_alive = node_info->is_alive;
report.last_heartbeat = *node_info->last_heartbeat;
node_reports_msg.reports.emplace_back(report);
}
pub_reports_->publish(node_reports_msg);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -50,6 +50,7 @@ class ControlCenter : public rclcpp_lifecycle::LifecycleNode
rclcpp::Time time_registered;
autoware_control_center_msgs::msg::Heartbeat::ConstSharedPtr last_heartbeat;
int count_registered;
bool is_alive;
rclcpp::Subscription<autoware_control_center_msgs::msg::Heartbeat>::SharedPtr heartbeat_sub;
};

Expand Down
184 changes: 99 additions & 85 deletions common/autoware_control_center/test/test_cc_registering.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,7 @@ class ControlCenterRegisteringTest : public ::testing::Test
{
rclcpp::init(0, nullptr);
node_options_.append_parameter_override("deadline_ms", 220.0);
node_options_.append_parameter_override("report_publish_rate", 1.0);
node_options_.append_parameter_override("report_publish_rate", 100.0);
executor_ = std::make_shared<rclcpp::executors::SingleThreadedExecutor>();

control_center_ = std::make_shared<autoware::control_center::ControlCenter>(node_options_);
Expand All @@ -50,54 +50,6 @@ class ControlCenterRegisteringTest : public ::testing::Test
}
}

// autoware_control_center_msgs::srv::Register::Response::ConstSharedPtr register_node(const
// std::string & node_name)
// {
// // create dummy node
// auto test_node = std::make_shared<rclcpp::Node>(node_name);
//
// auto client = test_node->create_client<autoware_control_center_msgs::srv::Register>(
// "/autoware/control_center/srv/register");
// auto request = std::make_shared<autoware_control_center_msgs::srv::Register::Request>();
// request->node_name_with_namespace = node_name;
//
// if (!client->wait_for_service(std::chrono::seconds(5))) {
// RCLCPP_ERROR(rclcpp::get_logger("test"), "Register service not available");
// return false;
// }
//
// auto result = client->async_send_request(request);
// if (result.wait_for(std::chrono::seconds(5)) == std::future_status::timeout) {
// RCLCPP_ERROR(rclcpp::get_logger("test"), "Failed to call register service");
// return false;
// }
//
// return result.get();
// }

// bool deregister_node(const unique_identifier_msgs::msg::UUID & uuid)
// {
// auto client = control_center_->create_client<autoware_control_center_msgs::srv::Deregister>(
// "/autoware/control_center/srv/deregister");
//
// auto request = std::make_shared<autoware_control_center_msgs::srv::Deregister::Request>();
// request->uuid_node = uuid;
//
// if (!client->wait_for_service(std::chrono::seconds(5))) {
// RCLCPP_ERROR(rclcpp::get_logger("test"), "Deregister service not available");
// return false;
// }
//
// auto result = client->async_send_request(request);
// if (result.wait_for(std::chrono::seconds(5)) == std::future_status::timeout) {
// RCLCPP_ERROR(rclcpp::get_logger("test"), "Failed to call deregister service");
// return false;
// }
//
// return result.get()->result_service.result ==
// autoware_control_center_msgs::msg::ResultService::SUCCESS;
// }

rclcpp::NodeOptions node_options_;
std::shared_ptr<rclcpp::executors::SingleThreadedExecutor> executor_;
ControlCenter::SharedPtr control_center_;
Expand Down Expand Up @@ -139,11 +91,12 @@ TEST_F(ControlCenterRegisteringTest, NodeRegistration)
// Make sure node is registered by subscribing to the node reports
std::promise<void> report_received;
auto future_report = report_received.get_future();
autoware_control_center_msgs::msg::NodeReport report;

auto node_reports_sub =
test_node->create_subscription<autoware_control_center_msgs::msg::NodeReports>(
"/autoware/control_center/node_reports", 10,
[&report_received,
[&report_received, &report,
node_name](const autoware_control_center_msgs::msg::NodeReports::SharedPtr msg) {
RCLCPP_INFO(rclcpp::get_logger("test"), "Received node reports");
for (const auto & node_report : msg->reports) {
Expand All @@ -152,6 +105,7 @@ TEST_F(ControlCenterRegisteringTest, NodeRegistration)
autoware_utils::to_hex_string(node_report.uuid).c_str());

if (node_report.name == node_name) {
report = node_report;
report_received.set_value();
return;
}
Expand All @@ -162,43 +116,103 @@ TEST_F(ControlCenterRegisteringTest, NodeRegistration)
rclcpp::spin_until_future_complete(test_node, future_report, std::chrono::seconds(5)),
rclcpp::FutureReturnCode::SUCCESS)
<< "Node report not received";
ASSERT_EQ(report.count_registered, 1);
ASSERT_TRUE(report.is_alive);
ASSERT_EQ(
report.last_heartbeat.status.operational_status,
autoware_control_center_msgs::msg::NodeStatus::OPERATIONAL_WARNING);
ASSERT_EQ(
report.last_heartbeat.status.activity_status,
autoware_control_center_msgs::msg::NodeStatus::ACTIVITY_INITIALIZING);
}

// TEST_F(ControlCenterRegisteringTest, NodeDuplicateRegistration)
//{
// ASSERT_TRUE(register_node("node_2"));
//
// auto uuid1 = control_center_->get_uuid("node_2");
//
// ASSERT_TRUE(register_node("node_2"));
//
// auto uuid2 = control_center_->get_uuid("node_2");
//
// ASSERT_TRUE(control_center_->is_registered(uuid2));
// ASSERT_TRUE(control_center_->is_registered("node_2"));
// ASSERT_FALSE(control_center_->is_registered(uuid1)); // old UUID should no longer be
// registered
// }
//
// TEST_F(ControlCenterRegisteringTest, NodeDeregistration)
//{
// ASSERT_TRUE(register_node("node_3"));
//
// auto uuid = control_center_->get_uuid("node_3");
//
// ASSERT_TRUE(deregister_node(uuid));
//
// ASSERT_FALSE(control_center_->is_registered(uuid));
// ASSERT_FALSE(control_center_->is_registered("node_3"));
// }
//
// TEST_F(ControlCenterRegisteringTest, DeregisterNonExistentNode)
//{
// unique_identifier_msgs::msg::UUID uuid;
// std::fill(uuid.uuid.begin(), uuid.uuid.end(), 0);
//
// ASSERT_FALSE(deregister_node(uuid));
// }
TEST_F(ControlCenterRegisteringTest, NodeDuplicateRegistration)
{
const std::string node_name = "node_test_duplicate";
auto test_node = std::make_shared<rclcpp::Node>(node_name);

auto client = test_node->create_client<autoware_control_center_msgs::srv::Register>(
"/autoware/control_center/srv/register");
auto request = std::make_shared<autoware_control_center_msgs::srv::Register::Request>();
request->node_name_with_namespace = node_name;

ASSERT_TRUE(client->wait_for_service(std::chrono::seconds(5)))
<< "Service initialization timeout";

// First registration
auto fut_result1 = client->async_send_request(request);
ASSERT_EQ(
rclcpp::spin_until_future_complete(test_node, fut_result1, std::chrono::seconds(5)),
rclcpp::FutureReturnCode::SUCCESS)
<< "Service call timeout or failed";

auto result1 = fut_result1.get();
ASSERT_EQ(
result1->result_service.result, autoware_control_center_msgs::msg::ResultService::SUCCESS);
ASSERT_EQ(
result1->result_registration.result,
autoware_control_center_msgs::msg::ResultRegistration::SUCCESS);
auto uuid1 = result1->uuid_node;

// Duplicate registration
auto fut_result2 = client->async_send_request(request);
ASSERT_EQ(
rclcpp::spin_until_future_complete(test_node, fut_result2, std::chrono::seconds(5)),
rclcpp::FutureReturnCode::SUCCESS)
<< "Service call timeout or failed";

auto result2 = fut_result2.get();
ASSERT_EQ(
result2->result_service.result, autoware_control_center_msgs::msg::ResultService::SUCCESS);
ASSERT_EQ(
result2->result_registration.result,
autoware_control_center_msgs::msg::ResultRegistration::SUCCESS);
auto uuid2 = result2->uuid_node;

// Ensure the UUID has changed
ASSERT_NE(uuid1, uuid2);

// Ensure the registration count incremented by subscribing to node reports
std::promise<void> report_received;
auto future_report = report_received.get_future();
autoware_control_center_msgs::msg::NodeReport report;

auto node_reports_sub =
test_node->create_subscription<autoware_control_center_msgs::msg::NodeReports>(
"/autoware/control_center/node_reports", 10,
[&report_received, &report,
node_name](const autoware_control_center_msgs::msg::NodeReports::SharedPtr msg) {
for (const auto & node_report : msg->reports) {
if (node_report.name == node_name) {
report = node_report;
report_received.set_value();
return;
}
}
});

ASSERT_EQ(
rclcpp::spin_until_future_complete(test_node, future_report, std::chrono::seconds(5)),
rclcpp::FutureReturnCode::SUCCESS)
<< "Node report not received";

ASSERT_EQ(report.count_registered, 2);
ASSERT_TRUE(report.is_alive);
ASSERT_EQ(
report.last_heartbeat.status.operational_status,
autoware_control_center_msgs::msg::NodeStatus::OPERATIONAL_WARNING);
ASSERT_EQ(
report.last_heartbeat.status.activity_status,
autoware_control_center_msgs::msg::NodeStatus::ACTIVITY_INITIALIZING);
}

TEST_F(ControlCenterRegisteringTest, NodeDeregistration)
{
}

TEST_F(ControlCenterRegisteringTest, DeregisterNonExistentNode)
{
}

int main(int argc, char ** argv)
{
Expand Down
1 change: 1 addition & 0 deletions common/autoware_control_center_msgs/msg/NodeReport.msg
Original file line number Diff line number Diff line change
Expand Up @@ -5,3 +5,4 @@ string name
unique_identifier_msgs/UUID uuid
autoware_control_center_msgs/Heartbeat last_heartbeat
bool is_alive
uint16 count_registered
Empty file.
Empty file.

0 comments on commit b832706

Please sign in to comment.