@@ -788,6 +788,8 @@ MapBasedPredictionNode::MapBasedPredictionNode(const rclcpp::NodeOptions & node_
788
788
acceleration_exponential_half_life_ =
789
789
declare_parameter<double >(" acceleration_exponential_half_life" );
790
790
791
+ use_crosswalk_signal_ = declare_parameter<bool >(" use_crosswalk_signal" );
792
+
791
793
path_generator_ = std::make_shared<PathGenerator>(
792
794
prediction_time_horizon_, lateral_control_time_horizon_, prediction_sampling_time_interval_,
793
795
min_crosswalk_user_velocity_);
@@ -801,6 +803,9 @@ MapBasedPredictionNode::MapBasedPredictionNode(const rclcpp::NodeOptions & node_
801
803
sub_map_ = this ->create_subscription <HADMapBin>(
802
804
" /vector_map" , rclcpp::QoS{1 }.transient_local (),
803
805
std::bind (&MapBasedPredictionNode::mapCallback, this , std::placeholders::_1));
806
+ sub_traffic_signals_ = this ->create_subscription <TrafficSignalArray>(
807
+ " /traffic_signals" , 1 ,
808
+ std::bind (&MapBasedPredictionNode::trafficSignalsCallback, this , std::placeholders::_1));
804
809
805
810
pub_objects_ = this ->create_publisher <PredictedObjects>(" ~/output/objects" , rclcpp::QoS{1 });
806
811
pub_debug_markers_ =
@@ -872,6 +877,14 @@ void MapBasedPredictionNode::mapCallback(const HADMapBin::ConstSharedPtr msg)
872
877
crosswalks_.insert (crosswalks_.end (), walkways.begin (), walkways.end ());
873
878
}
874
879
880
+ void MapBasedPredictionNode::trafficSignalsCallback (const TrafficSignalArray::ConstSharedPtr msg)
881
+ {
882
+ traffic_signal_id_map_.clear ();
883
+ for (const auto & signal : msg->signals ) {
884
+ traffic_signal_id_map_[signal .traffic_signal_id ] = signal ;
885
+ }
886
+ }
887
+
875
888
void MapBasedPredictionNode::objectsCallback (const TrackedObjects::ConstSharedPtr in_objects)
876
889
{
877
890
stop_watch_.tic ();
@@ -1218,6 +1231,18 @@ PredictedObject MapBasedPredictionNode::getPredictedObjectAsCrosswalkUser(
1218
1231
}
1219
1232
// try to find the edge points for all crosswalks and generate path to the crosswalk edge
1220
1233
for (const auto & crosswalk : crosswalks_) {
1234
+ const auto crosswalk_signal_id_opt = getTrafficSignalId (crosswalk);
1235
+ if (crosswalk_signal_id_opt.has_value () && use_crosswalk_signal_) {
1236
+ const auto signal_color = [&] {
1237
+ const auto elem_opt = getTrafficSignalElement (crosswalk_signal_id_opt.value ());
1238
+ return elem_opt ? elem_opt.value ().color : TrafficSignalElement::UNKNOWN;
1239
+ }();
1240
+
1241
+ if (signal_color == TrafficSignalElement::RED) {
1242
+ continue ;
1243
+ }
1244
+ }
1245
+
1221
1246
const auto edge_points = getCrosswalkEdgePoints (crosswalk);
1222
1247
1223
1248
const auto reachable_first = hasPotentialToReach (
@@ -2211,6 +2236,38 @@ bool MapBasedPredictionNode::isDuplicated(
2211
2236
2212
2237
return false ;
2213
2238
}
2239
+
2240
+ std::optional<lanelet::Id> MapBasedPredictionNode::getTrafficSignalId (
2241
+ const lanelet::ConstLanelet & way_lanelet)
2242
+ {
2243
+ const auto traffic_light_reg_elems =
2244
+ way_lanelet.regulatoryElementsAs <const lanelet::TrafficLight>();
2245
+ if (traffic_light_reg_elems.empty ()) {
2246
+ return std::nullopt;
2247
+ } else if (traffic_light_reg_elems.size () > 1 ) {
2248
+ RCLCPP_ERROR (
2249
+ get_logger (),
2250
+ " [Map Based Prediction]: "
2251
+ " Multiple regulatory elements as TrafficLight are defined to one lanelet object." );
2252
+ }
2253
+ return traffic_light_reg_elems.front ()->id ();
2254
+ }
2255
+
2256
+ std::optional<TrafficSignalElement> MapBasedPredictionNode::getTrafficSignalElement (
2257
+ const lanelet::Id & id)
2258
+ {
2259
+ if (traffic_signal_id_map_.count (id) != 0 ) {
2260
+ const auto & signal_elements = traffic_signal_id_map_.at (id).elements ;
2261
+ if (signal_elements.size () > 1 ) {
2262
+ RCLCPP_ERROR (
2263
+ get_logger (), " [Map Based Prediction]: Multiple TrafficSignalElement_ are received." );
2264
+ } else if (!signal_elements.empty ()) {
2265
+ return signal_elements.front ();
2266
+ }
2267
+ }
2268
+ return std::nullopt;
2269
+ }
2270
+
2214
2271
} // namespace map_based_prediction
2215
2272
2216
2273
#include < rclcpp_components/register_node_macro.hpp>
0 commit comments