forked from autowarefoundation/autoware.universe
-
Notifications
You must be signed in to change notification settings - Fork 34
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
Merge pull request #866 from tier4/fix/out-of-lane-beta-v0.11.0
fix(out_of_lane): improve stop decision
- Loading branch information
Showing
13 changed files
with
229 additions
and
136 deletions.
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
84 changes: 84 additions & 0 deletions
84
planning/behavior_velocity_out_of_lane_module/src/calculate_slowdown_points.hpp
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,84 @@ | ||
// Copyright 2023 TIER IV, Inc. | ||
// | ||
// Licensed under the Apache License, Version 2.0 (the "License"); | ||
// you may not use this file except in compliance with the License. | ||
// You may obtain a copy of the License at | ||
// | ||
// http://www.apache.org/licenses/LICENSE-2.0 | ||
// | ||
// Unless required by applicable law or agreed to in writing, software | ||
// distributed under the License is distributed on an "AS IS" BASIS, | ||
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. | ||
// See the License for the specific language governing permissions and | ||
// limitations under the License. | ||
|
||
#ifndef CALCULATE_SLOWDOWN_POINTS_HPP_ | ||
#define CALCULATE_SLOWDOWN_POINTS_HPP_ | ||
|
||
#include "footprint.hpp" | ||
#include "types.hpp" | ||
|
||
#include <motion_utils/trajectory/trajectory.hpp> | ||
|
||
#include <optional> | ||
#include <vector> | ||
|
||
namespace behavior_velocity_planner::out_of_lane | ||
{ | ||
|
||
bool can_decelerate( | ||
const EgoData & ego_data, const PathPointWithLaneId & point, const double target_vel) | ||
{ | ||
if (ego_data.velocity < 0.5) return true; | ||
const auto dist_ahead_of_ego = motion_utils::calcSignedArcLength( | ||
ego_data.path.points, ego_data.pose.position, point.point.pose.position); | ||
const auto acc_to_target_vel = | ||
(ego_data.velocity * ego_data.velocity - target_vel * target_vel) / (2 * dist_ahead_of_ego); | ||
return acc_to_target_vel < std::abs(ego_data.max_decel); | ||
} | ||
|
||
std::optional<PathPointWithLaneId> calculate_last_in_lane_pose( | ||
const EgoData & ego_data, const Slowdown & decision, const Polygon2d & footprint, | ||
const PlannerParam & params) | ||
{ | ||
const auto from_arc_length = | ||
motion_utils::calcSignedArcLength(ego_data.path.points, 0, ego_data.first_path_idx); | ||
const auto to_arc_length = | ||
motion_utils::calcSignedArcLength(ego_data.path.points, 0, decision.target_path_idx); | ||
PathPointWithLaneId interpolated_point; | ||
for (auto l = to_arc_length - params.precision; l > from_arc_length; l -= params.precision) { | ||
// TODO(Maxime): binary search | ||
interpolated_point.point.pose = motion_utils::calcInterpolatedPose(ego_data.path.points, l); | ||
const auto respect_decel_limit = | ||
!params.skip_if_over_max_decel || | ||
can_decelerate(ego_data, interpolated_point, decision.velocity); | ||
if ( | ||
respect_decel_limit && !boost::geometry::overlaps( | ||
project_to_pose(footprint, interpolated_point.point.pose), | ||
decision.lane_to_avoid.polygon2d().basicPolygon())) | ||
return interpolated_point; | ||
} | ||
return std::nullopt; | ||
} | ||
|
||
/// @brief calculate the slowdown point to insert in the path | ||
/// @param ego_data ego data (path, velocity, etc) | ||
/// @param decisions decision (before which point to stop, what lane to avoid entering, etc) | ||
/// @param params parameters | ||
/// @return optional slowdown point to insert in the path | ||
std::optional<SlowdownToInsert> calculate_slowdown_point( | ||
const EgoData & ego_data, const std::vector<Slowdown> & decisions, PlannerParam params) | ||
{ | ||
params.extra_front_offset += params.dist_buffer; | ||
const auto base_footprint = make_base_footprint(params); | ||
|
||
// search for the first slowdown decision for which a stop point can be inserted | ||
for (const auto & decision : decisions) { | ||
const auto last_in_lane_pose = | ||
calculate_last_in_lane_pose(ego_data, decision, base_footprint, params); | ||
if (last_in_lane_pose) return SlowdownToInsert{decision, *last_in_lane_pose}; | ||
} | ||
return std::nullopt; | ||
} | ||
} // namespace behavior_velocity_planner::out_of_lane | ||
#endif // CALCULATE_SLOWDOWN_POINTS_HPP_ |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
68 changes: 68 additions & 0 deletions
68
planning/behavior_velocity_out_of_lane_module/src/filter_predicted_objects.hpp
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,68 @@ | ||
// Copyright 2023 TIER IV, Inc. | ||
// | ||
// Licensed under the Apache License, Version 2.0 (the "License"); | ||
// you may not use this file except in compliance with the License. | ||
// You may obtain a copy of the License at | ||
// | ||
// http://www.apache.org/licenses/LICENSE-2.0 | ||
// | ||
// Unless required by applicable law or agreed to in writing, software | ||
// distributed under the License is distributed on an "AS IS" BASIS, | ||
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. | ||
// See the License for the specific language governing permissions and | ||
// limitations under the License. | ||
|
||
#ifndef FILTER_PREDICTED_OBJECTS_HPP_ | ||
#define FILTER_PREDICTED_OBJECTS_HPP_ | ||
|
||
#include "types.hpp" | ||
|
||
#include <string> | ||
|
||
namespace behavior_velocity_planner::out_of_lane | ||
{ | ||
/// @brief filter predicted objects and their predicted paths | ||
/// @param [in] objects predicted objects to filter | ||
/// @param [in] ego_data ego data | ||
/// @param [in] params parameters | ||
/// @return filtered predicted objects | ||
autoware_auto_perception_msgs::msg::PredictedObjects filter_predicted_objects( | ||
const autoware_auto_perception_msgs::msg::PredictedObjects & objects, const EgoData & ego_data, | ||
const PlannerParam & params) | ||
{ | ||
autoware_auto_perception_msgs::msg::PredictedObjects filtered_objects; | ||
filtered_objects.header = objects.header; | ||
for (const auto & object : objects.objects) { | ||
const auto is_pedestrian = | ||
std::find_if(object.classification.begin(), object.classification.end(), [](const auto & c) { | ||
return c.label == autoware_auto_perception_msgs::msg::ObjectClassification::PEDESTRIAN; | ||
}) != object.classification.end(); | ||
if (is_pedestrian) continue; | ||
|
||
auto filtered_object = object; | ||
const auto is_invalid_predicted_path = [&](const auto & predicted_path) { | ||
const auto is_low_confidence = predicted_path.confidence < params.objects_min_confidence; | ||
const auto lat_offset_to_current_ego = | ||
std::abs(motion_utils::calcLateralOffset(predicted_path.path, ego_data.pose.position)); | ||
const auto is_crossing_ego = | ||
lat_offset_to_current_ego <= | ||
object.shape.dimensions.y / 2.0 + std::max( | ||
params.left_offset + params.extra_left_offset, | ||
params.right_offset + params.extra_right_offset); | ||
return is_low_confidence || is_crossing_ego; | ||
}; | ||
if (params.objects_use_predicted_paths) { | ||
auto & predicted_paths = filtered_object.kinematics.predicted_paths; | ||
const auto new_end = | ||
std::remove_if(predicted_paths.begin(), predicted_paths.end(), is_invalid_predicted_path); | ||
predicted_paths.erase(new_end, predicted_paths.end()); | ||
} | ||
if (!params.objects_use_predicted_paths || !filtered_object.kinematics.predicted_paths.empty()) | ||
filtered_objects.objects.push_back(filtered_object); | ||
} | ||
return filtered_objects; | ||
} | ||
|
||
} // namespace behavior_velocity_planner::out_of_lane | ||
|
||
#endif // FILTER_PREDICTED_OBJECTS_HPP_ |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Oops, something went wrong.