Skip to content

Commit

Permalink
merge branch main into autoware_msg
Browse files Browse the repository at this point in the history
Signed-off-by: liu cui <[email protected]>
  • Loading branch information
cyn-liu committed Apr 29, 2024
2 parents 0f894d7 + 7f368a2 commit b2f138d
Show file tree
Hide file tree
Showing 112 changed files with 4,970 additions and 1,069 deletions.
5 changes: 0 additions & 5 deletions build_depends.repos
Original file line number Diff line number Diff line change
Expand Up @@ -41,8 +41,3 @@ repositories:
type: git
url: https://github.com/MORAI-Autonomous/MORAI-ROS2_morai_msgs.git
version: main
#vehicle
vehicle/sample_vehicle_launch:
type: git
url: https://github.com/autowarefoundation/sample_vehicle_launch.git
version: main
5 changes: 0 additions & 5 deletions common/global_parameter_loader/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -4,11 +4,6 @@ project(global_parameter_loader)
find_package(autoware_cmake REQUIRED)
autoware_package()

if(BUILD_TESTING)
file(GLOB_RECURSE test_files test/*.cpp)
ament_add_ros_isolated_gtest(test_global_params_launch ${test_files})
endif()

ament_auto_package(
INSTALL_TO_SHARE
launch
Expand Down
4 changes: 1 addition & 3 deletions common/global_parameter_loader/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -10,10 +10,8 @@
<buildtool_depend>ament_cmake_auto</buildtool_depend>
<buildtool_depend>autoware_cmake</buildtool_depend>

<depend>sample_vehicle_description</depend>
<depend>vehicle_info_util</depend>
<exec_depend>vehicle_info_util</exec_depend>

<test_depend>ament_cmake_ros</test_depend>
<test_depend>ament_lint_auto</test_depend>
<test_depend>autoware_lint_common</test_depend>

Expand Down
44 changes: 0 additions & 44 deletions common/global_parameter_loader/test/test_global_params_launch.cpp

This file was deleted.

Original file line number Diff line number Diff line change
Expand Up @@ -51,10 +51,14 @@ Planning:
behavior_path_avoidance_by_lane_change:
- node_name: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner
logger_name: lane_change.AVOIDANCE_BY_LANE_CHANGE
- node_name: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner
logger_name: lane_change.utils

behavior_path_lane_change:
- node_name: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner
logger_name: lane_change.NORMAL
- node_name: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner
logger_name: lane_change.utils

behavior_velocity_planner:
- node_name: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner
Expand All @@ -78,6 +82,10 @@ Planning:
- node_name: /planning/scenario_planning/motion_velocity_smoother
logger_name: tier4_autoware_utils

route_handler:
- node_name: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner
logger_name: route_handler

# ============================================================
# control
# ============================================================
Expand Down
14 changes: 11 additions & 3 deletions control/autonomous_emergency_braking/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -86,20 +86,28 @@ where $v$ and $\omega$ are current longitudinal velocity and angular velocity re

### 3. Get target obstacles from the input point cloud

After generating the ego predicted path, we select target obstacles from the input point cloud. This obstacle filtering has two major steps, which are rough filtering and rigorous filtering.
After generating the ego predicted path, we select target obstacles from the input point cloud. This obstacle filtering has three major steps, which are rough filtering, noise filtering with clustering and rigorous filtering.

#### Rough filtering

In rough filtering step, we select target obstacle with simple filter. Create a search area up to a certain distance (default 5[m]) away from the predicted path of the ego vehicle and ignore the point cloud (obstacles) that are not within it. The image of the rough filtering is illustrated below.
In rough filtering step, we select target obstacle with simple filter. Create a search area up to a certain distance (default is half of the ego vehicle width plus the `path_footprint_extra_margin` parameter) away from the predicted path of the ego vehicle and ignore the point cloud that are not within it. The image of the rough filtering is illustrated below.

![rough_filtering](./image/obstacle_filtering_1.drawio.svg)

#### Noise filtering with clustering and convex hulls

To prevent the AEB from considering noisy points, euclidean clustering is performed on the filtered point cloud. The points in the point cloud that are not close enough to other points to form a cluster are discarded. The parameters `cluster_tolerance`, `minimum_cluster_size` and `maximum_cluster_size` can be used to tune the clustering and the size of objects to be ignored, for more information about the clustering method used by the AEB module, please check the official documentation on euclidean clustering of the PCL library: <https://pcl.readthedocs.io/projects/tutorials/en/master/cluster_extraction.html>.

Furthermore, a 2D convex hull is created around each detected cluster, the vertices of each hull represent the most extreme/outside points of the cluster. These vertices are then checked in the next step.

#### Rigorous filtering

After rough filtering, it performs a geometric collision check to determine whether the filtered obstacles actually have possibility to collide with the ego vehicle. In this check, the ego vehicle is represented as a rectangle, and the point cloud obstacles are represented as points.
After Noise filtering, it performs a geometric collision check to determine whether the filtered obstacles/hull vertices actually have possibility to collide with the ego vehicle. In this check, the ego vehicle is represented as a rectangle, and the point cloud obstacles are represented as points. Only the vertices with a possibility of collision are kept.

![rigorous_filtering](./image/obstacle_filtering_2.drawio.svg)

Finally, the vertex that is closest to the ego vehicle is chosen as the candidate for collision checking: Since rss distance is used to judge if a collision will happen or not, if the closest vertex to the ego is deemed to be safe, the rest of the vertices (and the points in the clusters) will also be safe.

### 4. Collision check with target obstacles

In the fourth step, it checks the collision with filtered obstacles using RSS distance. RSS is formulated as:
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,7 @@
publish_debug_pointcloud: false
use_predicted_trajectory: true
use_imu_path: true
path_footprint_extra_margin: 1.0
detection_range_min_height: 0.0
detection_range_max_height_margin: 0.0
voxel_grid_x: 0.05
Expand All @@ -14,6 +15,9 @@
t_response: 1.0
a_ego_min: -3.0
a_obj_min: -1.0
cluster_tolerance: 0.1 #[m]
minimum_cluster_size: 10
maximum_cluster_size: 10000
imu_prediction_time_horizon: 1.5
imu_prediction_time_interval: 0.1
mpc_prediction_time_horizon: 1.5
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,7 @@
#include <diagnostic_updater/diagnostic_updater.hpp>
#include <pcl_ros/transforms.hpp>
#include <rclcpp/rclcpp.hpp>
#include <tier4_autoware_utils/geometry/geometry.hpp>
#include <vehicle_info_util/vehicle_info_util.hpp>

#include <autoware_planning_msgs/msg/trajectory.hpp>
Expand Down Expand Up @@ -64,7 +65,6 @@ using visualization_msgs::msg::Marker;
using visualization_msgs::msg::MarkerArray;
using Path = std::vector<geometry_msgs::msg::Pose>;
using Vector3 = geometry_msgs::msg::Vector3;

struct ObjectData
{
rclcpp::Time stamp;
Expand Down Expand Up @@ -138,15 +138,19 @@ class AEB : public rclcpp::Node
// main function
void onCheckCollision(DiagnosticStatusWrapper & stat);
bool checkCollision(MarkerArray & debug_markers);
bool hasCollision(
const double current_v, const Path & ego_path, const std::vector<ObjectData> & objects);
bool hasCollision(const double current_v, const ObjectData & closest_object);

Path generateEgoPath(const double curr_v, const double curr_w);
std::optional<Path> generateEgoPath(const Trajectory & predicted_traj);
std::vector<Polygon2d> generatePathFootprint(const Path & path, const double extra_width_margin);

Path generateEgoPath(const double curr_v, const double curr_w, std::vector<Polygon2d> & polygons);
std::optional<Path> generateEgoPath(
const Trajectory & predicted_traj, std::vector<Polygon2d> & polygons);
void createObjectData(
void createObjectDataUsingPointCloudClusters(
const Path & ego_path, const std::vector<Polygon2d> & ego_polys, const rclcpp::Time & stamp,
std::vector<ObjectData> & objects);
std::vector<ObjectData> & objects,
const pcl::PointCloud<pcl::PointXYZ>::Ptr obstacle_points_ptr);

void cropPointCloudWithEgoFootprintPath(
const std::vector<Polygon2d> & ego_polys, pcl::PointCloud<pcl::PointXYZ>::Ptr filtered_objects);

void addMarker(
const rclcpp::Time & current_time, const Path & path, const std::vector<Polygon2d> & polygons,
Expand Down Expand Up @@ -175,6 +179,7 @@ class AEB : public rclcpp::Node
bool publish_debug_pointcloud_;
bool use_predicted_trajectory_;
bool use_imu_path_;
double path_footprint_extra_margin_;
double detection_range_min_height_;
double detection_range_max_height_margin_;
double voxel_grid_x_;
Expand All @@ -186,6 +191,9 @@ class AEB : public rclcpp::Node
double t_response_;
double a_ego_min_;
double a_obj_min_;
double cluster_tolerance_;
int minimum_cluster_size_;
int maximum_cluster_size_;
double imu_prediction_time_horizon_;
double imu_prediction_time_interval_;
double mpc_prediction_time_horizon_;
Expand Down
Loading

0 comments on commit b2f138d

Please sign in to comment.