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 Dec 14, 2023
1 parent 6a23e60 commit 2e78a37
Show file tree
Hide file tree
Showing 2 changed files with 22 additions and 17 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -34,21 +34,22 @@ Distributor::Distributor() : Node("distributor")
srv_stop_mode_ = create_service<autoware_adapi_v1_msgs::srv::ChangeOperationMode>(
"/api/operation_mode/change_to_stop", std::bind(&Distributor::on_change_to_stop, this, _1, _2));
srv_autonomous_mode_ = create_service<autoware_adapi_v1_msgs::srv::ChangeOperationMode>(
"/api/operation_mode/change_to_autonomous", std::bind(&Distributor::on_change_to_autonomous, this, _1, _2));
"/api/operation_mode/change_to_autonomous",
std::bind(&Distributor::on_change_to_autonomous, this, _1, _2));

// Client
cli_main_initialize_ = create_client<autoware_adapi_v1_msgs::srv::InitializeLocalization>(
"/main/api/localization/initialize");
cli_sub_initialize_ = create_client<autoware_adapi_v1_msgs::srv::InitializeLocalization>(
"/sub/api/localization/initialize");
cli_main_set_route_ = create_client<autoware_adapi_v1_msgs::srv::SetRoute>(
"/main/api/localization/initialize");
cli_sub_set_route_ = create_client<autoware_adapi_v1_msgs::srv::SetRoute>(
"/sub/api/localization/initialize");
cli_main_clear_route_ = create_client<autoware_adapi_v1_msgs::srv::ClearRoute>(
"/main/api/localization/initialize");
cli_sub_clear_route_ = create_client<autoware_adapi_v1_msgs::srv::ClearRoute>(
"/sub/api/localization/initialize");
cli_main_set_route_ =
create_client<autoware_adapi_v1_msgs::srv::SetRoute>("/main/api/localization/initialize");
cli_sub_set_route_ =
create_client<autoware_adapi_v1_msgs::srv::SetRoute>("/sub/api/localization/initialize");
cli_main_clear_route_ =
create_client<autoware_adapi_v1_msgs::srv::ClearRoute>("/main/api/localization/initialize");
cli_sub_clear_route_ =
create_client<autoware_adapi_v1_msgs::srv::ClearRoute>("/sub/api/localization/initialize");
cli_main_stop_mode_ = create_client<autoware_adapi_v1_msgs::srv::ChangeOperationMode>(
"/main/api/localization/initialize");
cli_sub_stop_mode_ = create_client<autoware_adapi_v1_msgs::srv::ChangeOperationMode>(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,12 +15,12 @@
#ifndef DISTRIBUTOR_HPP_
#define DISTRIBUTOR_HPP_

#include <autoware_adapi_v1_msgs/srv/initialize_localization.hpp>
#include <rclcpp/rclcpp.hpp>

#include <autoware_adapi_v1_msgs/srv/change_operation_mode.hpp>
#include <autoware_adapi_v1_msgs/srv/clear_route.hpp>
#include <autoware_adapi_v1_msgs/srv/initialize_localization.hpp>
#include <autoware_adapi_v1_msgs/srv/set_route.hpp>
#include <autoware_adapi_v1_msgs/srv/change_operation_mode.hpp>

#include <rclcpp/rclcpp.hpp>

namespace ad_api_distributor
{
Expand All @@ -39,16 +39,20 @@ class Distributor : public rclcpp::Node
rclcpp::Service<autoware_adapi_v1_msgs::srv::ChangeOperationMode>::SharedPtr srv_autonomous_mode_;

// Client
rclcpp::Client<autoware_adapi_v1_msgs::srv::InitializeLocalization>::SharedPtr cli_main_initialize_;
rclcpp::Client<autoware_adapi_v1_msgs::srv::InitializeLocalization>::SharedPtr cli_sub_initialize_;
rclcpp::Client<autoware_adapi_v1_msgs::srv::InitializeLocalization>::SharedPtr
cli_main_initialize_;
rclcpp::Client<autoware_adapi_v1_msgs::srv::InitializeLocalization>::SharedPtr
cli_sub_initialize_;
rclcpp::Client<autoware_adapi_v1_msgs::srv::SetRoute>::SharedPtr cli_main_set_route_;
rclcpp::Client<autoware_adapi_v1_msgs::srv::SetRoute>::SharedPtr cli_sub_set_route_;
rclcpp::Client<autoware_adapi_v1_msgs::srv::ClearRoute>::SharedPtr cli_main_clear_route_;
rclcpp::Client<autoware_adapi_v1_msgs::srv::ClearRoute>::SharedPtr cli_sub_clear_route_;
rclcpp::Client<autoware_adapi_v1_msgs::srv::ChangeOperationMode>::SharedPtr cli_main_stop_mode_;
rclcpp::Client<autoware_adapi_v1_msgs::srv::ChangeOperationMode>::SharedPtr cli_sub_stop_mode_;
rclcpp::Client<autoware_adapi_v1_msgs::srv::ChangeOperationMode>::SharedPtr cli_main_autonomous_mode_;
rclcpp::Client<autoware_adapi_v1_msgs::srv::ChangeOperationMode>::SharedPtr cli_sub_autonomous_mode_;
rclcpp::Client<autoware_adapi_v1_msgs::srv::ChangeOperationMode>::SharedPtr
cli_main_autonomous_mode_;
rclcpp::Client<autoware_adapi_v1_msgs::srv::ChangeOperationMode>::SharedPtr
cli_sub_autonomous_mode_;

// Function
void on_initialize(
Expand Down

0 comments on commit 2e78a37

Please sign in to comment.