models

BEVSpeedConvEncoder

class core.models.BEVSpeedConvEncoder(obs_shape: Tuple, hidden_dim_list: List, embedding_size: int, kernel_size: List = [8, 4, 3], stride: List = [4, 2, 1])[source]

Convolutional encoder of Bird-eye View image and speed input. It takes a BeV image and a speed scalar as input. The BeV image is encoded by a convolutional encoder, to get a embedding feature which is half size of the embedding length. Then the speed value is repeated for half embedding length time, and concated to the above feature to get a final feature.

Arguments:
  • obs_shape (Tuple): BeV image shape.

  • hidden_dim_list (List): Conv encoder hidden layer dimension list.

  • embedding_size (int): Embedding feature dimensions.

  • kernel_size (List, optional): Conv kernel size for each layer. Defaults to [8, 4, 3].

  • stride (List, optional): Conv stride for each layer. Defaults to [4, 2, 1].

forward(data: Dict) Tensor[source]

Forward computation of encoder

Arguments:
  • data (Dict): Input data, must contain ‘birdview’ and ‘speed’

Returns:

torch.Tensor: Embedding feature.

VanillaVAE

class core.models.vae_model.VanillaVAE(in_channels: int, latent_dim: int, hidden_dims: List | None = None, kld_weight: float = 0.1)[source]

Vanilla Variational Auto Encoder model.

Interfaces:

encode, decode, reparameterize, forward, loss_function, sample, generate

Arguments:
  • in_channels (int): the channel number of input

  • latent_dim (int): the latent dimension of the middle representation

  • hidden_dims (List): the hidden dimensions of each layer in the MLP architecture in encoder and decoder

  • kld_weight(float): the weight of KLD loss

decode(z: Tensor) Tensor[source]

Maps the given latent codes onto the image space.

Arguments:
  • z (Tensor): [B x D]

Returns:

Tensor: Output decode tensor [B x C x H x W]

encode(input: Tensor) List[Tensor][source]

Encodes the input by passing through the encoder network and returns the latent codes.

Arguments:
  • input (Tensor): Input tensor to encode [N x C x H x W]

Returns:

Tensor: List of latent codes

forward(input: Tensor, **kwargs) List[Tensor][source]

[summary]

Arguments:
  • input (torch.Tensor): Input tensor

Returns:

List[torch.Tensor]: Input and output tensor

generate(x: Tensor, **kwargs) Tensor[source]

Given an input image x, returns the reconstructed image

Arguments:
  • x(Tensor): [B x C x H x W]

Returns:

Tensor: [B x C x H x W]

loss_function(*args, **kwargs) Dict[source]

Computes the VAE loss function.

\(KL(N(\mu, \sigma), N(0, 1)) = \log \frac{1}{\sigma} + \frac{\sigma^2 + \mu^2}{2} - \frac{1}{2}\)

Returns:

Dict: Dictionary containing loss information

reparameterize(mu: Tensor, logvar: Tensor) Tensor[source]

Reparameterization trick to sample from N(mu, var) from N(0,1).

Arguments:
  • mu (Tensor): Mean of the latent Gaussian [B x D]

  • logvar (Tensor): Standard deviation of the latent Gaussian [B x D]

Returns:

Tensor: [B x D]

sample(num_samples: int, current_device: int, **kwargs) Tensor[source]

Samples from the latent space and return the corresponding image space map.

Arguments:
  • num_samples(Int): Number of samples.

  • current_device(Int): Device to run the model.

Returns:

Tensor: Sampled decode tensor.

VehiclePIDController

class core.models.VehiclePIDController(args_lateral: Dict, args_longitudinal: Dict, max_throttle: float = 0.75, max_brake: float = 0.3, max_steering: float = 0.8)[source]

VehiclePIDController is the combination of two PID controllers (lateral and longitudinal) to perform the low level control a vehicle from client side.

The arguments dictionary of PID controller use the following semantics:

  • K_P – Proportional term

  • K_D – Differential term

  • K_I – Integral term

  • dt – Time step in seconds

Arguments:
  • args_lateral (Dict): dictionary of arguments to set the lateral PID controller.

  • args_longitudinal (Dict): dictionary of arguments to set the longitudinal PID controller.

  • max_throttle (float, optional): Max value of throttle. Defaults to 0.75.

  • max_brake (float, optional): Max value of brake. Defaults to 0.3.

  • max_steering (float, optional): Max steering. Defaults to 0.8.

Interfaces:

forward

forward(current_speed: float, current_loc: List, current_ori: List, target_speed: float, target_loc: List) Dict[source]

Execute one step of control invoking both lateral and longitudinal PID controllers to reach a target waypoint at a given target_speed. Thw steering change between to step must be within 0.1.

Arguments:
  • current_speed (float): Current hero vehicle speed in km/h.

  • current_loc (List): Current hero vehicle coordinate location.

  • current_vec (List): Current hero vehicle forward vector.

  • target_speed (float): Target speed in km/h

  • target_loc (List): Target coordinate location.

Returns:

Dict: Control signal containing steer, throttle and brake.

MPCController

class core.models.MPCController(args_objective: Dict | None = None, horizon: int = 10, fps: int = 5)[source]

Model Predictive Control (MPC) method for speed and angle control in DI-drive. MPC takes a target waypoints list as input. It will minimize the objective function that calculates the loss between target trajectory & speed and predicted vehicle states in future.

Arguments:
  • args_objective (Dict, optional): Args in objective function containing loss weights. Defaults to None.

  • horizon (int, optional): Steps MPC model predicts in calculating objective function. Defaults to 10.

  • fps (int, optional): FPS of predictive model. Defaults to 5.

forward(ego_pose: List, target_speed: float, waypoints: List) Dict[source]

Run one step of controller, return the control signal.

Arguments:
  • ego_pose (List): Current location of ego vehicle: [x, y, yaw, speed].

  • target_speed (float): Target driving speed.

  • waypoints (List): Target trajectory waypoints.

Returns:

Dict: Control signal containing steer, throttle and brake.

SteerNoiseWrapper

class core.models.model_wrappers.SteerNoiseWrapper(model: Any, noise_type: str = 'uniform', noise_args: dict = {}, noise_len: int = 5, drive_len: int = 100, noise_range: dict | None = None)[source]

Model wrapper to add noise in steer frequently.

Arguments:
  • model (Any): Model to wrap.

  • noise_type (str): Type to generate noise. Must in [‘gauss’, ‘uniform’].

  • noise_kwargs (dict, optional): Arguments to set up noise generator. Defaults to {}.

  • noise_len (int, optional): Length of frames to apply noise. Defaults to 5.

  • drive_len (int, optional): Length of noise. Defaults to 100.

  • noise_range (dict, optional): Range of noise value, containing ‘min’ and ‘max’. Defaults to None.

Instance:

forward

forward(*args, **kwargs) Dict[source]

Running forward and add noise.

Returns:

Dict: Noised control signal with real control.