diff --git a/autoware_iv_external_api_adaptor/src/rtc_controller.cpp b/autoware_iv_external_api_adaptor/src/rtc_controller.cpp index 4c82692..7af3204 100644 --- a/autoware_iv_external_api_adaptor/src/rtc_controller.cpp +++ b/autoware_iv_external_api_adaptor/src/rtc_controller.cpp @@ -97,7 +97,7 @@ RTCController::RTCController(const rclcpp::NodeOptions & options) avoidance_by_lc_left_ = std::make_unique(this, "avoidance_by_lane_change_left"); avoidance_by_lc_right_ = std::make_unique(this, "avoidance_by_lane_change_right"); goal_planner_ = std::make_unique(this, "goal_planner"); - pull_out_ = std::make_unique(this, "pull_out"); + start_planner_ = std::make_unique(this, "start_planner"); rtc_status_pub_ = create_publisher("/api/external/get/rtc_status", rclcpp::QoS(1)); @@ -164,7 +164,7 @@ void RTCController::onTimer() avoidance_by_lc_left_->insertMessage(cooperate_statuses); avoidance_by_lc_right_->insertMessage(cooperate_statuses); goal_planner_->insertMessage(cooperate_statuses); - pull_out_->insertMessage(cooperate_statuses); + start_planner_->insertMessage(cooperate_statuses); insertionSortAndValidation(cooperate_statuses); @@ -218,8 +218,8 @@ void RTCController::setRTC( goal_planner_->callService(request, responses); break; } - case Module::PULL_OUT: { - pull_out_->callService(request, responses); + case Module::START_PLANNER: { + start_planner_->callService(request, responses); break; } case Module::TRAFFIC_LIGHT: { @@ -295,8 +295,8 @@ void RTCController::setRTCAutoMode( goal_planner_->callAutoModeService(auto_mode_request, auto_mode_response); break; } - case Module::PULL_OUT: { - pull_out_->callAutoModeService(auto_mode_request, auto_mode_response); + case Module::START_PLANNER: { + start_planner_->callAutoModeService(auto_mode_request, auto_mode_response); break; } case Module::TRAFFIC_LIGHT: { diff --git a/autoware_iv_external_api_adaptor/src/rtc_controller.hpp b/autoware_iv_external_api_adaptor/src/rtc_controller.hpp index 771f43c..0838570 100644 --- a/autoware_iv_external_api_adaptor/src/rtc_controller.hpp +++ b/autoware_iv_external_api_adaptor/src/rtc_controller.hpp @@ -84,7 +84,7 @@ class RTCController : public rclcpp::Node std::unique_ptr avoidance_by_lc_left_; std::unique_ptr avoidance_by_lc_right_; std::unique_ptr goal_planner_; - std::unique_ptr pull_out_; + std::unique_ptr start_planner_; /* publishers */ rclcpp::Publisher::SharedPtr rtc_status_pub_;