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(safety_check): add hysteresis factor in safety check logic #4735

Merged
Merged
Show file tree
Hide file tree
Changes from 1 commit
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
Next Next commit
feat(safety_check): add hysteresis factor
Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com>
  • Loading branch information
satoshi-ota committed Aug 26, 2023
commit be8991af8cfb104c297220885956970a5ad4cb1f
Original file line number Diff line number Diff line change
Expand Up @@ -101,7 +101,7 @@ bool checkCollision(
const ExtendedPredictedObject & target_object,
const PredictedPathWithPolygon & target_object_path,
const BehaviorPathPlannerParameters & common_parameters, const RSSparams & rss_parameters,
CollisionCheckDebug & debug);
const double hysteresis_factor, CollisionCheckDebug & debug);

/**
* @brief Check collision between ego path footprints with extra longitudinal stopping margin and
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -232,7 +232,7 @@ bool checkCollision(
const ExtendedPredictedObject & target_object,
const PredictedPathWithPolygon & target_object_path,
const BehaviorPathPlannerParameters & common_parameters, const RSSparams & rss_parameters,
CollisionCheckDebug & debug)
double hysteresis_factor, CollisionCheckDebug & debug)
{
debug.lerped_path.reserve(target_object_path.path.size());

Expand Down Expand Up @@ -286,8 +286,8 @@ bool checkCollision(
const auto min_lon_length =
calcMinimumLongitudinalLength(front_object_velocity, rear_object_velocity, rss_parameters);

const auto & lon_offset = std::max(rss_dist, min_lon_length);
const auto & lat_margin = rss_parameters.lateral_distance_max_threshold;
const auto & lon_offset = std::max(rss_dist, min_lon_length) * hysteresis_factor;
kyoichi-sugahara marked this conversation as resolved.
Show resolved Hide resolved
const auto & lat_margin = rss_parameters.lateral_distance_max_threshold * hysteresis_factor;
const auto & extended_ego_polygon =
is_object_front
? createExtendedPolygon(ego_pose, ego_vehicle_info, lon_offset, lat_margin, debug)
Expand Down