Skip to content

Commit

Permalink
Merge pull request #1241 from tier4/cp-lane-change
Browse files Browse the repository at this point in the history
fix(lane_change):  cherry  pick small fixes
  • Loading branch information
shmpwk authored Apr 12, 2024
2 parents cbd60c6 + 071333e commit fbd9183
Show file tree
Hide file tree
Showing 13 changed files with 91 additions and 8 deletions.
3 changes: 2 additions & 1 deletion planning/behavior_path_lane_change_module/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -524,7 +524,8 @@ The following parameters are configurable in [lane_change.param.yaml](https://gi
| Name | Unit | Type | Description | Default value |
| :------------------------------------------------------- | ----- | ------- | ---------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | ------------- |
| `enable_collision_check_for_prepare_phase.general_lanes` | [-] | boolean | Perform collision check starting from the prepare phase for situations not explicitly covered by other settings (e.g., intersections). If `false`, collision check only evaluated for lane changing phase. | false |
| `enable_collision_check_for_prepare_phase.intersection` | [-] | boolean | Perform collision check starting from prepare phase when ego is in intersection. If `false`, collision check only evaluated for lane changing phase. | false |
| `enable_collision_check_for_prepare_phase.intersection` | [-] | boolean | Perform collision check starting from prepare phase when ego is in intersection. If `false`, collision check only evaluated for lane changing phase. | true |
| `enable_collision_check_for_prepare_phase.turns` | [-] | boolean | Perform collision check starting from prepare phase when ego is in lanelet with turn direction tags. If `false`, collision check only evaluated for lane changing phase. | true |
| `prepare_phase_ignore_target_speed_thresh` | [m/s] | double | Ignore collision check in prepare phase of object speed that is lesser that the configured value. `enable_collision_check_at_prepare_phase` must be `true` | 0.1 |
| `check_objects_on_current_lanes` | [-] | boolean | If true, the lane change module check objects on current lanes when performing collision assessment. | false |
| `check_objects_on_other_lanes` | [-] | boolean | If true, the lane change module include objects on other lanes. when performing collision assessment | false |
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -92,6 +92,7 @@
enable_collision_check_for_prepare_phase:
general_lanes: false
intersection: true
turns: true
prepare_segment_ignore_object_velocity_thresh: 0.1 # [m/s]
check_objects_on_current_lanes: true
check_objects_on_other_lanes: true
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -170,6 +170,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
Original file line number Diff line number Diff line change
Expand Up @@ -109,6 +109,7 @@ struct LaneChangeParameters
// collision check
bool enable_collision_check_for_prepare_phase_in_general_lanes{false};
bool enable_collision_check_for_prepare_phase_in_intersection{true};
bool enable_collision_check_for_prepare_phase_in_turns{true};
double prepare_segment_ignore_object_velocity_thresh{0.1};
bool check_objects_on_current_lanes{true};
bool check_objects_on_other_lanes{true};
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -262,6 +262,21 @@ bool isWithinIntersection(
const std::shared_ptr<RouteHandler> & route_handler, const lanelet::ConstLanelet & lanelet,
const Polygon2d & polygon);

/**
* @brief Determines if a polygon is within lanes designated for turning.
*
* Checks if a polygon overlaps with lanelets tagged for turning directions (excluding 'straight').
* It evaluates the lanelet's 'turn_direction' attribute and determines overlap with the lanelet's
* area.
*
* @param lanelet Lanelet representing the road segment whose turn direction is to be evaluated.
* @param polygon The polygon to be checked for its presence within turn direction lanes.
*
* @return bool True if the polygon is within a lane designated for turning, false if it is within a
* straight lane or no turn direction is specified.
*/
bool isWithinTurnDirectionLanes(const lanelet::ConstLanelet & lanelet, const Polygon2d & polygon);

/**
* @brief Calculates the distance required during a lane change operation.
*
Expand Down
2 changes: 2 additions & 0 deletions planning/behavior_path_lane_change_module/src/manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -72,6 +72,8 @@ void LaneChangeModuleManager::initParams(rclcpp::Node * node)
*node, parameter("enable_collision_check_for_prepare_phase.general_lanes"));
p.enable_collision_check_for_prepare_phase_in_intersection = getOrDeclareParameter<bool>(
*node, parameter("enable_collision_check_for_prepare_phase.intersection"));
p.enable_collision_check_for_prepare_phase_in_turns =
getOrDeclareParameter<bool>(*node, parameter("enable_collision_check_for_prepare_phase.turns"));
p.prepare_segment_ignore_object_velocity_thresh = getOrDeclareParameter<double>(
*node, parameter("prepare_segment_ignore_object_velocity_thresh"));
p.check_objects_on_current_lanes =
Expand Down
23 changes: 21 additions & 2 deletions planning/behavior_path_lane_change_module/src/scene.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1976,7 +1976,7 @@ PathSafetyStatus NormalLaneChange::isLaneChangePathSafe(
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 @@ -2071,6 +2071,17 @@ bool NormalLaneChange::isVehicleStuck(
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 Expand Up @@ -2147,7 +2158,15 @@ bool NormalLaneChange::check_prepare_phase() const
return utils::lane_change::isWithinIntersection(route_handler, current_lane, ego_footprint);
});

return check_in_intersection || check_in_general_lanes;
const auto check_in_turns = std::invoke([&]() {
if (!lane_change_parameters_->enable_collision_check_for_prepare_phase_in_turns) {
return false;
}

return utils::lane_change::isWithinTurnDirectionLanes(current_lane, ego_footprint);
});

return check_in_intersection || check_in_turns || check_in_general_lanes;
}

} // namespace behavior_path_planner
13 changes: 13 additions & 0 deletions planning/behavior_path_lane_change_module/src/utils/utils.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -37,6 +37,8 @@

#include <geometry_msgs/msg/detail/pose__struct.hpp>

#include <boost/geometry/algorithms/detail/disjoint/interface.hpp>

#include <lanelet2_core/LaneletMap.h>
#include <lanelet2_core/geometry/LineString.h>
#include <lanelet2_core/geometry/Point.h>
Expand Down Expand Up @@ -1222,6 +1224,17 @@ bool isWithinIntersection(
polygon, utils::toPolygon2d(lanelet::utils::to2D(lanelet_polygon.basicPolygon())));
}

bool isWithinTurnDirectionLanes(const lanelet::ConstLanelet & lanelet, const Polygon2d & polygon)
{
const std::string turn_direction = lanelet.attributeOr("turn_direction", "else");
if (turn_direction == "else" || turn_direction == "straight") {
return false;
}

return !boost::geometry::disjoint(
polygon, utils::toPolygon2d(lanelet::utils::to2D(lanelet.polygon2d().basicPolygon())));
}

double calcPhaseLength(
const double velocity, const double maximum_velocity, const double acceleration,
const double duration)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -38,6 +38,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 @@ -101,6 +102,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 @@ -140,6 +143,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 @@ BehaviorPathPlannerNode::BehaviorPathPlannerNode(const rclcpp::NodeOptions & nod
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));

// route_handler
vector_map_subscriber_ = create_subscription<HADMapBin>(
Expand Down Expand Up @@ -815,6 +820,19 @@ void BehaviorPathPlannerNode::onOperationMode(const OperationModeState::ConstSha
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 @@ -37,6 +37,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 @@ -64,6 +65,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 @@ -160,6 +162,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 @@ -478,7 +480,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 @@ -488,7 +490,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 @@ -504,7 +506,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 @@ -517,7 +519,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

0 comments on commit fbd9183

Please sign in to comment.