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_planner)!: ignore to garze against unknwon objects (#7177) #1331

Merged
merged 1 commit into from
Jun 10, 2024
Merged
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 @@ -87,7 +87,8 @@
obstacle_traj_angle_threshold : 1.22 # [rad] = 70 [deg], yaw threshold of crossing obstacle against the nearest trajectory point for cruise or stop

stop:
max_lat_margin: 0.3 # lateral margin between obstacle and trajectory band with ego's width
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
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 @@ -195,6 +195,7 @@ class ObstacleCruisePlannerNode : public rclcpp::Node
double prediction_resampling_time_horizon;
// max lateral margin
double max_lat_margin_for_stop;
double max_lat_margin_for_stop_against_unknown;
double max_lat_margin_for_cruise;
double max_lat_margin_for_slow_down;
double lat_hysteresis_margin_for_slow_down;
Expand Down
21 changes: 16 additions & 5 deletions planning/obstacle_cruise_planner/src/node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -247,6 +247,8 @@ ObstacleCruisePlannerNode::BehaviorDeterminationParam::BehaviorDeterminationPara

max_lat_margin_for_stop =
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_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 @@ -311,6 +313,9 @@ void ObstacleCruisePlannerNode::BehaviorDeterminationParam::onParam(

tier4_autoware_utils::updateParam<double>(
parameters, "behavior_determination.stop.max_lat_margin", max_lat_margin_for_stop);
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.cruise.max_lat_margin", max_lat_margin_for_cruise);
tier4_autoware_utils::updateParam<bool>(
Expand Down Expand Up @@ -680,8 +685,8 @@ std::vector<Obstacle> ObstacleCruisePlannerNode::convertToObstacles(
}();

const double max_lat_margin = std::max(
std::max(p.max_lat_margin_for_stop, p.max_lat_margin_for_cruise),
p.max_lat_margin_for_slow_down);
{p.max_lat_margin_for_stop, p.max_lat_margin_for_stop_against_unknown,
p.max_lat_margin_for_cruise, p.max_lat_margin_for_slow_down});
if (max_lat_margin < min_lat_dist_to_traj_poly) {
RCLCPP_INFO_EXPRESSION(
get_logger(), enable_debug_info_,
Expand Down Expand Up @@ -1171,7 +1176,13 @@ std::optional<StopObstacle> ObstacleCruisePlannerNode::createStopObstacle(
if (!isStopObstacle(obstacle.classification.label)) {
return std::nullopt;
}
if (p.max_lat_margin_for_stop < precise_lat_dist) {

const double max_lat_margin_for_stop =
(obstacle.classification.label == ObjectClassification::UNKNOWN)
? p.max_lat_margin_for_stop_against_unknown
: p.max_lat_margin_for_stop;

if (precise_lat_dist > std::max(max_lat_margin_for_stop, 1e-3)) {
return std::nullopt;
}

Expand Down Expand Up @@ -1204,7 +1215,7 @@ std::optional<StopObstacle> ObstacleCruisePlannerNode::createStopObstacle(
calcObstacleMaxLength(obstacle.shape) + p.decimate_trajectory_step_length +
std::hypot(
vehicle_info_.vehicle_length_m,
vehicle_info_.vehicle_width_m * 0.5 + p.max_lat_margin_for_stop));
vehicle_info_.vehicle_width_m * 0.5 + max_lat_margin_for_stop));
if (collision_points.empty()) {
RCLCPP_INFO_EXPRESSION(
get_logger(), enable_debug_info_,
Expand All @@ -1230,7 +1241,7 @@ std::optional<StopObstacle> ObstacleCruisePlannerNode::createStopObstacle(

// calculate collision points with trajectory with lateral stop margin
const auto traj_polys_with_lat_margin = createOneStepPolygons(
traj_points, vehicle_info_, ego_odom_ptr_->pose.pose, p.max_lat_margin_for_stop);
traj_points, vehicle_info_, ego_odom_ptr_->pose.pose, max_lat_margin_for_stop);

const auto collision_point = polygon_utils::getCollisionPoint(
traj_points, traj_polys_with_lat_margin, obstacle, is_driving_forward_, vehicle_info_);
Expand Down
Loading