simulation.src.simulation_evaluation.src.speaker.speakers package

Submodules

simulation.src.simulation_evaluation.src.speaker.speakers.area module

Classes:

AreaSpeaker(*, section_proxy, …)

Check in which area of the road the vehicle is (e.g.

class AreaSpeaker(*, section_proxy: Callable[], List[simulation_groundtruth.msg._Section.Section]], lane_proxy: Callable[[int], simulation_groundtruth.msg._Lane.Lane], parking_proxy: Callable[[int], Any], min_wheel_count: int, area_buffer: int)[source]

Bases: simulation.src.simulation_evaluation.src.speaker.speakers.speaker.Speaker

Check in which area of the road the vehicle is (e.g. right corridor, parking lot).

Attributes:

left_corridor

Concatenated left corridor from all sections.

right_corridor

Concatenated right corridor from all sections.

parking_lots

Return all parking bays as a list of polygons.

Methods:

speak()

Return a list of SpeakerMsgs.

property left_corridor

Concatenated left corridor from all sections.

property right_corridor

Concatenated right corridor from all sections.

property parking_lots

Return all parking bays as a list of polygons.

speak()[source]

Return a list of SpeakerMsgs.

With one of the following messages.

Contents:
  • Right lane -> Speaker.RIGHT_LANE,

  • right or left lange -> Speaker.LEFT_LANE,

  • right, left lane or parking lot -> Speaker.PARKING_LOT,

  • None of the above -> Speaker.OFF_ROAD

simulation.src.simulation_evaluation.src.speaker.speakers.broadcast module

Classes:

BroadcastSpeaker(*, section_proxy, …)

Keep high level information about the drive (e.g.

class BroadcastSpeaker(*, section_proxy: Callable[], List[simulation_groundtruth.msg._Section.Section]], lane_proxy: Callable[[int], simulation_groundtruth.msg._Lane.Lane], obstacle_proxy: Optional[Callable[[int], List[simulation_groundtruth.msg._LabeledPolygon.LabeledPolygon]]] = None, surface_marking_proxy: Optional[Callable[[int], List[simulation_groundtruth.msg._LabeledPolygon.LabeledPolygon]]] = None, intersection_proxy: Optional[Callable[[int], Any]] = None, sign_proxy: Optional[Callable[[int], List[simulation_groundtruth.msg._LabeledPolygon.LabeledPolygon]]] = None)[source]

Bases: simulation.src.simulation_evaluation.src.speaker.speakers.speaker.Speaker

Keep high level information about the drive (e.g. speed, distance driven).

Instead of returning Speaker msgs this speaker returns a Broadcast msg.

Methods:

speak()

Return a new broadcast msg in a list.

speak()List[simulation_evaluation.msg._Broadcast.Broadcast][source]

Return a new broadcast msg in a list.

simulation.src.simulation_evaluation.src.speaker.speakers.event module

Definition of the EventSpeaker class.

Classes:

EventSpeaker(*, section_proxy, …)

Find events that happen during a drive e.g collision, parked in spot.

class EventSpeaker(*, section_proxy: Callable[], List[simulation_groundtruth.msg._Section.Section]], lane_proxy: Callable[[int], simulation_groundtruth.msg._Lane.Lane], obstacle_proxy: Callable[[int], List[simulation_groundtruth.msg._LabeledPolygon.LabeledPolygon]], surface_marking_proxy: Callable[[int], List[simulation_groundtruth.msg._LabeledPolygon.LabeledPolygon]], parking_proxy: Callable[[int], Any], parking_spot_buffer: float, min_parking_wheels: int)[source]

Bases: simulation.src.simulation_evaluation.src.speaker.speakers.speaker.Speaker

Find events that happen during a drive e.g collision, parked in spot.

Attributes:

parking_spots

Return all parking spots as a list of polygons.

obstacles

All obstacles as a list of polygons.

blocked_areas

All blocked_areas as a list of polygons.

Methods:

speak()

Return a list of SpeakerMsgs.

property parking_spots

Return all parking spots as a list of polygons.

property obstacles: List[simulation.utils.geometry.polygon.Polygon]

All obstacles as a list of polygons.

property blocked_areas

All blocked_areas as a list of polygons.

speak()List[simulation_evaluation.msg._Speaker.Speaker][source]

Return a list of SpeakerMsgs.

Contents:
  • Collision with an obstacle -> Speaker.COLLISION,

  • inside a parking spot -> Speaker.PARKING_SPOT

simulation.src.simulation_evaluation.src.speaker.speakers.speaker module

Base class for all other speakers.

Classes:

LabeledSpeakerPolygon(id_, desc, frame, height)

Speaker(*, section_proxy, …)

Base class for all speakers.

class LabeledSpeakerPolygon(id_: int, desc: str, frame: simulation.utils.geometry.polygon.Polygon, height: float)[source]

Bases: object

Attributes:

id_: int
desc: str
frame: simulation.utils.geometry.polygon.Polygon
height: float
class Speaker(*, section_proxy: Callable[], List[simulation_groundtruth.msg._Section.Section]], lane_proxy: Callable[[int], simulation_groundtruth.msg._Lane.Lane], obstacle_proxy: Optional[Callable[[int], List[simulation_groundtruth.msg._LabeledPolygon.LabeledPolygon]]] = None, surface_marking_proxy: Optional[Callable[[int], List[simulation_groundtruth.msg._LabeledPolygon.LabeledPolygon]]] = None, intersection_proxy: Optional[Callable[[int], Any]] = None, sign_proxy: Optional[Callable[[int], List[simulation_groundtruth.msg._LabeledPolygon.LabeledPolygon]]] = None)[source]

Bases: object

Base class for all speakers.

This class is part of the evaluation pipeline used to automatically evaluate the cars behavior in simulation. It converts information about the cars state and the predefined groundtruth into SpeakerMsg’s which serve as inputs for the state machines.

Information is passed to the speaker by calling the Speaker.listen() function

with a new CarState msg.

Output can be retrieved in form of Speaker msgs by calling the .speak function.

sections

List of all sections as SectionMsgs

Type

Callable[[], List[SectionMsg]]

get_lanes

Get LaneMsg for a given section

Type

Callable[[int], LaneMsg]

get_obstacles

Get ObstacleMsg for a given section

Type

Callable[[int], List[LabeledPolygonMsg]]

get_intersection

Get intersections for a given section

Type

Callable[[int], Any]

Methods:

listen(msg)

Receive information about current observations and update internal values.

speak()

Speak about the current observations.

get_road_lines(section_id)

Request and return the road lines of a single section.

_get_labeled_polygons(proxy, section_id)

Get all objects inside a section returned by a service.

get_obstacles_in_section(section_id)

Get all obstacles in a section.

get_traffic_signs_in_section(section_id)

Get all traffic_signs inside section.

get_surface_markings_in_section(section_id)

Get all surface_markings inside a section.

get_interval_for_polygon(*polygons)

Get start and end points of the polygons.

car_is_inside(*polygons[, min_wheel_count])

Check if the car is currently inside one of the polygons.

wheel_count_inside(*polygons[, in_total])

Get the maximum number of wheels inside one of the polygons.

car_overlaps_with(*polygons)

Decide if the car overlaps with any of the polygons.

Attributes:

middle_line

Complete middle line.

left_line

Complete left line.

right_line

Complete right line.

arc_length

Position of the car projected on the middle line (== Length driven so far).

section_intervals

Get (start,end) intervals of all sections.

current_section

Get the current section.

listen(msg: gazebo_simulation.msg._CarState.CarState)[source]

Receive information about current observations and update internal values.

speak()List[simulation_evaluation.msg._Speaker.Speaker][source]

Speak about the current observations.

property middle_line

Complete middle line.

property left_line

Complete left line.

property right_line

Complete right line.

property arc_length

Position of the car projected on the middle line (== Length driven so far).

property section_intervals

Get (start,end) intervals of all sections.

property current_section

Get the current section.

Returns

SectionMsg of the current.

get_road_lines(section_id: int)simulation.utils.road.sections.line_tuple.LineTuple[source]

Request and return the road lines of a single section.

Parameters

section_id (int) – id of the section

Returns

LineTuple of the section as a named tuple.

_get_labeled_polygons(proxy: Callable[[int], List[simulation_groundtruth.msg._LabeledPolygon.LabeledPolygon]], section_id: int)List[simulation.src.simulation_evaluation.src.speaker.speakers.speaker.LabeledSpeakerPolygon][source]

Get all objects inside a section returned by a service.

Parameters
  • proxy – Service receiver function

  • section_id – id of the section

Returns

List of tuples containing id, description, polygon, and height.

get_obstacles_in_section(section_id: int)List[simulation.src.simulation_evaluation.src.speaker.speakers.speaker.LabeledSpeakerPolygon][source]

Get all obstacles in a section.

get_traffic_signs_in_section(section_id: int)List[simulation.src.simulation_evaluation.src.speaker.speakers.speaker.LabeledSpeakerPolygon][source]

Get all traffic_signs inside section.

get_surface_markings_in_section(section_id: int)List[simulation.src.simulation_evaluation.src.speaker.speakers.speaker.LabeledSpeakerPolygon][source]

Get all surface_markings inside a section.

get_interval_for_polygon(*polygons: Iterable[simulation.utils.geometry.polygon.Polygon])Tuple[float, float][source]

Get start and end points of the polygons.

Parameters

polygon – The polygon.

Returns

Start and end point for each polygon as a tuple

car_is_inside(*polygons: Iterable[simulation.utils.geometry.polygon.Polygon], min_wheel_count: Optional[int] = None)bool[source]

Check if the car is currently inside one of the polygons.

The car can also be in the union of the provided polygons.

Parameters
  • polygons – The polygons.

  • min_wheel_count – If provided it is enough for a given number of wheels to be inside the polygons (e.g. 3 wheels inside parking spot)

wheel_count_inside(*polygons: Iterable[simulation.utils.geometry.polygon.Polygon], in_total: bool = False)int[source]

Get the maximum number of wheels inside one of the polygons.

Parameters
  • polygons – The polygons.

  • in_total – If true, the number of wheels are summed up

car_overlaps_with(*polygons: Iterable[simulation.utils.geometry.polygon.Polygon])bool[source]

Decide if the car overlaps with any of the polygons.

Parameters

polygons – The polygons.

simulation.src.simulation_evaluation.src.speaker.speakers.speed module

Definition of the SpeedSpeaker class.

Classes:

SpeedSpeaker(time, speed_factor, …)

Publish information about the cars speed.

class SpeedSpeaker(time: float = 0, speed_factor: float = 36.0, stop_threshold: float = 1, halt_time: float = 1, stop_time: float = 3)[source]

Bases: simulation.src.simulation_evaluation.src.speaker.speakers.speaker.Speaker

Publish information about the cars speed.

Methods:

speak([current_time])

List of SpeakerMsgs with the current speed as the only entry.

speak(current_time: Optional[float] = None)List[simulation_evaluation.msg._Speaker.Speaker][source]

List of SpeakerMsgs with the current speed as the only entry.

simulation.src.simulation_evaluation.src.speaker.speakers.zone module

Class definition of the ZoneSpeaker.

Classes:

ZoneSpeaker(*, section_proxy, …)

Information about the zone of the road the car is in.

class ZoneSpeaker(*, section_proxy: Callable[], List[simulation_groundtruth.msg._Section.Section]], lane_proxy: Callable[[int], simulation_groundtruth.msg._Lane.Lane], obstacle_proxy: Callable[[int], List[simulation_groundtruth.msg._LabeledPolygon.LabeledPolygon]], surface_marking_proxy: Callable[[int], List[simulation_groundtruth.msg._LabeledPolygon.LabeledPolygon]], parking_proxy: Callable[[int], Any], intersection_proxy: Callable[[int], Any], overtaking_buffer: float = 2, start_zone_buffer: float = 1, end_zone_buffer: float = 1.5, yield_distance: Tuple[float, float] = (- 0.6, - 0.2))[source]

Bases: simulation.src.simulation_evaluation.src.speaker.speakers.speaker.Speaker

Information about the zone of the road the car is in.

Attributes:

overtaking_zones

Intervals in which the car is allowed to overtake along the Speaker.middle_line.

stop_zones

Intervals in which the car is supposed to stop (in front of intersections).

halt_zones

Intervals in which the car is supposed to halt (in front of intersections).

speed_zones

Methods:

_intersection_yield_zones(rule)

Intervals in which the car is supposed to halt/stop (in front of intersections).

_inside_any_interval(intervals)

Determine if the car is currently in any of the given intervals.

speak()

List of speaker msgs.

property overtaking_zones

Intervals in which the car is allowed to overtake along the Speaker.middle_line.

_intersection_yield_zones(rule: int)List[Tuple[float, float]][source]

Intervals in which the car is supposed to halt/stop (in front of intersections).

Parameters

rule – only intersections with this rule are considered

property stop_zones

Intervals in which the car is supposed to stop (in front of intersections).

property halt_zones

Intervals in which the car is supposed to halt (in front of intersections).

property speed_zones
_inside_any_interval(intervals: List[Tuple[float, float]])bool[source]

Determine if the car is currently in any of the given intervals.

speak()List[simulation_evaluation.msg._Speaker.Speaker][source]

List of speaker msgs.

Contents:
  • beginning of road -> Speaker.START_ZONE, end of road -> Speaker.END_ZONE, and in between -> Speaker.DRIVING_ZONE,

  • close to an obstacle -> Speaker.OVERTAKING_ZONE

  • before yield/stop lines -> Speaker.HALT_ZONE/SpeakerMsg.STOP_ZONE,

  • parking area -> Speaker.PARKING_ZONE

Module contents

The speakers package contains all speaker classes.

The common base class is Speaker. The speakers are used to combine the current CarState with known groundtruth information.

Classes:

Speaker(*, section_proxy, …)

Base class for all speakers.

EventSpeaker(*, section_proxy, …)

Find events that happen during a drive e.g collision, parked in spot.

AreaSpeaker(*, section_proxy, …)

Check in which area of the road the vehicle is (e.g.

SpeedSpeaker(time, speed_factor, …)

Publish information about the cars speed.

ZoneSpeaker(*, section_proxy, …)

Information about the zone of the road the car is in.

BroadcastSpeaker(*, section_proxy, …)

Keep high level information about the drive (e.g.

class Speaker(*, section_proxy: Callable[], List[simulation_groundtruth.msg._Section.Section]], lane_proxy: Callable[[int], simulation_groundtruth.msg._Lane.Lane], obstacle_proxy: Optional[Callable[[int], List[simulation_groundtruth.msg._LabeledPolygon.LabeledPolygon]]] = None, surface_marking_proxy: Optional[Callable[[int], List[simulation_groundtruth.msg._LabeledPolygon.LabeledPolygon]]] = None, intersection_proxy: Optional[Callable[[int], Any]] = None, sign_proxy: Optional[Callable[[int], List[simulation_groundtruth.msg._LabeledPolygon.LabeledPolygon]]] = None)[source]

Bases: object

Base class for all speakers.

This class is part of the evaluation pipeline used to automatically evaluate the cars behavior in simulation. It converts information about the cars state and the predefined groundtruth into SpeakerMsg’s which serve as inputs for the state machines.

Information is passed to the speaker by calling the Speaker.listen() function

with a new CarState msg.

Output can be retrieved in form of Speaker msgs by calling the .speak function.

sections

List of all sections as SectionMsgs

Type

Callable[[], List[SectionMsg]]

get_lanes

Get LaneMsg for a given section

Type

Callable[[int], LaneMsg]

get_obstacles

Get ObstacleMsg for a given section

Type

Callable[[int], List[LabeledPolygonMsg]]

get_intersection

Get intersections for a given section

Type

Callable[[int], Any]

Methods:

listen(msg)

Receive information about current observations and update internal values.

speak()

Speak about the current observations.

get_road_lines(section_id)

Request and return the road lines of a single section.

_get_labeled_polygons(proxy, section_id)

Get all objects inside a section returned by a service.

get_obstacles_in_section(section_id)

Get all obstacles in a section.

get_traffic_signs_in_section(section_id)

Get all traffic_signs inside section.

get_surface_markings_in_section(section_id)

Get all surface_markings inside a section.

get_interval_for_polygon(*polygons)

Get start and end points of the polygons.

car_is_inside(*polygons[, min_wheel_count])

Check if the car is currently inside one of the polygons.

wheel_count_inside(*polygons[, in_total])

Get the maximum number of wheels inside one of the polygons.

car_overlaps_with(*polygons)

Decide if the car overlaps with any of the polygons.

Attributes:

middle_line

Complete middle line.

left_line

Complete left line.

right_line

Complete right line.

arc_length

Position of the car projected on the middle line (== Length driven so far).

section_intervals

Get (start,end) intervals of all sections.

current_section

Get the current section.

listen(msg: gazebo_simulation.msg._CarState.CarState)[source]

Receive information about current observations and update internal values.

speak()List[simulation_evaluation.msg._Speaker.Speaker][source]

Speak about the current observations.

property middle_line

Complete middle line.

property left_line

Complete left line.

property right_line

Complete right line.

property arc_length

Position of the car projected on the middle line (== Length driven so far).

property section_intervals

Get (start,end) intervals of all sections.

property current_section

Get the current section.

Returns

SectionMsg of the current.

get_road_lines(section_id: int)simulation.utils.road.sections.line_tuple.LineTuple[source]

Request and return the road lines of a single section.

Parameters

section_id (int) – id of the section

Returns

LineTuple of the section as a named tuple.

_get_labeled_polygons(proxy: Callable[[int], List[simulation_groundtruth.msg._LabeledPolygon.LabeledPolygon]], section_id: int)List[simulation.src.simulation_evaluation.src.speaker.speakers.speaker.LabeledSpeakerPolygon][source]

Get all objects inside a section returned by a service.

Parameters
  • proxy – Service receiver function

  • section_id – id of the section

Returns

List of tuples containing id, description, polygon, and height.

get_obstacles_in_section(section_id: int)List[simulation.src.simulation_evaluation.src.speaker.speakers.speaker.LabeledSpeakerPolygon][source]

Get all obstacles in a section.

get_traffic_signs_in_section(section_id: int)List[simulation.src.simulation_evaluation.src.speaker.speakers.speaker.LabeledSpeakerPolygon][source]

Get all traffic_signs inside section.

get_surface_markings_in_section(section_id: int)List[simulation.src.simulation_evaluation.src.speaker.speakers.speaker.LabeledSpeakerPolygon][source]

Get all surface_markings inside a section.

get_interval_for_polygon(*polygons: Iterable[simulation.utils.geometry.polygon.Polygon])Tuple[float, float][source]

Get start and end points of the polygons.

Parameters

polygon – The polygon.

Returns

Start and end point for each polygon as a tuple

car_is_inside(*polygons: Iterable[simulation.utils.geometry.polygon.Polygon], min_wheel_count: Optional[int] = None)bool[source]

Check if the car is currently inside one of the polygons.

The car can also be in the union of the provided polygons.

Parameters
  • polygons – The polygons.

  • min_wheel_count – If provided it is enough for a given number of wheels to be inside the polygons (e.g. 3 wheels inside parking spot)

wheel_count_inside(*polygons: Iterable[simulation.utils.geometry.polygon.Polygon], in_total: bool = False)int[source]

Get the maximum number of wheels inside one of the polygons.

Parameters
  • polygons – The polygons.

  • in_total – If true, the number of wheels are summed up

car_overlaps_with(*polygons: Iterable[simulation.utils.geometry.polygon.Polygon])bool[source]

Decide if the car overlaps with any of the polygons.

Parameters

polygons – The polygons.

class EventSpeaker(*, section_proxy: Callable[], List[simulation_groundtruth.msg._Section.Section]], lane_proxy: Callable[[int], simulation_groundtruth.msg._Lane.Lane], obstacle_proxy: Callable[[int], List[simulation_groundtruth.msg._LabeledPolygon.LabeledPolygon]], surface_marking_proxy: Callable[[int], List[simulation_groundtruth.msg._LabeledPolygon.LabeledPolygon]], parking_proxy: Callable[[int], Any], parking_spot_buffer: float, min_parking_wheels: int)[source]

Bases: simulation.src.simulation_evaluation.src.speaker.speakers.speaker.Speaker

Find events that happen during a drive e.g collision, parked in spot.

Attributes:

parking_spots

Return all parking spots as a list of polygons.

obstacles

All obstacles as a list of polygons.

blocked_areas

All blocked_areas as a list of polygons.

Methods:

speak()

Return a list of SpeakerMsgs.

property parking_spots

Return all parking spots as a list of polygons.

property obstacles: List[simulation.utils.geometry.polygon.Polygon]

All obstacles as a list of polygons.

property blocked_areas

All blocked_areas as a list of polygons.

speak()List[simulation_evaluation.msg._Speaker.Speaker][source]

Return a list of SpeakerMsgs.

Contents:
  • Collision with an obstacle -> Speaker.COLLISION,

  • inside a parking spot -> Speaker.PARKING_SPOT

class AreaSpeaker(*, section_proxy: Callable[], List[simulation_groundtruth.msg._Section.Section]], lane_proxy: Callable[[int], simulation_groundtruth.msg._Lane.Lane], parking_proxy: Callable[[int], Any], min_wheel_count: int, area_buffer: int)[source]

Bases: simulation.src.simulation_evaluation.src.speaker.speakers.speaker.Speaker

Check in which area of the road the vehicle is (e.g. right corridor, parking lot).

Attributes:

left_corridor

Concatenated left corridor from all sections.

right_corridor

Concatenated right corridor from all sections.

parking_lots

Return all parking bays as a list of polygons.

Methods:

speak()

Return a list of SpeakerMsgs.

property left_corridor

Concatenated left corridor from all sections.

property right_corridor

Concatenated right corridor from all sections.

property parking_lots

Return all parking bays as a list of polygons.

speak()[source]

Return a list of SpeakerMsgs.

With one of the following messages.

Contents:
  • Right lane -> Speaker.RIGHT_LANE,

  • right or left lange -> Speaker.LEFT_LANE,

  • right, left lane or parking lot -> Speaker.PARKING_LOT,

  • None of the above -> Speaker.OFF_ROAD

class SpeedSpeaker(time: float = 0, speed_factor: float = 36.0, stop_threshold: float = 1, halt_time: float = 1, stop_time: float = 3)[source]

Bases: simulation.src.simulation_evaluation.src.speaker.speakers.speaker.Speaker

Publish information about the cars speed.

Methods:

speak([current_time])

List of SpeakerMsgs with the current speed as the only entry.

speak(current_time: Optional[float] = None)List[simulation_evaluation.msg._Speaker.Speaker][source]

List of SpeakerMsgs with the current speed as the only entry.

class ZoneSpeaker(*, section_proxy: Callable[], List[simulation_groundtruth.msg._Section.Section]], lane_proxy: Callable[[int], simulation_groundtruth.msg._Lane.Lane], obstacle_proxy: Callable[[int], List[simulation_groundtruth.msg._LabeledPolygon.LabeledPolygon]], surface_marking_proxy: Callable[[int], List[simulation_groundtruth.msg._LabeledPolygon.LabeledPolygon]], parking_proxy: Callable[[int], Any], intersection_proxy: Callable[[int], Any], overtaking_buffer: float = 2, start_zone_buffer: float = 1, end_zone_buffer: float = 1.5, yield_distance: Tuple[float, float] = (- 0.6, - 0.2))[source]

Bases: simulation.src.simulation_evaluation.src.speaker.speakers.speaker.Speaker

Information about the zone of the road the car is in.

Attributes:

overtaking_zones

Intervals in which the car is allowed to overtake along the Speaker.middle_line.

stop_zones

Intervals in which the car is supposed to stop (in front of intersections).

halt_zones

Intervals in which the car is supposed to halt (in front of intersections).

speed_zones

Methods:

_intersection_yield_zones(rule)

Intervals in which the car is supposed to halt/stop (in front of intersections).

_inside_any_interval(intervals)

Determine if the car is currently in any of the given intervals.

speak()

List of speaker msgs.

property overtaking_zones

Intervals in which the car is allowed to overtake along the Speaker.middle_line.

_intersection_yield_zones(rule: int)List[Tuple[float, float]][source]

Intervals in which the car is supposed to halt/stop (in front of intersections).

Parameters

rule – only intersections with this rule are considered

property stop_zones

Intervals in which the car is supposed to stop (in front of intersections).

property halt_zones

Intervals in which the car is supposed to halt (in front of intersections).

property speed_zones
_inside_any_interval(intervals: List[Tuple[float, float]])bool[source]

Determine if the car is currently in any of the given intervals.

speak()List[simulation_evaluation.msg._Speaker.Speaker][source]

List of speaker msgs.

Contents:
  • beginning of road -> Speaker.START_ZONE, end of road -> Speaker.END_ZONE, and in between -> Speaker.DRIVING_ZONE,

  • close to an obstacle -> Speaker.OVERTAKING_ZONE

  • before yield/stop lines -> Speaker.HALT_ZONE/SpeakerMsg.STOP_ZONE,

  • parking area -> Speaker.PARKING_ZONE

class BroadcastSpeaker(*, section_proxy: Callable[], List[simulation_groundtruth.msg._Section.Section]], lane_proxy: Callable[[int], simulation_groundtruth.msg._Lane.Lane], obstacle_proxy: Optional[Callable[[int], List[simulation_groundtruth.msg._LabeledPolygon.LabeledPolygon]]] = None, surface_marking_proxy: Optional[Callable[[int], List[simulation_groundtruth.msg._LabeledPolygon.LabeledPolygon]]] = None, intersection_proxy: Optional[Callable[[int], Any]] = None, sign_proxy: Optional[Callable[[int], List[simulation_groundtruth.msg._LabeledPolygon.LabeledPolygon]]] = None)[source]

Bases: simulation.src.simulation_evaluation.src.speaker.speakers.speaker.Speaker

Keep high level information about the drive (e.g. speed, distance driven).

Instead of returning Speaker msgs this speaker returns a Broadcast msg.

Methods:

speak()

Return a new broadcast msg in a list.

speak()List[simulation_evaluation.msg._Broadcast.Broadcast][source]

Return a new broadcast msg in a list.