Utils

Copyright MIT GNU General Public License v3.0

MIT BWSI Autonomous Drone Racing Course - UAV Neo

File Name: drone_utils.py File Description: Contains helper functions to support common operations.

class drone_utils.ARMarker(marker_id: int, marker_corners: NDArray)

Encapsulates information about an AR marker detected in a color image.

detect_colors(color_image: NDArray, potential_colors: list[tuple[tuple[int, int, int], tuple[int, int, int], str]]) None

Attempts to detect the provided colors in the border around the AR marker.

Parameters:
  • color_image – The image in which the marker was detected.

  • potential_colors – A list of colors which the marker border may be. Each candidate color is formated as (hsv_lower, hsv_upper, color_name).

Example:

# Define color candidates in the (hsv_lower, hsv_upper, color_name) format
BLUE = ((90, 100, 100), (120, 255, 255), "blue")
RED = ((170, 100, 100), (10, 255, 255), "red")

# Detect the AR markers in the current color image
image = uav.camera.get_color_image()
markers = uav_utils.get_ar_markers(image)

# Search for the colors RED and BLUE in all of the detected markers
for marker in markers:
    marker.detect_colors(image, [BLUE, RED])
get_color() str

Returns the color of the marker if it was successfully detected.

get_corners() NDArray

Returns the (row, col) coordinates of the four corners of the marker.

Note

The corners are ordered clockwise with the top-left corner of the pattern appearing first.

get_corners_aruco_format() NDArray

Returns the corners of the AR marker formatted as needed by the ArUco library.

get_id() int

Returns the integer identification number of the marker pattern.

get_orientation() Orientation

Returns the orientation of the marker.

class drone_utils.ColorBGR(*values)

Common colors defined in the blue-green-red (BGR) format, with each channel ranging from 0 to 255 inclusive.

black = (0, 0, 0)
blue = (255, 0, 0)
brown = (0, 63, 127)
dark_gray = (63, 63, 63)
dark_green = (0, 127, 0)
gray = (127, 127, 127)
green = (0, 255, 0)
light_blue = (255, 255, 0)
light_gray = (191, 191, 191)
orange = (0, 127, 255)
pink = (255, 0, 255)
purple = (255, 0, 127)
red = (0, 0, 255)
white = (255, 255, 255)
yellow = (0, 255, 255)
class drone_utils.NDArray
class drone_utils.Orientation(*values)

The orientations which an AR marker can face, with the value indicating the index of the corner which is currently oriented in the top-left in the image.

DOWN = 2
LEFT = 1
RIGHT = 3
UP = 0
class drone_utils.TerminalColor(*values)

Colors which can be used when printing text to the terminal, with each value corresponding to the ASCII code for that color.

black = 30
blue = 94
cyan = 96
dark_blue = 34
dark_cyan = 36
dark_green = 32
dark_grey = 90
dark_red = 31
green = 92
light_grey = 37
orange = 33
pink = 95
purple = 35
red = 91
yellow = 93
drone_utils.clamp(value: float, min: float, max: float) float

Clamps a value between a minimum and maximum value.

Parameters:
  • value – The input to clamp.

  • min – The minimum allowed value.

  • max – The maximum allowed value.

Returns:

The value saturated between min and max.

Example:

# a will be set to 3
a = uav_utils.clamp(3, 0, 10)

# b will be set to 0
b = uav_utils.clamp(-2, 0, 10)

# c will be set to 10
c = uav_utils.clamp(11, 0, 10)
drone_utils.colormap_depth_image(depth_image: NDArray, max_depth: int = 1000) NDArray

Converts a depth image to a colored image representing depth.

Parameters:
  • depth_image – The depth image to convert.

  • max_depth – The farthest depth to show in the image in cm. Anything past this depth is shown as the farthest color.

Returns:

A color image representation of the provided depth image.

Note

Each color value ranges from 0 to 255. The color of each pixel is determined by its distance.

Example:

# retrieve a depth image
depth_image = uav.camera.get_depth_image()

# get the colormapped depth image
depth_image_colormap = uav_utils.colormap_depth_image(depth_image)
drone_utils.crop(image: NDArray, top_left_inclusive: tuple[float, float], bottom_right_exclusive: tuple[float, float]) NDArray

Crops an image to a rectangle based on the specified pixel points.

Parameters:
  • image – The color or depth image to crop.

  • top_left_inclusive – The (row, column) of the top left pixel of the crop rectangle.

  • bottom_right_exclusive – The (row, column) of the pixel one past the bottom right corner of the crop rectangle.

Returns:

A cropped version of the image.

Note

The top_left_inclusive pixel is included in the crop rectangle, but the bottom_right_exclusive pixel is not.

If bottom_right_exclusive exceeds the bottom or right edge of the image, the full image is included along that axis.

Example:

image = uav.camera.get_color_image()

# Crop the image to only keep the top half
cropped_image = uav_utils.crop(
    image, (0, 0), (uav.camera.get_height() // 2, uav.camera.get_width())
)
drone_utils.draw_ar_markers(color_image: NDArray, markers: list[ARMarker], color: tuple[int, int, int] = (0, 255, 0)) NDArray

Draws annotations on the AR markers in an image.

Parameters:
  • color_image – The color image in which the AR markers were detected.

  • markers – The AR markers detected in the image.

  • color – The color used to outline each AR marker, represented in the BGR format.

Warning

This modifies the provided image. If you accessed the image with uav.camera.get_color_image_no_copy(), you must manually create a copy of the image first with copy.deepcopy().

Example:

# Detect the AR markers in the current color image
image = uav.camera.get_color_image()
markers = uav_utils.get_ar_markers(image)

# Draw the detected markers on the image and display it
uav_utils.draw_ar_markers(image, markers)
uav.display.show_color_image(color_image)
drone_utils.draw_circle(color_image: NDArray, center: tuple[int, int], color: tuple[int, int, int] = (0, 255, 255), radius: int = 6) None

Draws a circle on the provided image.

Parameters:
  • color_image – The color image on which to draw the contour.

  • center – The pixel (row, column) of the center of the image.

  • color – The color to draw the circle, specified as blue-green-red channels each ranging from 0 to 255 inclusive.

  • radius – The radius of the circle in pixels.

Example:

image = uav.camera.get_color_image()

# Extract the largest blue contour
BLUE_HSV_MIN = (90, 50, 50)
BLUE_HSV_MAX = (110, 255, 255)
contours = uav_utils.find_contours(image, BLUE_HSV_MIN, BLUE_HSV_MAX)
largest_contour = uav_utils.get_largest_contour(contours)

# Draw a dot at the center of this contour in red
if (largest_contour is not None):
    center = get_contour_center(contour)
    draw_circle(image, center, uav_utils.ColorBGR.red.value)
drone_utils.draw_contour(color_image: NDArray, contour: NDArray, color: tuple[int, int, int] = (0, 255, 0)) None

Draws a contour on the provided image.

Parameters:
  • color_image – The color image on which to draw the contour.

  • contour – The contour to draw on the image.

  • color – The color to draw the contour, specified as blue-green-red channels each ranging from 0 to 255 inclusive.

Example:

image = uav.camera.get_color_image()

# Extract the largest blue contour
BLUE_HSV_MIN = (90, 50, 50)
BLUE_HSV_MAX = (110, 255, 255)
contours = uav_utils.find_contours(image, BLUE_HSV_MIN, BLUE_HSV_MAX)
largest_contour = uav_utils.get_largest_contour(contours)

# Draw this contour onto image
if (largest_contour is not None):
    draw_contour(image, largest_contour)
drone_utils.find_contours(color_image: NDArray, hsv_lower: tuple[int, int, int], hsv_upper: tuple[int, int, int]) list[NDArray]

Finds all contours of the specified color range in the provided image.

Parameters:
  • color_image – The color image in which to find contours, with pixels represented in the bgr (blue-green-red) format.

  • hsv_lower – The lower bound for the hue, saturation, and value of colors to contour.

  • hsv_upper – The upper bound for the hue, saturation, and value of the colors to contour.

Returns:

A list of contours around the specified color ranges found in color_image.

Note

Each channel in hsv_lower and hsv_upper ranges from 0 to 255.

Example:

# Define the lower and upper hsv ranges for the color blue
BLUE_HSV_MIN = (90, 50, 50)
BLUE_HSV_MAX = (110, 255, 255)

# Extract contours around all blue portions of the current image
contours = uav_utils.find_contours(
    uav.camera.get_color_image(), BLUE_HSV_MIN, BLUE_HSV_MAX
)
drone_utils.format_colored(text: str, color: TerminalColor) str

Formats a string so that it is printed to the terminal with a specified color.

Parameters:
  • text – The text to format.

  • color – The color to print the text.

Example:

# Prints "Hello World!", where "World" is blue
print("Hello " + format_colored("World", uav_utils.TerminalColor.blue) + "!")
drone_utils.get_ar_markers(color_image: NDArray, potential_colors: list[tuple[tuple[int, int, int], tuple[int, int, int], str]] = None, marker_type: int = cv2.aruco.DICT_6X6_250) list[ARMarker]

Finds AR markers in an image.

Parameters:
  • color_image – The color image in which to search for AR markers.

  • potential_colors – The potential colors of the AR marker, each represented as (hsv_min, hsv_max, color_name)

  • marker_type – The type of ArUco marker to look for. By default, this function looks for 6x6 markers.

Warning

By default, this function looks for 6x6 AR markers which are used in the UAV Neo sim. To track the 5x5 markers used in-person, pass cv.aruco.DICT_5X5_250 to type.

Returns:

A list of each AR marker’s four corners clockwise and an array of the AR marker ids.

Example:

# Detect 6x6 ArUco markers in the current color image.
image = uav.camera.get_color_image()
markers = drone_utils.get_ar_markers(image)

# Or, detect 5x5 markers instead:
markers = drone_utils.get_ar_markers(image, marker_type=cv.aruco.DICT_5X5_250)

# Print information detected for the zeroth marker
if len(markers) >= 1:
    print(markers[0])
drone_utils.get_closest_pixel(depth_image: NDArray, kernel_size: int = 5) tuple[int, int]

Finds the closest pixel in a depth image.

Parameters:
  • depth_image – The depth image to process.

  • kernel_size – The size of the area to average around each pixel.

Returns:

The (row, column) of the pixel which is closest to the car.

Warning

kernel_size be positive and odd. It is highly recommended that you crop off the bottom of the image, or else this function will likely return the ground directly in front of the car.

Note

The larger the kernel_size, the more that the depth of each pixel is averaged with the distances of the surrounding pixels. This helps reduce noise at the cost of reduced accuracy.

Example:

depth_image = uav.camera.get_depth_image()

# Crop off the ground directly in front of the car
cropped_image = uav_utils.crop(
    image, (0, 0), (int(uav.camera.get_height() * 0.66), uav.camera.get_width())
)

# Find the closest pixel
closest_pixel = uav_utils.get_closest_pixel(depth_image)
drone_utils.get_contour_area(contour: NDArray) float

Finds the area of a contour from an image.

Parameters:

contour – The contour of which to measure the area.

Returns:

The number of pixels contained within the contour

Example:

# Extract the largest blue contour
BLUE_HSV_MIN = (90, 50, 50)
BLUE_HSV_MAX = (110, 255, 255)
contours = uav_utils.find_contours(
    uav.camera.get_color_image(), BLUE_HSV_MIN, BLUE_HSV_MAX
)
largest_contour = uav_utils.get_largest_contour(contours)

# Find the area of this contour (will evaluate to 0 if no contour was found)
area = uav_utils.get_contour_area(contour)
drone_utils.get_contour_center(contour: NDArray) tuple[int, int] | None

Finds the center of a contour from an image.

Parameters:

contour – The contour of which to find the center.

Returns:

The (row, column) of the pixel at the center of the contour, or None if the contour is empty.

Example:

# Extract the largest blue contour
BLUE_HSV_MIN = (90, 50, 50)
BLUE_HSV_MAX = (110, 255, 255)
contours = uav_utils.find_contours(
    uav.camera.get_color_image(), BLUE_HSV_MIN, BLUE_HSV_MAX
)
largest_contour = uav_utils.get_largest_contour(contours)

# Find the center of this contour if it exists
if (largest_contour is not None):
    center = uav_utils.get_contour_center(largest_contour)
drone_utils.get_depth_image_center_distance(depth_image: NDArray, kernel_size: int = 5) float

Finds the distance of the center object in a depth image.

Parameters:
  • depth_image – The depth image to process.

  • kernel_size – The size of the area to average around the center.

Returns:

The distance in cm of the object in the center of the image.

Warning

kernel_size must be positive and odd.

Note

The larger the kernel_size, the more that the center is averaged with the depth of the surrounding pixels. This helps reduce noise at the cost of reduced accuracy. If kernel_size = 1, no averaging is done.

Example:

depth_image = uav.camera.get_depth_image()

# Find the distance of the object (in cm) the center of depth_image
center_distance = uav_utils.get_depth_image_center_distance(depth_image)
drone_utils.get_largest_contour(contours: list[NDArray], min_area: int = 30) NDArray | None

Finds the largest contour with size greater than min_area.

Parameters:
  • contours – A list of contours found in an image.

  • min_area – The smallest contour to consider (in number of pixels)

Returns:

The largest contour from the list, or None if no contour was larger than min_area.

Example:

# Extract the blue contours
BLUE_HSV_MIN = (90, 50, 50)
BLUE_HSV_MAX = (110, 255, 255)
contours = uav_utils.find_contours(
    uav.camera.get_color_image(), BLUE_HSV_MIN, BLUE_HSV_MAX
)

# Find the largest contour
largest_contour = uav_utils.get_largest_contour(contours)
drone_utils.get_pixel_average_distance(depth_image: NDArray, pix_coord: tuple[int, int], kernel_size: int = 5) float

Finds the distance of a pixel averaged with its neighbors in a depth image.

Parameters:
  • depth_image – The depth image to process.

  • pix_coord – The (row, column) of the pixel to measure.

  • kernel_size – The size of the area to average around the pixel.

Returns:

The distance in cm of the object at the provided pixel.

Warning

kernel_size must be positive and odd.

Note

The larger the kernel_size, the more that the requested pixel is averaged with the distances of the surrounding pixels. This helps reduce noise at the cost of reduced accuracy.

Example:

depth_image = uav.camera.get_depth_image()

# Find the distance of the object (in cm) at the pixel (100, 20) of depth_image
average_distance = uav_utils.get_average_distance(depth_image, 100, 20)
drone_utils.pixelate_image(img: NDArray, size: tuple[int, int] = (24, 8)) NDArray

“Pixelates” and resizes a grayscale image to a smaller size, useful for displaying pictures on the dot matrix.

Parameters:
  • img – The grayscale image to pixelate.

  • size – The smaller width and height to pixelate the image to. By default, this resizes the image to the correct size for the dot matrix display.

Returns:

The pixelated image.

Example:

# Load and pixelate a black-and-white image
img = cv.imread('./frames/bad_apple_080.png', cv.IMREAD_GRAYSCALE)
pixelated = uav_utils.pixelate_image(img)

# Display the image on the dot matrix
uav.display.set_matrix(pixelated)
drone_utils.print_colored(text: str, color: TerminalColor) None

Prints a line of text to the terminal with a specified color.

Parameters:
  • text – The text to print to the terminal.

  • color – The color to print the text.

Example:

uav_utils.print_colored("This will be black", uav_utils.TerminalColor.black)
uav_utils.print_colored("This will be red", uav_utils.TerminalColor.red)
uav_utils.print_colored("This will be green", uav_utils.TerminalColor.green)
drone_utils.print_error(text: str) None

Prints a line of text to the terminal in red.

Parameters:

text – The text to print to the terminal.

Example:

# This text will be printed to the terminal in red
uav_utils.print_error("Error: No image detected")
drone_utils.print_warning(text: str) None

Prints a line of text to the terminal in yellow.

Parameters:

text – The text to print to the terminal.

Example:

# This text will be printed to the terminal in yellow
uav_utils.print_warning("Warning: Potential collision detected, reducing speed")
drone_utils.remap_range(val: float, old_min: float, old_max: float, new_min: float, new_max: float, saturate: bool = False) float

Remaps a value from one range to another range.

Parameters:
  • val – A number form the old range to be rescaled.

  • old_min – The inclusive ‘lower’ bound of the old range.

  • old_max – The inclusive ‘upper’ bound of the old range.

  • new_min – The inclusive ‘lower’ bound of the new range.

  • new_max – The inclusive ‘upper’ bound of the new range.

  • saturate – If true, the new_min and new_max limits are enforced.

Note

min need not be less than max; flipping the direction will cause the sign of the mapping to flip. val does not have to be between old_min and old_max.

Example:

# a will be set to 25
a = uav_utils.remap_range(5, 0, 10, 0, 50)

# b will be set to 975
b = uav_utils.remap_range(5, 0, 20, 1000, 900)

# c will be set to 30
c = uav_utils.remap_range(2, 0, 1, -10, 10)

# d will be set to 10
d = uav_utils.remap_range(2, 0, 1, -10, 10, True)
drone_utils.stack_images_horizontal(image_0: NDArray, image_1: NDArray) NDArray

Stack two images horizontally.

Parameters:
  • image_0 – The image to place on the left.

  • image_1 – The image to place on the right.

Returns:

An image with the original two images next to each other.

Note

The images must have the same height.

Example:

color_image = uav.camera.get_color_image()

depth_image = uav.camera.get_depth_image()
depth_image_colormap = uav_utils.colormap_depth_image(depth_image)

# Create a new image with the color on the left and depth on the right
new_image = uav_utils.stack_images_horizontally(color_image, depth_image_colormap)
drone_utils.stack_images_vertical(image_0: NDArray, image_1: NDArray) NDArray

Stack two images vertically.

Parameters:
  • image_0 – The image to place on the top.

  • image_1 – The image to place on the bottom.

Returns:

An image with the original two images on top of each other.

Note

The images must have the same width.

Example:

color_image = uav.camera.get_color_image()

depth_image = uav.camera.get_depth_image()
depth_image_colormap = uav_utils.colormap_depth_image(depth_image)

# Create a new image with the color on the top and depth on the bottom
new_image = uav_utils.stack_images_vertically(color_image, depth_image_colormap)