Skip to content

Commit

Permalink
fix(behavior_velocity): fix detection area ,stop line,traffic lights …
Browse files Browse the repository at this point in the history
…stop line insertion ,occlusion spot (#505)

Signed-off-by: tanaka3 <ttatcoder@outlook.jp>
  • Loading branch information
taikitanaka3 authored Mar 15, 2022
1 parent 4f4b727 commit fa2bca8
Show file tree
Hide file tree
Showing 10 changed files with 87 additions and 79 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -41,6 +41,7 @@
#include <pcl/point_types.h>
#include <tf2/utils.h>

#include <algorithm>
#include <limits>
#include <string>
#include <vector>
Expand Down Expand Up @@ -70,6 +71,8 @@ struct PointWithSearchRangeIndex
using autoware_auto_planning_msgs::msg::PathWithLaneId;
using Point2d = boost::geometry::model::d2::point_xy<double>;
using Polygons2d = std::vector<lanelet::BasicPolygon2d>;
using autoware_auto_planning_msgs::msg::PathPointWithLaneId;
using autoware_auto_planning_msgs::msg::PathWithLaneId;
namespace planning_utils
{
inline geometry_msgs::msg::Point getPoint(const geometry_msgs::msg::Point & p) { return p; }
Expand Down Expand Up @@ -108,6 +111,10 @@ inline geometry_msgs::msg::Pose getPose(
return traj.points.at(idx).pose;
}
void getAllPartitionLanelets(const lanelet::LaneletMapConstPtr ll, Polygons2d & polys);
void setVelocityFrom(const size_t idx, const double vel, PathWithLaneId * input);
void insertVelocity(
PathWithLaneId & path, const PathPointWithLaneId & path_point, const double v,
size_t & insert_index, const double min_distance = 0.001);
inline int64_t bitShift(int64_t original_id) { return original_id << (sizeof(int32_t) * 8 / 2); }

inline double square(const double & a) { return a * a; }
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -242,11 +242,13 @@ bool BlindSpotModule::generateStopLine(
}

/* insert judge point */
const int pass_judge_idx_ip = std::min(
// need to remove const because pass judge idx will be changed by insert stop point
int pass_judge_idx_ip = std::min(
static_cast<int>(path_ip.points.size()) - 1, std::max(stop_idx_ip - pass_judge_idx_dist, 0));
if (has_prior_stopline || stop_idx_ip == pass_judge_idx_ip) {
*pass_judge_line_idx = *stop_line_idx;
} else {
//! insertPoint check if there is no duplicated point
*pass_judge_line_idx = insertPoint(pass_judge_idx_ip, path_ip, path);
++(*stop_line_idx); // stop index is incremented by judge line insertion
}
Expand Down Expand Up @@ -309,6 +311,14 @@ int BlindSpotModule::insertPoint(
// copy from previous point
inserted_point = inout_path->points.at(std::max(insert_idx - 1, 0));
inserted_point.point.pose = path_ip.points[insert_idx_ip].point.pose;
constexpr double min_dist = 0.001;
//! avoid to insert duplicated point
if (
planning_utils::calcDist2d(inserted_point, inout_path->points.at(insert_idx).point) <
min_dist) {
inout_path->points.at(insert_idx).point.longitudinal_velocity_mps = 0.0;
return insert_idx;
}
inout_path->points.insert(it, inserted_point);
}
return insert_idx;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -157,15 +157,9 @@ bool insertTargetVelocityPoint(
}
// ----------------

// insert target point
output.points.insert(
output.points.begin() + insert_target_point_idx, target_point_with_lane_id);
planning_utils::insertVelocity(
output, target_point_with_lane_id, velocity, insert_target_point_idx);

// insert 0 velocity after target point
for (size_t j = insert_target_point_idx; j < output.points.size(); ++j) {
output.points.at(j).point.longitudinal_velocity_mps =
std::min(static_cast<float>(velocity), output.points.at(j).point.longitudinal_velocity_mps);
}
return true;
}
return false;
Expand Down Expand Up @@ -300,15 +294,9 @@ bool insertTargetVelocityPoint(
}
// ----------------

// insert target point
output.points.insert(
output.points.begin() + insert_target_point_idx, target_point_with_lane_id);

// insert 0 velocity after target point
for (size_t j = insert_target_point_idx; j < output.points.size(); ++j) {
output.points.at(j).point.longitudinal_velocity_mps =
std::min(static_cast<float>(velocity), output.points.at(j).point.longitudinal_velocity_mps);
}
// insert target point or replace with 0 velocity if same points found
planning_utils::insertVelocity(
output, target_point_with_lane_id, velocity, insert_target_point_idx);
return true;
}
return false;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -375,7 +375,7 @@ autoware_auto_planning_msgs::msg::PathWithLaneId DetectionAreaModule::insertStop
{
auto output_path = path;

const auto insert_idx = stop_point.first + 1;
size_t insert_idx = static_cast<size_t>(stop_point.first + 1);
const auto stop_pose = stop_point.second;

// To PathPointWithLaneId
Expand All @@ -384,14 +384,8 @@ autoware_auto_planning_msgs::msg::PathWithLaneId DetectionAreaModule::insertStop
stop_point_with_lane_id.point.pose = stop_pose;
stop_point_with_lane_id.point.longitudinal_velocity_mps = 0.0;

// Insert stop point
output_path.points.insert(output_path.points.begin() + insert_idx, stop_point_with_lane_id);

// Insert 0 velocity after stop point
for (size_t j = insert_idx; j < output_path.points.size(); ++j) {
output_path.points.at(j).point.longitudinal_velocity_mps = 0.0;
}

// Insert stop point or replace with zero velocity
planning_utils::insertVelocity(output_path, stop_point_with_lane_id, 0.0, insert_idx);
return output_path;
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -397,7 +397,7 @@ bool NoStoppingAreaModule::isStoppable(
void NoStoppingAreaModule::insertStopPoint(
autoware_auto_planning_msgs::msg::PathWithLaneId & path, const PathIndexWithPose & stop_point)
{
const auto insert_idx = stop_point.first + 1;
size_t insert_idx = static_cast<size_t>(stop_point.first + 1);
const auto stop_pose = stop_point.second;

// To PathPointWithLaneId
Expand All @@ -406,13 +406,8 @@ void NoStoppingAreaModule::insertStopPoint(
stop_point_with_lane_id.point.pose = stop_pose;
stop_point_with_lane_id.point.longitudinal_velocity_mps = 0.0;

// Insert stop point
path.points.insert(path.points.begin() + insert_idx, stop_point_with_lane_id);

// Insert 0 velocity after stop point
for (size_t j = insert_idx; j < path.points.size(); ++j) {
path.points.at(j).point.longitudinal_velocity_mps = 0.0;
}
// Insert stop point or replace with zero velocity
planning_utils::insertVelocity(path, stop_point_with_lane_id, 0.0, insert_idx);
}

boost::optional<PathIndexWithPose> NoStoppingAreaModule::createTargetPoint(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -85,23 +85,16 @@ int insertSafeVelocityToPath(
}
PathPointWithLaneId inserted_point;
inserted_point = inout_path->points.at(closest_idx);
int insert_idx = closest_idx;
size_t insert_idx = closest_idx;
// insert velocity to path if distance is not too close else insert new collision point
// if original path has narrow points it's better to set higher distance threshold
if (planning_utils::calcDist2d(in_pose, inserted_point.point) > 0.3) {
if (isAheadOf(in_pose, inout_path->points.at(closest_idx).point.pose)) {
++insert_idx;
}
// return if index is after the last path point
if (insert_idx == static_cast<int>(inout_path->points.size())) {
return -1;
}
auto it = inout_path->points.begin() + insert_idx;
inserted_point = inout_path->points.at(closest_idx);
inserted_point.point.pose = in_pose;
inout_path->points.insert(it, inserted_point);
if (isAheadOf(in_pose, inout_path->points.at(closest_idx).point.pose)) {
++insert_idx;
if (insert_idx == static_cast<size_t>(inout_path->points.size())) return -1;
}
setVelocityFrom(insert_idx, safe_vel, inout_path);
// return if index is after the last path point
inserted_point.point.pose = in_pose;
planning_utils::insertVelocity(*inout_path, inserted_point, safe_vel, insert_idx);
return 0;
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -166,22 +166,17 @@ autoware_auto_planning_msgs::msg::PathWithLaneId StopLineModule::insertStopPose(
auto modified_path = path;

// Insert stop pose to between segment start and end
const int insert_index = stop_pose_with_index.index + 1;
size_t insert_index = static_cast<size_t>(stop_pose_with_index.index + 1);
auto stop_point_with_lane_id = modified_path.points.at(insert_index);
stop_point_with_lane_id.point.pose = stop_pose_with_index.pose;
stop_point_with_lane_id.point.longitudinal_velocity_mps = 0.0;

// Update first stop index
first_stop_path_point_index_ = insert_index;
first_stop_path_point_index_ = static_cast<int>(insert_index);
debug_data_.stop_pose = stop_point_with_lane_id.point.pose;

// Insert stop point
modified_path.points.insert(modified_path.points.begin() + insert_index, stop_point_with_lane_id);

// Insert 0 velocity after stop point
for (size_t j = insert_index; j < modified_path.points.size(); ++j) {
modified_path.points.at(j).point.longitudinal_velocity_mps = 0.0;
}
// Insert stop point or replace with zero velocity
planning_utils::insertVelocity(modified_path, stop_point_with_lane_id, 0.0, insert_index);

// Get stop point and stop factor
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -460,23 +460,17 @@ autoware_auto_planning_msgs::msg::PathWithLaneId TrafficLightModule::insertStopP
modified_path = input;

// Create stop pose
const int target_velocity_point_idx = std::max(static_cast<int>(insert_target_point_idx - 1), 0);
size_t target_velocity_point_idx = std::max(static_cast<int>(insert_target_point_idx - 1), 0);
auto target_point_with_lane_id = modified_path.points.at(target_velocity_point_idx);
target_point_with_lane_id.point.pose.position.x = target_point.x();
target_point_with_lane_id.point.pose.position.y = target_point.y();
target_point_with_lane_id.point.longitudinal_velocity_mps = 0.0;

// Insert stop pose into path
modified_path.points.insert(
modified_path.points.begin() + insert_target_point_idx, target_point_with_lane_id);
debug_data_.stop_poses.push_back(target_point_with_lane_id.point.pose);

// insert 0 velocity after target point
for (size_t j = insert_target_point_idx; j < modified_path.points.size(); ++j) {
modified_path.points.at(j).point.longitudinal_velocity_mps = 0.0;
}
if (target_velocity_point_idx < first_stop_path_point_index_) {
first_stop_path_point_index_ = target_velocity_point_idx;
// Insert stop pose into path or replace with zero velocity
planning_utils::insertVelocity(
modified_path, target_point_with_lane_id, 0.0, target_velocity_point_idx);
if (static_cast<int>(target_velocity_point_idx) < first_stop_path_point_index_) {
first_stop_path_point_index_ = static_cast<int>(target_velocity_point_idx);
debug_data_.first_stop_pose = target_point_with_lane_id.point.pose;
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -279,17 +279,11 @@ size_t insertStopVelocityAtCollision(
return 0;
}

const auto insert_index = offset_segment.index + 1;
auto insert_index = static_cast<size_t>(offset_segment.index + 1);
auto insert_point = path->points.at(insert_index);
insert_point.point.pose = interpolated_pose;

path->points.insert(path->points.begin() + insert_index, insert_point);

// Insert 0 velocity after stop point
for (size_t i = insert_index; i < path->points.size(); ++i) {
path->points.at(i).point.longitudinal_velocity_mps = 0.0;
}

// Insert 0 velocity after stop point or replace velocity with 0
behavior_velocity_planner::planning_utils::insertVelocity(*path, insert_point, 0.0, insert_index);
return insert_index;
}
} // namespace
Expand Down
38 changes: 38 additions & 0 deletions planning/behavior_velocity_planner/src/utilization/util.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -59,6 +59,44 @@ SearchRangeIndex getPathIndexRangeIncludeLaneId(
}
return search_range;
}

void setVelocityFromIndex(const size_t begin_idx, const double vel, PathWithLaneId * input)
{
for (size_t i = begin_idx; i < input->points.size(); ++i) {
input->points.at(i).point.longitudinal_velocity_mps =
std::min(static_cast<float>(vel), input->points.at(i).point.longitudinal_velocity_mps);
}
return;
}

void insertVelocity(
PathWithLaneId & path, const PathPointWithLaneId & path_point, const double v,
size_t & insert_index, const double min_distance)
{
bool already_has_path_point = false;
// consider front/back point is near to insert point or not
int min_idx = std::max(0, static_cast<int>(insert_index - 1));
int max_idx =
std::min(static_cast<int>(insert_index + 1), static_cast<int>(path.points.size() - 1));
for (int i = min_idx; i <= max_idx; i++) {
if (
tier4_autoware_utils::calcDistance2d(path.points.at(static_cast<size_t>(i)), path_point) <
min_distance) {
path.points.at(i).point.longitudinal_velocity_mps = 0;
already_has_path_point = true;
insert_index = static_cast<size_t>(i);
// set velocity from is going to insert min velocity later
break;
}
}
//! insert velocity point only if there is no close point on path
if (!already_has_path_point) {
path.points.insert(path.points.begin() + insert_index, path_point);
}
// set zero velocity from insert index
setVelocityFromIndex(insert_index, v, &path);
}

Polygon2d toFootprintPolygon(const autoware_auto_perception_msgs::msg::PredictedObject & object)
{
Polygon2d obj_footprint;
Expand Down

0 comments on commit fa2bca8

Please sign in to comment.