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

feat: wait until autonomous mode is enabled #74

Merged
merged 1 commit into from
Jul 11, 2024
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
Original file line number Diff line number Diff line change
Expand Up @@ -97,6 +97,7 @@ void AutowareAutomaticGoalSender::onOperationMode(const OperationModeState::Cons
state_ = State::STOPPED;
else if (msg->mode == OperationModeState::AUTONOMOUS && state_ == State::STARTING)
state_ = State::STARTED;
is_autonomous_mode_available_ = msg->is_autonomous_mode_available;
onOperationModeUpdated(msg);
}

Expand Down Expand Up @@ -131,7 +132,8 @@ void AutowareAutomaticGoalSender::updateAutoExecutionTimerTick()
RCLCPP_INFO_STREAM(get_logger(), goal << ": Goal set as the next. Planning in progress...");
if (callPlanToGoalIndex(cli_set_route_, current_goal_)) state_ = State::PLANNING;

} else if (state_ == State::PLANNED) { // start plan to next goal
} else if (state_ == State::PLANNED && is_autonomous_mode_available_) { // start plan to next
// goal
RCLCPP_INFO_STREAM(get_logger(), goal << ": Route has been planned. Route starting...");
if (callService<ChangeOperationMode>(cli_change_to_autonomous_)) state_ = State::STARTING;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -168,6 +168,7 @@ class AutowareAutomaticGoalSender : public rclcpp::Node
std::vector<Route> goals_list_{};
std::map<unsigned, std::pair<std::string, unsigned>> goals_achieved_{};
std::string goals_achieved_file_path_{};
bool is_autonomous_mode_available_{false};

private:
void loadParams(rclcpp::Node * node);
Expand Down
Loading