Skip to content

Commit 5673d6d

Browse files
author
beyza
committed
add extra_object_footprint_width for predicted_footprint
Signed-off-by: beyza <bnk@leodrive.ai>
1 parent 3ae2b2d commit 5673d6d

File tree

4 files changed

+7
-4
lines changed

4 files changed

+7
-4
lines changed

planning/behavior_velocity_dynamic_obstacle_stop_module/config/dynamic_obstacle_stop.param.yaml

+1
Original file line numberDiff line numberDiff line change
@@ -2,6 +2,7 @@
22
ros__parameters:
33
dynamic_obstacle_stop: # module to stop or before entering the immediate path of a moving object
44
extra_object_width: 1.0 # [m] extra width around detected objects
5+
extra_object_footprint_width: 0.0 # [m] extra width around detected objects for footprint
56
minimum_object_velocity: 0.5 # [m/s] objects with a velocity bellow this value are ignored
67
stop_distance_buffer: 0.5 # [m] extra distance to add between the stop point and the collision point
78
time_horizon: 5.0 # [s] time horizon used for collision checks

planning/behavior_velocity_dynamic_obstacle_stop_module/src/footprint.cpp

+4-4
Original file line numberDiff line numberDiff line change
@@ -86,10 +86,10 @@ tier4_autoware_utils::MultiPolygon2d create_object_footprints(
8686
tier4_autoware_utils::MultiPolygon2d footprints;
8787

8888
for (const auto & object : objects) {
89-
const auto front = object.shape.dimensions.x / 2 + params.extra_object_width;
90-
const auto rear = -object.shape.dimensions.x / 2 - params.extra_object_width;
91-
const auto left = object.shape.dimensions.y / 2 + params.extra_object_width;
92-
const auto right = -object.shape.dimensions.y / 2 - params.extra_object_width;
89+
const auto front = object.shape.dimensions.x / 2 + params.extra_object_footprint_width;
90+
const auto rear = -object.shape.dimensions.x / 2 - params.extra_object_footprint_width;
91+
const auto left = object.shape.dimensions.y / 2 + params.extra_object_footprint_width;
92+
const auto right = -object.shape.dimensions.y / 2 - params.extra_object_footprint_width;
9393
tier4_autoware_utils::Polygon2d base_footprint;
9494
base_footprint.outer() = {
9595
Point2d{front, left}, Point2d{front, right}, Point2d{rear, right}, Point2d{rear, left},

planning/behavior_velocity_dynamic_obstacle_stop_module/src/manager.cpp

+1
Original file line numberDiff line numberDiff line change
@@ -31,6 +31,7 @@ DynamicObstacleStopModuleManager::DynamicObstacleStopModuleManager(rclcpp::Node
3131
auto & pp = planner_param_;
3232

3333
pp.extra_object_width = getOrDeclareParameter<double>(node, ns + ".extra_object_width");
34+
pp.extra_object_footprint_width = getOrDeclareParameter<double>(node, ns + ".extra_object_footprint_width");
3435
pp.minimum_object_velocity = getOrDeclareParameter<double>(node, ns + ".minimum_object_velocity");
3536
pp.stop_distance_buffer = getOrDeclareParameter<double>(node, ns + ".stop_distance_buffer");
3637
pp.time_horizon = getOrDeclareParameter<double>(node, ns + ".time_horizon");

planning/behavior_velocity_dynamic_obstacle_stop_module/src/types.hpp

+1
Original file line numberDiff line numberDiff line change
@@ -38,6 +38,7 @@ using Rtree = boost::geometry::index::rtree<BoxIndexPair, boost::geometry::index
3838
struct PlannerParam
3939
{
4040
double extra_object_width;
41+
double extra_object_footprint_width;
4142
double minimum_object_velocity;
4243
double stop_distance_buffer;
4344
double time_horizon;

0 commit comments

Comments
 (0)