48
48
#include < optional>
49
49
#include < string>
50
50
#include < unordered_map>
51
+ #include < unordered_set>
51
52
#include < utility>
52
53
#include < vector>
53
54
@@ -85,6 +86,12 @@ struct ObjectData
85
86
Maneuver::UNINITIALIZED}; // output maneuver considering previous one shot maneuvers
86
87
};
87
88
89
+ struct CrosswalkUserData
90
+ {
91
+ std_msgs::msg::Header header;
92
+ autoware_auto_perception_msgs::msg::TrackedObject tracked_object;
93
+ };
94
+
88
95
struct LaneletData
89
96
{
90
97
lanelet::Lanelet lanelet;
@@ -135,8 +142,10 @@ class MapBasedPredictionNode : public rclcpp::Node
135
142
std::unique_ptr<tier4_autoware_utils::DebugPublisher> processing_time_publisher_;
136
143
137
144
// Object History
138
- std::unordered_map<std::string, std::deque<ObjectData>> objects_history_ ;
145
+ std::unordered_map<std::string, std::deque<ObjectData>> road_users_history ;
139
146
std::map<std::pair<std::string, lanelet::Id>, rclcpp::Time> stopped_times_against_green_;
147
+ std::unordered_map<std::string, std::deque<CrosswalkUserData>> crosswalk_users_history_;
148
+ std::unordered_map<std::string, std::string> known_matches_;
140
149
141
150
// Lanelet Map Pointers
142
151
std::shared_ptr<lanelet::LaneletMap> lanelet_map_ptr_;
@@ -200,6 +209,9 @@ class MapBasedPredictionNode : public rclcpp::Node
200
209
std::vector<double > distance_set_for_no_intention_to_walk_;
201
210
std::vector<double > timeout_set_for_no_intention_to_walk_;
202
211
212
+ bool match_lost_and_appeared_crosswalk_users_;
213
+ bool remember_lost_crosswalk_users_;
214
+
203
215
std::unique_ptr<tier4_autoware_utils::PublishedTimePublisher> published_time_publisher_;
204
216
205
217
// Member Functions
@@ -222,8 +234,7 @@ class MapBasedPredictionNode : public rclcpp::Node
222
234
223
235
PredictedObject getPredictedObjectAsCrosswalkUser (const TrackedObject & object);
224
236
225
- void removeOldObjectsHistory (
226
- const double current_time, const TrackedObjects::ConstSharedPtr in_objects);
237
+ void removeStaleTrafficLightInfo (const TrackedObjects::ConstSharedPtr in_objects);
227
238
228
239
LaneletsData getCurrentLanelets (const TrackedObject & object);
229
240
bool checkCloseLaneletCondition (
@@ -232,10 +243,14 @@ class MapBasedPredictionNode : public rclcpp::Node
232
243
const lanelet::Lanelet & current_lanelet, const TrackedObject & object) const ;
233
244
void updateObjectData (TrackedObject & object);
234
245
235
- void updateObjectsHistory (
246
+ void updateRoadUsersHistory (
236
247
const std_msgs::msg::Header & header, const TrackedObject & object,
237
248
const LaneletsData & current_lanelets_data);
238
-
249
+ void updateCrosswalkUserHistory (
250
+ const std_msgs::msg::Header & header, const TrackedObject & object,
251
+ const std::string & object_id);
252
+ std::string tryMatchNewObjectToDisappeared (
253
+ const std::string & object_id, std::unordered_map<std::string, TrackedObject> & current_users);
239
254
std::vector<PredictedRefPath> getPredictedReferencePath (
240
255
const TrackedObject & object, const LaneletsData & current_lanelets_data,
241
256
const double object_detected_time);
0 commit comments