-
Notifications
You must be signed in to change notification settings - Fork 71
Hsinchu city (Taiwan) Map Bug - Lane=1720 is unreachable from any other lane on the map #1240
Description
Describe the bug
When I place the ego car on lane=1718 on the Hsinchu city (Taiwan) map and set the destination point to somewhere on lane=1720 , the ego car will not move during the simulation. And the simulation task failed.
Please see the TW map below, intuitively, according to the map visualization, the lane=1720 and lane=1721 should be reachable from lane=1718 (lane=1720 and lane=1721 are successors of lane=1718).
I also tested this scenario on Tier4 Scenario Editor. It failed too.
To Reproduce
Steps to reproduce the behavior:
- Launch Autoware through docker
- Run the scenario
1720.yml(at the end of this report), which usesHsinchu city (Taiwan)map. I downloaded it from here
ros2 launch scenario_test_runner scenario_test_runner.launch.py \
architecture_type:=awf/universe/20230906 \
record:=false \
scenario:=1720.yml \
sensor_model:=sample_sensor_kit \
vehicle_model:=sample_vehicle- Simulation runtime log:
[openscenario_interpreter_node-3] [INFO] [1714688055.375044352] [simulation.openscenario_interpreter]: InternalError: Requested the service "/api/routing/set_route_points" 1 times, but was unsuccessful.
[scenario_test_runner.py-1] [INFO] [1714688055.379492981] [simulation.scenario_test_runner]: finish execution- See the simulation result log:
<?xml version="1.0"?>
<testsuites name="/tmp/scenario_test_runner" failures="0" errors="1" tests="1">
<testsuite name="1720" failures="0" errors="1" tests="1">
<testcase name="1720_0">
<error type="InternalError" message="Requested the service "/api/routing/set_route_points" 1 times, but was not successful." />
</testcase>
</testsuite>
</testsuites>
Expected behavior
Expect routing to find valid route from lane=1718 to lane=1720
Root Cause
I think the reason behind this bug is:
- The end point of lane=1718's left bound != the start point of lane=1720's left bound
- The end point of lane=1718's right bound != the start point of lane=1720's right bound
I use your lanelet2 extension python library to get this:
lane=1718 left bound: [id: 1685, inverted point ids: 1688, 1687, 1686, 1684, 1683, 1708, 1699]
lane=1718 right bound: [id: 1679 point ids: 1677, 1678, 1680, 1681, 1717, 1694]
lane=1720 left bound: [id: 1704, inverted point ids: 1708, 1707, 1706, 1705, 1703, 1702, 1656]
lane=1720 right bound: [id: 1711, inverted point ids: 1717, 1716, 1715, 1714, 1713, 1712, 1710, 1709, 1658]
I tried to add point=1699 to lane=1720's left bound, and point=1694 to lane=1720's right bound. The modified version is like this:
And I did the simulation again, it worked. The ego car can depart from lane=1718 and arrive at lane=1720:
Desktop (please complete the following information):
- Ubuntu 22.04
- Autoware
- Chrome
Scenario file
ScenarioModifiers:
ScenarioModifier:
- name: __tier4_modifier_Vn
start: 8.4
step: 5.6
stop: 8.4
OpenSCENARIO:
FileHeader:
revMajor: 1
revMinor: 1
date: '2024-05-02T09:21:08.463Z'
description: ''
author: Hiroshi Igata
ParameterDeclarations:
ParameterDeclaration:
- name: __ego_dimensions_length__
parameterType: double
value: '0'
- name: __ego_dimensions_width__
parameterType: double
value: '0'
- name: __ego_dimensions_height__
parameterType: double
value: '0'
- name: __ego_center_x__
parameterType: double
value: '0'
- name: __ego_center_y__
parameterType: double
value: '0'
- name: __ego_center_z__
parameterType: double
value: '0'
- name: Vn
parameterType: double
value: __tier4_modifier_Vn
CatalogLocations:
CatalogLocation: []
RoadNetwork:
LogicFile:
filepath: Hsinchu city (Taiwan).osm
SceneGraphFile:
filepath: Hsinchu city (Taiwan).pcd
TrafficSignals:
TrafficSignalController: []
Entities:
ScenarioObject:
- name: ego
Vehicle:
name: ''
vehicleCategory: car
BoundingBox:
Center:
x: 1.355
y: 0
z: 1.25
Dimensions:
length: 4.77
width: 1.83
height: 2.5
Performance:
maxSpeed: 50
maxAcceleration: INF
maxDeceleration: INF
Axles:
FrontAxle:
maxSteering: 0.5236
wheelDiameter: 0.78
trackWidth: 1.63
positionX: 1.385
positionZ: 0.39
RearAxle:
maxSteering: 0.5236
wheelDiameter: 0.78
trackWidth: 1.63
positionX: 0
positionZ: 0.39
Properties:
Property: []
ObjectController:
Controller:
name: ''
Properties:
Property:
- name: isEgo
value: 'true'
Storyboard:
Init:
Actions:
Private:
- entityRef: ego
PrivateAction:
- TeleportAction:
Position:
LanePosition:
roadId: ''
laneId: '1718'
s: 43.8376
offset: 0.4681
Orientation:
type: relative
h: 0
p: -0.0
r: 0
- RoutingAction:
AcquirePositionAction:
Position:
LanePosition:
roadId: ''
laneId: '1720'
s: 21.508
offset: 0.2496
Orientation:
type: relative
h: 0
p: -0.0
r: 0
Story:
- name: ''
Act:
- name: _EndCondition
ManeuverGroup:
- maximumExecutionCount: 1
name: ''
Actors:
selectTriggeringEntities: false
EntityRef:
- entityRef: ego
Maneuver:
- name: ''
Event:
- name: ''
priority: parallel
StartTrigger:
ConditionGroup:
- Condition:
- name: ''
delay: 0
conditionEdge: none
ByEntityCondition:
TriggeringEntities:
triggeringEntitiesRule: any
EntityRef:
- entityRef: ego
EntityCondition:
ReachPositionCondition:
Position:
LanePosition:
roadId: ''
laneId: '1720'
s: 21.508
offset: 0.2496
Orientation:
type: relative
h: 0
p: -0.0
r: 0
tolerance: 1
- name: ''
delay: 0
conditionEdge: none
ByEntityCondition:
TriggeringEntities:
triggeringEntitiesRule: any
EntityRef:
- entityRef: ego
EntityCondition:
ReachPositionCondition:
Position:
LanePosition:
roadId: ''
laneId: '1720'
s: 21.508
offset: 0.2496
Orientation:
type: relative
h: 0
p: -0.0
r: 0
tolerance: 1
Action:
- name: ''
UserDefinedAction:
CustomCommandAction:
type: exitSuccess
- name: ''
priority: parallel
StartTrigger:
ConditionGroup:
- Condition:
- name: ''
delay: 0
conditionEdge: none
ByValueCondition:
SimulationTimeCondition:
value: 180
rule: greaterThan
Action:
- name: ''
UserDefinedAction:
CustomCommandAction:
type: exitFailure
StartTrigger:
ConditionGroup:
- Condition:
- name: ''
delay: 0
conditionEdge: none
ByValueCondition:
SimulationTimeCondition:
value: 0
rule: greaterThan
StopTrigger:
ConditionGroup: []





