Skip to content

Commit 0a8986f

Browse files
authored
Merge branch 'main' into feat/lidar_centerpoint_preprocessing_cuda
2 parents 25119c8 + 8dcddae commit 0a8986f

File tree

40 files changed

+508
-84
lines changed

40 files changed

+508
-84
lines changed

.github/CODEOWNERS

+1-1
Original file line numberDiff line numberDiff line change
@@ -192,7 +192,7 @@ planning/autoware_behavior_path_side_shift_module/** fumiya.watanabe@tier4.jp ky
192192
planning/behavior_path_start_planner_module/** daniel.sanchez@tier4.jp kosuke.takeuchi@tier4.jp kyoichi.sugahara@tier4.jp mamoru.sobue@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp tomohito.ando@tier4.jp tomoya.kimura@tier4.jp
193193
planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/** mamoru.sobue@tier4.jp shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp
194194
planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/** kyoichi.sugahara@tier4.jp mamoru.sobue@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp yuki.takagi@tier4.jp
195-
planning/behavior_velocity_planner/behavior_velocity_no_drivable_lane_module/** ahmed.ebrahim@leodrive.ai fumiya.watanabe@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp
195+
planning/behavior_velocity_planner/autoware_behavior_velocity_no_drivable_lane_module/** ahmed.ebrahim@leodrive.ai fumiya.watanabe@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp
196196
planning/behavior_velocity_planner/autoware_behavior_velocity_no_stopping_area_module/** kosuke.takeuchi@tier4.jp shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp
197197
planning/behavior_velocity_planner/autoware_behavior_velocity_occlusion_spot_module/** shumpei.wakabayashi@tier4.jp taiki.tanaka@tier4.jp tomoya.kimura@tier4.jp
198198
planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/** fumiya.watanabe@tier4.jp isamu.takagi@tier4.jp mamoru.sobue@tier4.jp shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp

control/autoware_autonomous_emergency_braking/CMakeLists.txt

+7
Original file line numberDiff line numberDiff line change
@@ -12,11 +12,18 @@ include_directories(
1212
${PCL_INCLUDE_DIRS}
1313
)
1414

15+
ament_auto_add_library(autoware_autonomous_emergency_braking_helpers SHARED
16+
include/autoware/autonomous_emergency_braking/utils.hpp
17+
src/utils.cpp
18+
)
19+
1520
set(AEB_NODE ${PROJECT_NAME}_node)
1621
ament_auto_add_library(${AEB_NODE} SHARED
22+
include/autoware/autonomous_emergency_braking/node.hpp
1723
src/node.cpp
1824
)
1925

26+
target_link_libraries(${AEB_NODE} autoware_autonomous_emergency_braking_helpers)
2027
rclcpp_components_register_node(${AEB_NODE}
2128
PLUGIN "autoware::motion::control::autonomous_emergency_braking::AEB"
2229
EXECUTABLE ${PROJECT_NAME}

control/autoware_autonomous_emergency_braking/config/autonomous_emergency_braking.param.yaml

+2
Original file line numberDiff line numberDiff line change
@@ -3,6 +3,8 @@
33
# Ego path calculation
44
use_predicted_trajectory: true
55
use_imu_path: false
6+
use_pointcloud_data: true
7+
use_predicted_object_data: true
68
use_object_velocity_calculation: true
79
min_generated_path_length: 0.5
810
imu_prediction_time_horizon: 1.5

control/autoware_autonomous_emergency_braking/include/autoware/autonomous_emergency_braking/node.hpp

+20
Original file line numberDiff line numberDiff line change
@@ -23,6 +23,7 @@
2323
#include <pcl_ros/transforms.hpp>
2424
#include <rclcpp/rclcpp.hpp>
2525

26+
#include <autoware_perception_msgs/msg/predicted_objects.hpp>
2627
#include <autoware_planning_msgs/msg/trajectory.hpp>
2728
#include <autoware_system_msgs/msg/autoware_state.hpp>
2829
#include <autoware_vehicle_msgs/msg/velocity_report.hpp>
@@ -68,6 +69,9 @@ using visualization_msgs::msg::Marker;
6869
using visualization_msgs::msg::MarkerArray;
6970
using Path = std::vector<geometry_msgs::msg::Pose>;
7071
using Vector3 = geometry_msgs::msg::Vector3;
72+
using autoware_perception_msgs::msg::PredictedObject;
73+
using autoware_perception_msgs::msg::PredictedObjects;
74+
7175
struct ObjectData
7276
{
7377
rclcpp::Time stamp;
@@ -176,6 +180,13 @@ class CollisionDataKeeper
176180
std::optional<double> calcObjectSpeedFromHistory(
177181
const ObjectData & closest_object, const Path & path, const double current_ego_speed)
178182
{
183+
// in case the object comes from predicted objects info, we reuse the speed.
184+
if (closest_object.velocity > 0.0) {
185+
this->setPreviousObjectData(closest_object);
186+
this->updateVelocityHistory(closest_object.velocity, closest_object.stamp);
187+
return this->getMedianObstacleVelocity();
188+
}
189+
179190
if (this->checkPreviousObjectDataExpired()) {
180191
this->setPreviousObjectData(closest_object);
181192
this->resetVelocityHistory();
@@ -243,6 +254,8 @@ class AEB : public rclcpp::Node
243254
autoware_universe_utils::InterProcessPollingSubscriber<Imu> sub_imu_{this, "~/input/imu"};
244255
autoware_universe_utils::InterProcessPollingSubscriber<Trajectory> sub_predicted_traj_{
245256
this, "~/input/predicted_trajectory"};
257+
autoware_universe_utils::InterProcessPollingSubscriber<PredictedObjects> predicted_objects_sub_{
258+
this, "~/input/objects"};
246259
autoware_universe_utils::InterProcessPollingSubscriber<AutowareState> sub_autoware_state_{
247260
this, "/autoware/state"};
248261
// publisher
@@ -275,6 +288,10 @@ class AEB : public rclcpp::Node
275288
std::vector<ObjectData> & objects,
276289
const pcl::PointCloud<pcl::PointXYZ>::Ptr obstacle_points_ptr);
277290

291+
void createObjectDataUsingPredictedObjects(
292+
const Path & ego_path, const std::vector<Polygon2d> & ego_polys,
293+
std::vector<ObjectData> & objects);
294+
278295
void cropPointCloudWithEgoFootprintPath(
279296
const std::vector<Polygon2d> & ego_polys, pcl::PointCloud<pcl::PointXYZ>::Ptr filtered_objects);
280297

@@ -298,6 +315,7 @@ class AEB : public rclcpp::Node
298315
VelocityReport::ConstSharedPtr current_velocity_ptr_{nullptr};
299316
Vector3::SharedPtr angular_velocity_ptr_{nullptr};
300317
Trajectory::ConstSharedPtr predicted_traj_ptr_{nullptr};
318+
PredictedObjects::ConstSharedPtr predicted_objects_ptr_{nullptr};
301319
AutowareState::ConstSharedPtr autoware_state_{nullptr};
302320

303321
tf2_ros::Buffer tf_buffer_{get_clock()};
@@ -313,6 +331,8 @@ class AEB : public rclcpp::Node
313331
bool publish_debug_pointcloud_;
314332
bool use_predicted_trajectory_;
315333
bool use_imu_path_;
334+
bool use_pointcloud_data_;
335+
bool use_predicted_object_data_;
316336
bool use_object_velocity_calculation_;
317337
double path_footprint_extra_margin_;
318338
double detection_range_min_height_;
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,88 @@
1+
// Copyright 2024 TIER IV, Inc.
2+
//
3+
// Licensed under the Apache License, Version 2.0 (the "License");
4+
// you may not use this file except in compliance with the License.
5+
// You may obtain a copy of the License at
6+
//
7+
// http://www.apache.org/licenses/LICENSE-2.0
8+
//
9+
// Unless required by applicable law or agreed to in writing, software
10+
// distributed under the License is distributed on an "AS IS" BASIS,
11+
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
// See the License for the specific language governing permissions and
13+
// limitations under the License.
14+
15+
#ifndef AUTOWARE__AUTONOMOUS_EMERGENCY_BRAKING__UTILS_HPP_
16+
#define AUTOWARE__AUTONOMOUS_EMERGENCY_BRAKING__UTILS_HPP_
17+
18+
#include <autoware/universe_utils/geometry/boost_polygon_utils.hpp>
19+
20+
#include <autoware_perception_msgs/msg/predicted_objects.hpp>
21+
#include <geometry_msgs/msg/point.hpp>
22+
#include <geometry_msgs/msg/pose.hpp>
23+
24+
#include <boost/geometry/algorithms/correct.hpp>
25+
26+
#include <tf2/utils.h>
27+
#ifdef ROS_DISTRO_GALACTIC
28+
#include <tf2_eigen/tf2_eigen.h>
29+
#include <tf2_geometry_msgs/tf2_geometry_msgs.h>
30+
#else
31+
#include <tf2_eigen/tf2_eigen.hpp>
32+
33+
#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
34+
#endif
35+
36+
#include <vector>
37+
38+
namespace autoware::motion::control::autonomous_emergency_braking::utils
39+
{
40+
using autoware_perception_msgs::msg::PredictedObject;
41+
using autoware_perception_msgs::msg::PredictedObjects;
42+
using autoware_universe_utils::Point2d;
43+
using autoware_universe_utils::Polygon2d;
44+
using geometry_msgs::msg::Point;
45+
using geometry_msgs::msg::Pose;
46+
using geometry_msgs::msg::TransformStamped;
47+
48+
/**
49+
* @brief Apply a transform to a predicted object
50+
* @param input the predicted object
51+
* @param transform_stamped the tf2 transform
52+
*/
53+
PredictedObject transformObjectFrame(
54+
const PredictedObject & input, geometry_msgs::msg::TransformStamped transform_stamped);
55+
56+
/**
57+
* @brief Get the predicted objects polygon as a geometry polygon
58+
* @param current_pose the predicted object's pose
59+
* @param obj_shape the object's shape
60+
*/
61+
Polygon2d convertPolygonObjectToGeometryPolygon(
62+
const Pose & current_pose, const autoware_perception_msgs::msg::Shape & obj_shape);
63+
64+
/**
65+
* @brief Get the predicted objects cylindrical shape as a geometry polygon
66+
* @param current_pose the predicted object's pose
67+
* @param obj_shape the object's shape
68+
*/
69+
Polygon2d convertCylindricalObjectToGeometryPolygon(
70+
const Pose & current_pose, const autoware_perception_msgs::msg::Shape & obj_shape);
71+
72+
/**
73+
* @brief Get the predicted objects bounding box shape as a geometry polygon
74+
* @param current_pose the predicted object's pose
75+
* @param obj_shape the object's shape
76+
*/
77+
Polygon2d convertBoundingBoxObjectToGeometryPolygon(
78+
const Pose & current_pose, const double & base_to_front, const double & base_to_rear,
79+
const double & base_to_width);
80+
81+
/**
82+
* @brief Get the predicted object's shape as a geometry polygon
83+
* @param obj the object
84+
*/
85+
Polygon2d convertObjToPolygon(const PredictedObject & obj);
86+
} // namespace autoware::motion::control::autonomous_emergency_braking::utils
87+
88+
#endif // AUTOWARE__AUTONOMOUS_EMERGENCY_BRAKING__UTILS_HPP_

control/autoware_autonomous_emergency_braking/launch/autoware_autonomous_emergency_braking.launch.xml

+2
Original file line numberDiff line numberDiff line change
@@ -5,6 +5,7 @@
55
<arg name="input_imu" default="/sensing/imu/imu_data"/>
66
<arg name="input_odometry" default="/localization/kinematic_state"/>
77
<arg name="input_predicted_trajectory" default="/control/trajectory_follower/lateral/predicted_trajectory"/>
8+
<arg name="input_objects" default="/perception/object_recognition/objects"/>
89

910
<node pkg="autoware_autonomous_emergency_braking" exec="autoware_autonomous_emergency_braking" name="autonomous_emergency_braking" output="screen">
1011
<!-- load config files -->
@@ -15,5 +16,6 @@
1516
<remap from="~/input/imu" to="$(var input_imu)"/>
1617
<remap from="~/input/odometry" to="$(var input_odometry)"/>
1718
<remap from="~/input/predicted_trajectory" to="$(var input_predicted_trajectory)"/>
19+
<remap from="~/input/objects" to="$(var input_objects)"/>
1820
</node>
1921
</launch>

0 commit comments

Comments
 (0)