Skip to content

Commit

Permalink
feat(dynamic_avoidance): suppress flickering of dynamic avoidance lau…
Browse files Browse the repository at this point in the history
…nching (autowarefoundation#4048)

* feat(dynamic_avoidance): suppress flickering of dynamic avoidance launching

Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com>

* update config

Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com>

---------

Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com>
  • Loading branch information
takayuki5168 committed Jun 23, 2023
1 parent 64b2caf commit 8227c22
Show file tree
Hide file tree
Showing 5 changed files with 63 additions and 11 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -12,21 +12,23 @@
motorcycle: true
pedestrian: false

min_obstacle_vel: 1.0 # [m/s]
min_obstacle_vel: 0.0 # [m/s]

successive_num_to_entry_dynamic_avoidance_condition: 5

drivable_area_generation:
lat_offset_from_obstacle: 1.3 # [m]
lat_offset_from_obstacle: 0.8 # [m]
max_lat_offset_to_avoid: 0.5 # [m]

# for same directional object
overtaking_object:
max_time_to_collision: 3.0 # [s]
start_duration_to_avoid: 4.0 # [s]
end_duration_to_avoid: 5.0 # [s]
end_duration_to_avoid: 8.0 # [s]
duration_to_hold_avoidance: 3.0 # [s]

# for opposite directional object
oncoming_object:
max_time_to_collision: 3.0 # [s]
start_duration_to_avoid: 9.0 # [s]
start_duration_to_avoid: 12.0 # [s]
end_duration_to_avoid: 0.0 # [s]
Original file line number Diff line number Diff line change
Expand Up @@ -47,6 +47,7 @@ struct DynamicAvoidanceParameters
bool avoid_motorcycle{false};
bool avoid_pedestrian{false};
double min_obstacle_vel{0.0};
int successive_num_to_entry_dynamic_avoidance_condition{0};

// drivable area generation
double lat_offset_from_obstacle{0.0};
Expand Down Expand Up @@ -87,6 +88,24 @@ class DynamicAvoidanceModule : public SceneModuleInterface

bool is_left;
};
struct DynamicAvoidanceObjectCandidate
{
DynamicAvoidanceObject object;
int alive_counter;

static std::optional<DynamicAvoidanceObjectCandidate> getObjectFromUuid(
const std::vector<DynamicAvoidanceObjectCandidate> & objects, const std::string & target_uuid)
{
const auto itr = std::find_if(objects.begin(), objects.end(), [&](const auto & object) {
return object.object.uuid == target_uuid;
});

if (itr == objects.end()) {
return std::nullopt;
}
return *itr;
}
};

#ifdef USE_OLD_ARCHITECTURE
DynamicAvoidanceModule(
Expand Down Expand Up @@ -119,12 +138,14 @@ class DynamicAvoidanceModule : public SceneModuleInterface

private:
bool isLabelTargetObstacle(const uint8_t label) const;
std::vector<DynamicAvoidanceObject> calcTargetObjects() const;
std::vector<DynamicAvoidanceObjectCandidate> calcTargetObjectsCandidate() const;
std::pair<lanelet::ConstLanelets, lanelet::ConstLanelets> getAdjacentLanes(
const double forward_distance, const double backward_distance) const;
std::optional<tier4_autoware_utils::Polygon2d> calcDynamicObstaclePolygon(
const DynamicAvoidanceObject & object) const;

std::vector<DynamicAvoidanceModule::DynamicAvoidanceObjectCandidate>
prev_target_objects_candidate_;
std::vector<DynamicAvoidanceModule::DynamicAvoidanceObject> target_objects_;
// std::vector<DynamicAvoidanceModule::DynamicAvoidanceObject> prev_target_objects_;
std::shared_ptr<DynamicAvoidanceParameters> parameters_;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -721,6 +721,8 @@ DynamicAvoidanceParameters BehaviorPathPlannerNode::getDynamicAvoidanceParam()
p.avoid_motorcycle = declare_parameter<bool>(ns + "motorcycle");
p.avoid_pedestrian = declare_parameter<bool>(ns + "pedestrian");
p.min_obstacle_vel = declare_parameter<double>(ns + "min_obstacle_vel");
p.successive_num_to_entry_dynamic_avoidance_condition =
declare_parameter<int>(ns + "successive_num_to_entry_dynamic_avoidance_condition");
}

{ // drivable_area_generation
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -192,7 +192,19 @@ bool DynamicAvoidanceModule::isExecutionReady() const

void DynamicAvoidanceModule::updateData()
{
target_objects_ = calcTargetObjects();
// calculate target objects candidate
const auto target_objects_candidate = calcTargetObjectsCandidate();
prev_target_objects_candidate_ = target_objects_candidate;

// calculate target objects considering flickering suppress
target_objects_.clear();
for (const auto & target_object_candidate : target_objects_candidate) {
if (
parameters_->successive_num_to_entry_dynamic_avoidance_condition <=
target_object_candidate.alive_counter) {
target_objects_.push_back(target_object_candidate.object);
}
}
}

ModuleStatus DynamicAvoidanceModule::updateState()
Expand Down Expand Up @@ -295,8 +307,8 @@ bool DynamicAvoidanceModule::isLabelTargetObstacle(const uint8_t label) const
return false;
}

std::vector<DynamicAvoidanceModule::DynamicAvoidanceObject>
DynamicAvoidanceModule::calcTargetObjects() const
std::vector<DynamicAvoidanceModule::DynamicAvoidanceObjectCandidate>
DynamicAvoidanceModule::calcTargetObjectsCandidate() const
{
const auto prev_module_path = getPreviousModuleOutput().path;
const auto & predicted_objects = planner_data_->dynamic_object->objects;
Expand Down Expand Up @@ -331,7 +343,7 @@ DynamicAvoidanceModule::calcTargetObjects() const
// 4. check if object will cut into the ego lane.
// NOTE: The oncoming object will be ignored.
constexpr double epsilon_path_lat_diff = 0.3;
std::vector<DynamicAvoidanceObject> output_objects;
std::vector<DynamicAvoidanceObjectCandidate> output_objects_candidate;
for (const bool is_left : {true, false}) {
for (const auto & object : (is_left ? objects_in_left_lanes : objects_in_right_lanes)) {
const auto reliable_predicted_path = std::max_element(
Expand Down Expand Up @@ -360,13 +372,24 @@ DynamicAvoidanceModule::calcTargetObjects() const
continue;
}

// get previous object if it exists
const auto prev_target_object_candidate = DynamicAvoidanceObjectCandidate::getObjectFromUuid(
prev_target_objects_candidate_, object.uuid);
const int alive_counter =
prev_target_object_candidate
? std::min(
parameters_->successive_num_to_entry_dynamic_avoidance_condition,
prev_target_object_candidate->alive_counter + 1)
: 0;

auto target_object = object;
target_object.is_left = is_left;
output_objects.push_back(target_object);
output_objects_candidate.push_back(
DynamicAvoidanceObjectCandidate{target_object, alive_counter});
}
}

return output_objects;
return output_objects_candidate;
}

std::pair<lanelet::ConstLanelets, lanelet::ConstLanelets> DynamicAvoidanceModule::getAdjacentLanes(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -49,6 +49,10 @@ void DynamicAvoidanceModuleManager::updateModuleParams(
updateParam<bool>(parameters, ns + "pedestrian", p->avoid_pedestrian);

updateParam<double>(parameters, ns + "min_obstacle_vel", p->min_obstacle_vel);

updateParam<int>(
parameters, ns + "successive_num_to_entry_dynamic_avoidance_condition",
p->successive_num_to_entry_dynamic_avoidance_condition);
}

{ // drivable_area_generation
Expand Down

0 comments on commit 8227c22

Please sign in to comment.