l5kit.geometry package¶
- l5kit.geometry.angle_between_vectors(v1: numpy.ndarray, v2: numpy.ndarray) float ¶
angle_between_vectors returns the angle in radians between two vectors.
- Parameters
v1 (np.ndarray) – Vector 1 of shape (N)
v2 (np.ndarray) – Vector 2 of same shape as
v1
- Returns
angle in radians
- Return type
float
- l5kit.geometry.angular_distance(angle_a: Union[float, numpy.ndarray], angle_b: Union[float, numpy.ndarray]) Union[float, numpy.ndarray] ¶
A function that takes two arrays of angles in radian and compute the angular distance, wrap the angular distance such that they are always in the [-pi, pi) range.
- Parameters
angle_a (np.ndarray, float) – first array of angles in radians
angle_b (np.ndarray, float) – second array of angles in radians
- Returns
angular distance in radians between two arrays of angles
- l5kit.geometry.compute_agent_pose(agent_centroid_m: numpy.ndarray, agent_yaw_rad: float) numpy.ndarray ¶
Return the agent pose as a 3x3 matrix. This corresponds to world_from_agent matrix.
- Parameters
agent_centroid_m (np.ndarry) – 2D coordinates of the agent
agent_yaw_rad (float) – yaw of the agent
- Returns
3x3 world_from_agent matrix
- Return type
(np.ndarray)
- l5kit.geometry.compute_yaw_around_north_from_direction(direction_vector: numpy.ndarray) float ¶
compute_yaw_from_direction computes the yaw as angle between a 2D input direction vector and the y-axis direction vector (0, 1).
- Args:
direction_vector (np.ndarray): Vector of shape (2,)
- Returns:
float: angle to (0,1) vector in radians
- l5kit.geometry.crop_rectangle_from_image(image: numpy.ndarray, corners: numpy.ndarray) numpy.ndarray ¶
crop_rectangle_from_image
takes an image and 4 corners in pixel coordinates, it returns the sub-image inside that cropped area, rotated upright.- Parameters
image (np.ndarray) – image to crop from
corners (np.ndarray) – corners, array of shape (4,2)
- Returns
crop from input containing the corners
- Return type
np.ndarray
- l5kit.geometry.ecef_to_geodetic(point: Union[numpy.ndarray, Sequence[float]]) numpy.ndarray ¶
Convert given ECEF coordinate into latitude, longitude, altitude.
- Parameters
point (Union[np.ndarray, Sequence[float]]) – ECEF coordinate vector
- Returns
latitude, altitude, longitude
- Return type
np.ndarray
- l5kit.geometry.geodetic_to_ecef(lla_point: Union[numpy.ndarray, Sequence[float]]) numpy.ndarray ¶
Convert given latitude, longitude, and optionally altitude into ECEF coordinates. If no altitude is given, altitude 0 is assumed.
- Parameters
lla_point (Union[np.ndarray, Sequence[float]]) – Latitude, Longitude and optionally Altitude
- Returns
3D ECEF coordinate
- Return type
np.ndarray
- l5kit.geometry.normalize_intensity(x: numpy.ndarray, max_intensity: float) numpy.ndarray ¶
Normalize (divide by max) and clip intensity values to fall between 0 and 1.
- Parameters
x (np.npdarray) – numpy array of any shape
max_intensity (float) – Maximum intensity value (anything above this will become 1)
- Returns
np.ndarray – array of same type and shape as x with values between 0 and 1 only
- l5kit.geometry.points_within_bounds(coords: numpy.ndarray, shape: Union[Collection[int], numpy.ndarray]) numpy.ndarray ¶
- Parameters
coords (np.ndarray) – (N,3)-shaped array containing points.
shape (tuple of ints or np.ndarray) – shape to use as bounds, should be length 3
- Returns
Binary mask for given coords array which is True for points that fall within the bounds of shape.
- l5kit.geometry.rotation33_as_yaw(rotation: numpy.ndarray) float ¶
Compute the yaw component of given 3x3 rotation matrix.
- Parameters
rotation (np.ndarray) – 3x3 rotation matrix (np.float64 dtype recommended)
- Returns
yaw rotation in radians
- Return type
float
- l5kit.geometry.transform_point(point: numpy.ndarray, transf_matrix: numpy.ndarray) numpy.ndarray ¶
Transform a single vector using transformation matrix. This function call transform_points internally
- Parameters
point – vector of shape (N)
transf_matrix – transformation matrix of shape (N+1, N+1)
- Returns
vector of same shape as input point
- l5kit.geometry.transform_points(points: numpy.ndarray, transf_matrix: numpy.ndarray) numpy.ndarray ¶
Transform a set of 2D/3D points using the given transformation matrix. Assumes row major ordering of the input points. The transform function has 3 modes: - points (N, F), transf_matrix (F+1, F+1) all points are transformed using the matrix and the output points have shape (N, F). - points (B, N, F), transf_matrix (F+1, F+1) all sequences of points are transformed using the same matrix and the output points have shape (B, N, F). transf_matrix is broadcasted. - points (B, N, F), transf_matrix (B, F+1, F+1) each sequence of points is transformed using its own matrix and the output points have shape (B, N, F). Note this function assumes points.shape[-1] == matrix.shape[-1] - 1, which means that last rows in the matrices do not influence the final results. For 2D points only the first 2x3 parts of the matrices will be used.
- Parameters
points – Input points of shape (N, F) or (B, N, F) with F = 2 or 3 depending on input points are 2D or 3D points.
transf_matrix – Transformation matrix of shape (F+1, F+1) or (B, F+1, F+1) with F = 2 or 3.
- Returns
Transformed points of shape (N, F) or (B, N, F) depending on the dimensions of the input points.
- l5kit.geometry.vertical_flip(tm: numpy.ndarray, y_dim_size: int) numpy.ndarray ¶
Return a new matrix that also performs a flip on the y axis.
- Parameters
tm – the original 3x3 matrix
y_dim_size – this should match the resolution on y. It makes all coordinates positive
Returns: a new 3x3 matrix.
- l5kit.geometry.voxel_coords_to_intensity_grid(voxel_coords: numpy.ndarray, shape: tuple, dtype: numpy.dtype = <class 'numpy.float32'>, drop_out_of_bounds: bool = True) numpy.ndarray ¶
Puts coords into a grid: for each grid cell the number of points is written there.
- Parameters
voxel_coords (np.ndarray) – input array with coords (N,3) in intensity grid
shape (tuple of ints) – intensity grid shape
- Keyword Arguments
dtype (data-type) – data type for the intensity grid (default: {np.float32})
drop_out_of_bounds (bool) – [description] (default: {True})
- Returns
np.ndarray – Array with given shape, the value of each cell is the amount of coords for that point.
- l5kit.geometry.yaw_as_rotation33(yaw: float) numpy.ndarray ¶
Create a 3x3 rotation matrix from given yaw. The rotation is counter-clockwise and it is equivalent to: [cos(yaw), -sin(yaw), 0.0], [sin(yaw), cos(yaw), 0.0], [0.0, 0.0, 1.0],
- Parameters
yaw (float) – yaw rotation in radians
- Returns
3x3 rotation matrix
- Return type
np.ndarray