Skip to content

Commit

Permalink
Addressed comments from Andres and Michel
Browse files Browse the repository at this point in the history
  • Loading branch information
Alexis Pojomovsky committed May 8, 2018
1 parent ac2e16b commit b282b89
Show file tree
Hide file tree
Showing 3 changed files with 97 additions and 120 deletions.
85 changes: 20 additions & 65 deletions backend/python/examples/all_cars_in_dragway.py
Original file line number Diff line number Diff line change
Expand Up @@ -17,79 +17,21 @@
from delphyne.bindings import (
Any,
AutomotiveSimulator,
MaliputRailcarParams,
MaliputRailcarState,
RoadBuilder,
SimulatorRunner
)
from delphyne.simulation_utils import (
add_simple_car,
add_maliput_railcar,
add_mobil_car,
launch_interactive_simulation
)
from pydrake.automotive import (
LaneDirection,
SimpleCarState
)

SIMULATION_TIME_STEP_SECS = 0.001

def add_simple_car(simulator):
"""Instanciates a new Simple Prius Car
and adds it to the simulation.
"""
# Creates the initial car state for the simple car.
simple_car_state = SimpleCarState()
simple_car_state.set_x(0.0)
simple_car_state.set_y(3.7)
# Instantiates a Loadable Simple Car
simulator.AddLoadableAgent("simple-car", {}, "SimpleCar", simple_car_state)


def add_mobil_car(simulator, road):
"""Instanciates a new MOBIL Car and adds
it to the simulation.
"""
# Creates the initial car state for the MOBIL car.
mobil_car_state = SimpleCarState()
mobil_car_state.set_x(0.0)
mobil_car_state.set_y(-3.7)
mobil_params = {
"initial_with_s": Any(True),
"road": Any(road)
}
# Instantiates a Loadable MOBIL Car.
simulator.AddLoadableAgent(
"mobil-car", mobil_params, "MobilCar", mobil_car_state)


def add_maliput_railcar(simulator, road):
"""Instanciates a new Maliput Railcar and adds
it to the simulation.
"""
# Defines the lane that will be used by the dragway car.
lane = road.junction(0).segment(0).lane(1)
# Creates the initial car state for the Railcar.
maliput_car_state = MaliputRailcarState()
maliput_car_state.s = 0.0
maliput_car_state.speed = 3.0
lane_direction = LaneDirection(lane, True)
start_params = MaliputRailcarParams()
start_params.r = 0
start_params.h = 0
railcar_params = {
"road": Any(road),
"initial_with_s": Any(True),
"lane_direction": Any(lane_direction),
"start_params": Any(start_params)
}
# Instantiate a Loadable Rail Car.
simulator.AddLoadableAgent("rail-car",
railcar_params,
"RailCar",
maliput_car_state)


def main():
"""Excercises a simulator loaded it with multiple different cars."""
"""Excercises a simulator loaded with multiple different cars."""

simulator = AutomotiveSimulator()
builder = RoadBuilder(simulator)
Expand All @@ -105,9 +47,22 @@ def main():
dragway_shoulder_width, maximum_height)

# Adds the different cars.
add_simple_car(simulator)
add_mobil_car(simulator, dragway)
add_maliput_railcar(simulator, dragway)
simple_car_position_x = 0.0
simple_car_position_y = 3.7
car_id = 0
add_simple_car(simulator, car_id, simple_car_position_x,
simple_car_position_y)

mobil_car_position_x = 0.0
mobil_car_position_y = -3.7
car_id += 1
add_mobil_car(simulator, car_id, dragway,
mobil_car_position_x, mobil_car_position_y)

railcar_s = 0.0
railcar_speed = 3.0
car_id += 1
add_maliput_railcar(simulator, car_id, dragway, railcar_s, railcar_speed)

runner = SimulatorRunner(simulator, SIMULATION_TIME_STEP_SECS)

Expand Down
63 changes: 14 additions & 49 deletions backend/python/examples/loadable_agent_simulation.py
Original file line number Diff line number Diff line change
Expand Up @@ -45,6 +45,9 @@
SimulatorRunner
)
from delphyne.simulation_utils import (
add_simple_car,
add_maliput_railcar,
add_mobil_car,
launch_interactive_simulation
)
from pydrake.automotive import (
Expand Down Expand Up @@ -84,66 +87,28 @@ def main():

args = parser.parse_args()

car_id = 0
if args.type == "simple":
state = SimpleCarState()
state.set_x(0.0)
state.set_y(1.0)

# Instantiate a LoadablePriusSimpleCar with 0 id and originally
# placed in (0.0, 1.0)
simulator.AddLoadableAgent("simple-car",
{},
args.type,
state)
position_x = 0.0
position_y = 1.0
add_simple_car(simulator, car_id, position_x, position_y)

elif args.type == "mobil":
dragway = build_demo_dragway(simulator, "Mobil dragway")
position_x = 0.0
position_y = -3.7
add_mobil_car(simulator, car_id, dragway,
position_x, position_y)

state = SimpleCarState()
state.set_x(0.0)
state.set_y(-3.7)

mobil_params = {
"initial_with_s": Any(True),
"road": Any(dragway)
}

# Instantiate a MobilControlledSimpleCar
# and originally placed in (0.0, -3.7). The road for the car to
# follow is the previously created dragway.
simulator.AddLoadableAgent("mobil-car",
mobil_params,
args.type,
state)
elif args.type == "rail":
dragway = build_demo_dragway(simulator, "Railcar dragway")

lane = dragway.junction(0).segment(0).lane(1)

state = MaliputRailcarState()
state.s = 0.0
state.speed = 3.0

lane_direction = LaneDirection(lane, True)

start_params = MaliputRailcarParams()
start_params.r = 0
start_params.h = 0

railcar_params = {
"road": Any(dragway),
"initial_with_s": Any(True),
"lane_direction": Any(lane_direction),
"start_params": Any(start_params)
}

# Instantiate a LoadableMaliputRailCar and
# originally placed at the start of the second lane of the dragway
# previously created. The car initial speed is 3 meters per sec.
simulator.AddLoadableAgent("rail-car",
railcar_params,
args.type,
state)
s_coordinate = 0.0
speed = 3.0
add_maliput_railcar(simulator, car_id, dragway, s_coordinate, speed)
else:
raise RuntimeError("Option {} not recognized".format(args.type))

Expand Down
69 changes: 63 additions & 6 deletions backend/python/simulation_utils.py
Original file line number Diff line number Diff line change
Expand Up @@ -13,10 +13,14 @@

from contextlib import contextmanager
from delphyne.bindings import (
AutomotiveSimulator
Any,
AutomotiveSimulator,
MaliputRailcarParams,
MaliputRailcarState
)
from delphyne.launcher import Launcher
from pydrake.automotive import (
LaneDirection,
SimpleCarState
)

Expand Down Expand Up @@ -69,11 +73,7 @@ def build_simple_car_simulator(initial_positions=None):
simulator = AutomotiveSimulator()
car_id = 0
for car_position in initial_positions:
state = SimpleCarState()
state.set_y(car_position[0])
state.set_x(car_position[1])
simulator.AddLoadableAgent("simple-car", {}, str(car_id), state)

add_simple_car(simulator, car_id, car_position[1], car_position[0])
car_id += 1
return simulator

Expand Down Expand Up @@ -102,3 +102,60 @@ def launch_visualizer(launcher, layout_filename):
layout_path = os.path.join(get_delphyne_resource_root(), layout_filename)
teleop_config = layout_key + layout_path
launcher.launch([ign_visualizer, teleop_config])


def add_simple_car(simulator, robot_id, position_x=0, position_y=0):
"""Instantiates a new Simple Prius Car
and adds it to the simulation.
"""
# Creates the initial car state for the simple car.
simple_car_state = SimpleCarState()
simple_car_state.set_x(position_x)
simple_car_state.set_y(position_y)
# Instantiates a Loadable Simple Car
simulator.AddLoadableAgent(
"simple-car", {}, str(robot_id), simple_car_state)


def add_mobil_car(simulator, robot_id, road, position_x=0, position_y=0):
"""Instantiates a new MOBIL Car and adds
it to the simulation.
"""
# Creates the initial car state for the MOBIL car.
mobil_car_state = SimpleCarState()
mobil_car_state.set_x(position_x)
mobil_car_state.set_y(position_y)
mobil_params = {
"initial_with_s": Any(True),
"road": Any(road)
}
# Instantiates a Loadable MOBIL Car.
simulator.AddLoadableAgent(
"mobil-car", mobil_params, str(robot_id), mobil_car_state)


def add_maliput_railcar(simulator, robot_id, road, s_coordinate=0, speed=0):
"""Instantiates a new Maliput Railcar and adds
it to the simulation.
"""
# Defines the lane that will be used by the dragway car.
lane = road.junction(0).segment(0).lane(1)
# Creates the initial car state for the Railcar.
maliput_car_state = MaliputRailcarState()
maliput_car_state.s = s_coordinate
maliput_car_state.speed = speed
lane_direction = LaneDirection(lane, True)
start_params = MaliputRailcarParams()
start_params.r = 0
start_params.h = 0
railcar_params = {
"road": Any(road),
"initial_with_s": Any(True),
"lane_direction": Any(lane_direction),
"start_params": Any(start_params)
}
# Instantiates a Loadable Rail Car.
simulator.AddLoadableAgent("rail-car",
railcar_params,
str(robot_id),
maliput_car_state)

0 comments on commit b282b89

Please sign in to comment.