Skip to content

Commit 3dc7d04

Browse files
authored
Merge pull request #1576 from tier4/docs/fix_architecture_type
2 parents 311a95c + ed90c0d commit 3dc7d04

File tree

5 files changed

+9
-8
lines changed

5 files changed

+9
-8
lines changed

docs/developer_guide/Communication.md

Lines changed: 3 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -29,15 +29,16 @@
2929
| `/perception/object_recognition/ground_truth/objects` | [`autoware_perception_msgs/msg/TrackedObjects`](https://github.com/autowarefoundation/autoware_msgs/blob/main/autoware_perception_msgs/msg/TrackedObjects.msg) | [Simulated by `simple_sensor_simulator`](https://tier4.github.io/scenario_simulator_v2-docs/developer_guide/SimpleSensorSimulator/#object-detection-results-simulation) |
3030
| `/perception/obstacle_segmentation/pointcloud` | [`sensor_msgs/msg/PointCloud2`](https://github.com/ros2/common_interfaces/blob/master/sensor_msgs/msg/PointCloud2.msg) | [Simulated by `simple_sensor_simulator`](https://tier4.github.io/scenario_simulator_v2-docs/developer_guide/SimpleSensorSimulator/#lidar-simulation) |
3131
| `/perception/occupancy_grid_map/map` | [`nav_msgs/msg/OccupancyGrid`](https://github.com/ros2/common_interfaces/blob/master/nav_msgs/msg/OccupancyGrid.msg) | [Simulated by `simple_sensor_simulator`](https://tier4.github.io/scenario_simulator_v2-docs/developer_guide/SimpleSensorSimulator/#occupancy-grid-sensor-simulation) |
32-
| `/perception/traffic_light_recognition/external/traffic_signals` | [`autoware_perception_msgs/msg/TrafficLightGroupArray`](https://github.com/autowarefoundation/autoware_msgs/blob/main/autoware_perception_msgs/msg/TrafficLightGroupArray.msg) | V2I traffic light interface for `architecture_type` equal to `awf/universe/20240605` |
32+
| `/perception/traffic_light_recognition/external/traffic_signals` | [`autoware_perception_msgs/msg/TrafficLightGroupArray`](https://github.com/autowarefoundation/autoware_msgs/blob/main/autoware_perception_msgs/msg/TrafficLightGroupArray.msg) | V2I traffic light interface for `architecture_type` equal to `awf/universe/20240605` or `awf/universe/20250130` |
3333
| `/perception/traffic_light_recognition/external/traffic_signals` | [`autoware_perception_msgs/msg/TrafficSignalArray`](https://github.com/autowarefoundation/autoware_msgs/blob/main/autoware_perception_msgs/msg/TrafficSignalArray.msg) | V2I traffic light interface for `architecture_type` equal to `awf/universe/20230906` |
34-
| `/perception/traffic_light_recognition/internal/traffic_signals` | [`autoware_perception_msgs/msg/TrafficLightGroupArray`](https://github.com/autowarefoundation/autoware_msgs/blob/main/autoware_perception_msgs/msg/TrafficLightGroupArray.msg) | Optical traffic light interface for `architecture_type` equal to `awf/universe/20240605` |
34+
| `/perception/traffic_light_recognition/internal/traffic_signals` | [`autoware_perception_msgs/msg/TrafficLightGroupArray`](https://github.com/autowarefoundation/autoware_msgs/blob/main/autoware_perception_msgs/msg/TrafficLightGroupArray.msg) | Optical traffic light interface for `architecture_type` equal to `awf/universe/20240605` or `awf/universe/20250130` |
3535
| `/perception/traffic_light_recognition/internal/traffic_signals` | [`autoware_perception_msgs/msg/TrafficSignalArray`](https://github.com/autowarefoundation/autoware_msgs/blob/main/autoware_perception_msgs/msg/TrafficSignalArray.msg) | Optical traffic light interface for `architecture_type` equal to `awf/universe/20230906` |
3636
| `/planning/mission_planning/checkpoint` | [`geometry_msgs/msg/PoseStamped`](https://github.com/ros2/common_interfaces/blob/master/geometry_msgs/msg/PoseStamped.msg) | |
3737
| `/planning/mission_planning/goal` | [`geometry_msgs/msg/PoseStamped`](https://github.com/ros2/common_interfaces/blob/master/geometry_msgs/msg/PoseStamped.msg) | |
3838
| `/sensing/imu/imu_data` | [`sensor_msgs/msg/Imu`](https://github.com/ros2/common_interfaces/blob/master/sensor_msgs/msg/Imu.msg) | |
3939
| `/v2x/traffic_signals` | [`autoware_perception_msgs/msg/TrafficLightGroupArray`](https://github.com/autowarefoundation/autoware_msgs/blob/main/autoware_perception_msgs/msg/TrafficLightGroupArray.msg) | Additional V2I traffic light interface for `architecture_type` equal to `awf/universe/20240605` |
4040
| `/v2x/traffic_signals` | [`autoware_perception_msgs/msg/TrafficSignalArray`](https://github.com/autowarefoundation/autoware_msgs/blob/main/autoware_perception_msgs/msg/TrafficSignalArray.msg) | Additional V2I traffic light interface for `architecture_type` equal to `awf/universe/20230906` |
41+
| `/v2x/traffic_signals` | [`autoware_perception_msgs/msg/TrafficLightGroupArray`](https://github.com/autowarefoundation/autoware_msgs/blob/main/autoware_perception_msgs/msg/TrafficLightGroupArray.msg) | Additional V2I traffic light interface for `architecture_type` equal to `awf/universe/20240605` or `awf/universe/20250130` |
4142
| `/vehicle/status/control_mode` | [`autoware_vehicle_msgs/msg/ControlModeReport`](https://github.com/autowarefoundation/autoware_msgs/tree/main/autoware_vehicle_msgs/msg/ControlModeReport.msg) | |
4243
| `/vehicle/status/gear_status` | [`autoware_vehicle_msgs/msg/GearReport`](https://github.com/autowarefoundation/autoware_msgs/tree/main/autoware_vehicle_msgs/msg/GearReport.msg) | |
4344
| `/vehicle/status/steering_status` | [`autoware_vehicle_msgs/msg/SteeringReport`](https://github.com/autowarefoundation/autoware_msgs/tree/main/autoware_vehicle_msgs/msg/SteeringReport.msg) | |

docs/user_guide/QuickStart.md

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -69,7 +69,7 @@ This guide provides step-by-step instructions for building and running **Scenari
6969
#### scenario_test_runner
7070
```bash
7171
ros2 launch scenario_test_runner scenario_test_runner.launch.py \
72-
architecture_type:=awf/universe/20230906 \
72+
architecture_type:=awf/universe/20250130 \
7373
record:=false \
7474
scenario:='$(find-pkg-share scenario_test_runner)/scenario/sample.yaml' \
7575
sensor_model:=sample_sensor_kit \
@@ -84,7 +84,7 @@ This guide provides step-by-step instructions for building and running **Scenari
8484
#### random_test_runner
8585
```bash
8686
ros2 launch random_test_runner random_test.launch.py \
87-
architecture_type:=awf/universe/20230906 \
87+
architecture_type:=awf/universe/20250130 \
8888
sensor_model:=sample_sensor_kit \
8989
vehicle_model:=sample_vehicle timeout:=120.0
9090
```

docs/user_guide/random_test_runner/QuickStart.md

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -125,7 +125,7 @@ Random test runner will load `result.yaml` file and rerun test.
125125
```bash
126126
ros2 launch random_test_runner random_test.launch.py map_name:=shinjuku_map simulator_type:=awsim \
127127
npc_count:=5 initialize_duration:=260 sensor_model:=awsim_sensor_kit vehicle_model:=sample_vehicle \
128-
autoware_launch_file:=e2e_simulator.launch.xml autoware_architecture:="awf/universe/20230906"
128+
autoware_launch_file:=e2e_simulator.launch.xml autoware_architecture:="awf/universe/20250130"
129129
```
130130

131131
![Random test runner launched](img/random_test_runner_awsim.png)

docs/user_guide/random_test_runner/Usage.md

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -73,7 +73,7 @@ and sensor model is used in the simulation
7373

7474
| Parameter name | Default value | Description |
7575
|---------------------|-------------------------------|---------------------------------------------------------------------------|
76-
| `architecture_type` | `"awf/universe/20230906"` | Autoware architecture type. Currently supported values are: `awf/universe/20230906` and `awf/universe/20240605`. |
76+
| `architecture_type` | `"awf/universe/20240605"` | Autoware architecture type. Currently supported values are: `awf/universe/20230906`, `awf/universe/20240605` and `awf/universe/20250130`. |
7777
| `sensor_model` | `"sample_sensor_kit"` | Ego sensor model. |
7878
| `vehicle_model` | `"sample_vehicle"` | Ego vehicle model. |
7979

docs/user_guide/scenario_test_runner/RealtimeFactor.md

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -11,7 +11,7 @@ It is possible to modify the speed of simulation (the speed of time published on
1111

1212
```bash
1313
ros2 launch scenario_test_runner scenario_test_runner.launch.py \
14-
architecture_type:=awf/universe/20230906 \
14+
architecture_type:=awf/universe/20250130 \
1515
record:=false \
1616
scenario:='$(find-pkg-share scenario_test_runner)/scenario/sample.yaml' \
1717
sensor_model:=sample_sensor_kit \
@@ -47,7 +47,7 @@ Parameter `use_sim_time` of `openscenario_interpreter` is **false** by default a
4747

4848
```bash
4949
ros2 launch scenario_test_runner scenario_test_runner.launch.py \
50-
architecture_type:=awf/universe/20230906 \
50+
architecture_type:=awf/universe/20250130 \
5151
record:=false \
5252
scenario:='$(find-pkg-share scenario_test_runner)/scenario/sample.yaml' \
5353
sensor_model:=sample_sensor_kit \

0 commit comments

Comments
 (0)