@@ -62,7 +62,7 @@ void TrafficLightModuleManager::modifyPathVelocity(
62
62
stop_reason_array.header .stamp = path->header .stamp ;
63
63
64
64
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 );
66
66
for (const auto & scene_module : scene_modules_) {
67
67
tier4_planning_msgs::msg::StopReason stop_reason;
68
68
std::shared_ptr<TrafficLightModule> traffic_light_scene_module (
@@ -85,8 +85,8 @@ void TrafficLightModuleManager::modifyPathVelocity(
85
85
}
86
86
if (
87
87
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_ =
90
90
traffic_light_scene_module->getFirstRefStopPathPointIndex ();
91
91
if (
92
92
traffic_light_scene_module->getTrafficLightModuleState () !=
@@ -126,15 +126,14 @@ void TrafficLightModuleManager::launchNewModules(
126
126
127
127
// Use lanelet_id to unregister module when the route is changed
128
128
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)) {
131
130
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 );
135
134
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 );
138
137
}
139
138
}
140
139
}
@@ -146,33 +145,17 @@ TrafficLightModuleManager::getModuleExpiredFunction(
146
145
const auto lanelet_id_set = planning_utils::getLaneletIdSetOnPath<TrafficLight>(
147
146
path, planner_data_->route_handler_ ->getLaneletMapPtr (), planner_data_->current_odometry ->pose );
148
147
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) {
150
150
for (const auto & id : lanelet_id_set) {
151
- if (isModuleRegisteredFromRegElement (id, scene_module-> getModuleId () )) {
151
+ if (isModuleRegisteredFromExistingAssociatedModule (id)) {
152
152
return false ;
153
153
}
154
154
}
155
155
return true ;
156
156
};
157
157
}
158
158
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
-
176
159
bool TrafficLightModuleManager::isModuleRegisteredFromExistingAssociatedModule (
177
160
const lanelet::Id & id) const
178
161
{
0 commit comments