Skip to content

Commit a58468e

Browse files
authored
refactor(start_planner): rename pull out to start planner (#108)
Signed-off-by: kosuke55 <kosuke.tnp@gmail.com>
1 parent 65fba62 commit a58468e

File tree

2 files changed

+7
-7
lines changed

2 files changed

+7
-7
lines changed

autoware_iv_external_api_adaptor/src/rtc_controller.cpp

+6-6
Original file line numberDiff line numberDiff line change
@@ -97,7 +97,7 @@ RTCController::RTCController(const rclcpp::NodeOptions & options)
9797
avoidance_by_lc_left_ = std::make_unique<RTCModule>(this, "avoidance_by_lane_change_left");
9898
avoidance_by_lc_right_ = std::make_unique<RTCModule>(this, "avoidance_by_lane_change_right");
9999
goal_planner_ = std::make_unique<RTCModule>(this, "goal_planner");
100-
pull_out_ = std::make_unique<RTCModule>(this, "pull_out");
100+
start_planner_ = std::make_unique<RTCModule>(this, "start_planner");
101101

102102
rtc_status_pub_ =
103103
create_publisher<CooperateStatusArray>("/api/external/get/rtc_status", rclcpp::QoS(1));
@@ -164,7 +164,7 @@ void RTCController::onTimer()
164164
avoidance_by_lc_left_->insertMessage(cooperate_statuses);
165165
avoidance_by_lc_right_->insertMessage(cooperate_statuses);
166166
goal_planner_->insertMessage(cooperate_statuses);
167-
pull_out_->insertMessage(cooperate_statuses);
167+
start_planner_->insertMessage(cooperate_statuses);
168168

169169
insertionSortAndValidation(cooperate_statuses);
170170

@@ -218,8 +218,8 @@ void RTCController::setRTC(
218218
goal_planner_->callService(request, responses);
219219
break;
220220
}
221-
case Module::PULL_OUT: {
222-
pull_out_->callService(request, responses);
221+
case Module::START_PLANNER: {
222+
start_planner_->callService(request, responses);
223223
break;
224224
}
225225
case Module::TRAFFIC_LIGHT: {
@@ -295,8 +295,8 @@ void RTCController::setRTCAutoMode(
295295
goal_planner_->callAutoModeService(auto_mode_request, auto_mode_response);
296296
break;
297297
}
298-
case Module::PULL_OUT: {
299-
pull_out_->callAutoModeService(auto_mode_request, auto_mode_response);
298+
case Module::START_PLANNER: {
299+
start_planner_->callAutoModeService(auto_mode_request, auto_mode_response);
300300
break;
301301
}
302302
case Module::TRAFFIC_LIGHT: {

autoware_iv_external_api_adaptor/src/rtc_controller.hpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -84,7 +84,7 @@ class RTCController : public rclcpp::Node
8484
std::unique_ptr<RTCModule> avoidance_by_lc_left_;
8585
std::unique_ptr<RTCModule> avoidance_by_lc_right_;
8686
std::unique_ptr<RTCModule> goal_planner_;
87-
std::unique_ptr<RTCModule> pull_out_;
87+
std::unique_ptr<RTCModule> start_planner_;
8888

8989
/* publishers */
9090
rclcpp::Publisher<CooperateStatusArray>::SharedPtr rtc_status_pub_;

0 commit comments

Comments
 (0)