Agents¶
-
class
vista.entities.agents.Car.Car(world: <module 'vista.core.World' from '/home/amini/projects/vista/vista/core/World.py'>, car_config: Dict)[source]¶ The class of a car agent. This object lives in the
Worldand is attached to a trace object that provides pointers to dataset for data-driven simulation and zero or one or more sensor objects that synthesize sensory measurement. The update of vehicle state is handled in this object.- Parameters
world (World) – The world that this agent lives in.
car_config (Dict) –
Configuration of the car. An example (default) is,
>>> DEFAULT_CONFIG = { 'length': 5., 'width': 2., 'wheel_base': 2.78, 'steering_ratio': 14.7, 'lookahead_road': False, 'road_buffer_size': 200, }
Example Usage (always make sure reset is called first to initialize vehicle state or pointer to the dataset for data-driven simulation):
>>> car = world.spawn_agent(car_config) >>> car.spawn_camera(camera_config) >>> world.reset() >>> car.step_dynamics(action) # update vehicle states >>> car.step_sensors() # do sensor capture >>> observation = car.observations # fetch sensory measurement >>> car.step_dataset() # simply get next frame in the dataset without synthesis
-
spawn_camera(config: Dict) → vista.entities.sensors.Camera.Camera[source]¶ Spawn and attach a camera to this car.
- Parameters
config (Dict) – Configuration of camera and rendering. For more details, please check the doc of
Camerasensor.- Returns
a vista camera sensor object spawned.
- Return type
-
spawn_lidar(config: Dict) → vista.entities.sensors.Lidar.Lidar[source]¶ Spawn and attach a LiDAR to this car.
- Parameters
config (Dict) – Configuration of LiDAR. For more details, please check the doc of
Lidarsensor.- Returns
a vista Lidar sensor object spawned.
- Return type
-
spawn_event_camera(config: Dict) → vista.entities.sensors.EventCamera.EventCamera[source]¶ Spawn and attach an event camera to this car.
- Parameters
config (Dict) – Configuration of event camera. For more details, please check the doc of
EventCamerasensor.- Returns
a vista event camera sensor object spawned.
- Return type
-
reset(trace_index: int, segment_index: int, frame_index: int, initial_dynamics_fn: Optional[Callable] = None, step_sensors: Optional[bool] = True) → None[source]¶ Reset the car. This involves pointing to somewhere in the dataset for later-on data-driven simulation, initializing vehicle state, and resetting all sensors attached to this car. If
lookahead_road = True, the road cache will also be reset.- Parameters
trace_index (int) – A pointer to which trace to be simulated on.
segment_index (int) – A pointer to which segment in a trace to be simulated on.
frame_index (int) – A pointer to which frame in a segment to be simulated on.
initial_dynamics_fn (Callable) – A function to initialize vehicle state. The function takes x, y, yaw, steering (tire angle), and speed as inputs. Default is set to
None, which initialize vehicle with the same state as the dataset.step_sensors (bool) – Whether to step sensor; default is set to
True.
-
step_dataset(step_dynamics=True)[source]¶ Step through the dataset without rendering. This is basically fetching the next frame from the dataset. Normally, it is called when doing imitation learning.
- Parameters
step_dynamics (bool) – Whether to update vehicle state; default is set to
True.- Raises
NotImplementedError – if any attached sensor has no implemented function for stepping through dataset.
-
step_dynamics(action: numpy.ndarray, dt: Optional[float] = 0.03333333333333333, update_road: Optional[bool] = True) → None[source]¶ Update vehicle state given control command based on vehicle dynamics and update timestamp, which is then used to update pointer to the dataset for data-driven simulation.
- Parameters
action (np.ndarray) – Control command (curvature and speed).
dt (float) – Elapsed time.
update_road (bool) – Whether to update road cache; default is set to
True.
-
property
trace¶ The
Tracecurrently associated with the car.
-
property
sensors¶ All sensors attached to this car.
-
property
relative_state¶ Relative transform between
ego_dynamicsandhuman_dynamics.
-
property
ego_dynamics¶ Current simulated vehicle state.
-
property
human_dynamics¶ Vehicle state of the current pointer to the dataset (human trajectory).
-
property
length¶ Car length.
-
property
width¶ Car width.
-
property
wheel_base¶ Wheel base.
-
property
steering_ratio¶ Steering ratio.
-
property
speed¶ Speed of simulated trajectory (this car) in current timestamp.
-
property
curvature¶ Curvature of simulated trajectory (this car) in current timestamp.
-
property
steering¶ Steering angle of simulated trajectory (this car) in current timestamp.
-
property
tire_angle¶ Tire angle of simulated trajectory (this car) in current timestamp.
-
property
human_speed¶ Speed of human trajectory in current timestamp.
-
property
human_curvature¶ Curvature of human trajectory in current timestamp.
-
property
human_steering¶ Steering angle of human trajectory in current timestamp.
-
property
human_tire_angle¶ Tire angle of human trajectory in current timestamp.
-
property
timestamp¶ Current timestamp (normally ROS timestamp). This serves as a continuous pointer to the dataset as opposed to
trace_index,segment_index, andframe_index.
-
property
frame_number¶ Current frame number. Note that this is different from
frame_indexas it is a different pointer based on how we define frame in themaster_sensorinstead of a pointer to the dataset. There is only one unique pointer to the dataset, which can be mapped to (potentially) different pointers to the frame number in different sensors.
-
property
trace_index¶ Current pointer to the trace.
-
property
segment_index¶ Current pointer to the segment in the current trace.
-
property
frame_index¶ Current pointer to the frame in the current segment.
-
property
observations¶ Sensory measurement at current timestamp.
-
property
done¶ Whether exceeding the end of the trace currently associated with the car.
-
property
road¶ Road cache if
lookahead_road = TrueotherwiseNone.
-
property
config¶ Configuration of this car.
-
property
id¶ The identifier of this entity.
-
property
parent¶ The parent of this entity.
-
class
vista.entities.agents.Dynamics.StateDynamics(x: Optional[float] = 0.0, y: Optional[float] = 0.0, yaw: Optional[float] = 0.0, steering: Optional[float] = 0.0, speed: Optional[float] = 0.0, steering_bound: Optional[List[float]] = [- 0.75, 0.75], speed_bound: Optional[List[float]] = [0.0, 15.0], wheel_base: Optional[float] = 2.8)[source]¶ Simple continuous kinematic (bicycle) model of a rear-wheel driven vehicle. Check out Eq.3 in https://www.autonomousrobots.nl/docs/17-schwartig-autonomy-icra.pdf
- Parameters
x (float) – Position of the car in x-axis.
y (float) – Position of the car in y-axis.
yaw (float) – Heading/yaw of the car.
steering (float) – Steering angle of tires instead of steering wheel.
speed (float) – Forward speed.
steering_bound (list) – Upper and lower bound of steering angle.
speed_bound (list) – Upper and lower bound of speed.
wheel_base (float) – Wheel base.
-
step(steering_velocity: float, acceleration: float, dt: float, max_steps: Optional[int] = 100) → numpy.ndarray[source]¶ Step the vehicle state by solving ODE of the continuous kinematic (bicycle) model.
- Parameters
steering_velocity (float) – Steering velocity (of tire angle).
acceleration (float) – Acceleration.
dt (float) – Elapsed time.
max_steps (int) – Maximal step to run the ODE solver; default to 100.
- Returns
The updated state (x, y, yaw, tire angle, speed).
- Return type
np.ndarray
-
numpy() → numpy.ndarray[source]¶ Return a numpy array of vehicle state.
- Returns
Vehicle state.
- Return type
np.ndarray
-
update(x: float, y: float, yaw: float, steering: float, speed: float) → None[source]¶ Set state. :param x: Position of the car in x-axis. :type x: float :param y: Position of the car in y-axis. :type y: float :param yaw: Heading/yaw of the car. :type yaw: float :param steering: Steering angle of tires instead of steering wheel. :type steering: float :param speed: Forward speed. :type speed: float
-
property
x¶ Position of the car in x-axis.
-
property
y¶ Position of the car in y-axis.
-
property
yaw¶ Heading/yaw of the car.
-
property
steering¶ Steering (tire) angle.
-
property
steering_bound¶ Lower and upper bound of steering (tire) angle.
-
property
speed¶ Speed.
-
property
speed_bound¶ Lower and upper bound of speed.
-
vista.entities.agents.Dynamics.curvature2tireangle(curvature: float, wheel_base: float) → float[source]¶ Convert curvature to tire angle.
- Parameters
curvature (float) – Curvature.
wheel_base (float) – Wheel base.
- Returns
Tire angle.
- Return type
float
-
vista.entities.agents.Dynamics.tireangle2curvature(tire_angle: float, wheel_base: float) → float[source]¶ Convert tire angel to curvature.
- Parameters
tire_angle (float) – Tire angle.
wheel_base (float) – Wheel base.
- Returns
Curvature.
- Return type
float
-
vista.entities.agents.Dynamics.curvature2steering(curvature: float, wheel_base: float, steering_ratio: float) → float[source]¶ Convert curvature to steering angle.
- Parameters
curvature (float) – Curvature.
wheel_base (float) – Wheel base.
steering_ratio (float) – Steering ratio.
- Returns
Steering (wheel) angle.
- Return type
float
-
vista.entities.agents.Dynamics.steering2curvature(steering: float, wheel_base: float, steering_ratio: float) → float[source]¶ Convert steering angle to curvature.
- Parameters
steering (float) – Steering (wheel) angle.
wheel_base (float) – Wheel base.
steering_ratio (float) – Steering ratio.
- Returns
Curvature.
- Return type
float
-
vista.entities.agents.Dynamics.update_with_perfect_controller(desired_state: List[float], dt: float, dynamics: vista.entities.agents.Dynamics.StateDynamics) → None[source]¶ Update vehicle state assuming a perfect low-level controller. This basically simulate that the low-level controller can “instantaneously” achieve the desired state (e.g., steering (tire) angle and speed) with control command (steering velocity and accleration) in vehicle dynamics.
- Parameters
desired_state (List[float]) – A list of desired vehicle state.
dt (float) – Elapsed time.
dynamics (StateDynamics) – Vehicle state.