Skip to content

Commit c65b08e

Browse files
committed
Added new trigger quickstart script.
New script 32-pedestrian-time-to-collision plays a scenario where pedestrian forces a collision with ego vehicle. Fixed 30-time-to-collision-trigger.
1 parent 6231dad commit c65b08e

File tree

3 files changed

+95
-8
lines changed

3 files changed

+95
-8
lines changed

quickstart/30-time-to-collision-trigger.py

Lines changed: 2 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -1,13 +1,12 @@
11
#!/usr/bin/env python3
22
#
3-
# Copyright (c) 2019 LG Electronics, Inc.
3+
# Copyright (c) 2020 LG Electronics, Inc.
44
#
55
# This software contains code licensed as described in LICENSE.
66
#
77

88
import os
99
import lgsvl
10-
import math
1110

1211
sim = lgsvl.Simulator(os.environ.get("SIMULATOR_HOST", "127.0.0.1"), 8181)
1312
if sim.current_scene == "BorregasAve":
@@ -20,7 +19,6 @@
2019
layer_mask |= 1 << 0 # 0 is the layer for the road (default)
2120

2221
# EGO
23-
2422
state = lgsvl.AgentState()
2523
forward = lgsvl.utils.transform_to_forward(spawns[0])
2624
right = lgsvl.utils.transform_to_right(spawns[0])
@@ -70,8 +68,7 @@ def on_collision(agent1, agent2, contact):
7068
hit = sim.raycast(npc_position, lgsvl.Vector(0,-1,0), layer_mask)
7169

7270
trigger = None
73-
if i == 1:
74-
parameters = {"value": 4.0}
71+
if i == 0:
7572
effector = lgsvl.TriggerEffector("TimeToCollision", {})
7673
trigger = lgsvl.WaypointTrigger([effector])
7774
wp = lgsvl.DriveWaypoint(position=hit.point, speed=speed, angle=angle, idle=0, trigger_distance=0, trigger = trigger)

quickstart/31-wait-for-distance-trigger.py

Lines changed: 1 addition & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -1,13 +1,12 @@
11
#!/usr/bin/env python3
22
#
3-
# Copyright (c) 2019 LG Electronics, Inc.
3+
# Copyright (c) 2020 LG Electronics, Inc.
44
#
55
# This software contains code licensed as described in LICENSE.
66
#
77

88
import os
99
import lgsvl
10-
import math
1110

1211
sim = lgsvl.Simulator(os.environ.get("SIMULATOR_HOST", "127.0.0.1"), 8181)
1312
if sim.current_scene == "BorregasAve":
@@ -20,7 +19,6 @@
2019
layer_mask |= 1 << 0 # 0 is the layer for the road (default)
2120

2221
# EGO
23-
2422
state = lgsvl.AgentState()
2523
forward = lgsvl.utils.transform_to_forward(spawns[0])
2624
right = lgsvl.utils.transform_to_right(spawns[0])
Lines changed: 92 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,92 @@
1+
#!/usr/bin/env python3
2+
#
3+
# Copyright (c) 2019 LG Electronics, Inc.
4+
#
5+
# This software contains code licensed as described in LICENSE.
6+
#
7+
8+
import os
9+
import lgsvl
10+
11+
sim = lgsvl.Simulator(os.environ.get("SIMULATOR_HOST", "127.0.0.1"), 8181)
12+
if sim.current_scene == "BorregasAve":
13+
sim.reset()
14+
else:
15+
sim.load("BorregasAve")
16+
17+
spawns = sim.get_spawn()
18+
layer_mask = 0
19+
layer_mask |= 1 << 0 # 0 is the layer for the road (default)
20+
21+
# EGO
22+
state = lgsvl.AgentState()
23+
ego_position = lgsvl.Vector(342.0, 0.0, -87.7)
24+
hit = sim.raycast(ego_position, lgsvl.Vector(0, -1, 0), layer_mask)
25+
state.transform.position = hit.point
26+
state.transform.rotation = lgsvl.Vector(0.0, 15.0, 0.0)
27+
forward = lgsvl.Vector(0.2, 0.0, 0.8)
28+
state.velocity = forward*15
29+
a = sim.add_agent("Lincoln2017MKZ (Apollo 5.0)", lgsvl.AgentType.EGO, state)
30+
31+
# Pedestrian
32+
state = lgsvl.AgentState()
33+
pedestrian_position = lgsvl.Vector(350.0, 0.0, -12)
34+
hit = sim.raycast(pedestrian_position, lgsvl.Vector(0, -1, 0), layer_mask)
35+
pedestrian_rotation = lgsvl.Vector(0.0, 105.0, 0.0)
36+
state.transform.position = hit.point
37+
state.transform.rotation = pedestrian_rotation
38+
pedestrian = sim.add_agent("Bob", lgsvl.AgentType.PEDESTRIAN, state)
39+
40+
agents = {
41+
a: "EGO",
42+
pedestrian: "Bob"
43+
}
44+
45+
46+
# Executed upon receiving collision callback -- pedestrian is expected to walk into colliding objects
47+
def on_collision(agent1, agent2, contact):
48+
name1 = agents[agent1]
49+
name2 = agents[agent2] if agent2 is not None else "OBSTACLE"
50+
print("{} collided with {}".format(name1, name2))
51+
52+
53+
a.on_collision(on_collision)
54+
pedestrian.on_collision(on_collision)
55+
56+
# This block creates the list of waypoints that the pedestrian will follow
57+
# Each waypoint is an position vector paired with the speed that the pedestrian will walk to
58+
waypoints = []
59+
60+
trigger = None
61+
speed = 3
62+
hit = sim.raycast(pedestrian_position+lgsvl.Vector(7.4, 0.0, -2.2), lgsvl.Vector(0, -1, 0), layer_mask)
63+
effector = lgsvl.TriggerEffector("TimeToCollision", {})
64+
trigger = lgsvl.WaypointTrigger([effector])
65+
wp = lgsvl.WalkWaypoint(position=hit.point, speed=speed, idle=0, trigger_distance=0, trigger=trigger)
66+
waypoints.append(wp)
67+
68+
hit = sim.raycast(pedestrian_position+lgsvl.Vector(12.4, 0.0, -3.4), lgsvl.Vector(0, -1, 0), layer_mask)
69+
wp = lgsvl.WalkWaypoint(position=hit.point, speed=speed, idle=0, trigger_distance=0, trigger=None)
70+
waypoints.append(wp)
71+
72+
73+
def on_waypoint(agent, index):
74+
print("waypoint {} reached".format(index))
75+
76+
77+
def agents_traversed_waypoints():
78+
print("All agents traversed their waypoints.")
79+
sim.stop()
80+
81+
82+
# The above function needs to be added to the list of callbacks for the pedestrian
83+
pedestrian.on_waypoint_reached(on_waypoint)
84+
sim.agents_traversed_waypoints(agents_traversed_waypoints)
85+
86+
# The pedestrian needs to be given the list of waypoints. A bool can be passed as the 2nd argument that controls
87+
# whether or not the pedestrian loops over the waypoints (default false)
88+
pedestrian.follow(waypoints, False)
89+
90+
input("Press Enter to run")
91+
92+
sim.run()

0 commit comments

Comments
 (0)