Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

refactor(start_planner): rename pull out to start planner #108

Merged
merged 1 commit into from
Jun 7, 2023
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
12 changes: 6 additions & 6 deletions autoware_iv_external_api_adaptor/src/rtc_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -97,7 +97,7 @@ RTCController::RTCController(const rclcpp::NodeOptions & options)
avoidance_by_lc_left_ = std::make_unique<RTCModule>(this, "avoidance_by_lane_change_left");
avoidance_by_lc_right_ = std::make_unique<RTCModule>(this, "avoidance_by_lane_change_right");
goal_planner_ = std::make_unique<RTCModule>(this, "goal_planner");
pull_out_ = std::make_unique<RTCModule>(this, "pull_out");
start_planner_ = std::make_unique<RTCModule>(this, "start_planner");

rtc_status_pub_ =
create_publisher<CooperateStatusArray>("/api/external/get/rtc_status", rclcpp::QoS(1));
Expand Down Expand Up @@ -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);

Expand Down Expand Up @@ -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: {
Expand Down Expand Up @@ -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: {
Expand Down
2 changes: 1 addition & 1 deletion autoware_iv_external_api_adaptor/src/rtc_controller.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -84,7 +84,7 @@ class RTCController : public rclcpp::Node
std::unique_ptr<RTCModule> avoidance_by_lc_left_;
std::unique_ptr<RTCModule> avoidance_by_lc_right_;
std::unique_ptr<RTCModule> goal_planner_;
std::unique_ptr<RTCModule> pull_out_;
std::unique_ptr<RTCModule> start_planner_;

/* publishers */
rclcpp::Publisher<CooperateStatusArray>::SharedPtr rtc_status_pub_;
Expand Down