Skip to content

Commit 395a6b2

Browse files
committed
merge branch main into autoware_msg
Signed-off-by: liu cui <cynthia.liu@autocore.ai>
2 parents b2f138d + edc7878 commit 395a6b2

File tree

70 files changed

+1697
-685
lines changed

Some content is hidden

Large Commits have some content hidden by default. Use the searchbox below for content that may be hidden.

70 files changed

+1697
-685
lines changed

.github/PULL_REQUEST_TEMPLATE/small-change.md

+4
Original file line numberDiff line numberDiff line change
@@ -15,6 +15,10 @@ Not applicable.
1515

1616
Not applicable.
1717

18+
## Interface changes
19+
20+
<!-- Describe any changed interfaces, such as topics, services, or parameters, including debugging interfaces -->
21+
1822
## Pre-review checklist for the PR author
1923

2024
The PR author **must** check the checkboxes below when creating the PR.

.github/PULL_REQUEST_TEMPLATE/standard-change.md

+13
Original file line numberDiff line numberDiff line change
@@ -18,6 +18,19 @@
1818

1919
<!-- Describe any changed interfaces, such as topics, services, or parameters. -->
2020

21+
### ROS Topic Changes
22+
23+
<!-- | Topic Name | Type | Direction | Update Description | -->
24+
<!-- | ---------------- | ------------------- | --------- | ------------------------------------------------------------- | -->
25+
<!-- | `/example_topic` | `std_msgs/String` | Subscribe | Description of what the topic is used for in the system | -->
26+
<!-- | `/another_topic` | `sensor_msgs/Image` | Publish | Also explain if it is added / modified / deleted with the PR | -->
27+
28+
### ROS Parameter Changes
29+
30+
<!-- | Parameter Name | Default Value | Update Description | -->
31+
<!-- | -------------------- | ------------- | --------------------------------------------------- | -->
32+
<!-- | `example_parameters` | `1.0` | Describe the parameter and also explain the updates | -->
33+
2134
## Effects on system behavior
2235

2336
<!-- Describe how this PR affects the system behavior. -->

common/autoware_auto_common/include/autoware_auto_common/common/types.hpp

+2
Original file line numberDiff line numberDiff line change
@@ -37,7 +37,9 @@ namespace types
3737
// We don't currently require code to comply to MISRA, but we should try to where it is
3838
// easily possible.
3939
using bool8_t = bool;
40+
#if __cplusplus < 201811L || !__cpp_char8_t
4041
using char8_t = char;
42+
#endif
4143
using uchar8_t = unsigned char;
4244
// If we ever compile on a platform where this is not true, float32_t and float64_t definitions
4345
// need to be adjusted.

common/autoware_perception_rviz_plugin/include/autoware_perception_rviz_plugin/object_detection/object_polygon_detail.hpp

+5-1
Original file line numberDiff line numberDiff line change
@@ -57,6 +57,9 @@ struct ObjectPropertyValues
5757
float alpha{0.999F};
5858
};
5959

60+
// Control object marker visualization
61+
enum class ObjectFillType { Skeleton, Fill };
62+
6063
// Map defining colors according to value of label field in ObjectClassification msg
6164
const std::map<
6265
autoware_perception_msgs::msg::ObjectClassification::_label_type, ObjectPropertyValues>
@@ -85,7 +88,8 @@ get_shape_marker_ptr(
8588
const autoware_perception_msgs::msg::Shape & shape_msg,
8689
const geometry_msgs::msg::Point & centroid, const geometry_msgs::msg::Quaternion & orientation,
8790
const std_msgs::msg::ColorRGBA & color_rgba, const double & line_width,
88-
const bool & is_orientation_available = true);
91+
const bool & is_orientation_available = true,
92+
const ObjectFillType fill_type = ObjectFillType::Skeleton);
8993

9094
AUTOWARE_PERCEPTION_RVIZ_PLUGIN_PUBLIC visualization_msgs::msg::Marker::SharedPtr
9195
get_2d_shape_marker_ptr(

common/autoware_perception_rviz_plugin/include/autoware_perception_rviz_plugin/object_detection/object_polygon_display_base.hpp

+13-1
Original file line numberDiff line numberDiff line change
@@ -112,6 +112,12 @@ class AUTOWARE_PERCEPTION_RVIZ_PLUGIN_PUBLIC ObjectPolygonDisplayBase
112112
m_confidence_interval_property->addOption("95%", 2);
113113
m_confidence_interval_property->addOption("99%", 3);
114114

115+
m_object_fill_type_property = new rviz_common::properties::EnumProperty(
116+
"Object Fill Type", "skeleton", "Change object fill type in visualization", this);
117+
m_object_fill_type_property->addOption(
118+
"skeleton", static_cast<int>(detail::ObjectFillType::Skeleton));
119+
m_object_fill_type_property->addOption("Fill", static_cast<int>(detail::ObjectFillType::Fill));
120+
115121
// iterate over default values to create and initialize the properties.
116122
for (const auto & map_property_it : detail::kDefaultObjectPropertyValues) {
117123
const auto & class_property_values = map_property_it.second;
@@ -189,9 +195,13 @@ class AUTOWARE_PERCEPTION_RVIZ_PLUGIN_PUBLIC ObjectPolygonDisplayBase
189195
const bool & is_orientation_available) const
190196
{
191197
const std_msgs::msg::ColorRGBA color_rgba = get_color_rgba(labels);
198+
const auto fill_type =
199+
static_cast<detail::ObjectFillType>(m_object_fill_type_property->getOptionInt());
200+
192201
if (m_display_type_property->getOptionInt() == 0) {
193202
return detail::get_shape_marker_ptr(
194-
shape_msg, centroid, orientation, color_rgba, line_width, is_orientation_available);
203+
shape_msg, centroid, orientation, color_rgba, line_width, is_orientation_available,
204+
fill_type);
195205
} else if (m_display_type_property->getOptionInt() == 1) {
196206
return detail::get_2d_shape_marker_ptr(
197207
shape_msg, centroid, orientation, color_rgba, line_width, is_orientation_available);
@@ -526,6 +536,8 @@ class AUTOWARE_PERCEPTION_RVIZ_PLUGIN_PUBLIC ObjectPolygonDisplayBase
526536
rviz_common::properties::EnumProperty * m_simple_visualize_mode_property;
527537
// Property to set confidence interval of state estimations
528538
rviz_common::properties::EnumProperty * m_confidence_interval_property;
539+
// Property to set visualization type
540+
rviz_common::properties::EnumProperty * m_object_fill_type_property;
529541
// Property to enable/disable label visualization
530542
rviz_common::properties::BoolProperty m_display_label_property;
531543
// Property to enable/disable uuid visualization

common/autoware_perception_rviz_plugin/src/object_detection/object_polygon_detail.cpp

+19-7
Original file line numberDiff line numberDiff line change
@@ -495,23 +495,37 @@ visualization_msgs::msg::Marker::SharedPtr get_shape_marker_ptr(
495495
const autoware_perception_msgs::msg::Shape & shape_msg,
496496
const geometry_msgs::msg::Point & centroid, const geometry_msgs::msg::Quaternion & orientation,
497497
const std_msgs::msg::ColorRGBA & color_rgba, const double & line_width,
498-
const bool & is_orientation_available)
498+
const bool & is_orientation_available, const ObjectFillType fill_type)
499499
{
500500
auto marker_ptr = std::make_shared<Marker>();
501501
marker_ptr->ns = std::string("shape");
502+
marker_ptr->color = color_rgba;
503+
marker_ptr->scale.x = line_width;
502504

503505
using autoware_perception_msgs::msg::Shape;
504506
if (shape_msg.type == Shape::BOUNDING_BOX) {
505-
marker_ptr->type = visualization_msgs::msg::Marker::LINE_LIST;
506-
calc_bounding_box_line_list(shape_msg, marker_ptr->points);
507+
if (fill_type == ObjectFillType::Skeleton) {
508+
marker_ptr->type = visualization_msgs::msg::Marker::LINE_LIST;
509+
calc_bounding_box_line_list(shape_msg, marker_ptr->points);
510+
} else if (fill_type == ObjectFillType::Fill) {
511+
marker_ptr->type = visualization_msgs::msg::Marker::CUBE;
512+
marker_ptr->scale = shape_msg.dimensions;
513+
marker_ptr->color.a = 0.75f;
514+
}
507515
if (is_orientation_available) {
508516
calc_bounding_box_direction_line_list(shape_msg, marker_ptr->points);
509517
} else {
510518
calc_bounding_box_orientation_line_list(shape_msg, marker_ptr->points);
511519
}
512520
} else if (shape_msg.type == Shape::CYLINDER) {
513-
marker_ptr->type = visualization_msgs::msg::Marker::LINE_LIST;
514-
calc_cylinder_line_list(shape_msg, marker_ptr->points);
521+
if (fill_type == ObjectFillType::Skeleton) {
522+
marker_ptr->type = visualization_msgs::msg::Marker::LINE_LIST;
523+
calc_cylinder_line_list(shape_msg, marker_ptr->points);
524+
} else if (fill_type == ObjectFillType::Fill) {
525+
marker_ptr->type = visualization_msgs::msg::Marker::CYLINDER;
526+
marker_ptr->scale = shape_msg.dimensions;
527+
marker_ptr->color.a = 0.75f;
528+
}
515529
} else if (shape_msg.type == Shape::POLYGON) {
516530
marker_ptr->type = visualization_msgs::msg::Marker::LINE_LIST;
517531
calc_polygon_line_list(shape_msg, marker_ptr->points);
@@ -523,8 +537,6 @@ visualization_msgs::msg::Marker::SharedPtr get_shape_marker_ptr(
523537
marker_ptr->action = visualization_msgs::msg::Marker::MODIFY;
524538
marker_ptr->pose = to_pose(centroid, orientation);
525539
marker_ptr->lifetime = rclcpp::Duration::from_seconds(0.15);
526-
marker_ptr->scale.x = line_width;
527-
marker_ptr->color = color_rgba;
528540

529541
return marker_ptr;
530542
}

common/tier4_logging_level_configure_rviz_plugin/config/logger_config.yaml

+2
Original file line numberDiff line numberDiff line change
@@ -33,6 +33,8 @@ Planning:
3333
logger_name: planning.scenario_planning.lane_driving.behavior_planning.behavior_path_planner
3434
- node_name: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner
3535
logger_name: tier4_autoware_utils
36+
- node_name: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner
37+
logger_name: behavior_path_planner.path_shifter
3638

3739
behavior_path_planner_avoidance:
3840
- node_name: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner

common/tier4_simulated_clock_rviz_plugin/README.md

+29-10
Original file line numberDiff line numberDiff line change
@@ -10,18 +10,37 @@ This plugin allows publishing and controlling the simulated ROS time.
1010
| -------- | --------------------------- | -------------------------- |
1111
| `/clock` | `rosgraph_msgs::msg::Clock` | the current simulated time |
1212

13-
## HowToUse
13+
## How to use the plugin
14+
15+
1. Launch [planning simulator](https://autowarefoundation.github.io/autoware-documentation/main/tutorials/ad-hoc-simulation/planning-simulation/#1-launch-autoware) with `use_sim_time:=true`.
16+
17+
```shell
18+
ros2 launch autoware_launch planning_simulator.launch.xml map_path:=$HOME/autoware_map/sample-map-planning vehicle_model:=sample_vehicle sensor_model:=sample_sensor_kit use_sim_time:=true
19+
```
20+
21+
> <span style="color: orange; font-weight: bold;">Warning</span>
22+
> If you launch the planning simulator without adding the `tier4_simulated_clock_rviz_plugin`, your simulation will not be running. You'll not even be able to place the initial and the goal poses.
23+
24+
2. Start rviz and select panels/Add new panel.
1425

15-
1. Start rviz and select panels/Add new panel.
1626
![select_panel](./images/select_panels.png)
17-
2. Select tier4_clock_rviz_plugin/SimulatedClock and press OK.
27+
28+
3. Select tier4_clock_rviz_plugin/SimulatedClock and press OK.
29+
1830
![select_clock_plugin](./images/select_clock_plugin.png)
19-
3. Use the added panel to control how the simulated clock is published.
31+
32+
4. Use the added panel to control how the simulated clock is published.
33+
2034
![use_clock_plugin](./images/use_clock_plugin.png)
2135

22-
- Pause button: pause/resume the clock.
23-
- Speed: speed of the clock relative to the system clock.
24-
- Rate: publishing rate of the clock.
25-
- Step button: advance the clock by the specified time step.
26-
- Time step: value used to advance the clock when pressing the step button d).
27-
- Time unit: time unit associated with the value from e).
36+
<ol type="a">
37+
<li>Pause button: pause/resume the clock.</li>
38+
<li>Speed: speed of the clock relative to the system clock.</li>
39+
<li>Rate: publishing rate of the clock.</li>
40+
<li>Step button: advance the clock by the specified time step.</li>
41+
<li>Time step: value used to advance the clock when pressing the step button d).</li>
42+
<li>Time unit: time unit associated with the value from e).</li>
43+
</ol>
44+
45+
> <span style="color: orange; font-weight: bold;">Warning</span>
46+
> If you set the time step too large, your simulation will go haywire.

control/autonomous_emergency_braking/README.md

+27
Original file line numberDiff line numberDiff line change
@@ -108,6 +108,33 @@ After Noise filtering, it performs a geometric collision check to determine whet
108108

109109
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.
110110

111+
#### Obstacle velocity estimation
112+
113+
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 speed using the following equations:
114+
115+
$$
116+
d_{t} = o_{time stamp} - prev_{time stamp}
117+
$$
118+
119+
$$
120+
d_{pos} = norm(o_{pos} - prev_{pos})
121+
$$
122+
123+
$$
124+
v_{norm} = d_{pos} / d_{t}
125+
$$
126+
127+
Where $o_{time stamp}$ and $prev_{time stamp}$ 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_{pos}$ and $prev_{pos}$ are the positions of those objects, respectively.
128+
129+
Finally, the velocity vector is compared against the ego's predicted path to get the longitudinal velocity $v_{obj}$:
130+
131+
$$
132+
v_{obj} = v_{norm} * Cos(yaw_{diff}) + v_{ego}
133+
$$
134+
135+
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 speed, which accounts for the movement of points caused by the ego moving and not the object.
136+
All these equations are performed disregarding the z axis (in 2D).
137+
111138
### 4. Collision check with target obstacles
112139

113140
In the fourth step, it checks the collision with filtered obstacles using RSS distance. RSS is formulated as:
Original file line numberDiff line numberDiff line change
@@ -1,26 +1,38 @@
11
/**:
22
ros__parameters:
3-
publish_debug_pointcloud: false
3+
# Ego path calculation
44
use_predicted_trajectory: true
5-
use_imu_path: true
6-
path_footprint_extra_margin: 1.0
5+
use_imu_path: false
6+
min_generated_path_length: 0.5
7+
imu_prediction_time_horizon: 1.5
8+
imu_prediction_time_interval: 0.1
9+
mpc_prediction_time_horizon: 1.5
10+
mpc_prediction_time_interval: 0.1
11+
12+
# Debug
13+
publish_debug_pointcloud: false
14+
15+
# Point cloud partitioning
716
detection_range_min_height: 0.0
817
detection_range_max_height_margin: 0.0
918
voxel_grid_x: 0.05
1019
voxel_grid_y: 0.05
1120
voxel_grid_z: 100000.0
12-
min_generated_path_length: 0.5
21+
22+
# Point cloud cropping
1323
expand_width: 0.1
24+
path_footprint_extra_margin: 4.0
25+
26+
# Point cloud clustering
27+
cluster_tolerance: 0.1 #[m]
28+
minimum_cluster_size: 10
29+
maximum_cluster_size: 10000
30+
31+
# RSS distance collision check
1432
longitudinal_offset: 2.0
1533
t_response: 1.0
1634
a_ego_min: -3.0
1735
a_obj_min: -1.0
18-
cluster_tolerance: 0.1 #[m]
19-
minimum_cluster_size: 10
20-
maximum_cluster_size: 10000
21-
imu_prediction_time_horizon: 1.5
22-
imu_prediction_time_interval: 0.1
23-
mpc_prediction_time_horizon: 1.5
24-
mpc_prediction_time_interval: 0.1
25-
collision_keeping_sec: 0.0
36+
collision_keeping_sec: 2.0
37+
previous_obstacle_keep_time: 1.0
2638
aeb_hz: 10.0

0 commit comments

Comments
 (0)