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

feat(lane_change): use external velocity limit in safety check #6760

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 @@ -172,6 +172,8 @@ class NormalLaneChange : public LaneChangeBase
bool isVehicleStuck(
const lanelet::ConstLanelets & current_lanes, const double obstacle_check_distance) const;

double get_max_velocity_for_safety_check() const;

bool isVehicleStuck(const lanelet::ConstLanelets & current_lanes) const;

bool check_prepare_phase() const;
Expand Down
13 changes: 12 additions & 1 deletion planning/behavior_path_lane_change_module/src/scene.cpp
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
// Copyright 2023 TIER IV, Inc.

Check notice on line 1 in planning/behavior_path_lane_change_module/src/scene.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

ℹ Getting worse: Lines of Code in a Single File

The lines of code increases from 1675 to 1684, improve code health by reducing it to 1000. The number of Lines of Code in a single file. More Lines of Code lowers the code health.

Check notice on line 1 in planning/behavior_path_lane_change_module/src/scene.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

✅ Getting better: Overall Code Complexity

The mean cyclomatic complexity decreases from 5.42 to 5.35, threshold = 4. This file has many conditional statements (e.g. if, for, while) across its implementation, leading to lower code health. Avoid adding more conditionals.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
Expand Down Expand Up @@ -1967,7 +1967,7 @@
for (const auto & obj_path : obj_predicted_paths) {
const auto collided_polygons = utils::path_safety_checker::getCollidedPolygons(
path, ego_predicted_path, obj, obj_path, common_parameters, rss_params, 1.0,
current_debug_data.second);
get_max_velocity_for_safety_check(), current_debug_data.second);

if (collided_polygons.empty()) {
utils::path_safety_checker::updateCollisionCheckDebugMap(
Expand Down Expand Up @@ -2062,6 +2062,17 @@
return false;
}

double NormalLaneChange::get_max_velocity_for_safety_check() const
{
const auto external_velocity_limit_ptr = planner_data_->external_limit_max_velocity;
if (external_velocity_limit_ptr) {
return std::min(
static_cast<double>(external_velocity_limit_ptr->max_velocity), getCommonParam().max_vel);
}

return getCommonParam().max_vel;
}

bool NormalLaneChange::isVehicleStuck(const lanelet::ConstLanelets & current_lanes) const
{
if (current_lanes.empty()) {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -40,6 +40,7 @@
#include <tier4_planning_msgs/msg/reroute_availability.hpp>
#include <tier4_planning_msgs/msg/scenario.hpp>
#include <tier4_planning_msgs/msg/stop_reason_array.hpp>
#include <tier4_planning_msgs/msg/velocity_limit.hpp>
#include <visualization_msgs/msg/marker.hpp>

#include <map>
Expand Down Expand Up @@ -103,6 +104,8 @@ class BehaviorPathPlannerNode : public rclcpp::Node
rclcpp::Publisher<PoseWithUuidStamped>::SharedPtr modified_goal_publisher_;
rclcpp::Publisher<StopReasonArray>::SharedPtr stop_reason_publisher_;
rclcpp::Publisher<RerouteAvailability>::SharedPtr reroute_availability_publisher_;
rclcpp::Subscription<tier4_planning_msgs::msg::VelocityLimit>::SharedPtr
external_limit_max_velocity_subscriber_;
rclcpp::TimerBase::SharedPtr timer_;

std::map<std::string, rclcpp::Publisher<Path>::SharedPtr> path_candidate_publishers_;
Expand Down Expand Up @@ -142,6 +145,9 @@ class BehaviorPathPlannerNode : public rclcpp::Node
void onRoute(const LaneletRoute::ConstSharedPtr route_msg);
void onOperationMode(const OperationModeState::ConstSharedPtr msg);
void onLateralOffset(const LateralOffset::ConstSharedPtr msg);
void on_external_velocity_limiter(
const tier4_planning_msgs::msg::VelocityLimit::ConstSharedPtr msg);

SetParametersResult onSetParam(const std::vector<rclcpp::Parameter> & parameters);

OnSetParametersCallbackHandle::SharedPtr m_set_param_res;
Expand Down
18 changes: 18 additions & 0 deletions planning/behavior_path_planner/src/behavior_path_planner_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -112,6 +112,11 @@
current_scenario_ = std::make_shared<Scenario>(*msg);
},
createSubscriptionOptions(this));
external_limit_max_velocity_subscriber_ =
create_subscription<tier4_planning_msgs::msg::VelocityLimit>(
"/planning/scenario_planning/max_velocity", 1,
std::bind(&BehaviorPathPlannerNode::on_external_velocity_limiter, this, _1),
createSubscriptionOptions(this));

Check warning on line 119 in planning/behavior_path_planner/src/behavior_path_planner_node.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ Getting worse: Large Method

BehaviorPathPlannerNode::BehaviorPathPlannerNode increases from 104 to 109 lines of code, threshold = 70. Large functions with many lines of code are generally harder to understand and lower the code health. Avoid adding more lines to this function.

// route_handler
vector_map_subscriber_ = create_subscription<HADMapBin>(
Expand Down Expand Up @@ -817,6 +822,19 @@
const std::lock_guard<std::mutex> lock(mutex_pd_);
planner_data_->operation_mode = msg;
}

void BehaviorPathPlannerNode::on_external_velocity_limiter(
const tier4_planning_msgs::msg::VelocityLimit::ConstSharedPtr msg)
{
// Note: Using this parameter during path planning might cause unexpected deceleration or jerk.
// Therefore, do not use it for anything other than safety checks.
if (!msg) {
return;
}

const std::lock_guard<std::mutex> lock(mutex_pd_);
planner_data_->external_limit_max_velocity = msg;
}
void BehaviorPathPlannerNode::onLateralOffset(const LateralOffset::ConstSharedPtr msg)
{
std::lock_guard<std::mutex> lock(mutex_pd_);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -38,6 +38,7 @@
#include <geometry_msgs/msg/pose_stamped.hpp>
#include <nav_msgs/msg/occupancy_grid.hpp>
#include <nav_msgs/msg/odometry.hpp>
#include <tier4_planning_msgs/msg/detail/velocity_limit__struct.hpp>
#include <tier4_planning_msgs/msg/lateral_offset.hpp>

#include <limits>
Expand Down Expand Up @@ -65,6 +66,7 @@ using route_handler::RouteHandler;
using tier4_planning_msgs::msg::LateralOffset;
using PlanResult = PathWithLaneId::SharedPtr;
using lanelet::TrafficLight;
using tier4_planning_msgs::msg::VelocityLimit;
using unique_identifier_msgs::msg::UUID;

struct TrafficSignalStamped
Expand Down Expand Up @@ -161,6 +163,7 @@ struct PlannerData
std::map<int64_t, TrafficSignalStamped> traffic_light_id_map;
BehaviorPathPlannerParameters parameters{};
drivable_area_expansion::DrivableAreaExpansionParameters drivable_area_expansion_parameters{};
VelocityLimit::ConstSharedPtr external_limit_max_velocity{};

mutable std::vector<geometry_msgs::msg::Pose> drivable_area_expansion_prev_path_poses{};
mutable std::vector<double> drivable_area_expansion_prev_curvatures{};
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -141,7 +141,7 @@ std::vector<Polygon2d> getCollidedPolygons(
const ExtendedPredictedObject & target_object,
const PredictedPathWithPolygon & target_object_path,
const BehaviorPathPlannerParameters & common_parameters, const RSSparams & rss_parameters,
const double hysteresis_factor, CollisionCheckDebug & debug);
const double hysteresis_factor, const double max_velocity_limit, CollisionCheckDebug & debug);

bool checkPolygonsIntersects(
const std::vector<Polygon2d> & polys_1, const std::vector<Polygon2d> & polys_2);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -26,6 +26,8 @@
#include <boost/geometry/algorithms/union.hpp>
#include <boost/geometry/strategies/strategies.hpp>

#include <limits>

namespace behavior_path_planner::utils::path_safety_checker
{

Expand Down Expand Up @@ -560,7 +562,7 @@ bool checkCollision(
{
const auto collided_polygons = getCollidedPolygons(
planned_path, predicted_ego_path, target_object, target_object_path, common_parameters,
rss_parameters, hysteresis_factor, debug);
rss_parameters, hysteresis_factor, std::numeric_limits<double>::max(), debug);
return collided_polygons.empty();
}

Expand All @@ -570,7 +572,7 @@ std::vector<Polygon2d> getCollidedPolygons(
const ExtendedPredictedObject & target_object,
const PredictedPathWithPolygon & target_object_path,
const BehaviorPathPlannerParameters & common_parameters, const RSSparams & rss_parameters,
double hysteresis_factor, CollisionCheckDebug & debug)
double hysteresis_factor, const double max_velocity_limit, CollisionCheckDebug & debug)
{
{
debug.ego_predicted_path = predicted_ego_path;
Expand All @@ -586,7 +588,7 @@ std::vector<Polygon2d> getCollidedPolygons(
// get object information at current time
const auto & obj_pose = obj_pose_with_poly.pose;
const auto & obj_polygon = obj_pose_with_poly.poly;
const auto & object_velocity = obj_pose_with_poly.velocity;
const auto object_velocity = obj_pose_with_poly.velocity;

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

// check overlap
if (boost::geometry::overlaps(ego_polygon, obj_polygon)) {
Expand Down
Loading