35
35
#include < utility>
36
36
#include < vector>
37
37
38
+ namespace
39
+ {
40
+ template <typename T>
41
+ bool isInVector (const T & val, const std::vector<T> & vec)
42
+ {
43
+ return std::find (vec.begin (), vec.end (), val) != vec.end ();
44
+ }
45
+
46
+ template <typename T, typename S>
47
+ std::vector<T> getAllKeys (const std::unordered_map<T, S> & map)
48
+ {
49
+ std::vector<T> keys;
50
+ for (const auto & pair : map) {
51
+ keys.push_back (pair.first );
52
+ }
53
+ return keys;
54
+ }
55
+ } // namespace
56
+
38
57
namespace behavior_path_planner
39
58
{
40
59
using autoware_auto_perception_msgs::msg::PredictedPath;
@@ -97,6 +116,10 @@ struct DynamicAvoidanceParameters
97
116
double max_time_for_lat_shift{0.0 };
98
117
double lpf_gain_for_lat_avoid_to_offset{0.0 };
99
118
119
+ double max_ego_lat_acc{0.0 };
120
+ double max_ego_lat_jerk{0.0 };
121
+ double delay_time_ego_shift{0.0 };
122
+
100
123
double max_time_to_collision_overtaking_object{0.0 };
101
124
double start_duration_to_avoid_overtaking_object{0.0 };
102
125
double end_duration_to_avoid_overtaking_object{0.0 };
@@ -113,6 +136,11 @@ struct TimeWhileCollision
113
136
double time_to_end_collision;
114
137
};
115
138
139
+ struct LatFeasiblePaths
140
+ {
141
+ std::vector<geometry_msgs::msg::Point > left_path;
142
+ std::vector<geometry_msgs::msg::Point > right_path;
143
+ };
116
144
class DynamicAvoidanceModule : public SceneModuleInterface
117
145
{
118
146
public:
@@ -151,6 +179,7 @@ class DynamicAvoidanceModule : public SceneModuleInterface
151
179
bool is_collision_left{false };
152
180
bool should_be_avoided{false };
153
181
std::vector<PathPointWithLaneId> ref_path_points_for_obj_poly;
182
+ LatFeasiblePaths ego_lat_feasible_paths;
154
183
155
184
void update (
156
185
const MinMaxValue & arg_lon_offset_to_avoid, const MinMaxValue & arg_lat_offset_to_avoid,
@@ -172,14 +201,18 @@ class DynamicAvoidanceModule : public SceneModuleInterface
172
201
{
173
202
}
174
203
int max_count_{0 };
175
- int min_count_{0 };
204
+ int min_count_{0 }; // TODO(murooka): The sign needs to be opposite?
176
205
177
206
void initialize () { current_uuids_.clear (); }
178
207
void updateObject (const std::string & uuid, const DynamicAvoidanceObject & object)
179
208
{
180
209
// add/update object
181
210
if (object_map_.count (uuid) != 0 ) {
211
+ const auto prev_object = object_map_.at (uuid);
182
212
object_map_.at (uuid) = object;
213
+ // TODO(murooka) refactor this. Counter can be moved to DynamicObject,
214
+ // and TargetObjectsManager can be removed.
215
+ object_map_.at (uuid).ego_lat_feasible_paths = prev_object.ego_lat_feasible_paths ;
183
216
} else {
184
217
object_map_.emplace (uuid, object);
185
218
}
@@ -195,14 +228,12 @@ class DynamicAvoidanceModule : public SceneModuleInterface
195
228
current_uuids_.push_back (uuid);
196
229
}
197
230
198
- void finalize ()
231
+ void finalize (const LatFeasiblePaths & ego_lat_feasible_paths )
199
232
{
200
233
// decrease counter for not updated uuids
201
234
std::vector<std::string> not_updated_uuids;
202
235
for (const auto & object : object_map_) {
203
- if (
204
- std::find (current_uuids_.begin (), current_uuids_.end (), object.first ) ==
205
- current_uuids_.end ()) {
236
+ if (!isInVector (object.first , current_uuids_)) {
206
237
not_updated_uuids.push_back (object.first );
207
238
}
208
239
}
@@ -214,45 +245,46 @@ class DynamicAvoidanceModule : public SceneModuleInterface
214
245
}
215
246
}
216
247
217
- // remove objects whose counter is lower than threshold
218
- std::vector<std::string> obsolete_uuids;
248
+ // update valid object uuids and its variable
219
249
for (const auto & counter : counter_map_) {
220
- if (counter.second < min_count_) {
221
- obsolete_uuids.push_back (counter.first );
250
+ if (!isInVector (counter.first , valid_object_uuids_) && max_count_ <= counter.second ) {
251
+ valid_object_uuids_.push_back (counter.first );
252
+ object_map_.at (counter.first ).ego_lat_feasible_paths = ego_lat_feasible_paths;
222
253
}
223
254
}
224
- for (const auto & obsolete_uuid : obsolete_uuids) {
225
- counter_map_.erase (obsolete_uuid);
226
- object_map_.erase (obsolete_uuid);
255
+ valid_object_uuids_.erase (
256
+ std::remove_if (
257
+ valid_object_uuids_.begin (), valid_object_uuids_.end (),
258
+ [&](const auto & uuid) {
259
+ return counter_map_.count (uuid) == 0 || counter_map_.at (uuid) < max_count_;
260
+ }),
261
+ valid_object_uuids_.end ());
262
+
263
+ // remove objects whose counter is lower than threshold
264
+ const auto counter_map_keys = getAllKeys (counter_map_);
265
+ for (const auto & key : counter_map_keys) {
266
+ if (counter_map_.at (key) < min_count_) {
267
+ counter_map_.erase (key);
268
+ object_map_.erase (key);
269
+ }
227
270
}
228
271
}
229
272
std::vector<DynamicAvoidanceObject> getValidObjects () const
230
273
{
231
- std::vector<DynamicAvoidanceObject> objects;
232
- for (const auto & object : object_map_) {
233
- if (counter_map_.count (object.first ) != 0 ) {
234
- if (max_count_ <= counter_map_.at (object.first )) {
235
- objects.push_back (object.second );
236
- }
274
+ std::vector<DynamicAvoidanceObject> valid_objects;
275
+ for (const auto & valid_object_uuid : valid_object_uuids_) {
276
+ if (object_map_.count (valid_object_uuid) == 0 ) {
277
+ std::cerr
278
+ << " [DynamicAvoidance] Internal calculation has an error when getting valid objects."
279
+ << std::endl;
280
+ continue ;
237
281
}
282
+ valid_objects.push_back (object_map_.at (valid_object_uuid));
238
283
}
239
- return objects;
240
- }
241
- std::optional<DynamicAvoidanceObject> getValidObject (const std::string & uuid) const
242
- {
243
- // add/update object
244
- if (counter_map_.count (uuid) == 0 ) {
245
- return std::nullopt;
246
- }
247
- if (counter_map_.at (uuid) < max_count_) {
248
- return std::nullopt;
249
- }
250
- if (object_map_.count (uuid) == 0 ) {
251
- return std::nullopt;
252
- }
253
- return object_map_.at (uuid);
284
+
285
+ return valid_objects;
254
286
}
255
- void updateObject (
287
+ void updateObjectVariables (
256
288
const std::string & uuid, const MinMaxValue & lon_offset_to_avoid,
257
289
const MinMaxValue & lat_offset_to_avoid, const bool is_collision_left,
258
290
const bool should_be_avoided,
@@ -269,6 +301,7 @@ class DynamicAvoidanceModule : public SceneModuleInterface
269
301
// NOTE: positive is for meeting entry condition, and negative is for exiting.
270
302
std::unordered_map<std::string, int > counter_map_;
271
303
std::unordered_map<std::string, DynamicAvoidanceObject> object_map_;
304
+ std::vector<std::string> valid_object_uuids_{};
272
305
};
273
306
274
307
struct DecisionWithReason
@@ -319,6 +352,8 @@ class DynamicAvoidanceModule : public SceneModuleInterface
319
352
320
353
bool isLabelTargetObstacle (const uint8_t label) const ;
321
354
void updateTargetObjects ();
355
+ LatFeasiblePaths generateLateralFeasiblePaths (
356
+ const geometry_msgs::msg::Pose & ego_pose, const double ego_vel) const ;
322
357
void updateRefPathBeforeLaneChange (const std::vector<PathPointWithLaneId> & ego_ref_path_points);
323
358
bool willObjectCutIn (
324
359
const std::vector<PathPointWithLaneId> & ego_path, const PredictedPath & predicted_path,
0 commit comments