diff --git a/common/autoware_control_center/include/autoware_control_center/autoware_control_center.hpp b/common/autoware_control_center/include/autoware_control_center/autoware_control_center.hpp index 23ef5e55..82611897 100644 --- a/common/autoware_control_center/include/autoware_control_center/autoware_control_center.hpp +++ b/common/autoware_control_center/include/autoware_control_center/autoware_control_center.hpp @@ -174,7 +174,8 @@ class AutowareControlCenter : public rclcpp_lifecycle::LifecycleNode Filter out deregister services from list of all services in the system by type. \param[srv_list] The list of services available in the system. */ - static void filter_deregister_services(std::map> & srv_list); + static void filter_deregister_services( + std::map> & srv_list); }; } // namespace autoware_control_center diff --git a/common/autoware_control_center/src/autoware_control_center.cpp b/common/autoware_control_center/src/autoware_control_center.cpp index b24fbe30..7f08db3f 100644 --- a/common/autoware_control_center/src/autoware_control_center.cpp +++ b/common/autoware_control_center/src/autoware_control_center.cpp @@ -78,7 +78,7 @@ void AutowareControlCenter::register_node( RCLCPP_INFO(get_logger(), "register_node is called from %s", request->name_node.c_str()); std::optional node_uuid = - node_registry_.register_node(request->name_node , autoware_utils::generate_uuid()); + node_registry_.register_node(request->name_node, autoware_utils::generate_uuid()); if (node_uuid == std::nullopt) { response->uuid_node = autoware_utils::generate_default_uuid(); @@ -91,7 +91,7 @@ void AutowareControlCenter::register_node( node_status_map_.insert({request->name_node, {false, this->now(), "", un_state}}); // Create heartbeat sub rclcpp::Subscription::SharedPtr - heartbeat_node_sub = create_heartbeat_sub(request->name_node ); + heartbeat_node_sub = create_heartbeat_sub(request->name_node); heartbeat_sub_map_.insert({request->name_node, heartbeat_node_sub}); RCLCPP_INFO(get_logger(), "Subscribed to topic %s", heartbeat_node_sub->get_topic_name()); response->uuid_node = node_uuid.value(); @@ -107,7 +107,7 @@ void AutowareControlCenter::deregister_node( RCLCPP_INFO(get_logger(), "deregister_node is called from %s", request->name_node.c_str()); std::optional node_uuid = - node_registry_.deregister_node( request->name_node); + node_registry_.deregister_node(request->name_node); if (node_uuid == std::nullopt) { response->uuid_node = autoware_utils::generate_default_uuid(); @@ -122,9 +122,10 @@ void AutowareControlCenter::deregister_node( void AutowareControlCenter::startup_callback() { - // wait for N sec and + // wait for N sec and // check if some node has been registered - double time_difference = rclcpp::Duration(this->get_clock()->now() - startup_timestamp_).seconds(); + double time_difference = + rclcpp::Duration(this->get_clock()->now() - startup_timestamp_).seconds(); if (node_registry_.is_empty()) { RCLCPP_INFO(get_logger(), "Node register map is empty. Waiting for %.1f s.", time_difference); } diff --git a/common/autoware_control_center/test/test_autoware_control_center.cpp b/common/autoware_control_center/test/test_autoware_control_center.cpp index e26ae9b8..3d6d58ca 100644 --- a/common/autoware_control_center/test/test_autoware_control_center.cpp +++ b/common/autoware_control_center/test/test_autoware_control_center.cpp @@ -26,7 +26,7 @@ #include #include #include - + using std::chrono::operator""s; class AutowareControlCenterTest : public ::testing::Test diff --git a/common/test_node/src/test_pub.cpp b/common/test_node/src/test_pub.cpp index d13f66ae..b6c6b215 100644 --- a/common/test_node/src/test_pub.cpp +++ b/common/test_node/src/test_pub.cpp @@ -21,7 +21,6 @@ #include #include - /* This example creates a subclass of Node and uses std::bind() to register a * member function as a callback from the timer. */