Skip to content

Commit 232d882

Browse files
feat(lane_change): use external velocity limit in safety check (autowarefoundation#6760)
* feat(lane_change): use external velocity limit in safety check Signed-off-by: Muhammad Zulfaqar <zulfaqar.azmi@tier4.jp> * style(pre-commit): autofix * Minor refactoring Signed-off-by: Muhammad Zulfaqar <zulfaqar.azmi@tier4.jp> * Fix spell check and remove headers Signed-off-by: Muhammad Zulfaqar Azmi <zulfaqar.azmi@tier4.jp> * Add warning Signed-off-by: Muhammad Zulfaqar Azmi <zulfaqar.azmi@tier4.jp> --------- Signed-off-by: Muhammad Zulfaqar <zulfaqar.azmi@tier4.jp> Signed-off-by: Muhammad Zulfaqar Azmi <zulfaqar.azmi@tier4.jp> Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>
1 parent 3c28a15 commit 232d882

File tree

3 files changed

+10
-5
lines changed

3 files changed

+10
-5
lines changed

planning/behavior_path_planner_common/include/behavior_path_planner_common/data_manager.hpp

+3
Original file line numberDiff line numberDiff line change
@@ -38,6 +38,7 @@
3838
#include <geometry_msgs/msg/pose_stamped.hpp>
3939
#include <nav_msgs/msg/occupancy_grid.hpp>
4040
#include <nav_msgs/msg/odometry.hpp>
41+
#include <tier4_planning_msgs/msg/detail/velocity_limit__struct.hpp>
4142
#include <tier4_planning_msgs/msg/lateral_offset.hpp>
4243

4344
#include <limits>
@@ -65,6 +66,7 @@ using route_handler::RouteHandler;
6566
using tier4_planning_msgs::msg::LateralOffset;
6667
using PlanResult = PathWithLaneId::SharedPtr;
6768
using lanelet::TrafficLight;
69+
using tier4_planning_msgs::msg::VelocityLimit;
6870
using unique_identifier_msgs::msg::UUID;
6971

7072
struct TrafficSignalStamped
@@ -161,6 +163,7 @@ struct PlannerData
161163
std::map<int64_t, TrafficSignalStamped> traffic_light_id_map;
162164
BehaviorPathPlannerParameters parameters{};
163165
drivable_area_expansion::DrivableAreaExpansionParameters drivable_area_expansion_parameters{};
166+
VelocityLimit::ConstSharedPtr external_limit_max_velocity{};
164167

165168
mutable std::vector<geometry_msgs::msg::Pose> drivable_area_expansion_prev_path_poses{};
166169
mutable std::vector<double> drivable_area_expansion_prev_curvatures{};

planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/path_safety_checker/safety_check.hpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -141,7 +141,7 @@ std::vector<Polygon2d> getCollidedPolygons(
141141
const ExtendedPredictedObject & target_object,
142142
const PredictedPathWithPolygon & target_object_path,
143143
const BehaviorPathPlannerParameters & common_parameters, const RSSparams & rss_parameters,
144-
const double hysteresis_factor, CollisionCheckDebug & debug);
144+
const double hysteresis_factor, const double max_velocity_limit, CollisionCheckDebug & debug);
145145

146146
bool checkPolygonsIntersects(
147147
const std::vector<Polygon2d> & polys_1, const std::vector<Polygon2d> & polys_2);

planning/behavior_path_planner_common/src/utils/path_safety_checker/safety_check.cpp

+6-4
Original file line numberDiff line numberDiff line change
@@ -26,6 +26,8 @@
2626
#include <boost/geometry/algorithms/union.hpp>
2727
#include <boost/geometry/strategies/strategies.hpp>
2828

29+
#include <limits>
30+
2931
namespace behavior_path_planner::utils::path_safety_checker
3032
{
3133

@@ -560,7 +562,7 @@ bool checkCollision(
560562
{
561563
const auto collided_polygons = getCollidedPolygons(
562564
planned_path, predicted_ego_path, target_object, target_object_path, common_parameters,
563-
rss_parameters, hysteresis_factor, debug);
565+
rss_parameters, hysteresis_factor, std::numeric_limits<double>::max(), debug);
564566
return collided_polygons.empty();
565567
}
566568

@@ -570,7 +572,7 @@ std::vector<Polygon2d> getCollidedPolygons(
570572
const ExtendedPredictedObject & target_object,
571573
const PredictedPathWithPolygon & target_object_path,
572574
const BehaviorPathPlannerParameters & common_parameters, const RSSparams & rss_parameters,
573-
double hysteresis_factor, CollisionCheckDebug & debug)
575+
double hysteresis_factor, const double max_velocity_limit, CollisionCheckDebug & debug)
574576
{
575577
{
576578
debug.ego_predicted_path = predicted_ego_path;
@@ -586,7 +588,7 @@ std::vector<Polygon2d> getCollidedPolygons(
586588
// get object information at current time
587589
const auto & obj_pose = obj_pose_with_poly.pose;
588590
const auto & obj_polygon = obj_pose_with_poly.poly;
589-
const auto & object_velocity = obj_pose_with_poly.velocity;
591+
const auto object_velocity = obj_pose_with_poly.velocity;
590592

591593
// get ego information at current time
592594
// Note: we can create these polygons in advance. However, it can decrease the readability and
@@ -599,7 +601,7 @@ std::vector<Polygon2d> getCollidedPolygons(
599601
}
600602
const auto & ego_pose = interpolated_data->pose;
601603
const auto & ego_polygon = interpolated_data->poly;
602-
const auto & ego_velocity = interpolated_data->velocity;
604+
const auto ego_velocity = std::min(interpolated_data->velocity, max_velocity_limit);
603605

604606
// check overlap
605607
if (boost::geometry::overlaps(ego_polygon, obj_polygon)) {

0 commit comments

Comments
 (0)