Skip to content

Commit

Permalink
style(pre-commit): autofix
Browse files Browse the repository at this point in the history
  • Loading branch information
pre-commit-ci[bot] committed Apr 17, 2024
1 parent a2a1508 commit d834855
Show file tree
Hide file tree
Showing 4 changed files with 9 additions and 8 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -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<std::string, std::vector<std::string>> & srv_list);
static void filter_deregister_services(
std::map<std::string, std::vector<std::string>> & srv_list);
};

} // namespace autoware_control_center
Expand Down
11 changes: 6 additions & 5 deletions common/autoware_control_center/src/autoware_control_center.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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<unique_identifier_msgs::msg::UUID> 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();
Expand All @@ -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<autoware_control_center_msgs::msg::Heartbeat>::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();
Expand All @@ -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<unique_identifier_msgs::msg::UUID> 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();
Expand All @@ -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);
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,7 @@
#include <iostream>
#include <memory>
#include <string>

using std::chrono::operator""s;

class AutowareControlCenterTest : public ::testing::Test
Expand Down
1 change: 0 additions & 1 deletion common/test_node/src/test_pub.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,6 @@
#include <memory>
#include <string>


/* This example creates a subclass of Node and uses std::bind() to register a
* member function as a callback from the timer. */

Expand Down

0 comments on commit d834855

Please sign in to comment.