Skip to content

Commit ef90fb7

Browse files
authored
feat(behavior_velocity_traffic_light): do not overwrite unknown with past known color (#7044)
feat(behavior_velocity_traffic_light): do not overwrite UNKNOWN with past KNOWN color remove first_stop_path_point_index Revert "remove first_stop_path_point_index" This reverts commit 09bba6981c0478832d90e3c0af1212ff2b94d928. fix Signed-off-by: Mamoru Sobue <mamoru.sobue@tier4.jp>
1 parent 74da4c1 commit ef90fb7

File tree

6 files changed

+21
-38
lines changed

6 files changed

+21
-38
lines changed

planning/behavior_velocity_planner/src/node.cpp

+1
Original file line numberDiff line numberDiff line change
@@ -352,6 +352,7 @@ void BehaviorVelocityPlannerNode::onTrafficSignals(
352352
planner_data_.traffic_light_id_map_last_observed_[signal.traffic_signal_id].stamp =
353353
msg->stamp;
354354
} else {
355+
// if (1)the observation is not UNKNOWN or (2)the very first observation is UNKNOWN
355356
planner_data_.traffic_light_id_map_last_observed_[signal.traffic_signal_id] = traffic_signal;
356357
}
357358
}

planning/behavior_velocity_traffic_light_module/package.xml

+1
Original file line numberDiff line numberDiff line change
@@ -8,6 +8,7 @@
88
<maintainer email="satoshi.ota@tier4.jp">Satoshi Ota</maintainer>
99
<maintainer email="tomoya.kimura@tier4.jp">Tomoya Kimura</maintainer>
1010
<maintainer email="shumpei.wakabayashi@tier4.jp">Shumpei Wakabayashi</maintainer>
11+
<maintainer email="mamoru.sobue@tier4.jp">Mamoru Sobue</maintainer>
1112

1213
<license>Apache License 2.0</license>
1314

planning/behavior_velocity_traffic_light_module/src/manager.cpp

+12-29
Original file line numberDiff line numberDiff line change
@@ -62,7 +62,7 @@ void TrafficLightModuleManager::modifyPathVelocity(
6262
stop_reason_array.header.stamp = path->header.stamp;
6363

6464
first_stop_path_point_index_ = static_cast<int>(path->points.size() - 1);
65-
first_ref_stop_path_point_index_ = static_cast<int>(path->points.size() - 1);
65+
nearest_ref_stop_path_point_index_ = static_cast<int>(path->points.size() - 1);
6666
for (const auto & scene_module : scene_modules_) {
6767
tier4_planning_msgs::msg::StopReason stop_reason;
6868
std::shared_ptr<TrafficLightModule> traffic_light_scene_module(
@@ -85,8 +85,8 @@ void TrafficLightModuleManager::modifyPathVelocity(
8585
}
8686
if (
8787
traffic_light_scene_module->getFirstRefStopPathPointIndex() <
88-
first_ref_stop_path_point_index_) {
89-
first_ref_stop_path_point_index_ =
88+
nearest_ref_stop_path_point_index_) {
89+
nearest_ref_stop_path_point_index_ =
9090
traffic_light_scene_module->getFirstRefStopPathPointIndex();
9191
if (
9292
traffic_light_scene_module->getTrafficLightModuleState() !=
@@ -126,15 +126,14 @@ void TrafficLightModuleManager::launchNewModules(
126126

127127
// Use lanelet_id to unregister module when the route is changed
128128
const auto lane_id = traffic_light_reg_elem.second.id();
129-
const auto module_id = lane_id;
130-
if (!isModuleRegisteredFromExistingAssociatedModule(module_id)) {
129+
if (!isModuleRegisteredFromExistingAssociatedModule(lane_id)) {
131130
registerModule(std::make_shared<TrafficLightModule>(
132-
module_id, lane_id, *(traffic_light_reg_elem.first), traffic_light_reg_elem.second,
133-
planner_param_, logger_.get_child("traffic_light_module"), clock_));
134-
generateUUID(module_id);
131+
lane_id, *(traffic_light_reg_elem.first), traffic_light_reg_elem.second, planner_param_,
132+
logger_.get_child("traffic_light_module"), clock_));
133+
generateUUID(lane_id);
135134
updateRTCStatus(
136-
getUUID(module_id), true, State::WAITING_FOR_EXECUTION,
137-
std::numeric_limits<double>::lowest(), path.header.stamp);
135+
getUUID(lane_id), true, State::WAITING_FOR_EXECUTION, std::numeric_limits<double>::lowest(),
136+
path.header.stamp);
138137
}
139138
}
140139
}
@@ -146,33 +145,17 @@ TrafficLightModuleManager::getModuleExpiredFunction(
146145
const auto lanelet_id_set = planning_utils::getLaneletIdSetOnPath<TrafficLight>(
147146
path, planner_data_->route_handler_->getLaneletMapPtr(), planner_data_->current_odometry->pose);
148147

149-
return [this, lanelet_id_set](const std::shared_ptr<SceneModuleInterface> & scene_module) {
148+
return [this, lanelet_id_set](
149+
[[maybe_unused]] const std::shared_ptr<SceneModuleInterface> & scene_module) {
150150
for (const auto & id : lanelet_id_set) {
151-
if (isModuleRegisteredFromRegElement(id, scene_module->getModuleId())) {
151+
if (isModuleRegisteredFromExistingAssociatedModule(id)) {
152152
return false;
153153
}
154154
}
155155
return true;
156156
};
157157
}
158158

159-
bool TrafficLightModuleManager::isModuleRegisteredFromRegElement(
160-
const lanelet::Id & id, const size_t module_id) const
161-
{
162-
const auto lane = planner_data_->route_handler_->getLaneletMapPtr()->laneletLayer.get(id);
163-
164-
const auto registered_lane =
165-
planner_data_->route_handler_->getLaneletMapPtr()->laneletLayer.get(module_id);
166-
for (const auto & registered_element : registered_lane.regulatoryElementsAs<TrafficLight>()) {
167-
for (const auto & element : lane.regulatoryElementsAs<TrafficLight>()) {
168-
if (hasSameTrafficLight(element, registered_element)) {
169-
return true;
170-
}
171-
}
172-
}
173-
return false;
174-
}
175-
176159
bool TrafficLightModuleManager::isModuleRegisteredFromExistingAssociatedModule(
177160
const lanelet::Id & id) const
178161
{

planning/behavior_velocity_traffic_light_module/src/manager.hpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -58,7 +58,7 @@ class TrafficLightModuleManager : public SceneModuleManagerInterfaceWithRTC
5858
// Debug
5959
rclcpp::Publisher<autoware_perception_msgs::msg::TrafficSignal>::SharedPtr pub_tl_state_;
6060

61-
std::optional<int> first_ref_stop_path_point_index_;
61+
std::optional<int> nearest_ref_stop_path_point_index_;
6262
};
6363

6464
class TrafficLightModulePlugin : public PluginWrapper<TrafficLightModuleManager>

planning/behavior_velocity_traffic_light_module/src/scene.cpp

+4-5
Original file line numberDiff line numberDiff line change
@@ -162,11 +162,10 @@ bool calcStopPointAndInsertIndex(
162162
} // namespace
163163

164164
TrafficLightModule::TrafficLightModule(
165-
const int64_t module_id, const int64_t lane_id,
166-
const lanelet::TrafficLight & traffic_light_reg_elem, lanelet::ConstLanelet lane,
167-
const PlannerParam & planner_param, const rclcpp::Logger logger,
165+
const int64_t lane_id, const lanelet::TrafficLight & traffic_light_reg_elem,
166+
lanelet::ConstLanelet lane, const PlannerParam & planner_param, const rclcpp::Logger logger,
168167
const rclcpp::Clock::SharedPtr clock)
169-
: SceneModuleInterface(module_id, logger, clock),
168+
: SceneModuleInterface(lane_id, logger, clock),
170169
lane_id_(lane_id),
171170
traffic_light_reg_elem_(traffic_light_reg_elem),
172171
lane_(lane),
@@ -365,7 +364,7 @@ bool TrafficLightModule::findValidTrafficSignal(TrafficSignalStamped & valid_tra
365364
{
366365
// get traffic signal associated with the regulatory element id
367366
const auto traffic_signal_stamped_opt = planner_data_->getTrafficSignal(
368-
traffic_light_reg_elem_.id(), true /* traffic light module keeps last observation */);
367+
traffic_light_reg_elem_.id(), false /* traffic light module does not keep last observation */);
369368
if (!traffic_signal_stamped_opt) {
370369
RCLCPP_WARN_STREAM_ONCE(
371370
logger_, "the traffic signal data associated with regulatory element id "

planning/behavior_velocity_traffic_light_module/src/scene.hpp

+2-3
Original file line numberDiff line numberDiff line change
@@ -66,9 +66,8 @@ class TrafficLightModule : public SceneModuleInterface
6666

6767
public:
6868
TrafficLightModule(
69-
const int64_t module_id, const int64_t lane_id,
70-
const lanelet::TrafficLight & traffic_light_reg_elem, lanelet::ConstLanelet lane,
71-
const PlannerParam & planner_param, const rclcpp::Logger logger,
69+
const int64_t lane_id, const lanelet::TrafficLight & traffic_light_reg_elem,
70+
lanelet::ConstLanelet lane, const PlannerParam & planner_param, const rclcpp::Logger logger,
7271
const rclcpp::Clock::SharedPtr clock);
7372

7473
bool modifyPathVelocity(PathWithLaneId * path, StopReason * stop_reason) override;

0 commit comments

Comments
 (0)