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

fix(behavior_velocity_planner): fix rtc in crosswalk module #1273

Merged
merged 3 commits into from
Jul 8, 2022
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 @@ -106,6 +106,9 @@ class CrosswalkModule : public SceneModuleInterface
private:
int64_t module_id_;

boost::optional<std::pair<size_t, PathPointWithLaneId>> findRTCStopPoint(
const PathWithLaneId & ego_path);

boost::optional<std::pair<size_t, PathPointWithLaneId>> findNearestStopPoint(
const PathWithLaneId & ego_path, StopReason & stop_reason);

Expand All @@ -119,7 +122,8 @@ class CrosswalkModule : public SceneModuleInterface
std::pair<double, double> getAttentionRange(const PathWithLaneId & ego_path);

void insertDecelPoint(
const std::pair<size_t, PathPointWithLaneId> & stop_point, PathWithLaneId & output);
const std::pair<size_t, PathPointWithLaneId> & stop_point, const float target_velocity,
PathWithLaneId & output);

void clampAttentionRangeByNeighborCrosswalks(
const PathWithLaneId & ego_path, double & near_attention_range, double & far_attention_range);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -355,19 +355,28 @@ bool CrosswalkModule::modifyPathVelocity(PathWithLaneId * path, StopReason * sto
stop_watch_.toc("total_processing_time", false));

const auto nearest_stop_point = findNearestStopPoint(ego_path, *stop_reason);
const auto rtc_stop_point = findRTCStopPoint(ego_path);

RCLCPP_INFO_EXPRESSION(
logger_, planner_param_.show_processing_time, "- step3: %f ms",
stop_watch_.toc("total_processing_time", false));

setSafe(!nearest_stop_point);

if (!nearest_stop_point) {
const auto target_velocity =
nearest_stop_point ? calcTargetVelocity(nearest_stop_point.get().second, ego_path) : 0.0;

if (isActivated()) {
if (1e-3 < target_velocity) {
insertDecelPoint(nearest_stop_point.get(), target_velocity, *path);
}
return true;
}

if (!isActivated()) {
insertDecelPoint(nearest_stop_point.get(), *path);
if (nearest_stop_point) {
insertDecelPoint(nearest_stop_point.get(), target_velocity, *path);
} else if (rtc_stop_point) {
insertDecelPoint(rtc_stop_point.get(), target_velocity, *path);
}

RCLCPP_INFO_EXPRESSION(
Expand Down Expand Up @@ -406,6 +415,26 @@ boost::optional<std::pair<double, geometry_msgs::msg::Point>> CrosswalkModule::g
return {};
}

boost::optional<std::pair<size_t, PathPointWithLaneId>> CrosswalkModule::findRTCStopPoint(
const PathWithLaneId & ego_path)
{
const auto & base_link2front = planner_data_->vehicle_info_.max_longitudinal_offset_m;

const auto p_stop_line = getStopLine(ego_path);
if (!p_stop_line) {
return {};
}

const auto & p_stop = p_stop_line.get().second;
const auto & margin = planner_param_.stop_line_distance;

const size_t base_idx = findNearestSegmentIndex(ego_path.points, p_stop);
const auto residual_length = calcLongitudinalOffsetToSegment(ego_path.points, base_idx, p_stop);
const auto update_margin = margin - residual_length + base_link2front;

return getBackwardInsertPointFromBasePoint(base_idx, ego_path, update_margin);
}

boost::optional<std::pair<size_t, PathPointWithLaneId>> CrosswalkModule::findNearestStopPoint(
const PathWithLaneId & ego_path, StopReason & stop_reason)
{
Expand Down Expand Up @@ -514,8 +543,6 @@ boost::optional<std::pair<size_t, PathPointWithLaneId>> CrosswalkModule::findNea
const auto need_to_stop =
found_pedestrians || found_stuck_vehicle || external_stop || external_slowdown;
if (!need_to_stop) {
setDistance(
std::abs(p_stop_line.get().first - planner_param_.stop_line_distance - base_link2front));
return {};
}

Expand All @@ -542,9 +569,6 @@ boost::optional<std::pair<size_t, PathPointWithLaneId>> CrosswalkModule::findNea
stop_factor.stop_pose = stop_point.get().second.point.pose;
planning_utils::appendStopReason(stop_factor, &stop_reason);

setDistance(
std::abs(calcSignedArcLength(ego_path.points, ego_pos, p_stop) - margin - base_link2front));

return stop_point;
}

Expand Down Expand Up @@ -576,7 +600,8 @@ std::pair<double, double> CrosswalkModule::getAttentionRange(const PathWithLaneI
}

void CrosswalkModule::insertDecelPoint(
const std::pair<size_t, PathPointWithLaneId> & stop_point, PathWithLaneId & output)
const std::pair<size_t, PathPointWithLaneId> & stop_point, const float target_velocity,
PathWithLaneId & output)
{
const auto traj_end_idx = output.points.size() - 1;
const auto & stop_idx = stop_point.first;
Expand All @@ -603,20 +628,28 @@ void CrosswalkModule::insertDecelPoint(
update_stop_idx = std::min(update_stop_idx + 1, traj_end_idx);
}

const auto target_velocity = calcTargetVelocity(p_insert, output);
for (size_t i = update_stop_idx; i < output.points.size(); ++i) {
const auto & original_velocity = output.points.at(i).point.longitudinal_velocity_mps;
output.points.at(i).point.longitudinal_velocity_mps =
std::min(original_velocity, target_velocity);
}

const auto & ego_pos = planner_data_->current_pose.pose.position;
const auto & stop_point_distance =
calcSignedArcLength(output.points, ego_pos, getPoint(stop_point.second));
setDistance(std::abs(stop_point_distance));

debug_data_.first_stop_pose = stop_point.second.point.pose;
debug_data_.stop_poses.push_back(stop_point.second.point.pose);
}

float CrosswalkModule::calcTargetVelocity(
const PathPointWithLaneId & stop_point, const PathWithLaneId & ego_path) const
{
if (!isActivated()) {
return 0.0;
}

if (isTargetExternalInputStatus(CrosswalkStatus::SLOWDOWN)) {
return planner_param_.slow_velocity;
}
Expand Down