Package Summary
Tags | No category tags. |
Version | 0.43.0 |
License | Apache License 2.0 |
Build type | AMENT_CMAKE |
Use | RECOMMENDED |
Repository Summary
Checkout URI | https://github.com/autowarefoundation/autoware_universe.git |
VCS Type | git |
VCS Version | main |
Last Updated | 2025-04-03 |
Dev Status | UNMAINTAINED |
CI status | No Continuous Integration |
Released | UNRELEASED |
Tags | No category tags. |
Contributing |
Help Wanted (0)
Good First Issues (0) Pull Requests to Review (0) |
Package Description
Additional Links
Maintainers
- Takamasa Horibe
- Tomoya Kimura
- Mamoru Sobue
- Daniel Sanchez
- Kyoichi Sugahara
- Alqudah Mohammad
Authors
Autonomous Emergency Braking (AEB)
Purpose / Role
autonomous_emergency_braking
is a module that prevents collisions with obstacles on the predicted path created by a control module or sensor values estimated from the control module.
Assumptions
This module has following assumptions.
-
The predicted path of the ego vehicle can be made from either the path created from sensors or the path created from a control module, or both.
-
The current speed and angular velocity can be obtained from the sensors of the ego vehicle, and it uses points as obstacles.
-
The AEBs target obstacles are 2D points that can be obtained from the input point cloud or by obtaining the intersection points between the predicted ego footprint path and a predicted object’s shape.
IMU path generation: steering angle vs IMU’s angular velocity
Currently, the IMU-based path is generated using the angular velocity obtained by the IMU itself. It has been suggested that the steering angle could be used instead onf the angular velocity.
The pros and cons of both approaches are:
IMU angular velocity:
- (+) Usually, it has high accuracy
- (-) Vehicle vibration might introduce noise.
Steering angle:
- (+) Not so noisy
- (-) May have a steering offset or a wrong gear ratio, and the steering angle of Autoware and the real steering may not be the same.
For the moment, there are no plans to implement the steering angle on the path creation process of the AEB module.
Inner-workings / Algorithms
AEB has the following steps before it outputs the emergency stop signal.
-
Activate AEB if necessary.
-
Generate a predicted path of the ego vehicle.
-
Get target obstacles from the input point cloud and/or predicted object data.
-
Estimate the closest obstacle speed.
-
Collision check with target obstacles.
-
Send emergency stop signals to
/diagnostics
.
We give more details of each section below.
1. Activate AEB if necessary
We do not activate AEB module if it satisfies the following conditions.
-
Ego vehicle is not in autonomous driving state
-
When the ego vehicle is not moving (Current Velocity is below a 0.1 m/s threshold)
2. Generate a predicted path of the ego vehicle
2.1 Overview of IMU Path Generation
AEB generates a predicted footprint path based on current velocity and current angular velocity obtained from attached sensors. Note that if use_imu_path
is false
, it skips this step. This predicted path is generated as:
where $v$ and $\omega$ are current longitudinal velocity and angular velocity respectively. $dt$ is time interval that users can define in advance with the imu_prediction_time_interval
parameter. The IMU path is generated considering a time horizon, defined by the imu_prediction_time_horizon
parameter.
2.2 Constraints and Countermeasures in IMU Path Generation
Since the IMU path generation only uses the ego vehicle’s current angular velocity, disregarding the MPC’s planner steering, the shape of the IMU path tends to get distorted quite easily and protrude out of the ego vehicle’s current lane, possibly causing unwanted emergency stops. There are two countermeasures for this issue:
-
Control using the
max_generated_imu_path_length
parameter- Generation stops when path length exceeds the set value
- Avoid using a large
imu_prediction_time_horizon
-
Control based on lateral deviation
- Set the
limit_imu_path_lat_dev
parameter to “true” - Set deviation threshold using
imu_path_lat_dev_threshold
- Path generation stops when lateral deviation exceeds the threshold
- Set the
2.3 Advantages and Limitations of Lateral Deviation Control
The advantage of setting a lateral deviation limit with the limit_imu_path_lat_dev
parameter is that the imu_prediction_time_horizon
and the max_generated_imu_path_length
can be increased without worries about the IMU predicted path deforming beyond a certain threshold. The downside is that the IMU path will be cut short when the ego has a high angular velocity, in said cases, the AEB module would mostly rely on the MPC path to prevent or mitigate collisions.
If it is assumed the ego vehicle will mostly travel along the centerline of its lanelets, it can be useful to set the lateral deviation threshold parameter imu_path_lat_dev_threshold
to be equal to or smaller than the average lanelet width divided by 2, that way, the chance of the IMU predicted path leaving the current ego lanelet is smaller, and it is possible to increase the imu_prediction_time_horizon
to prevent frontal collisions when the ego is mostly traveling in a straight line.
The lateral deviation is measured using the ego vehicle’s current position as a reference, and it measures the distance of the furthermost vertex of the predicted ego footprint to the predicted path. The following image illustrates how the lateral deviation of a given ego pose is measured.
2.4 IMU Path Generation Algorithm
2.4.1 Selection of Lateral Deviation Check Points
Select vehicle vertices for lateral deviation checks based on the following conditions:
- Forward motion ($v > 0$)
- Right turn ($\omega > 0$): Right front vertex
- Left turn ($\omega < 0$): Left front vertex
- Reverse motion ($v < 0$)
- Right turn ($\omega > 0$): Right rear vertex
- Left turn ($\omega < 0$): Left rear vertex
- Straight motion ($\omega = 0$): Check both front/rear vertices depending on forward/reverse motion
2.4.2 Path Generation Process
Execute the following steps at each time step:
-
State Update
- Calculate next position $(x_{k+1}, y_{k+1})$ and yaw angle $\theta_{k+1}$ based on current velocity $v$ and angular velocity $\omega$
- Time interval $dt$ is based on the
imu_prediction_time_interval
parameter
-
Vehicle Footprint Generation
- Place vehicle footprint at calculated position
- Calculate check point coordinates
-
Lateral Deviation Calculation
- Calculate lateral deviation from selected vertex to path
- Update path length and elapsed time
-
Evaluation of Termination Conditions
2.4.3 Termination Conditions
Path generation terminates when any of the following conditions are met:
-
Basic Termination Conditions (both must be satisfied)
- Predicted time exceeds
imu_prediction_time_horizon
- AND path length exceeds
min_generated_imu_path_length
- Predicted time exceeds
-
Path Length Termination Condition
- Path length exceeds
max_generated_imu_path_length
- Path length exceeds
-
Lateral Deviation Termination Condition (when
limit_imu_path_lat_dev = true
)- Lateral deviation of selected vertex exceeds
imu_path_lat_dev_threshold
- Lateral deviation of selected vertex exceeds
MPC path generation
If the use_predicted_trajectory
parameter is set to true, the AEB module will directly use the predicted path from the MPC as a base to generate a footprint path. It will copy the ego poses generated by the MPC until a given time horizon. The mpc_prediction_time_horizon
parameter dictates how far ahead in the future the MPC path will predict the ego vehicle’s movement. Both the IMU footprint path and the MPC footprint path can be used at the same time.
3. Get target obstacles
After generating the ego footprint path(s), the target obstacles are identified. There are two methods to find target obstacles: using the input point cloud, or using the predicted object information coming from perception modules.
Pointcloud obstacle filtering
The AEB module can filter the input pointcloud to find target obstacles with which the ego vehicle might collide. This method can be enable if the use_pointcloud_data
parameter is set to true. The pointcloud 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 is half of the ego vehicle width plus the path_footprint_extra_margin
parameter plus the expand_width
parameter) away from the predicted path of the ego vehicle and ignore the point cloud that are not within it. The rough filtering step is illustrated below.
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. Furthermore, each point in a cluster is compared against the cluster_minimum_height
parameter, if no point inside a cluster has a height/z value greater than cluster_minimum_height
, the whole cluster of points is 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 Noise filtering, the module 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 labeled as target obstacles.
Obstacle labeling
After rigorous filtering, the remaining obstacles are labeled. An obstacle is given a “target” label for collision checking only if it falls within the ego vehicle’s defined footprint (made using the ego vehicle’s width and the expand_width
parameter). For an emergency stop to occur, at least one obstacle needs to be labeled as a target.
Using predicted objects to get target obstacles
If the use_predicted_object_data
parameter is set to true, the AEB can use predicted object data coming from the perception modules, to get target obstacle points. This is done by obtaining the 2D intersection points between the ego’s predicted footprint path (made using the ego vehicle’s width and the expand_width
parameter) and each of the predicted objects enveloping polygon or bounding box. if there is no intersection, all points are discarded.
Finding the closest target obstacle
After identifying all possible obstacles using pointcloud data and/or predicted object data, the AEB module selects the closest point to the ego vehicle as the candidate for collision checking. The “closest object” is defined as an obstacle within the ego vehicle’s footprint, determined by its width and the expand_width
parameter, that is closest to the ego vehicle along the longitudinal axis, using the IMU or MPC path as a reference. Target obstacles are prioritized over those outside the ego path, even if the latter are longitudinally closer. This prioritization ensures that the collision check focuses on objects that pose the highest risk based on the vehicle’s trajectory.
If no target obstacles are found, the AEB module considers other nearby obstacles outside the path. In such cases, it skips the collision check but records the position of the closest obstacle to calculate its speed (Step #4). Note that, obstacles obtained with predicted object data are all target obstacles since they are within the ego footprint path and it is not necessary to calculate their speed (it is already calculated by the perception module). Such obstacles are excluded from step #4.
4. Obstacle velocity estimation
To begin calculating the target point’s velocity, the point must enter the speed calculation area,
which is defined by the speed_calculation_expansion_margin
parameter plus the ego vehicles width and the expand_width
parameter.
Depending on the operational environment,
this margin can reduce unnecessary autonomous emergency braking
caused by velocity miscalculations during the initial calculation steps.
Once the position of the closest obstacle/point is determined, the AEB modules uses the history of previously detected objects to estimate the closest object relative speed using the following equations:
\[d_{t} = t_{1} - t_{0}\] \[d_{x} = norm(o_{x} - prev_{x})\] \[v_{norm} = d_{x} / d_{t}\]Where $t_{1}$ and $t_{0}$ are the timestamps of the point clouds used to detect the current closest object and the closest object of the previous point cloud frame, and $o_{x}$ and $prev_{x}$ are the positions of those objects, respectively.
Note that, when the closest obstacle/point comes from using predicted object data, $v_{norm}$ is calculated by directly computing the norm of the predicted object’s velocity in the x and y axes.
The velocity vector is then compared against the ego’s predicted path to get the longitudinal velocity $v_{obj}$:
\[v_{obj} = v_{norm} * Cos(yaw_{diff}) + v_{ego}\]where $yaw_{diff}$ is the difference in yaw between the ego path and the displacement vector \(v_{pos} = o_{pos} - prev_{pos}\) and $v_{ego}$ is the ego’s current speed, which accounts for the movement of points caused by the ego moving and not the object. All these equations are performed disregarding the z axis (in 2D).
Note that the object velocity is calculated against the ego’s current movement direction. If the object moves in the opposite direction to the ego’s movement, the object velocity will be negative, which will reduce the rss distance on the next step.
The resulting estimated object speed is added to a queue of speeds with timestamps. The AEB then checks for expiration of past speed estimations and eliminates expired speed measurements from the queue, the object expiration is determined by checking if the time elapsed since the speed was first added to the queue is larger than the parameter previous_obstacle_keep_time
. Finally, the median speed of the queue is calculated. The median speed will be used to calculate the RSS distance used for collision checking.
5. Collision check with target obstacles using RSS distance
In the fifth step, the AEB module checks for collision with the closest target obstacle using RSS distance. Only the closest target object is evaluated because RSS distance is used to determine collision risk. If the nearest target point is deemed safe, all other potential obstacles within the path are also assumed to be safe.
RSS distance is formulated as:
\[d = v_{ego}*t_{response} + v_{ego}^2/(2*a_{min}) -(sign(v_{obj})) * v_{obj}^2/(2*a_{obj_{min}}) + offset\]where $v_{ego}$ and $v_{obj}$ is current ego and obstacle velocity, $a_{min}$ and $a_{obj_{min}}$ is ego and object minimum acceleration (maximum deceleration), $t_{response}$ is response time of the ego vehicle to start deceleration. Therefore the distance from the ego vehicle to the obstacle is smaller than this RSS distance $d$, the ego vehicle send emergency stop signals.
Only obstacles classified as “targets” (as defined in Step #3) are considered for RSS distance calculations. Among these “target” obstacles, the one closest to the ego vehicle is used for the calculation. If no “target” obstacles are present—meaning no obstacles fall within the ego vehicle’s predicted path (determined by its width and an expanded margin)—this step is skipped. Instead, the position of the closest obstacle is recorded for future speed calculations (Step #4). In this scenario, no emergency stop diagnostic message is generated. The process is illustrated in the accompanying diagram.
6. Send emergency stop signals to /diagnostics
If AEB detects collision with point cloud obstacles in the previous step, it sends emergency signal to /diagnostics
in this step. Note that in order to enable emergency stop, it has to send ERROR level emergency. Moreover, AEB user should modify the setting file to keep the emergency level, otherwise Autoware does not hold the emergency state.
Use cases
Front vehicle suddenly brakes
The AEB can activate when a vehicle in front suddenly brakes, and a collision is detected by the AEB module. Provided the distance between the ego vehicle and the front vehicle is large enough and the ego’s emergency acceleration value is high enough, it is possible to avoid or soften collisions with vehicles in front that suddenly brake. NOTE: the acceleration used by the AEB to calculate rss_distance is NOT necessarily the acceleration used by the ego while doing an emergency brake. The acceleration used by the real vehicle can be tuned by changing the mrm_emergency stop jerk and acceleration values.
Stop for objects that appear suddenly
When an object appears suddenly, the AEB can act as a fail-safe to stop the ego vehicle when other modules fail to detect the object on time. If sudden object cut ins are expected, it might be useful for the AEB module to detect collisions of objects BEFORE they enter the real ego vehicle path by increasing the expand_width
parameter.
Preventing Collisions with rear objects
The AEB module can also prevent collisions when the ego vehicle is moving backwards.
Preventing collisions in case of wrong Odometry (IMU path only)
When vehicle odometry information is faulty, it is possible that the MPC fails to predict a correct path for the ego vehicle. If the MPC predicted path is wrong, collision avoidance will not work as intended on the planning modules. However, the AEB’s IMU path does not depend on the MPC and could be able to predict a collision when the other modules cannot. As an example you can see a figure of a hypothetical case in which the MPC path is wrong and only the AEB’s IMU path detects a collision.
Parameters
Name | Unit | Type | Description | Default value |
---|---|---|---|---|
publish_debug_markers | [-] | bool | flag to publish debug markers | true |
publish_debug_pointcloud | [-] | bool | flag to publish the point cloud used for debugging | false |
use_predicted_trajectory | [-] | bool | flag to use the predicted path from the control module | true |
use_imu_path | [-] | bool | flag to use the predicted path generated by sensor data | true |
use_object_velocity_calculation | [-] | bool | flag to use the object velocity calculation. If set to false, object velocity is set to 0 [m/s] | true |
check_autoware_state | [-] | bool | flag to enable or disable autoware state check. If set to false, the AEB module will run even when the ego vehicle is not in AUTONOMOUS state. | true |
detection_range_min_height | [m] | double | minimum hight of detection range used for avoiding the ghost brake by false positive point clouds | 0.0 |
detection_range_max_height_margin | [m] | double | margin for maximum hight of detection range used for avoiding the ghost brake by false positive point clouds. detection_range_max_height = vehicle_height + detection_range_max_height_margin
|
0.0 |
voxel_grid_x | [m] | double | down sampling parameters of x-axis for voxel grid filter | 0.05 |
voxel_grid_y | [m] | double | down sampling parameters of y-axis for voxel grid filter | 0.05 |
voxel_grid_z | [m] | double | down sampling parameters of z-axis for voxel grid filter | 100000.0 |
cluster tolerance | [m] | double | maximum allowable distance between any two points to be considered part of the same cluster | 0.15 |
cluster_minimum_height | [m] | double | at least one point in a cluster must be higher than this value for the cluster to be included in the set of possible collision targets | 0.1 |
minimum_cluster_size | [-] | int | minimum required amount of points contained by a cluster for it to be considered as a possible target obstacle | 10 |
maximum_cluster_size | [-] | int | maximum amount of points contained by a cluster for it to be considered as a possible target obstacle | 10000 |
min_generated_imu_path_length | [m] | double | minimum distance for a predicted path generated by sensors | 0.5 |
max_generated_imu_path_length | [m] | double | maximum distance for a predicted path generated by sensors | 10.0 |
expand_width | [m] | double | expansion width of the ego vehicle for collision checking, path cropping and speed calculation | 0.1 |
longitudinal_offset_margin | [m] | double | longitudinal offset distance for collision check | 2.0 |
t_response | [s] | double | response time for the ego to detect the front vehicle starting deceleration | 1.0 |
a_ego_min | [m/ss] | double | maximum deceleration value of the ego vehicle | -3.0 |
a_obj_min | [m/ss] | double | maximum deceleration value of objects | -3.0 |
imu_prediction_time_horizon | [s] | double | time horizon of the predicted path generated by sensors | 1.5 |
imu_prediction_time_interval | [s] | double | time interval of the predicted path generated by sensors | 0.1 |
mpc_prediction_time_horizon | [s] | double | time horizon of the predicted path generated by mpc | 1.5 |
mpc_prediction_time_interval | [s] | double | time interval of the predicted path generated by mpc | 0.1 |
aeb_hz | [-] | double | frequency at which AEB operates per second | 10 |
speed_calculation_expansion_margin | [m] | double | expansion width of the ego vehicle footprint used when calculating the closest object’s speed | 0.7 |
path_footprint_extra_margin | [m] | double | this parameters expands the ego footprint used to crop the AEB input pointcloud | 1.0 |
Limitations
-
The distance required to stop after collision detection depends on the ego vehicle’s speed and deceleration performance. To avoid collisions, it’s necessary to increase the detection distance and set a higher deceleration rate. However, this creates a trade-off as it may also increase the number of unnecessary activations. Therefore, it’s essential to consider what role this module should play and adjust the parameters accordingly.
-
AEB might not be able to react with obstacles that are close to the ground. It depends on the performance of the pre-processing methods applied to the point cloud.
-
Longitudinal acceleration information obtained from sensors is not used due to the high amount of noise.
-
The accuracy of the predicted path created from sensor data depends on the accuracy of sensors attached to the ego vehicle.
Changelog for package autoware_autonomous_emergency_braking
0.43.0 (2025-03-21)
- Merge remote-tracking branch 'origin/main' into chore/bump-version-0.43
- chore: rename from [autoware.universe]{.title-ref} to [autoware_universe]{.title-ref} (#10306)
- Contributors: Hayato Mizushima, Yutaka Kondo
0.42.0 (2025-03-03)
- Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base
- feat(autoware_utils): replace autoware_universe_utils with autoware_utils (#10191)
- chore(autonomous_emergency_braking): remove unnecessary dependency (#10120)
- Contributors: Fumiya Watanabe, Takayuki Murooka, 心刚
0.41.2 (2025-02-19)
- chore: bump version to 0.41.1 (#10088)
- Contributors: Ryohsuke Mitsudome
0.41.1 (2025-02-10)
0.41.0 (2025-01-29)
0.40.0 (2024-12-12)
- Merge branch 'main' into release-0.40.0
- Revert "chore(package.xml): bump version to 0.39.0 (#9587)" This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5.
- fix: fix ticket links in CHANGELOG.rst (#9588)
- chore(package.xml): bump version to 0.39.0
(#9587)
- chore(package.xml): bump version to 0.39.0
- fix: fix ticket links in CHANGELOG.rst
* fix: remove unnecessary diff ---------Co-authored-by: Yutaka Kondo <<yutaka.kondo@youtalk.jp>>
- fix: fix ticket links in CHANGELOG.rst (#9588)
- chore(autoware_autonomous_emergency_braking): add package maintainer (#9580) add package maintainer
- fix(cpplint): include what you use - control (#9565)
- refactor(autoware_autonomous_emergency_braking): update longitudinal offset parameter name (#9463) Update the parameter name for the longitudinal offset distance used for collision check in the autonomous emergency braking control module. The parameter name has been changed from "longitudinal_offset" to "longitudinal_offset_margin" to better reflect its purpose.
-
refactor(autoware_autonomous_emergency_braking): add getObjectOnPathData and getLongitudinalOffset functions (#9462) * feat(aeb): add getObjectOnPathData and getLongitudinalOffset functions ---------
- docs(autoware_autonomous_emergency_braking): enhance IMU path generation section with constraints and algorithm details (#9458)
- feat(autonomous_emergency_braking): set a lateral deviation limit
for AEB IMU path
(#9410)
- add a steer limit option for AEB
- wip refactor and add max lat dev param
- fix issue with test
- delete unwanted parts
- delete unwanted changes
- set to false
- change back path length
- add suggestions
- update readme
- cpp check
- fix some sentences
- expand explanation
- update image
- update README
- update description
- fix typo
- fix sentences
* improve readme ---------
- 0.39.0
- update changelog
- Merge commit '6a1ddbd08bd' into release-0.39.0
- fix: fix ticket links to point to https://github.com/autowarefoundation/autoware_universe (#9304)
- fix(control): missing dependency in control components (#9073)
- fix: fix ticket links to point to https://github.com/autowarefoundation/autoware_universe (#9304)
- feat(tier4_metric_msgs): apply tier4_metric_msgs for
scenario_simulator_v2_adapter, control_evaluator,
planning_evaluator, autonomous_emergency_braking,
obstacle_cruise_planner, motion_velocity_planner,
processing_time_checker
(#9180)
- first commit
- fix building errs.
- change diagnostic messages to metric messages for publishing decision.
- fix bug about motion_velocity_planner
- change the diagnostic msg to metric msg in autoware_obstacle_cruise_planner.
- tmp save for planning_evaluator
- change the topic to which metrics published to.
- fix typo.
- remove unnesessary publishing of metrics.
- mke planning_evaluator publish msg of MetricArray instead of Diags.
- update aeb with metric type for decision.
- fix some bug
- remove autoware_evaluator_utils package.
- remove diagnostic_msgs dependency of planning_evaluator
- use metric_msgs for autoware_processing_time_checker.
- rewrite diagnostic_convertor to scenario_simulator_v2_adapter, supporting metric_msgs.
- pre-commit and fix typo
- publish metrics even if there is no metric in the MetricArray.
- modify the metric name of processing_time.
- update unit test for test_planning/control_evaluator
* manual pre-commit ---------
- chore(package.xml): bump version to 0.38.0
(#9266)
(#9284)
- unify package.xml version to 0.37.0
- remove system_monitor/CHANGELOG.rst
- add changelog
* 0.38.0
- fix(autonomous_emergency_braking): solve issue with arc length
(#9247)
- solve issue with arc length
* fix problem with points one vehicle apart from path ---------
- Contributors: Esteve Fernandez, Fumiya Watanabe, Kem (TiankuiXian), Kyoichi Sugahara, M. Fatih Cırıt, Ryohsuke Mitsudome, Yutaka Kondo, danielsanchezaran, mkquda, ぐるぐる
0.39.0 (2024-11-25)
- Merge commit '6a1ddbd08bd' into release-0.39.0
- fix: fix ticket links to point to https://github.com/autowarefoundation/autoware_universe (#9304)
- fix(control): missing dependency in control components (#9073)
- fix: fix ticket links to point to https://github.com/autowarefoundation/autoware_universe (#9304)
- feat(tier4_metric_msgs): apply tier4_metric_msgs for
scenario_simulator_v2_adapter, control_evaluator,
planning_evaluator, autonomous_emergency_braking,
obstacle_cruise_planner, motion_velocity_planner,
processing_time_checker
(#9180)
- first commit
- fix building errs.
- change diagnostic messages to metric messages for publishing decision.
- fix bug about motion_velocity_planner
- change the diagnostic msg to metric msg in autoware_obstacle_cruise_planner.
- tmp save for planning_evaluator
- change the topic to which metrics published to.
- fix typo.
- remove unnesessary publishing of metrics.
- mke planning_evaluator publish msg of MetricArray instead of Diags.
- update aeb with metric type for decision.
- fix some bug
- remove autoware_evaluator_utils package.
- remove diagnostic_msgs dependency of planning_evaluator
- use metric_msgs for autoware_processing_time_checker.
- rewrite diagnostic_convertor to scenario_simulator_v2_adapter, supporting metric_msgs.
- pre-commit and fix typo
- publish metrics even if there is no metric in the MetricArray.
- modify the metric name of processing_time.
- update unit test for test_planning/control_evaluator
* manual pre-commit ---------
- chore(package.xml): bump version to 0.38.0
(#9266)
(#9284)
- unify package.xml version to 0.37.0
- remove system_monitor/CHANGELOG.rst
- add changelog
* 0.38.0
- fix(autonomous_emergency_braking): solve issue with arc length
(#9247)
- solve issue with arc length
* fix problem with points one vehicle apart from path ---------
- Contributors: Esteve Fernandez, Kem (TiankuiXian), Yutaka Kondo, danielsanchezaran, ぐるぐる
0.38.0 (2024-11-08)
- unify package.xml version to 0.37.0
- fix(autonomous_emergency_braking): fix no backward imu path and
wrong back distance usage
(#9141)
- fix no backward imu path and wrong back distance usage
* use the motion utils isDrivingForward function ---------
- refactor(autoware_autonomous_emergency_braking): rename info_marker_publisher to virtual_wall_publisher (#9078)
- feat(autonomous_emergency_braking): set max imu path length
(#9004)
- set a limit to the imu path length
- fix test and add a new one
- update readme
- pre-commit
- use velocity and time directly to get arc length
- refactor to reduce repeated code
* cleaning code ---------
- feat(autonomous_emergency_braking): add sanity chackes (#8998) add sanity chackes
- feat(autonomous_emergency_braking): calculate the object's
velocity in the search area
(#8591)
- refactor PR
- WIP
- change using polygon to lateral offset
- improve code
- remove redundant code
- skip close points in MPC path generation
- fix empty path points in short parking scenario
* fix readme conflicts ---------
- docs(autonomous_emergency_braking): add missing params to README (#8950) add missing params
- feat(autonomous_emergency_braking): make hull markers 3d (#8930) make hull markers 3d
- docs(autonomous_emergency_braking): make a clearer image for aeb when localization is faulty (#8873) make a clearer image for aeb when localization is faulty
- feat(autonomous_emergency_braking): add markers showing aeb convex
hull polygons for debugging purposes
(#8865)
- add markers showing aeb convex hull polygons for debugging purposes
- fix briefs
* fix typo ---------
- fix(control): align the parameters with launcher (#8789) align the control parameters
- feat(autonomous_emergency_braking): speed up aeb
(#8778)
- add missing rclcpp::Time(0)
- refactor to reduce cropping to once per iteration
- add LookUpTransform to utils
- separate object creation and clustering
* error handling of empty pointcloud ---------
- feat(autonomous_emergency_braking): increase aeb speed by getting last transform (#8734) set stamp to 0 to get the latest stamp instead of waiting for the stamp
- feat(autonomous_emergency_braking): add timekeeper to AEB
(#8706)
- add timekeeper to AEB
* add more info to output ---------
- docs(autoware_autonomous_emergency_braking): improve AEB
module's README
(#8612)
- docs: improve AEB module's README
* update rss distance length ---------
- fix(autonomous_emergency_braking): fix debug marker visual bug (#8611) fix bug by using the collision data keeper
- feat(autonomous_emergency_braking): enable aeb with only one req
path
(#8569)
- make it so AEB works with only one req path type (imu or MPC)
- fix missing mpc path return
- add check
* modify no path msg ---------
- feat(autonomous_emergency_braking): add some tests to aeb
(#8126)
- add initial tests
- add more tests
- more tests
- WIP add publishing and test subscription
- add more tests
- fix lint cmake
- WIP tf topic
* Revert "WIP tf topic" This reverts commit b5ef11b499e719b2cdbe0464bd7de7778de54e76.
- add path crop test
- add test for transform object
- add briefs
* delete repeated test ---------
- docs(autonomous_emergency_braking): update readme for new param (#8330) update readme for new param
- feat(autonomous_emergency_braking): add info marker and override for state (#8312) add info marker and override for state
- refactor(pointcloud_preprocessor): prefix package and namespace
with autoware
(#7983)
- refactor(pointcloud_preprocessor)!: prefix package and namespace with autoware
- style(pre-commit): autofix
- style(pointcloud_preprocessor): suppress line length check for macros
- fix(pointcloud_preprocessor): missing prefix
- fix(pointcloud_preprocessor): missing prefix
- fix(pointcloud_preprocessor): missing prefix
- fix(pointcloud_preprocessor): missing prefix
- fix(pointcloud_preprocessor): missing prefix
- refactor(pointcloud_preprocessor): directory structure (soft)
* refactor(pointcloud_preprocessor): directory structure (hard) ---------Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]\@users.noreply.github.com> Co-authored-by: Kenzo Lobos Tsunekawa <<kenzo.lobos@tier4.jp>>
- feat(autonomous_emergency_braking): add virtual stop wall to aeb
(#7894)
- add virtual stop wall to aeb
- add maintainer
- add uppercase
* use motion utils function instead of shiftPose ---------
- chore(autonomous_emergency_braking): apply clangd suggestions to
aeb
(#7703)
- apply clangd suggestions
* add maintainer ---------
- feat(autonomous_emergency_braking): aeb add support negative
speeds
(#7707)
- add support for negative speeds
* remove negative speed check for predicted obj ---------
- fix(autonomous_emergency_braking): aeb strange mpc polygon (#7740) change resize to reserve
- feat(autonomous_emergency_braking): add cluster min height for aeb
(#7605)
- add minimum cluster height threshold
- add update param option
- use param
- avoid the float check if cluster_surpasses_threshold_height is already true
- update README
* add cluster height description ---------
- refactor(universe_utils/motion_utils)!: add autoware namespace (#7594)
- feat(autonomous_emergency_braking): add predicted object support
for aeb
(#7548)
- add polling sub to predicted objects
- WIP requires changing path frame to map
- add parameters and reuse predicted obj speed
- introduce early break to reduce computation time
- resolve merge conflicts
- fix guard
- remove unused declaration
- fix include
- fix include issues
- remove inline
- delete unused dependencies
- add utils.cpp
* remove _ for non member variable ---------
- refactor(motion_utils)!: add autoware prefix and include dir (#7539) refactor(motion_utils): add autoware prefix and include dir
- feat(autoware_universe_utils)!: rename from tier4_autoware_utils (#7538) Co-authored-by: kosuke55 <<kosuke.tnp@gmail.com>>
- refactor(control)!: refactor directory structures of the control
checkers
(#7524)
- aeb
- control_validator
- lane_departure_checker
- shift_decider
* fix
- feat(autonomous_emergency_braking): aeb disable obj velocity calc
w param
(#7493)
* feat(autonomous_emergenct_braking): update README and imgs of
aeb
(#7482)
update README
- add param to toggle on or off object speed calc for aeb
* pre-commit readme ---------
- fix(planning): set single depth sensor data qos for pointlcoud polling subscribers (#7490) set single depth sensor data qos for pointlcoud polling subscribers
- feat(autonomous_emergenct_braking): update README and imgs of aeb (#7482) update README
- feat(autonomous_emergency_braking): aeb for backwards driving
(#7279)
- add support for backward path AEB
- fix sign)
- add abs and protect against nan
* solve sign problem with relative speed ---------
- refactor(vehicle_info_utils)!: prefix package and namespace with
autoware
(#7353)
- chore(autoware_vehicle_info_utils): rename header
- chore(bpp-common): vehicle info
- chore(path_optimizer): vehicle info
- chore(velocity_smoother): vehicle info
- chore(bvp-common): vehicle info
- chore(static_centerline_generator): vehicle info
- chore(obstacle_cruise_planner): vehicle info
- chore(obstacle_velocity_limiter): vehicle info
- chore(mission_planner): vehicle info
- chore(obstacle_stop_planner): vehicle info
- chore(planning_validator): vehicle info
- chore(surround_obstacle_checker): vehicle info
- chore(goal_planner): vehicle info
- chore(start_planner): vehicle info
- chore(control_performance_analysis): vehicle info
- chore(lane_departure_checker): vehicle info
- chore(predicted_path_checker): vehicle info
- chore(vehicle_cmd_gate): vehicle info
- chore(obstacle_collision_checker): vehicle info
- chore(operation_mode_transition_manager): vehicle info
- chore(mpc): vehicle info
- chore(control): vehicle info
- chore(common): vehicle info
- chore(perception): vehicle info
- chore(evaluator): vehicle info
- chore(freespace): vehicle info
- chore(planning): vehicle info
- chore(vehicle): vehicle info
- chore(simulator): vehicle info
- chore(launch): vehicle info
- chore(system): vehicle info
- chore(sensing): vehicle info
* fix(autoware_joy_controller): remove unused deps ---------
- feat(autonomous_emergency_braking): prefix package and namespace
with autoware_
(#7294)
- change package name
- add the prefix
- change option
- change back node name
- eliminate some prefixes that are not required
* fix node name ---------
- Contributors: Amadeusz Szymko, Ismet Atabay, Kosuke Takeuchi, Kyoichi Sugahara, Satoshi OTA, Takayuki Murooka, Yuki TAKAGI, Yutaka Kondo, Zhe Shen, danielsanchezaran, mkquda
0.26.0 (2024-04-03)
Wiki Tutorials
Package Dependencies
System Dependencies
Dependant Packages
Launch files
- launch/autoware_autonomous_emergency_braking.launch.xml
-
- param_path [default: $(find-pkg-share autoware_autonomous_emergency_braking)/config/autonomous_emergency_braking.param.yaml]
- input_pointcloud [default: /perception/obstacle_segmentation/pointcloud]
- input_velocity [default: /vehicle/status/velocity_status]
- input_imu [default: /sensing/imu/imu_data]
- input_predicted_trajectory [default: /control/trajectory_follower/lateral/predicted_trajectory]
- input_objects [default: /perception/object_recognition/objects]