Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

feat(obstacle_cruise)!: add height filter as unknown objects #1318

Closed
Closed
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -89,6 +89,7 @@
stop:
max_lat_margin: 0.3 # lateral margin between the obstacles except for unknown and ego's footprint
max_lat_margin_against_unknown: -0.3 # lateral margin between the unknown obstacles and ego's footprint
max_lat_margin_against_unknown_height_threshold: 0.6 # Only for unknowns lower than this height, the parameter above for unknowns is referenced.
crossing_obstacle:
collision_time_margin : 4.0 # time threshold of collision between obstacle adn ego for cruise or stop [s]

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -201,6 +201,7 @@ class ObstacleCruisePlannerNode : public rclcpp::Node
// max lateral margin
double max_lat_margin_for_stop;
double max_lat_margin_for_stop_against_unknown;
double max_lat_margin_for_stop_against_unknown_height_threshold;
double max_lat_margin_for_cruise;
double max_lat_margin_for_slow_down;
double lat_hysteresis_margin_for_slow_down;
Expand Down
8 changes: 7 additions & 1 deletion planning/obstacle_cruise_planner/src/node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -249,6 +249,8 @@ ObstacleCruisePlannerNode::BehaviorDeterminationParam::BehaviorDeterminationPara
node.declare_parameter<double>("behavior_determination.stop.max_lat_margin");
max_lat_margin_for_stop_against_unknown =
node.declare_parameter<double>("behavior_determination.stop.max_lat_margin_against_unknown");
max_lat_margin_for_stop_against_unknown_height_threshold = node.declare_parameter<double>(
"behavior_determination.stop.max_lat_margin_against_unknown_height_threshold");
max_lat_margin_for_cruise =
node.declare_parameter<double>("behavior_determination.cruise.max_lat_margin");
enable_yield = node.declare_parameter<bool>("behavior_determination.cruise.yield.enable_yield");
Expand Down Expand Up @@ -316,6 +318,9 @@ void ObstacleCruisePlannerNode::BehaviorDeterminationParam::onParam(
tier4_autoware_utils::updateParam<double>(
parameters, "behavior_determination.stop.max_lat_margin_against_unknown",
max_lat_margin_for_stop_against_unknown);
tier4_autoware_utils::updateParam<double>(
parameters, "behavior_determination.stop.max_lat_margin_against_unknown_height_threshold",
max_lat_margin_for_stop_against_unknown_height_threshold);
tier4_autoware_utils::updateParam<double>(
parameters, "behavior_determination.cruise.max_lat_margin", max_lat_margin_for_cruise);
tier4_autoware_utils::updateParam<bool>(
Expand Down Expand Up @@ -1181,7 +1186,8 @@ std::optional<StopObstacle> ObstacleCruisePlannerNode::createStopObstacle(
}

const double max_lat_margin_for_stop =
(obstacle.classification.label == ObjectClassification::UNKNOWN)
(obstacle.classification.label == ObjectClassification::UNKNOWN &&
obstacle.shape.dimensions.z < p.max_lat_margin_for_stop_against_unknown_height_threshold)
? p.max_lat_margin_for_stop_against_unknown
: p.max_lat_margin_for_stop;

Expand Down
Loading