|
16 | 16 | #define AUTOWARE__BEHAVIOR_PATH_DYNAMIC_OBSTACLE_AVOIDANCE_MODULE__SCENE_HPP_
|
17 | 17 |
|
18 | 18 | #include "autoware/behavior_path_planner_common/interface/scene_module_interface.hpp"
|
19 |
| -#include "autoware/universe_utils/system/stop_watch.hpp" |
20 | 19 |
|
21 | 20 | #include <autoware/universe_utils/geometry/boost_geometry.hpp>
|
22 | 21 | #include <rclcpp/rclcpp.hpp>
|
@@ -206,20 +205,20 @@ class DynamicObstacleAvoidanceModule : public SceneModuleInterface
|
206 | 205 | std::optional<MinMaxValue> lat_offset_to_avoid{std::nullopt};
|
207 | 206 | bool is_collision_left{false};
|
208 | 207 | bool should_be_avoided{false};
|
209 |
| - std::vector<PathPointWithLaneId> ref_path_points_for_obj_poly; |
| 208 | + std::vector<geometry_msgs::msg::Pose> ref_points_for_obj_poly; |
210 | 209 | LatFeasiblePaths ego_lat_feasible_paths;
|
211 | 210 |
|
212 | 211 | // add additional information (not update to the latest data)
|
213 | 212 | void update(
|
214 | 213 | const MinMaxValue & arg_lon_offset_to_avoid, const MinMaxValue & arg_lat_offset_to_avoid,
|
215 | 214 | const bool arg_is_collision_left, const bool arg_should_be_avoided,
|
216 |
| - const std::vector<PathPointWithLaneId> & arg_ref_path_points_for_obj_poly) |
| 215 | + const std::vector<geometry_msgs::msg::Pose> & arg_ref_points_for_obj_poly) |
217 | 216 | {
|
218 | 217 | lon_offset_to_avoid = arg_lon_offset_to_avoid;
|
219 | 218 | lat_offset_to_avoid = arg_lat_offset_to_avoid;
|
220 | 219 | is_collision_left = arg_is_collision_left;
|
221 | 220 | should_be_avoided = arg_should_be_avoided;
|
222 |
| - ref_path_points_for_obj_poly = arg_ref_path_points_for_obj_poly; |
| 221 | + ref_points_for_obj_poly = arg_ref_points_for_obj_poly; |
223 | 222 | }
|
224 | 223 | };
|
225 | 224 |
|
@@ -317,12 +316,12 @@ class DynamicObstacleAvoidanceModule : public SceneModuleInterface
|
317 | 316 | const std::string & uuid, const MinMaxValue & lon_offset_to_avoid,
|
318 | 317 | const MinMaxValue & lat_offset_to_avoid, const bool is_collision_left,
|
319 | 318 | const bool should_be_avoided,
|
320 |
| - const std::vector<PathPointWithLaneId> & ref_path_points_for_obj_poly) |
| 319 | + const std::vector<geometry_msgs::msg::Pose> & ref_points_for_obj_poly) |
321 | 320 | {
|
322 | 321 | if (object_map_.count(uuid) != 0) {
|
323 | 322 | object_map_.at(uuid).update(
|
324 | 323 | lon_offset_to_avoid, lat_offset_to_avoid, is_collision_left, should_be_avoided,
|
325 |
| - ref_path_points_for_obj_poly); |
| 324 | + ref_points_for_obj_poly); |
326 | 325 | }
|
327 | 326 | }
|
328 | 327 |
|
@@ -409,24 +408,25 @@ class DynamicObstacleAvoidanceModule : public SceneModuleInterface
|
409 | 408 | std::optional<std::pair<size_t, size_t>> calcCollisionSection(
|
410 | 409 | const std::vector<PathPointWithLaneId> & ego_path, const PredictedPath & obj_path) const;
|
411 | 410 | LatLonOffset getLateralLongitudinalOffset(
|
412 |
| - const std::vector<PathPointWithLaneId> & ego_path, const geometry_msgs::msg::Pose & obj_pose, |
| 411 | + const std::vector<geometry_msgs::msg::Pose> & ego_points, |
| 412 | + const geometry_msgs::msg::Pose & obj_pose, const size_t obj_seg_idx, |
413 | 413 | const autoware_perception_msgs::msg::Shape & obj_shape) const;
|
414 | 414 | double calcValidLengthToAvoid(
|
415 | 415 | const PredictedPath & obj_path, const geometry_msgs::msg::Pose & obj_pose,
|
416 | 416 | const autoware_perception_msgs::msg::Shape & obj_shape,
|
417 | 417 | const bool is_object_same_direction) const;
|
418 | 418 | MinMaxValue calcMinMaxLongitudinalOffsetToAvoid(
|
419 |
| - const std::vector<PathPointWithLaneId> & ref_path_points_for_obj_poly, |
| 419 | + const std::vector<geometry_msgs::msg::Pose> & ref_points_for_obj_poly, |
420 | 420 | const geometry_msgs::msg::Pose & obj_pose, const Polygon2d & obj_points, const double obj_vel,
|
421 | 421 | const PredictedPath & obj_path, const autoware_perception_msgs::msg::Shape & obj_shape,
|
422 | 422 | const TimeWhileCollision & time_while_collision) const;
|
423 | 423 | std::optional<MinMaxValue> calcMinMaxLateralOffsetToAvoidRegulatedObject(
|
424 |
| - const std::vector<PathPointWithLaneId> & ref_path_points_for_obj_poly, |
| 424 | + const std::vector<geometry_msgs::msg::Pose> & ref_points_for_obj_poly, |
425 | 425 | const Polygon2d & obj_points, const geometry_msgs::msg::Point & obj_pos, const double obj_vel,
|
426 | 426 | const bool is_collision_left, const double obj_normal_vel,
|
427 | 427 | const std::optional<DynamicAvoidanceObject> & prev_object) const;
|
428 | 428 | std::optional<MinMaxValue> calcMinMaxLateralOffsetToAvoidUnregulatedObject(
|
429 |
| - const std::vector<PathPointWithLaneId> & ref_path_points_for_obj_poly, |
| 429 | + const std::vector<geometry_msgs::msg::Pose> & ref_points_for_obj_poly, |
430 | 430 | const std::optional<DynamicAvoidanceObject> & prev_object,
|
431 | 431 | const DynamicAvoidanceObject & object) const;
|
432 | 432 | std::pair<lanelet::ConstLanelets, lanelet::ConstLanelets> getAdjacentLanes(
|
@@ -454,10 +454,6 @@ class DynamicObstacleAvoidanceModule : public SceneModuleInterface
|
454 | 454 | std::shared_ptr<DynamicAvoidanceParameters> parameters_;
|
455 | 455 |
|
456 | 456 | TargetObjectsManager target_objects_manager_;
|
457 |
| - |
458 |
| - mutable autoware::universe_utils::StopWatch< |
459 |
| - std::chrono::milliseconds, std::chrono::microseconds, std::chrono::steady_clock> |
460 |
| - stop_watch_; |
461 | 457 | };
|
462 | 458 | } // namespace autoware::behavior_path_planner
|
463 | 459 |
|
|
0 commit comments