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

fix(avoidance): reset rtc status in yield status #3798

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 @@ -199,6 +199,7 @@ class AvoidanceModule : public SceneModuleInterface

// -- for pre-processing --
void initVariables();
void initRTCStatus();
AvoidancePlanningData calcAvoidancePlanningData(DebugData & debug) const;

ObjectDataArray registered_objects_;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -540,17 +540,20 @@ AvoidanceState AvoidanceModule::updateEgoState(const AvoidancePlanningData & dat

void AvoidanceModule::updateEgoBehavior(const AvoidancePlanningData & data, ShiftedPath & path)
{
if (parameters_->disable_path_update) {
return;
}

switch (data.state) {
case AvoidanceState::NOT_AVOID: {
break;
}
case AvoidanceState::YIELD: {
insertYieldVelocity(path);
insertWaitPoint(parameters_->use_constraints_for_decel, path);
initRTCStatus();
removeAllRegisteredShiftPoints(path_shifter_);
clearWaitingApproval();
unlockNewModuleLaunch();
removeRTCStatus();
break;
}
case AvoidanceState::AVOID_PATH_NOT_READY: {
Expand Down Expand Up @@ -2816,13 +2819,14 @@ BehaviorModuleOutput AvoidanceModule::plan()
}

avoidance_data_.state = updateEgoState(data);
if (!parameters_->disable_path_update) {

// update output data
{
updateEgoBehavior(data, avoidance_path);
updateInfoMarker(avoidance_data_);
updateDebugMarker(avoidance_data_, path_shifter_, debug_data_);
}

updateInfoMarker(avoidance_data_);
updateDebugMarker(avoidance_data_, path_shifter_, debug_data_);

output.path = std::make_shared<PathWithLaneId>(avoidance_path.path);
output.reference_path = getPreviousModuleOutput().reference_path;
path_reference_ = getPreviousModuleOutput().reference_path;
Expand Down Expand Up @@ -3160,12 +3164,14 @@ void AvoidanceModule::updateData()
void AvoidanceModule::processOnEntry()
{
initVariables();
initRTCStatus();
waitApproval();
}

void AvoidanceModule::processOnExit()
{
initVariables();
initRTCStatus();
}

void AvoidanceModule::initVariables()
Expand All @@ -3174,8 +3180,6 @@ void AvoidanceModule::initVariables()
prev_linear_shift_path_ = ShiftedPath();
prev_reference_ = PathWithLaneId();
path_shifter_ = PathShifter{};
left_shift_array_.clear();
right_shift_array_.clear();

debug_data_ = DebugData();
debug_marker_.markers.clear();
Expand All @@ -3187,6 +3191,17 @@ void AvoidanceModule::initVariables()
is_avoidance_maneuver_starts = false;
}

void AvoidanceModule::initRTCStatus()
{
removeRTCStatus();
clearWaitingApproval();
left_shift_array_.clear();
right_shift_array_.clear();
uuid_map_.at("left") = generateUUID();
uuid_map_.at("right") = generateUUID();
candidate_uuid_ = generateUUID();
}

TurnSignalInfo AvoidanceModule::calcTurnSignalInfo(const ShiftedPath & path) const
{
const auto shift_lines = path_shifter_.getShiftLines();
Expand Down