Skip to content

Commit ac73ed2

Browse files
committed
fix logic to avoid chattering
Signed-off-by: Maxime CLEMENT <maxime.clement@tier4.jp>
1 parent 0ee5cb5 commit ac73ed2

File tree

2 files changed

+20
-15
lines changed

2 files changed

+20
-15
lines changed

planning/behavior_velocity_dynamic_obstacle_stop_module/src/object_filtering.cpp

+14-12
Original file line numberDiff line numberDiff line change
@@ -65,25 +65,27 @@ std::vector<autoware_auto_perception_msgs::msg::PredictedObject> filter_predicte
6565
const auto ego_yaw = tf2::getYaw(ego_data.pose.orientation);
6666
const auto yaw_diff = std::abs(tier4_autoware_utils::normalizeRadian(o_yaw - ego_yaw));
6767
const auto opposite_heading = yaw_diff > M_PI_2 + M_PI_4;
68-
auto distance = std::abs(
69-
(o_pose.position.y - ego_data.pose.position.y) * std::cos(o_yaw) -
70-
(o_pose.position.x - ego_data.pose.position.x) * std::sin(o_yaw));
68+
const auto collision_distance_threshold =
69+
params.ego_lateral_offset + o.shape.dimensions.y / 2.0 + params.hysteresis;
70+
auto has_collision = std::abs(
71+
(o_pose.position.y - ego_data.pose.position.y) * std::cos(o_yaw) -
72+
(o_pose.position.x - ego_data.pose.position.x) * std::sin(o_yaw)) <=
73+
collision_distance_threshold;
7174
if (ego_data.earliest_stop_pose) {
72-
distance = std::min(
73-
distance,
75+
const auto collision_at_earliest_stop_pose =
7476
std::abs(
7577
(o_pose.position.y - ego_data.earliest_stop_pose->position.y) * std::cos(o_yaw) -
76-
(o_pose.position.x - ego_data.earliest_stop_pose->position.x) * std::sin(o_yaw)));
78+
(o_pose.position.x - ego_data.earliest_stop_pose->position.x) * std::sin(o_yaw)) <=
79+
collision_distance_threshold;
80+
has_collision |= collision_at_earliest_stop_pose;
7781
}
78-
return opposite_heading &&
79-
distance <= params.ego_lateral_offset + o.shape.dimensions.y / 2.0 + hysteresis;
82+
return opposite_heading && has_collision;
8083
};
8184
for (const auto & object : objects.objects) {
85+
const auto is_not_too_slow = object.kinematics.initial_twist_with_covariance.twist.linear.x >=
86+
params.minimum_object_velocity;
8287
if (
83-
is_vehicle(object) &&
84-
object.kinematics.initial_twist_with_covariance.twist.linear.x >=
85-
params.minimum_object_velocity &&
86-
is_in_range(object) && is_not_too_close(object) &&
88+
is_vehicle(object) && is_not_too_slow && is_in_range(object) && is_not_too_close(object) &&
8789
(!params.ignore_unavoidable_collisions || !is_unavoidable(object)))
8890
filtered_objects.push_back(object);
8991
}

planning/behavior_velocity_dynamic_obstacle_stop_module/src/scene_dynamic_obstacle_stop.cpp

+6-3
Original file line numberDiff line numberDiff line change
@@ -44,7 +44,9 @@ DynamicObstacleStopModule::DynamicObstacleStopModule(
4444
const rclcpp::Clock::SharedPtr clock)
4545
: SceneModuleInterface(module_id, logger, clock), params_(std::move(planner_param))
4646
{
47-
prev_stop_decision_time_ = rclcpp::Time(int64_t{0}, clock->get_clock_type());
47+
prev_stop_decision_time_ =
48+
clock->now() -
49+
rclcpp::Duration(std::chrono::duration<double>(params_.decision_duration_buffer));
4850
velocity_factor_.init(PlanningBehavior::UNKNOWN);
4951
}
5052

@@ -76,8 +78,9 @@ bool DynamicObstacleStopModule::modifyPathVelocity(PathWithLaneId * path, StopRe
7678
ego_data.path.points, ego_data.pose.position, min_stop_distance);
7779

7880
make_ego_footprint_rtree(ego_data, params_);
81+
const auto start_time = clock_->now();
7982
const auto has_decided_to_stop =
80-
(clock_->now() - prev_stop_decision_time_).seconds() < params_.decision_duration_buffer;
83+
(start_time - prev_stop_decision_time_).seconds() < params_.decision_duration_buffer;
8184
if (!has_decided_to_stop) current_stop_pose_.reset();
8285
double hysteresis = has_decided_to_stop ? params_.hysteresis : 0.0;
8386
const auto dynamic_obstacles =
@@ -109,7 +112,7 @@ bool DynamicObstacleStopModule::modifyPathVelocity(PathWithLaneId * path, StopRe
109112
path->points, stop_pose->position,
110113
current_stop_pose_->position) > 0.0;
111114
if (use_new_stop_pose) current_stop_pose_ = *stop_pose;
112-
prev_stop_decision_time_ = clock_->now();
115+
prev_stop_decision_time_ = start_time;
113116
}
114117
}
115118

0 commit comments

Comments
 (0)