Skip to content

Commit b09501e

Browse files
feat(lane_change): use external velocity limit in safety check (#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 d682442 commit b09501e

File tree

7 files changed

+48
-6
lines changed

7 files changed

+48
-6
lines changed

planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/scene.hpp

+2
Original file line numberDiff line numberDiff line change
@@ -172,6 +172,8 @@ class NormalLaneChange : public LaneChangeBase
172172
bool isVehicleStuck(
173173
const lanelet::ConstLanelets & current_lanes, const double obstacle_check_distance) const;
174174

175+
double get_max_velocity_for_safety_check() const;
176+
175177
bool isVehicleStuck(const lanelet::ConstLanelets & current_lanes) const;
176178

177179
bool check_prepare_phase() const;

planning/behavior_path_lane_change_module/src/scene.cpp

+12-1
Original file line numberDiff line numberDiff line change
@@ -1967,7 +1967,7 @@ PathSafetyStatus NormalLaneChange::isLaneChangePathSafe(
19671967
for (const auto & obj_path : obj_predicted_paths) {
19681968
const auto collided_polygons = utils::path_safety_checker::getCollidedPolygons(
19691969
path, ego_predicted_path, obj, obj_path, common_parameters, rss_params, 1.0,
1970-
current_debug_data.second);
1970+
get_max_velocity_for_safety_check(), current_debug_data.second);
19711971

19721972
if (collided_polygons.empty()) {
19731973
utils::path_safety_checker::updateCollisionCheckDebugMap(
@@ -2062,6 +2062,17 @@ bool NormalLaneChange::isVehicleStuck(
20622062
return false;
20632063
}
20642064

2065+
double NormalLaneChange::get_max_velocity_for_safety_check() const
2066+
{
2067+
const auto external_velocity_limit_ptr = planner_data_->external_limit_max_velocity;
2068+
if (external_velocity_limit_ptr) {
2069+
return std::min(
2070+
static_cast<double>(external_velocity_limit_ptr->max_velocity), getCommonParam().max_vel);
2071+
}
2072+
2073+
return getCommonParam().max_vel;
2074+
}
2075+
20652076
bool NormalLaneChange::isVehicleStuck(const lanelet::ConstLanelets & current_lanes) const
20662077
{
20672078
if (current_lanes.empty()) {

planning/behavior_path_planner/include/behavior_path_planner/behavior_path_planner_node.hpp

+6
Original file line numberDiff line numberDiff line change
@@ -40,6 +40,7 @@
4040
#include <tier4_planning_msgs/msg/reroute_availability.hpp>
4141
#include <tier4_planning_msgs/msg/scenario.hpp>
4242
#include <tier4_planning_msgs/msg/stop_reason_array.hpp>
43+
#include <tier4_planning_msgs/msg/velocity_limit.hpp>
4344
#include <visualization_msgs/msg/marker.hpp>
4445

4546
#include <map>
@@ -103,6 +104,8 @@ class BehaviorPathPlannerNode : public rclcpp::Node
103104
rclcpp::Publisher<PoseWithUuidStamped>::SharedPtr modified_goal_publisher_;
104105
rclcpp::Publisher<StopReasonArray>::SharedPtr stop_reason_publisher_;
105106
rclcpp::Publisher<RerouteAvailability>::SharedPtr reroute_availability_publisher_;
107+
rclcpp::Subscription<tier4_planning_msgs::msg::VelocityLimit>::SharedPtr
108+
external_limit_max_velocity_subscriber_;
106109
rclcpp::TimerBase::SharedPtr timer_;
107110

108111
std::map<std::string, rclcpp::Publisher<Path>::SharedPtr> path_candidate_publishers_;
@@ -142,6 +145,9 @@ class BehaviorPathPlannerNode : public rclcpp::Node
142145
void onRoute(const LaneletRoute::ConstSharedPtr route_msg);
143146
void onOperationMode(const OperationModeState::ConstSharedPtr msg);
144147
void onLateralOffset(const LateralOffset::ConstSharedPtr msg);
148+
void on_external_velocity_limiter(
149+
const tier4_planning_msgs::msg::VelocityLimit::ConstSharedPtr msg);
150+
145151
SetParametersResult onSetParam(const std::vector<rclcpp::Parameter> & parameters);
146152

147153
OnSetParametersCallbackHandle::SharedPtr m_set_param_res;

planning/behavior_path_planner/src/behavior_path_planner_node.cpp

+18
Original file line numberDiff line numberDiff line change
@@ -112,6 +112,11 @@ BehaviorPathPlannerNode::BehaviorPathPlannerNode(const rclcpp::NodeOptions & nod
112112
current_scenario_ = std::make_shared<Scenario>(*msg);
113113
},
114114
createSubscriptionOptions(this));
115+
external_limit_max_velocity_subscriber_ =
116+
create_subscription<tier4_planning_msgs::msg::VelocityLimit>(
117+
"/planning/scenario_planning/max_velocity", 1,
118+
std::bind(&BehaviorPathPlannerNode::on_external_velocity_limiter, this, _1),
119+
createSubscriptionOptions(this));
115120

116121
// route_handler
117122
vector_map_subscriber_ = create_subscription<HADMapBin>(
@@ -821,6 +826,19 @@ void BehaviorPathPlannerNode::onOperationMode(const OperationModeState::ConstSha
821826
const std::lock_guard<std::mutex> lock(mutex_pd_);
822827
planner_data_->operation_mode = msg;
823828
}
829+
830+
void BehaviorPathPlannerNode::on_external_velocity_limiter(
831+
const tier4_planning_msgs::msg::VelocityLimit::ConstSharedPtr msg)
832+
{
833+
// Note: Using this parameter during path planning might cause unexpected deceleration or jerk.
834+
// Therefore, do not use it for anything other than safety checks.
835+
if (!msg) {
836+
return;
837+
}
838+
839+
const std::lock_guard<std::mutex> lock(mutex_pd_);
840+
planner_data_->external_limit_max_velocity = msg;
841+
}
824842
void BehaviorPathPlannerNode::onLateralOffset(const LateralOffset::ConstSharedPtr msg)
825843
{
826844
std::lock_guard<std::mutex> lock(mutex_pd_);

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)