Skip to content

Commit

Permalink
Polished behaviour tree-based API.
Browse files Browse the repository at this point in the history
Signed-off-by: Michel Hidalgo <michel@ekumenlabs.com>
  • Loading branch information
hidmic committed Aug 20, 2019
1 parent 5bdee09 commit 7aa73ee
Show file tree
Hide file tree
Showing 9 changed files with 297 additions and 154 deletions.
121 changes: 85 additions & 36 deletions python/delphyne/behaviours/agents.py
Original file line number Diff line number Diff line change
@@ -1,118 +1,167 @@
# Copyright 2019 Toyota Research Institute

"""
A module providing basic agent behaviours.
"""

import delphyne.agents
import delphyne.blackboard.blackboard_helper as bb_helper
import delphyne.blackboard

from delphyne.blackboard.providers import resolve

import py_trees.behaviours
import py_trees.common

def resolve(expression, *args, **kwargs):
if callable(expression):
expression = expression(*args, **kwargs)
return expression

class SimpleCar(py_trees.behaviours.Success):
"""Introduce a simple car in the road."""

def __init__(self, name=py_trees.common.Name.AUTO_GENERATED,
initial_x=0., initial_y=0., heading=0., speed=1.):
initial_pose=(0., 0., 0.), speed=1.):
"""
:param name: a name for the car.
:param initial_pose: initial car (SE2) pose in the world frame.
That is, its (x, y, heading) coordinates, either as a tuple of
floats or as a callable expression that takes a road geometry
and returns a tuple of floats.
:param speed: for the agent as measured in the world frame, in m/s.
"""
super().__init__(name)
self.initial_x = initial_x
self.initial_y = initial_y
self.heading = heading
self.initial_pose = initial_pose
self.speed = speed

def setup(self, *, builder):
initial_x, initial_y, heading = resolve(
self.initial_pose, builder.get_road_geometry()
)
builder.add_agent(
delphyne.agents.SimpleCarBlueprint(
name=self.name,
x=self.initial_x, # initial x-coordinate (m)
y=self.initial_y, # initial y-coordinate (m)
heading=self.heading, # heading (radians)
x=initial_x, # initial x-coordinate (m)
y=initial_y, # initial y-coordinate (m)
heading=heading, # heading (radians)
speed=self.speed # speed in the direction of travel (m/s)
)
)


class MobilCar(py_trees.behaviours.Success):
"""Introduce a MOBIL car in the road."""

'''
MobilCar agent. You can give a function to lane_pos_generator parameter
that returns a pair (Lane, LanePosition)
'''
def __init__(self, name=py_trees.common.Name.AUTO_GENERATED,
initial_pose=(0., 0., 0.), # x, y and initial heading coord.
speed=1., direction_of_travel=True):
initial_pose=(0., 0., 0.), speed=1.,
direction_of_travel=True):
"""
:param name: a name for the car.
:param initial_pose: initial car (SE2) pose in the world frame.
That is, its (x, y, heading), either as a tuple of floats or
as a callable expression that takes a road geometry and returns
a tuple of floats.
:param speed: speed of the car as measured in the world frame, in
meters per second.
:param direction_of_travel: with or against the lane s-direction.
"""
super().__init__(name)
self.initial_pose = initial_pose
self.direction_of_travel = direction_of_travel
self.speed = speed

def setup(self, *, builder):
road_geometry = bb_helper.get_road_geometry()
self.initial_pose = resolve(self.initial_pose, road_geometry)
road_geometry = builder.get_road_geometry()
initial_x, initial_y, initial_heading = resolve(
self.initial_pose, road_geometry
)
builder.add_agent(
delphyne.agents.MobilCarBlueprint(
name=self.name, # unique name
# with or against the lane s-direction
direction_of_travel=self.direction_of_travel,
x=self.initial_pose[0], # x-coordinate (m)
y=self.initial_pose[1], # y-coordinate (m)
heading=self.initial_pose[2], # heading (radians)
x=initial_x, # x-coordinate (m)
y=initial_y, # y-coordinate (m)
heading=initial_heading, # heading (radians)
speed=self.speed # the s-direction (m/s)
)
)


class RailCar(py_trees.behaviours.Success):
"""Introduce a rail car in the road."""

def __init__(self, lane_id, direction_of_travel=True,
longitudinal_position=0., lateral_offset=0.,
speed=1., nominal_speed=20.,
name=py_trees.common.Name.AUTO_GENERATED):
"""
:param lane_id: ID of the lane to drive on, either as a string or
as a callable expression that takes a road geometry and returns
a string.
:param direction_of_travel: with or against the lane s-direction.
:param longitudinal_position: initial s-coordinate of the car in the
lane frame, either as a float or as a callable expression that
takes a road geometry and a lane and returns a float.
:param lateral_offset: initial r-coordinate in the lane frame.
:param speed: speed of the car as measured in the world frame, in m/s.
:param nominal_speed: nominal speed (as in, maximum most likely speed) of
the agent as measured in the world frame, in m/s.
:param name: a name for the car.
"""
super().__init__(name)
self.lane_id = lane_id
self.direction_of_travel = direction_of_travel
self.longitudinal_position = longitudinal_position
self.lateral_offset = lateral_offset
self.speed = speed
self.nominal_speed = nominal_speed
self.agent = None
bb_helper.initialize_agent_attributes(self.name)

def initialise(self):
if self.agent is None:
self.agent = bb_helper.get_simulation().get_agent_by_name(self.name)
delphyne.blackboard.state.initialize_agent_attributes(self.name)

def setup(self, *, builder):
road_geometry = builder.get_road_geometry()
road_index = road_geometry.ById()
self.lane_id = resolve(self.lane_id, road_geometry)
self.longitudinal_position = resolve(self.longitudinal_position,
road_geometry, self.lane_id)
lane = road_index.GetLane(self.lane_id)
lane_id = resolve(self.lane_id, road_geometry)
lane = road_index.GetLane(lane_id)
longitudinal_position = resolve(
self.longitudinal_position, road_geometry, lane
)

builder.add_agent(
delphyne.agents.RailCarBlueprint(
name=self.name, # unique name
lane=lane, # lane
direction_of_travel=self.direction_of_travel, # direction_of_travel
longitudinal_position=self.longitudinal_position, # lane s-coordinate (m)
longitudinal_position=longitudinal_position, # lane s-coordinate (m)
lateral_offset=self.lateral_offset, # lane r-coordinate (m)
speed=self.speed, # initial speed in
# s-direction (m/s)
nominal_speed=self.nominal_speed # nominal_speed (m/s)
)
)

def initialise(self):
simulation = delphyne.blackboard.state.get_simulation()
self.agent = simulation.get_agent_by_name(self.name)

def update(self):
speed = bb_helper.get_attribute_for_agent(self.name, "speed")
from delphyne.blackboard.state import get_attribute_for_agent
speed = get_attribute_for_agent(self.name, "speed")
if self.agent is not None and speed is not None and speed != self.speed:
self.speed = self.agent.set_speed(speed)
return py_trees.common.Status.SUCCESS



class TrajectoryAgent(py_trees.behaviours.Success):
"""Introduce a trajectory following car in the road."""

def __init__(self, times, headings, waypoints,
name=py_trees.common.Name.AUTO_GENERATED):
"""
:param times: time of each waypoint in the trajectory to occur,
in seconds.
:param headings: orientation about the world frame's Z axis of
the car at each waypoint, in radians.
:param waypoints: (x, y, z) position in the world frame of the
car at each waypoint, in meters.
:param name: a name for the car.
"""
super().__init__(name)
self.times = times
self.headings = headings
Expand Down
40 changes: 37 additions & 3 deletions python/delphyne/behaviours/roads.py
Original file line number Diff line number Diff line change
@@ -1,10 +1,24 @@
# Copyright 2019 Toyota Research Institute

"""
A module providing road composites.
"""

import delphyne.roads
import delphyne.blackboard.blackboard_helper as bb_helper
import delphyne.blackboard

import py_trees.composites
import py_trees.common


class Road(py_trees.composites.Sequence):
"""
A sequence composite for behaviours that take place in a road (i.e. world).
Subclasses are expected to take care of road setup in simulation.
As children may require road access during construction, roads go
through a two stage setup: once before their children, once afterwards.
"""

def __init__(self, *args, **kwargs):
super().__init__(*args, **kwargs)
Expand All @@ -17,9 +31,19 @@ def iterate(self, *args, **kwargs):


class Dragway(Road):
"""
A maliput dragway road.
"""

def __init__(self, num_lanes, length, lane_width, shoulder_width,
maximum_height, name=py_trees.common.Name.AUTO_GENERATED):
"""
:param num_lanes: number of dragway lanes.
:param length: length of the dragway lanes, in meters.
:param lane_width: width of the dragway lanes, in meters.
:param shoulder_width: should width for dragway lanes, in meters.
:param maximum_height: h upper bound for dragway lanes, in meters.
"""
super().__init__(name)
self.num_lanes = num_lanes
self.length = length
Expand All @@ -29,6 +53,7 @@ def __init__(self, num_lanes, length, lane_width, shoulder_width,

def setup(self, *, builder):
if self.road_geometry is None:
# Setup a road geometry only the first time.
self.road_geometry = builder.set_road_geometry(
delphyne.roads.create_dragway(
name=self.name,
Expand All @@ -39,19 +64,28 @@ def setup(self, *, builder):
maximum_height=self.maximum_height
)
)
bb_helper.set_road_geometry(self.road_geometry)
delphyne.blackboard.state.set_road_geometry(self.road_geometry)


class Multilane(Road):
"""
A maliput multilane road.
"""

def __init__(self, file_path, name=py_trees.common.Name.AUTO_GENERATED):
"""
:param file_path: path to the YAML description file of a maliput
multilane road geometry.
:param name: for the road geometry to be loaded.
"""
super().__init__(name)
self.file_path = file_path

def setup(self, *, builder):
if self.road_geometry is None:
# Setup a road geometry only the first time.
self.road_geometry = builder.set_road_geometry(
delphyne.roads.create_multilane_from_file(
self.file_path)
)
bb_helper.set_road_geometry(self.road_geometry)
delphyne.blackboard.state.set_road_geometry(self.road_geometry)
9 changes: 7 additions & 2 deletions python/delphyne/blackboard/__init__.py
Original file line number Diff line number Diff line change
@@ -1,5 +1,10 @@
from . import blackboard_helper
# Copyright 2019 Toyota Research Institute

from . import providers
from . import state


__all__ = [
blackboard_helper
'providers',
'state',
]
Loading

0 comments on commit 7aa73ee

Please sign in to comment.