Skip to content

Commit 344c01f

Browse files
committed
perf(dynamic_obstacle_avoidance): decrease the computation time with time_keeper (autowarefoundation#7986)
* decrease computation cost Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com> * remove TODO Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com> * fix Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com> --------- Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com>
1 parent 94c336f commit 344c01f

File tree

2 files changed

+200
-123
lines changed
  • planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module

2 files changed

+200
-123
lines changed

planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/include/autoware/behavior_path_dynamic_obstacle_avoidance_module/scene.hpp

+10-14
Original file line numberDiff line numberDiff line change
@@ -16,7 +16,6 @@
1616
#define AUTOWARE__BEHAVIOR_PATH_DYNAMIC_OBSTACLE_AVOIDANCE_MODULE__SCENE_HPP_
1717

1818
#include "autoware/behavior_path_planner_common/interface/scene_module_interface.hpp"
19-
#include "autoware/universe_utils/system/stop_watch.hpp"
2019

2120
#include <autoware/universe_utils/geometry/boost_geometry.hpp>
2221
#include <rclcpp/rclcpp.hpp>
@@ -206,20 +205,20 @@ class DynamicObstacleAvoidanceModule : public SceneModuleInterface
206205
std::optional<MinMaxValue> lat_offset_to_avoid{std::nullopt};
207206
bool is_collision_left{false};
208207
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;
210209
LatFeasiblePaths ego_lat_feasible_paths;
211210

212211
// add additional information (not update to the latest data)
213212
void update(
214213
const MinMaxValue & arg_lon_offset_to_avoid, const MinMaxValue & arg_lat_offset_to_avoid,
215214
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)
217216
{
218217
lon_offset_to_avoid = arg_lon_offset_to_avoid;
219218
lat_offset_to_avoid = arg_lat_offset_to_avoid;
220219
is_collision_left = arg_is_collision_left;
221220
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;
223222
}
224223
};
225224

@@ -317,12 +316,12 @@ class DynamicObstacleAvoidanceModule : public SceneModuleInterface
317316
const std::string & uuid, const MinMaxValue & lon_offset_to_avoid,
318317
const MinMaxValue & lat_offset_to_avoid, const bool is_collision_left,
319318
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)
321320
{
322321
if (object_map_.count(uuid) != 0) {
323322
object_map_.at(uuid).update(
324323
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);
326325
}
327326
}
328327

@@ -409,24 +408,25 @@ class DynamicObstacleAvoidanceModule : public SceneModuleInterface
409408
std::optional<std::pair<size_t, size_t>> calcCollisionSection(
410409
const std::vector<PathPointWithLaneId> & ego_path, const PredictedPath & obj_path) const;
411410
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,
413413
const autoware_perception_msgs::msg::Shape & obj_shape) const;
414414
double calcValidLengthToAvoid(
415415
const PredictedPath & obj_path, const geometry_msgs::msg::Pose & obj_pose,
416416
const autoware_perception_msgs::msg::Shape & obj_shape,
417417
const bool is_object_same_direction) const;
418418
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,
420420
const geometry_msgs::msg::Pose & obj_pose, const Polygon2d & obj_points, const double obj_vel,
421421
const PredictedPath & obj_path, const autoware_perception_msgs::msg::Shape & obj_shape,
422422
const TimeWhileCollision & time_while_collision) const;
423423
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,
425425
const Polygon2d & obj_points, const geometry_msgs::msg::Point & obj_pos, const double obj_vel,
426426
const bool is_collision_left, const double obj_normal_vel,
427427
const std::optional<DynamicAvoidanceObject> & prev_object) const;
428428
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,
430430
const std::optional<DynamicAvoidanceObject> & prev_object,
431431
const DynamicAvoidanceObject & object) const;
432432
std::pair<lanelet::ConstLanelets, lanelet::ConstLanelets> getAdjacentLanes(
@@ -454,10 +454,6 @@ class DynamicObstacleAvoidanceModule : public SceneModuleInterface
454454
std::shared_ptr<DynamicAvoidanceParameters> parameters_;
455455

456456
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_;
461457
};
462458
} // namespace autoware::behavior_path_planner
463459

0 commit comments

Comments
 (0)