simulation.src.simulation_evaluation.src.referee package

Submodules

simulation.src.simulation_evaluation.src.referee.node module

Classes:

RefereeNode()

Evaluate the drive.

class RefereeNode[source]

Bases: simulation.utils.ros_base.node_base.NodeBase

Evaluate the drive.

Keep track of the state machines and the broadcast speaker to calculate a score.

Methods:

start()

Called when activating the node.

stop()

Called when deactivating or shutting down the node.

_connect_state_machine(sm_topics)

update(broadcast)

Update referee output with new broadcast msg.

reset_cb(msg)

Reset the referee.

start()[source]

Called when activating the node.

stop()[source]

Called when deactivating or shutting down the node.

_connect_state_machine(sm_topics)Tuple[rospy.topics.Subscriber, rospy.topics.Publisher, simulation.src.simulation_evaluation.src.referee.referee.StateMachineConnector][source]
update(broadcast: simulation_evaluation.msg._Broadcast.Broadcast)[source]

Update referee output with new broadcast msg.

reset_cb(msg: std_msgs.msg._Bool.Bool)[source]

Reset the referee.

Parameters

msg – Reset observation’s or only the state.

simulation.src.simulation_evaluation.src.referee.referee module

Definition of the Referee class.

The referee is used to provide a score and other metrics to a simulated drive.

Classes:

StateMachineConnector(state, set_state, None])

Helper class to store states and manipulate corresponding state machine.

Observation(start_time, current_time, …)

Track what happens while driving and calculate a score.

Referee(lane, progress, overtaking, parking, …)

Class to evaluate a drive by keeping track of the state_machines.

class StateMachineConnector(state: int, set_state: Callable[[int], None])[source]

Bases: object

Helper class to store states and manipulate corresponding state machine.

Parameters
  • state – State of the state machine.

  • set_state – Call to change the state of the state_machine.

Attributes:

previous_state

State the state machine was in before the current state.

set_state

Change the state of the state_machine.

state

State of the state machine.

previous_state: int

State the state machine was in before the current state.

_state: int
set_state: Callable[[int], None]

Change the state of the state_machine.

property state

State of the state machine.

class Observation(start_time: float = 0, current_time: float = 0, start_distance: float = 0, current_distance: float = 0, multiplicator: float = 1, mistakes: float = 0, parking_successes: int = 0)[source]

Bases: object

Track what happens while driving and calculate a score.

Attributes:

start_time

Time [s] when the car left the start zone.

current_time

Current time [s].

start_distance

Distance [m] already driven in start zone.

current_distance

Distance [m] already driven.

multiplicator

Multiplicator used to calculate the score.

mistakes

Mistakes [point] made by the car.

parking_successes

Number of successful parking attempts.

score

Score calculated from other attributes.

distance

Difference between start and current distance.

duration

Difference between start and current time.

start_time: float = 0

Time [s] when the car left the start zone.

current_time: float = 0

Current time [s].

start_distance: float = 0

Distance [m] already driven in start zone.

current_distance: float = 0

Distance [m] already driven.

multiplicator: float = 1

Multiplicator used to calculate the score.

mistakes: float = 0

Mistakes [point] made by the car.

parking_successes: int = 0

Number of successful parking attempts.

property score: float

Score calculated from other attributes.

property distance: float

Difference between start and current distance.

property duration: float

Difference between start and current time.

class Referee(lane: simulation.src.simulation_evaluation.src.referee.referee.StateMachineConnector, progress: simulation.src.simulation_evaluation.src.referee.referee.StateMachineConnector, overtaking: simulation.src.simulation_evaluation.src.referee.referee.StateMachineConnector, parking: simulation.src.simulation_evaluation.src.referee.referee.StateMachineConnector, priority: simulation.src.simulation_evaluation.src.referee.referee.StateMachineConnector, speed: simulation.src.simulation_evaluation.src.referee.referee.StateMachineConnector, initial_observation: Optional[simulation.src.simulation_evaluation.src.referee.referee.Observation] = None)[source]

Bases: object

Class to evaluate a drive by keeping track of the state_machines.

Parameters
  • lane – Connector to lane state machine.

  • progress – Connector to progress state machine.

  • overtaking – Connector to overtaking state machine.

  • parking – Connector to parking state machine.

  • priority – Connector to priority state machine.

  • initial_observation – Referee’s observation initialization value.

  • reset_callback – Function to reset the referee.

Methods:

update(time, distance)

Update the referee’s observation.

reset([initial_observation])

Reset referee observations, state and state machines.

update(time: float, distance: float)[source]

Update the referee’s observation.

Parameters
  • time – Current time in seconds.

  • distance – Distance driven in meters.

reset(initial_observation: Optional[simulation.src.simulation_evaluation.src.referee.referee.Observation] = None)[source]

Reset referee observations, state and state machines.

Module contents

Referee class and node definition.