@@ -97,7 +97,7 @@ RTCController::RTCController(const rclcpp::NodeOptions & options)
97
97
avoidance_by_lc_left_ = std::make_unique<RTCModule>(this , " avoidance_by_lane_change_left" );
98
98
avoidance_by_lc_right_ = std::make_unique<RTCModule>(this , " avoidance_by_lane_change_right" );
99
99
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 " );
101
101
102
102
rtc_status_pub_ =
103
103
create_publisher<CooperateStatusArray>(" /api/external/get/rtc_status" , rclcpp::QoS (1 ));
@@ -164,7 +164,7 @@ void RTCController::onTimer()
164
164
avoidance_by_lc_left_->insertMessage (cooperate_statuses);
165
165
avoidance_by_lc_right_->insertMessage (cooperate_statuses);
166
166
goal_planner_->insertMessage (cooperate_statuses);
167
- pull_out_ ->insertMessage (cooperate_statuses);
167
+ start_planner_ ->insertMessage (cooperate_statuses);
168
168
169
169
insertionSortAndValidation (cooperate_statuses);
170
170
@@ -218,8 +218,8 @@ void RTCController::setRTC(
218
218
goal_planner_->callService (request, responses);
219
219
break ;
220
220
}
221
- case Module::PULL_OUT : {
222
- pull_out_ ->callService (request, responses);
221
+ case Module::START_PLANNER : {
222
+ start_planner_ ->callService (request, responses);
223
223
break ;
224
224
}
225
225
case Module::TRAFFIC_LIGHT: {
@@ -295,8 +295,8 @@ void RTCController::setRTCAutoMode(
295
295
goal_planner_->callAutoModeService (auto_mode_request, auto_mode_response);
296
296
break ;
297
297
}
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);
300
300
break ;
301
301
}
302
302
case Module::TRAFFIC_LIGHT: {
0 commit comments