Skip to content

Commit

Permalink
feat(lane_change): fix safety check functions (#661)
Browse files Browse the repository at this point in the history
* update

Signed-off-by: yutaka <purewater0901@gmail.com>

* update

Signed-off-by: yutaka <purewater0901@gmail.com>

* update

Signed-off-by: yutaka <purewater0901@gmail.com>

* update

Signed-off-by: yutaka <purewater0901@gmail.com>

* fix(lane_change): fix activation timing of the  passParkedObject funtion (autowarefoundation#4239)

fix(lane_change): fix activation timing of the  passParkedObject function

Signed-off-by: yutaka <purewater0901@gmail.com>

* update

Signed-off-by: yutaka <purewater0901@gmail.com>

---------

Signed-off-by: yutaka <purewater0901@gmail.com>
Co-authored-by: Kyoichi Sugahara <kyoichi.sugahara@tier4.jp>
Co-authored-by: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com>
  • Loading branch information
3 people authored Jul 14, 2023
1 parent 828c6e9 commit 6a02360
Show file tree
Hide file tree
Showing 16 changed files with 635 additions and 518 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -463,6 +463,33 @@ The following parameters are configurable in `lane_change.param.yaml`.

## Debug Marker & Visualization

To enable the debug marker, execute `ros2 param set /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner lane_change.publish_debug_marker true` (no restart is needed) or simply set the `publish_debug_marker` to `true` in the `lane_change.param.yaml` for permanent effect (restart is needed). Then add the marker `/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/debug/lanechange` in `rviz2`.
To enable the debug marker, execute (no restart is needed)

![debug](../image/lane_change/lane_change-debug.png)
```shell
ros2 param set /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner lane_change.publish_debug_marker true

```

or simply set the `publish_debug_marker` to `true` in the `lane_change.param.yaml` for permanent effect (restart is needed).

Then add the marker

```shell
/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/debug/lane_change_left
```

in `rviz2`.

![debug](../image/lane_change/lane_change-debug-1.png)

![debug2](../image/lane_change/lane_change-debug-2.png)

![debug3](../image/lane_change/lane_change-debug-3.png)

Available information

1. Ego to object relation, plus safety check information
2. Ego vehicle interpolated pose up to the latest safety check position.
3. Object is safe or not, shown by the color of the polygon (Green = Safe, Red = unsafe)
4. Valid candidate paths.
5. Position when lane changing start and end.
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Binary file not shown.
Original file line number Diff line number Diff line change
Expand Up @@ -57,6 +57,10 @@ struct CollisionCheckDebug
Pose expected_ego_pose{};
Pose expected_obj_pose{};
Pose relative_to_ego{};
double rss_longitudinal{0.0};
double ego_to_obj_margin{0.0};
double longitudinal_offset{0.0};
double lateral_offset{0.0};
bool is_front{false};
bool allow_lane_change{false};
std::vector<Pose> lerped_path;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -27,6 +27,51 @@
namespace behavior_path_planner
{

struct PoseWithVelocity
{
Pose pose;
double velocity;

PoseWithVelocity(const Pose & pose, const double velocity) : pose(pose), velocity(velocity) {}
};

struct PoseWithVelocityStamped : public PoseWithVelocity
{
double time;

PoseWithVelocityStamped(const double time, const Pose & pose, const double velocity)
: PoseWithVelocity(pose, velocity), time(time)
{
}
};

struct PoseWithVelocityAndPolygonStamped : public PoseWithVelocityStamped
{
Polygon2d poly;

PoseWithVelocityAndPolygonStamped(
const double time, const Pose & pose, const double velocity, const Polygon2d & poly)
: PoseWithVelocityStamped(time, pose, velocity), poly(poly)
{
}
};

struct PredictedPathWithPolygon
{
float confidence;
std::vector<PoseWithVelocityAndPolygonStamped> path;
};

struct ExtendedPredictedObject
{
unique_identifier_msgs::msg::UUID uuid;
geometry_msgs::msg::PoseWithCovariance initial_pose;
geometry_msgs::msg::TwistWithCovariance initial_twist;
geometry_msgs::msg::AccelWithCovariance initial_acceleration;
autoware_auto_perception_msgs::msg::Shape shape;
std::vector<PredictedPathWithPolygon> predicted_paths;
};

struct LaneChangeCancelParameters
{
bool enable_on_prepare_phase{true};
Expand Down Expand Up @@ -108,6 +153,13 @@ struct LaneChangeTargetObjectIndices
std::vector<size_t> other_lane{};
};

struct LaneChangeTargetObjects
{
std::vector<ExtendedPredictedObject> current_lane{};
std::vector<ExtendedPredictedObject> target_lane{};
std::vector<ExtendedPredictedObject> other_lane{};
};

enum class LaneChangeModuleType {
NORMAL = 0,
EXTERNAL_REQUEST,
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,7 @@
#include "behavior_path_planner/parameters.hpp"
#include "behavior_path_planner/utils/lane_change/lane_change_module_data.hpp"
#include "behavior_path_planner/utils/lane_change/lane_change_path.hpp"
#include "behavior_path_planner/utils/safety_check.hpp"
#include "behavior_path_planner/utils/utils.hpp"

#include <route_handler/route_handler.hpp>
Expand All @@ -42,6 +43,9 @@ using autoware_auto_perception_msgs::msg::PredictedObject;
using autoware_auto_perception_msgs::msg::PredictedObjects;
using autoware_auto_perception_msgs::msg::PredictedPath;
using autoware_auto_planning_msgs::msg::PathWithLaneId;
using behavior_path_planner::ExtendedPredictedObject;
using behavior_path_planner::PoseWithVelocityAndPolygonStamped;
using behavior_path_planner::PredictedPathWithPolygon;
using data::lane_change::PathSafetyStatus;
using geometry_msgs::msg::Point;
using geometry_msgs::msg::Pose;
Expand Down Expand Up @@ -96,19 +100,12 @@ std::optional<LaneChangePath> constructCandidatePath(
const double terminal_lane_changing_velocity, const LaneChangePhaseInfo lane_change_time);

PathSafetyStatus isLaneChangePathSafe(
const LaneChangePath & lane_change_path, const PredictedObjects::ConstSharedPtr dynamic_objects,
const LaneChangeTargetObjectIndices & dynamic_object_indices, const Pose & current_pose,
const Twist & current_twist, const BehaviorPathPlannerParameters & common_parameter,
const LaneChangePath & lane_change_path, const LaneChangeTargetObjects & target_objects,
const Pose & current_pose, const Twist & current_twist,
const BehaviorPathPlannerParameters & common_parameter,
const behavior_path_planner::LaneChangeParameters & lane_change_parameter,
const double front_decel, const double rear_decel,
std::unordered_map<std::string, CollisionCheckDebug> & debug_data, const double prepare_acc,
const double lane_changing_acc);

bool isObjectIndexIncluded(
const size_t & index, const std::vector<size_t> & dynamic_objects_indices);

bool isObjectIndexIncluded(
const size_t & index, const std::vector<size_t> & dynamic_objects_indices);
std::unordered_map<std::string, CollisionCheckDebug> & debug_data);

bool hasEnoughLength(
const LaneChangePath & path, const lanelet::ConstLanelets & current_lanes,
Expand Down Expand Up @@ -170,21 +167,32 @@ boost::optional<lanelet::ConstLanelet> getLaneChangeTargetLane(
const RouteHandler & route_handler, const lanelet::ConstLanelets & current_lanes,
const LaneChangeModuleType type, const Direction & direction);

std::vector<PoseWithVelocityStamped> convertToPredictedPath(
const LaneChangePath & lane_change_path, const Twist & vehicle_twist, const Pose & pose,
const BehaviorPathPlannerParameters & common_parameter, const double resolution);

PredictedPath convertToPredictedPath(
const PathWithLaneId & path, const Twist & vehicle_twist, const Pose & pose,
const size_t nearest_seg_idx, const double duration, const double resolution,
const double prepare_time, const double prepare_acc, const double lane_changing_acc);
const std::vector<PoseWithVelocityStamped> & path, const double time_resolution);

bool isParkedObject(
const PathWithLaneId & path, const RouteHandler & route_handler,
const ExtendedPredictedObject & object, const double object_check_min_road_shoulder_width,
const double object_shiftable_ratio_threshold,
const double static_object_velocity_threshold = 1.0);

bool isParkedObject(
const lanelet::ConstLanelet & closest_lanelet, const lanelet::BasicLineString2d & boundary,
const ExtendedPredictedObject & object, const double buffer_to_bound,
const double ratio_threshold);

bool passParkedObject(
const RouteHandler & route_handler, const LaneChangePath & lane_change_path,
const PathWithLaneId & current_lane_path, const PredictedObjects & objects,
const std::vector<size_t> & target_lane_obj_indices, const double minimum_lane_change_length,
const bool is_goal_in_route, const double object_check_min_road_shoulder_width,
const double object_shiftable_ratio_threshold);
const std::vector<ExtendedPredictedObject> & objects, const double minimum_lane_change_length,
const bool is_goal_in_route, const LaneChangeParameters & lane_change_parameters);

boost::optional<size_t> getLeadingStaticObjectIdx(
const RouteHandler & route_handler, const LaneChangePath & lane_change_path,
const PredictedObjects & objects, const std::vector<size_t> & obj_indices,
const std::vector<ExtendedPredictedObject> & objects,
const double object_check_min_road_shoulder_width, const double object_shiftable_ratio_threshold);

std::optional<lanelet::BasicPolygon2d> createPolygon(
Expand All @@ -194,6 +202,17 @@ LaneChangeTargetObjectIndices filterObject(
const PredictedObjects & objects, const lanelet::ConstLanelets & current_lanes,
const lanelet::ConstLanelets & target_lanes, const lanelet::ConstLanelets & target_backward_lanes,
const Pose & current_pose, const RouteHandler & route_handler,
const LaneChangeParameters & lane_change_parameter);
const LaneChangeParameters & lane_change_parameters);

ExtendedPredictedObject transform(
const PredictedObject & object, const BehaviorPathPlannerParameters & common_parameters,
const LaneChangeParameters & lane_change_parameters);

LaneChangeTargetObjects getTargetObjects(
const PredictedObjects & objects, const lanelet::ConstLanelets & current_lanes,
const lanelet::ConstLanelets & target_lanes, const lanelet::ConstLanelets & target_backward_lanes,
const Pose & current_pose, const RouteHandler & route_handler,
const BehaviorPathPlannerParameters & common_parameters,
const LaneChangeParameters & lane_change_parameters);
} // namespace behavior_path_planner::utils::lane_change
#endif // BEHAVIOR_PATH_PLANNER__UTILS__LANE_CHANGE__UTILS_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -48,13 +48,9 @@ using geometry_msgs::msg::Twist;
using marker_utils::CollisionCheckDebug;
using tier4_autoware_utils::Point2d;
using tier4_autoware_utils::Polygon2d;
using vehicle_info_util::VehicleInfo;

namespace bg = boost::geometry;
struct ProjectedDistancePoint
{
Point2d projected_point;
double distance{0.0};
};

bool isTargetObjectFront(
const PathWithLaneId & path, const geometry_msgs::msg::Pose & ego_pose,
Expand All @@ -65,10 +61,10 @@ bool isTargetObjectFront(

Polygon2d createExtendedPolygon(
const Pose & base_link_pose, const vehicle_info_util::VehicleInfo & vehicle_info,
const double lon_length, const double lat_margin);
const double lon_length, const double lat_margin, CollisionCheckDebug & debug);
Polygon2d createExtendedPolygon(
const Pose & obj_pose, const Shape & shape, const double lon_length, const double lat_margin);
double calcMaxDistFromPoseToPolygonPoint(const Pose & pose, const Polygon2d & polygon);
const Pose & obj_pose, const Shape & shape, const double lon_length, const double lat_margin,
CollisionCheckDebug & debug);

double calcRssDistance(
const double front_object_velocity, const double rear_object_velocity,
Expand All @@ -79,32 +75,33 @@ double calcMinimumLongitudinalLength(
const double front_object_velocity, const double rear_object_velocity,
const BehaviorPathPlannerParameters & params);

/**
* @brief Iterate the points in the ego and target's predicted path and
* perform safety check for each of the iterated points.
* @return true if distance is safe.
*/
bool isSafeInLaneletCollisionCheck(
const PathWithLaneId & path,
const std::vector<std::pair<Pose, tier4_autoware_utils::Polygon2d>> & interpolated_ego,
const Twist & ego_current_twist, const std::vector<double> & check_duration,
const double prepare_duration, const PredictedObject & target_object,
const PredictedPath & target_object_path, const BehaviorPathPlannerParameters & common_parameters,
const double prepare_phase_ignore_target_speed_thresh, const double front_decel,
const double rear_decel, CollisionCheckDebug & debug);
boost::optional<PoseWithVelocityStamped> calcInterpolatedPoseWithVelocity(
const std::vector<PoseWithVelocityStamped> & path, const double relative_time);

boost::optional<PoseWithVelocityAndPolygonStamped> getInterpolatedPoseWithVelocityAndPolygonStamped(
const std::vector<PoseWithVelocityStamped> & pred_path, const double current_time,
const VehicleInfo & ego_info);

/**
* @brief Iterate the points in the ego and target's predicted path and
* perform safety check for each of the iterated points.
* @param planned_path The predicted path of the ego vehicle.
* @param predicted_ego_path Ego vehicle's predicted path
* @param ego_current_velocity Current velocity of the ego vehicle.
* @param target_object The predicted object to check collision with.
* @param target_object_path The predicted path of the target object.
* @param common_parameters The common parameters used in behavior path planner.
* @param front_object_deceleration The deceleration of the object in the front.(used in RSS)
* @param rear_object_deceleration The deceleration of the object in the rear.(used in RSS)
* @param debug The debug information for collision checking.
* @return true if distance is safe.
*/
bool isSafeInFreeSpaceCollisionCheck(
const PathWithLaneId & path,
const std::vector<std::pair<Pose, tier4_autoware_utils::Polygon2d>> & interpolated_ego,
const Twist & ego_current_twist, const std::vector<double> & check_duration,
const double prepare_duration, const PredictedObject & target_object,
const BehaviorPathPlannerParameters & common_parameters,
const double prepare_phase_ignore_target_velocity_thresh, const double front_object_deceleration,
bool checkCollision(
const PathWithLaneId & planned_path,
const std::vector<PoseWithVelocityStamped> & predicted_ego_path,
const ExtendedPredictedObject & target_object,
const PredictedPathWithPolygon & target_object_path,
const BehaviorPathPlannerParameters & common_parameters, const double front_object_deceleration,
const double rear_object_deceleration, CollisionCheckDebug & debug);

} // namespace behavior_path_planner::utils::safety_check
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -380,11 +380,8 @@ lanelet::ConstLanelets calcLaneAroundPose(
const double dist_threshold = std::numeric_limits<double>::max(),
const double yaw_threshold = std::numeric_limits<double>::max());

std::vector<PredictedPath> getPredictedPathFromObj(
const PredictedObject & obj, const bool & is_use_all_predicted_path);

boost::optional<std::pair<Pose, Polygon2d>> getEgoExpectedPoseAndConvertToPolygon(
const PredictedPath & pred_path, const double current_time, const VehicleInfo & ego_info);
std::vector<PredictedPathWithPolygon> getPredictedPathFromObj(
const ExtendedPredictedObject & obj, const bool & is_use_all_predicted_path);

bool checkPathRelativeAngle(const PathWithLaneId & path, const double angle_threshold);

Expand Down Expand Up @@ -412,15 +409,6 @@ void makeBoundLongitudinallyMonotonic(PathWithLaneId & path, const bool is_bound
std::optional<lanelet::Polygon3d> getPolygonByPoint(
const std::shared_ptr<RouteHandler> & route_handler, const lanelet::ConstPoint3d & point,
const std::string & polygon_name);

bool isParkedObject(
const PathWithLaneId & path, const RouteHandler & route_handler, const PredictedObject & object,
const double object_check_min_road_shoulder_width, const double object_shiftable_ratio_threshold,
const double static_object_velocity_threshold = 1.0);

bool isParkedObject(
const lanelet::ConstLanelet & closest_lanelet, const lanelet::BasicLineString2d & boundary,
const PredictedObject & object, const double buffer_to_bound, const double ratio_threshold);
} // namespace behavior_path_planner::utils

#endif // BEHAVIOR_PATH_PLANNER__UTILS__UTILS_HPP_
Loading

0 comments on commit 6a02360

Please sign in to comment.