Skip to content

Commit

Permalink
feat(behavior_velocity): add the option to keep the last valid observ…
Browse files Browse the repository at this point in the history
…ation

Signed-off-by: Mamoru Sobue <mamoru.sobue@tier4.jp>
  • Loading branch information
soblin committed Jan 9, 2024
1 parent 618ad01 commit 70df4f4
Show file tree
Hide file tree
Showing 6 changed files with 53 additions and 32 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -1055,19 +1055,20 @@ bool CrosswalkModule::isRedSignalForPedestrians() const
crosswalk_.regulatoryElementsAs<const lanelet::TrafficLight>();

for (const auto & traffic_lights_reg_elem : traffic_lights_reg_elems) {
const auto traffic_signal_stamped =
const auto traffic_signal_stamped_opt =
planner_data_->getTrafficSignal(traffic_lights_reg_elem->id());
if (!traffic_signal_stamped) {
if (!traffic_signal_stamped_opt) {
continue;
}
const auto traffic_signal_stamped = traffic_signal_stamped_opt.value();

if (
planner_param_.traffic_light_state_timeout <
(clock_->now() - traffic_signal_stamped->stamp).seconds()) {
(clock_->now() - traffic_signal_stamped.stamp).seconds()) {
continue;
}

const auto & lights = traffic_signal_stamped->signal.elements;
const auto & lights = traffic_signal_stamped.signal.elements;
if (lights.empty()) {
continue;
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -940,12 +940,11 @@ bool IntersectionModule::modifyPathVelocity(PathWithLaneId * path, StopReason *
return true;
}

static bool isGreenSolidOn(
lanelet::ConstLanelet lane, const std::map<int, TrafficSignalStamped> & tl_infos)
bool IntersectionModule::isGreenSolidOn(lanelet::ConstLanelet lane)
{
using TrafficSignalElement = autoware_perception_msgs::msg::TrafficSignalElement;

std::optional<int> tl_id = std::nullopt;
std::optional<lanelet::Id> tl_id = std::nullopt;
for (auto && tl_reg_elem : lane.regulatoryElementsAs<lanelet::TrafficLight>()) {
tl_id = tl_reg_elem->id();
break;
Expand All @@ -954,12 +953,12 @@ static bool isGreenSolidOn(
// this lane has no traffic light
return false;
}
const auto tl_info_it = tl_infos.find(tl_id.value());
if (tl_info_it == tl_infos.end()) {
const auto tl_info_opt = planner_data_->getTrafficSignal(tl_id.value());
if (!tl_info_opt) {
// the info of this traffic light is not available
return false;
}
const auto & tl_info = tl_info_it->second;
const auto & tl_info = tl_info_opt.value();

Check notice on line 961 in planning/behavior_velocity_intersection_module/src/scene_intersection.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

✅ No longer an issue: Complex Method

isGreenSolidOn is no longer above the threshold for cyclomatic complexity. This function has many conditional statements (e.g. if, for, while), leading to lower code health. Avoid adding more conditionals and code to it without refactoring.

Check notice on line 961 in planning/behavior_velocity_intersection_module/src/scene_intersection.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

ℹ New issue: Complex Method

IntersectionModule::isGreenSolidOn has a cyclomatic complexity of 9, threshold = 9. This function has many conditional statements (e.g. if, for, while), leading to lower code health. Avoid adding more conditionals and code to it without refactoring.
for (auto && tl_light : tl_info.signal.elements) {
if (
tl_light.color == TrafficSignalElement::GREEN &&
Expand Down Expand Up @@ -1004,8 +1003,7 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail(

// at the very first time of regisTration of this module, the path may not be conflicting with the
// attention area, so update() is called to update the internal data as well as traffic light info
const auto traffic_prioritized_level =
getTrafficPrioritizedLevel(assigned_lanelet, planner_data_->traffic_light_id_map);
const auto traffic_prioritized_level = getTrafficPrioritizedLevel(assigned_lanelet);
const bool is_prioritized =
traffic_prioritized_level == TrafficPrioritizedLevel::FULLY_PRIORITIZED;
intersection_lanelets.update(is_prioritized, interpolated_path_info, footprint, baselink2front);
Expand Down Expand Up @@ -1259,8 +1257,7 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail(
// If there are any vehicles on the attention area when ego entered the intersection on green
// light, do pseudo collision detection because the vehicles are very slow and no collisions may
// be detected. check if ego vehicle entered assigned lanelet
const bool is_green_solid_on =
isGreenSolidOn(assigned_lanelet, planner_data_->traffic_light_id_map);
const bool is_green_solid_on = isGreenSolidOn(assigned_lanelet);
if (is_green_solid_on) {
if (!initial_green_light_observed_time_) {
const auto assigned_lane_begin_point = assigned_lanelet.centerline().front();
Expand Down Expand Up @@ -1413,12 +1410,11 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail(
}
}

TrafficPrioritizedLevel IntersectionModule::getTrafficPrioritizedLevel(
lanelet::ConstLanelet lane, const std::map<int, TrafficSignalStamped> & tl_infos)
TrafficPrioritizedLevel IntersectionModule::getTrafficPrioritizedLevel(lanelet::ConstLanelet lane)
{
using TrafficSignalElement = autoware_perception_msgs::msg::TrafficSignalElement;

std::optional<int> tl_id = std::nullopt;
std::optional<lanelet::Id> tl_id = std::nullopt;
for (auto && tl_reg_elem : lane.regulatoryElementsAs<lanelet::TrafficLight>()) {
tl_id = tl_reg_elem->id();
break;
Expand All @@ -1427,12 +1423,11 @@ TrafficPrioritizedLevel IntersectionModule::getTrafficPrioritizedLevel(
// this lane has no traffic light
return TrafficPrioritizedLevel::NOT_PRIORITIZED;
}
const auto tl_info_it = tl_infos.find(tl_id.value());
if (tl_info_it == tl_infos.end()) {
// the info of this traffic light is not available
const auto tl_info_opt = planner_data_->getTrafficSignal(tl_id.value());
if (!tl_info_opt) {
return TrafficPrioritizedLevel::NOT_PRIORITIZED;
}
const auto & tl_info = tl_info_it->second;
const auto & tl_info = tl_info_opt.value();
bool has_amber_signal{false};
for (auto && tl_light : tl_info.signal.elements) {
if (tl_light.color == TrafficSignalElement::AMBER) {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -631,8 +631,7 @@ class IntersectionModule : public SceneModuleInterface
* @fn
* @brief find TrafficPrioritizedLevel
*/
TrafficPrioritizedLevel getTrafficPrioritizedLevel(
lanelet::ConstLanelet lane, const std::map<int, TrafficSignalStamped> & tl_infos);
TrafficPrioritizedLevel getTrafficPrioritizedLevel(lanelet::ConstLanelet lane);

/**
* @fn
Expand Down Expand Up @@ -738,6 +737,12 @@ class IntersectionModule : public SceneModuleInterface
const std::vector<lanelet::ConstLineString3d> & lane_divisions,
const TargetObjects & target_objects);

/*
* @fn
* @brief check if associated traffic light is green
*/
bool isGreenSolidOn(lanelet::ConstLanelet lane);

/*
bool IntersectionModule::checkFrontVehicleDeceleration(
lanelet::ConstLanelets & ego_lane_with_next_lane, lanelet::ConstLanelet & closest_lanelet,
Expand Down
16 changes: 15 additions & 1 deletion planning/behavior_velocity_planner/src/node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -327,7 +327,21 @@ void BehaviorVelocityPlannerNode::onTrafficSignals(
TrafficSignalStamped traffic_signal;
traffic_signal.stamp = msg->stamp;
traffic_signal.signal = signal;
planner_data_.traffic_light_id_map[signal.traffic_signal_id] = traffic_signal;
planner_data_.traffic_light_id_map_raw_[signal.traffic_signal_id] = traffic_signal;
const bool is_unknown_observation =
std::any_of(signal.elements.begin(), signal.elements.end(), [](const auto & element) {
return element.color == autoware_perception_msgs::msg::TrafficSignalElement::UNKNOWN;
});
// if the observation is UNKNOWN and past observation is available, only update the timestamp
// and keep the body of the info
if (
is_unknown_observation &&
planner_data_.traffic_light_id_map_last_observed_.count(signal.traffic_signal_id) == 1) {
planner_data_.traffic_light_id_map_last_observed_[signal.traffic_signal_id].stamp =
msg->stamp;
} else {
planner_data_.traffic_light_id_map_last_observed_[signal.traffic_signal_id] = traffic_signal;
}
}
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -76,7 +76,10 @@ struct PlannerData
double ego_nearest_yaw_threshold;

// other internal data
std::map<int, TrafficSignalStamped> traffic_light_id_map;
// traffic_light_id_map_raw is the raw observation, while traffic_light_id_map_keep_last keeps the
// last observed infomation for UNKNOWN
std::map<lanelet::Id, TrafficSignalStamped> traffic_light_id_map_raw_;
std::map<lanelet::Id, TrafficSignalStamped> traffic_light_id_map_last_observed_;
std::optional<tier4_planning_msgs::msg::VelocityLimit> external_velocity_limit;
tier4_v2x_msgs::msg::VirtualTrafficLightStateArray::ConstSharedPtr virtual_traffic_light_states;

Expand Down Expand Up @@ -125,12 +128,15 @@ struct PlannerData
return true;
}

std::shared_ptr<TrafficSignalStamped> getTrafficSignal(const int id) const
std::optional<TrafficSignalStamped> getTrafficSignal(
const lanelet::Id id, const bool keep_last_observation = true) const
{
const auto & traffic_light_id_map =
keep_last_observation ? traffic_light_id_map_last_observed_ : traffic_light_id_map_raw_;
if (traffic_light_id_map.count(id) == 0) {
return {};
return std::nullopt;
}
return std::make_shared<TrafficSignalStamped>(traffic_light_id_map.at(id));
return std::make_optional<TrafficSignalStamped>(traffic_light_id_map.at(id));
}
};
} // namespace behavior_velocity_planner
Expand Down
8 changes: 4 additions & 4 deletions planning/behavior_velocity_traffic_light_module/src/scene.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -353,15 +353,15 @@ bool TrafficLightModule::isPassthrough(const double & signed_arc_length) const
bool TrafficLightModule::findValidTrafficSignal(TrafficSignalStamped & valid_traffic_signal) const
{
// get traffic signal associated with the regulatory element id
const auto traffic_signal_stamped = planner_data_->getTrafficSignal(traffic_light_reg_elem_.id());
if (!traffic_signal_stamped) {
const auto traffic_signal_stamped_opt =
planner_data_->getTrafficSignal(traffic_light_reg_elem_.id());
if (!traffic_signal_stamped_opt) {
RCLCPP_WARN_THROTTLE(
logger_, *clock_, 5000 /* ms */,
"the traffic signal data associated with regulatory element id is not received");
return false;
}

valid_traffic_signal = *traffic_signal_stamped;
valid_traffic_signal = traffic_signal_stamped_opt.value();
return true;
}

Expand Down

0 comments on commit 70df4f4

Please sign in to comment.