Hacemos Envíos a Todo el País

Para cotizaciones y pedidos mándanos un mensaje en este enlace. En Cochabamba visítanos en nuestras oficinas, estamos a tu servicio, tu consulta no nos molesta.

Imprimir

Aplicación de Seguimiento de Objetos con Drones: Usando OpenCV, MAVSDK y PX4

Escrito por Raúl Alvarez.

Autor: Raul Alvarez-Torrico

Esta es una traducción automática (pueden haber algunos errores de traducción) de mi artículo original en inglés publicado por la revista "Circuit Cellar" (#362 de Septiembre, 2020). El código de programa y diagramas aún están en Inglés.

Seguimiento de Objetos con DronesResumen

En este artículo discuto cómo desarrollar una aplicación básica de seguimiento autónomo de objetos para un quadrirotor en simulación, mediante la integración de detección de objetos por visión por computador y la librería MAVSDK MAVLink para control de vuelo autónomo. Se usará simulación "Software In The Loop" (SITL) de PX4 para probar el ejemplo de código. Hablaré acerca de cómo configurar un entorno de desarrollo en el sistema operativo Ubuntu que incluya todas las herramientas necesarias: el entorno de simulación PX4 SITL, la librería MAVSDK-Python y la librería Python OpenCV. Luego explicaré un flujo de trabajo para leer y procesar imágenes para detección de objetos usando una técnica de visión por computador muy básica: segmentación del rango de color. Los resultados obtenidos del proceso de detección se utilizarán para controlar un quadrirotor simulado usando la librería MAVSDK-Python para el protocolo MAVLink, de modo que rastree de forma autónoma el objeto detectado. La segmentación de rango de color no es el mejor, ni el más robusto método para detectar y seguir objetos con visión por computador, pero sirve bien para el propósito de introducir conceptos sobre cómo interconectar tareas de detección mediante visión por computador con vuelo autónomo de drones.

El objetivo de este artículo es presentar un ejemplo básico sobre cómo integrar OpenCV, MASVDK y el entorno de simulación PX4, y está dirigido a estudiantes y aficionados interesados en experimentar en el área de seguimiento autónomo con drones. Para aprovechar este artículo, debes tener al menos experiencia básica con OpenCV, así como conocimientos generales sobre cómo funcionan los cuadricópteros, el protocolo MAVLink y cómo usar la simulación PX4 SITL para escribir aplicaciones de vuelo autónomo con drones usando la biblioteca MAVSDK-Python. Consulta mi artículo publicado anteriormente "Escribiendo Aplicaciones MAVSDK/PX4 Para Drones" para una introducción rápida al desarrollo de aplicaciones MAVSDK con simulación PX4 SITL.

Videos

Demo Track and Follow


Demo Track and Follow
Demo Track and Follow
Selección del Rango de Color
Selección del Rango de Color
Modificar/Correr con el Nuevo Rango de Color
Modificar/Correr con el Nuevo Rango de Color

Si los videos no están visibles en esta página, puedes verlos directamente en nuestro canal de YouTube.

1. Demo "Track and Follow"
2. Selección del Rango de Color
3. Modificar/Correr con el Nuevo Rango de Color

4. (Más videos muy pronto)

* Suscríbete a nuestro boletín para recibir noticias

Pregunta anti spam. Ingresa abajo las últimas 4 letras de: asteroide
Nombre:
Email:

Diagrama de Flujo y Descripción Funcional

Debido a que usaremos simulación, todo el hardware necesario para ejecutar el ejemplo de código de este artículo es una computadora con el sistema operativo Ubuntu 18.04 y una cámara web. Si sólo dispones de una máquina Windows o MacOS, puedes instalar VirtualBox y crear una máquina virtual Ubuntu 18.04 para probar el ejemplo.

La Figura 1 muestra el diagrama de flujo del algoritmo principal. Primero, inicializamos la cámara web, hacemos una conexión con el dron y configuramos sus coordenadas por defecto A continuación, el programa entra en un bucle infinito en el que se realizarán de forma recurrente las siguientes tareas: Primero, obtenemos las coordenadas de "imagen de cámara" del objetivo detectado. Si no se detectó ningún objetivo estas coordenadas quedarán indefinidas, en cuyo caso haremos que sean iguales a las coordenadas del punto central del cuadro de la imagen, el cual será el origen de nuestro sistema de coordenadas Cartesianas. De otro modo, si se detecta un objetivo, aplicaremos un filtro pasa bajo de promedio móvil a las coordenadas para eliminar el ruido de alta frecuencia inherente al proceso de detección con visión por computador.

Diagrama de flujo del algoritmo principal

Figura 1: Diagrama de flujo del algoritmo principal

Las coordenadas devueltas por el algoritmo de detección son coordenadas de "imagen de cámara" (ancho, alto) en unidades de píxeles. Este sistema de coordenadas es usado con cámaras y librerías de imágenes en entornos computacionales típicos para representar posiciones de píxeles en una imagen digital. El origen del sistema de coordenadas está ubicado en la esquina superior izquierda de la imagen (ver Figura 2.a). Por otro lado, las coordenadas en el sistema NED ("North, East, Down" - Norte, Este, Abajo) se utilizarán para controlar el dron. La conversión entre los sistemas de coordenadas Cartesiano y NED es muy sencilla, como se puede ver en la Figura 2.b. Entonces, después de obtener las coordenadas de imagen de cámara del objetivo, debemos convertirlas a coordenadas Cartesianas usando las fórmulas que se muestran en la Figura 2.a. Las coordenadas de imagen de cámara y Cartesianas están en unidades de píxeles. Una vez que tenemos el punto objetivo en coordenadas Cartesianas, debemos determinar su posición en relación al área del "rectángulo central" definido alrededor del centro del cuadro de la imagen (el rectángulo de color naranja en la Figura 3). Si el objetivo está fuera del rectángulo central, el objetivo debe ser seguido (es decir, tiene que ser re-centrado en el cuadro de la imagen), para lo que calculamos un nuevo conjunto de coordenadas NED a partir de las coordenadas Cartesianas que ya tenemos. Si el objetivo ya está dentro del rectángulo central, entonces ya está centrado y las últimas coordenadas NED calculadas seguirán siendo las actuales.

Sistemas de coordenadas

Figura 2: Sistemas de coordenadas. a) "Imagen de cámara" y Cartesiano, b) NED

Cuadro de imagen de la detección

Figura 3: Cuadro de imagen de la detección

Para obtener las coordenadas NED multiplicamos las coordenadas Cartesianas por un factor de conversión COORD_SYS_CONV_FACTOR determinado empíricamente. Este factor de conversión nos da una correspondencia aproximada entre las distancias en el cuadro de imagen en unidades de píxeles y las distancias reales en el suelo en metros, asumiendo que estamos rastreando objetos a la altura del suelo. Revisa el archivo "run_track_and_follow.md" incluido con el código fuente del artículo para obtener pautas sobre cómo estimar este factor de conversión. A continuación, ordenamos al dron que navegue hasta las coordenadas NED actuales. Luego visualizamos el cuadro de imagen usado en la detección (Figura 3) en la pantalla del computador y repetimos el bucle infinito hasta que el usuario emita un comando "quit" (salir) desde el teclado del computador para romper el bucle infinito. Si es así, devolvemos el dron a la posición de inicio y finalizamos la aplicación.

Entorno de Desarrollo

El archivo "install_run_simulation.md" incluido con el código fuente de este proyecto describe el proceso de instalación del entorno de simulación PX4 SITL, la librería MAVSDK-Python y el software de estación terrestre QGroundControl. Esta es la misma guía de instalación presentada en mi artículo anterior "Escribiendo Aplicaciones MAVSDK/PX4 Para Drones". De aquí en adelante, puedes consultar ese artículo si deseas revisar conceptos mencionados en este artículo relacionados con MAVSDK, simulación PX4 SITL y programación asíncrona en Python con la librería 'asyncio', que no se discutirán en detalle en este artículo.

Una vez que MAVSDK y el entorno de simulación SITL están instalados, debes instalar también la librería Python OpenCV para visión por computador. El proceso es muy sencillo, consulta el archivo guía "install_opencv.md" incluido con el código fuente de este artículo.

Función Principal de Entrada

El Listado de Código 1 muestra la definición de la función async def run(), que es la función principal de entrada para nuestra aplicación. En la línea 6 vid_cam = cv2.VideoCapture(0) instanciamos un objeto OpenCV 'VideoCapture', luego de pasar como argumento el índice de la cámara web al que queremos acceder. Por lo general, '0' será el índice de la cámara web predeterminada conectada a tu PC. En las líneas 8-11, verificamos si el objeto 'VideoCapture' se ha inicializado correctamente, si no es así, imprimimos un mensaje de error y emitimos una instrucción "return" para terminar la aplicación. En la línea 13, ejecutamos la función get_image_params(vid_cam), la cual calculará una serie de parámetros constantes útiles derivados del tamaño del cuadro de imagen. Estos parámetros se almacenan en el diccionario de Python 'params'; una variable global a la que se accede en varias partes del código para realizar cálculos clave. A continuación, en las líneas 16-17 inicializamos la interfaz MAVSDK con el dron creando un objeto 'drone' y abriendo una conexión UDP al mismo. Omitiré la explicación de otros pasos de inicialización del dron que siguen, porque ya los cubrí en mi artículo anterior mencionado anteriormente [Referencia 1].

### ---------- This is the application's 'main' asynchronous function ----------
async def run():
    """ Detects a target by using color range segmentation and follows it
    by using Offboard control and position NED coordinates. """
    
    vid_cam = cv2.VideoCapture(0)

    if vid_cam.isOpened() is False: 
        print('[ERROR] Couldnt open the camera.')
        return
    print('-- Camera opened successfully')

    await get_image_params(vid_cam) 
    print(f"-- Original image width, height: {params['image_width']}, {params['image_height']}")

    drone = System()
    await drone.connect(system_address="udp://:14540")
    # ... Additional drone initialization code lines go here...

    N_coord = 0
    E_coord = 0
    D_coord = -HOVERING_ALTITUDE
    yaw_angle = 0

    await drone.offboard.set_position_ned(PositionNedYaw(N_coord, E_coord, D_coord, yaw_angle))
    await asyncio.sleep(4)

    while True:
        tgt_cam_coord, frame, contour = await get_target_coordinates(vid_cam)
        
        if tgt_cam_coord['width'] is not None and tgt_cam_coord['height'] is not None:
            tgt_filt_cam_coord = await moving_average_filter(tgt_cam_coord)
        else:
            tgt_cam_coord = {'width':params['y_ax_pos'], 'height':params['x_ax_pos']}
            tgt_filt_cam_coord = {'width':params['y_ax_pos'], 'height':params['x_ax_pos']}

        tgt_cart_coord = {'x':(tgt_filt_cam_coord['width'] - params['y_ax_pos']),
                          'y':(params['x_ax_pos'] - tgt_filt_cam_coord['height'])}

        COORD_SYS_CONV_FACTOR = 0.1

        if abs(tgt_cart_coord['x']) > params['cent_rect_half_width'] or \
        abs(tgt_cart_coord['y']) > params['cent_rect_half_height']:
            E_coord = tgt_cart_coord['x'] * COORD_SYS_CONV_FACTOR
            N_coord = tgt_cart_coord['y'] * COORD_SYS_CONV_FACTOR
            # D_coord, yaw_angle don't change

        await drone.offboard.set_position_ned(PositionNedYaw(N_coord, E_coord, D_coord, yaw_angle))

        frame = await draw_objects(tgt_cam_coord, tgt_filt_cam_coord, frame, contour)

        cv2.imshow("Detect and Track", frame)

        key = cv2.waitKey(1) & 0xFF
        if key == ord("q"):
            break

    print("-- Return to launch...")
    await drone.action.return_to_launch()
    print("NOTE: check the drone has landed already before running again this script.")
    await asyncio.sleep(5)

Listado de Código 1: Función principal de entrada

En las líneas 20-23, definimos una pose por defecto para el dron, con las coordenadas Norte, Este y el ángulo "Yaw" en cero, y la coordenada "Down" en -HOVERING_ALTITUDE, que establece la altitud de vuelo estacionario del dron como igual a la constante mencionada anteriormente, la cual está definida al comienzo del programa (consulta el listado completo del código fuente). La línea 25 envía la pose inicial al dron, lo que hará que el dron despegue, y la línea 26 genera un retraso de 4 segundos para dar tiempo a que el dron se aleje del suelo.

Las líneas 28-56 muestran las tareas principales de la aplicación, tal como se indica en el diagrama de flujo. Por ejemplo, en la línea 29, llamamos a la función get_target_coordinates(vid_cam), que devolverá las coordenadas de "cuadro de cámara" del objetivo detectado, junto con el cuadro de la imagen al que el algoritmo de detección ha sido aplicado y adicionalmente también el contorno geométrico del objetivo detectado. A continuación, en la línea 31, verificamos si las coordenadas devueltas son válidas (diferente de 'None'). Si es así, llamamos a la función moving_average_filter(tgt_cam_coord), pasando esas coordenadas como parámetros para obtener sus valores filtrados en retorno. De lo contrario, hacemos las coordenadas de destino iguales a las coordenadas del centro de la imagen; es decir, el punto en el que se ubica el origen Cartesiano (ver líneas 34-35). En las líneas 37-38 hacemos la conversión de coordenadas de "imagen de cámara" a coordenadas Cartesianas usando las fórmulas descritas en la Figura 2.a.

Luego, en las líneas 42-45, verificamos si las coordenadas del objetivo están fuera del "rectángulo central" (el rectángulo naranja en el centro de la imagen en la Figura 3). Si es así, calculamos nuevas coordenadas Este y Norte, multiplicando las coordenadas cartesianas (x, y) por COORD_SYS_CONV_FACTOR; que es el factor de conversión de unidades de píxeles en el sistema de coordenadas "imagen de cámara" y el sistemas de coordenadas Cartesianas, a metros en el sistema de coordenadas NED. Consulta el archivo "run_track_and_follow.md" acerca de cómo estimar este factor de conversión. Si el objetivo está dentro del rectángulo central, asumimos que el objetivo ya está lo suficientemente "centrado" en el cuadro de la imagen, por lo que el dron no cambiará sus coordenadas anteriores Norte y Este y permanecerá en su posición actual. De lo contrario, el dron debe cambiar de posición para volver a centrar el objetivo en el cuadro de la imagen.

A continuación, en la línea 48 llamamos a la función drone.offboard.set_position_ned() para comandar el dron a las coordenadas NED actuales. En la línea 50 dibujamos algunos objetos en el cuadro de la imagen a fin de visualizar el proceso de detección, tal como se muestra en la Figura 3. Dibujamos los ejes de coordenadas Cartesianas, el rectángulo central, el punto sin filtrar y el texto de sus coordenadas (en rojo), el filtrado punto y sus coordenadas (en azul) y el contorno del objetivo (en verde). Para esto, llamamos a la función draw_objects(), pasando como argumentos las coordenadas "imagen de cámara" del objetivo no filtradas y filtradas, el cuadro de imagen y el contorno del objetivo.

En la línea 52 llamamos a la función 'imshow' de OpenCV para crear una ventana en la que se mostrará el cuadro de la imagen de detección (Figura 3). En las líneas 54-56, verificamos si el usuario ha presionado la tecla 'q' ("quit" - salir) en el teclado de la computadora para romper el bucle infinito 'while'. Si no es así, continuaremos repitiendo todos los pasos en el ciclo 'while' hasta que se presione la tecla 'q'. Finalmente, después de romper el bucle infinito, en la línea 59 llamamos a la función drone.action.return_to_launch() para hacer que el dron regrese a casa, antes de que finalice la ejecución del script.

Detección de Rango de Color

El Listado de Código 2 muestra la definición de la función get_image_params(vid_cam). Se ejecuta una vez en la función principal, antes de que el algoritmo entre al ciclo infinito "while" y calcula un conjunto de parámetros derivados del tamaño del cuadro de imagen. Estos parámetros se utilizarán en el resto del código para realizar cálculos clave. En las líneas 4-5, la función lee un cuadro de imagen de la cámara y obtiene su altura y ancho. A continuación, en las líneas 7-10 compara la altura del cuadro de imagen original con la constante DESIRED_IMAGE_HEIGHT definida al principio del script (consulta el listado completo del código fuente). Si son diferentes, calcula un 'scaling_factor' (factor de escala) que se utilizará para reducir o ampliar el cuadro de imagen para el proceso de detección. Por lo general, queremos reducir el tamaño de la imagen para reducir la carga de trabajo de cálculo en el proceso de detección (menos píxeles, menos cálculo). En las líneas 12-13, calculamos la nueva anchura y altura del cuadro de imagen mediante la aplicación del 'scaling_factor', y en líneas 14-15 cambiamos el tamaño del cuadro actual en consecuencia, antes de calcular el resto de los parámetros.

async def get_image_params(vid_cam):
    """ Computes useful general parameters derived from the camera image size."""

    _, frame = vid_cam.read()
    params['image_height'], params['image_width'], _ = frame.shape

    if params['image_height'] != DESIRED_IMAGE_HEIGHT:
        params['scaling_factor'] = round((DESIRED_IMAGE_HEIGHT / params['image_height']), 2)
    else:
        params['scaling_factor'] = 1

    params['resized_width'] = int(params['image_width'] * params['scaling_factor'])
    params['resized_height'] = int(params['image_height'] * params['scaling_factor'])
    dimension = (params['resized_width'], params['resized_height'])
    frame = cv2.resize(frame, dimension, interpolation = cv2.INTER_AREA)

    params['cent_rect_half_width'] = round(params['resized_width'] * (0.5 * PERCENT_CENTER_RECT)) 
    params['cent_rect_half_height'] = round(params['resized_height'] * (0.5 * PERCENT_CENTER_RECT)) 

    params['min_tgt_radius'] = round(params['resized_width'] * PERCENT_TARGET_RADIUS)

    params['x_ax_pos'] = int(params['resized_height']/2 - 1)
    params['y_ax_pos'] = int(params['resized_width']/2 - 1)

    params['cent_rect_p1'] = (params['y_ax_pos']-params['cent_rect_half_width'], 
                              params['x_ax_pos']-params['cent_rect_half_height'])
    params['cent_rect_p2'] = (params['y_ax_pos']+params['cent_rect_half_width'], 
                              params['x_ax_pos']+params['cent_rect_half_height'])

    return

async def get_target_coordinates(vid_cam):
    """ Detects a target by using color range segmentation and returns its
        'camera pixel' coordinates."""

    HSV_LOWER_BOUND = (107, 119, 41)
    HSV_UPPER_BOUND = (124, 255, 255)

    _, frame = vid_cam.read()

    if params['scaling_factor'] != 1:
        dimension = (params['resized_width'], params['resized_height'])
        frame = cv2.resize(frame, dimension, interpolation = cv2.INTER_AREA)

    blurred = cv2.GaussianBlur(frame, (11, 11), 0) 
    hsv = cv2.cvtColor(blurred, cv2.COLOR_BGR2HSV)
    mask = cv2.inRange(hsv, HSV_LOWER_BOUND, HSV_UPPER_BOUND)
    mask = cv2.erode(mask, None, iterations=3)
    mask = cv2.dilate(mask, None, iterations=3)

    _, contours, _ = cv2.findContours(mask, cv2.RETR_EXTERNAL, cv2.CHAIN_APPROX_SIMPLE)

    cX = None
    cY = None
    largest_contour = None

    if len(contours) > 0:
        largest_contour = max(contours, key=cv2.contourArea)
        ((x, y), radius) = cv2.minEnclosingCircle(largest_contour)

        if radius > params['min_tgt_radius']:
            M = cv2.moments(largest_contour)
            cX = int(M["m10"] / M["m00"])
            cY = int(M["m01"] / M["m00"])

    return {'width':cX, 'height':cY}, frame, largest_contour

Listado de Código 2: Funciones auxiliares 1

En las líneas 17-18 calculamos el tamaño del rectángulo central utilizado para "centrar" el objetivo en el cuadro de imagen. En la línea 20 calculamos un radio objetivo mínimo. Solo los objetos con un radio mayor que ese serán rastreados por el dron, los objetivos más pequeños serán ignorados. En las líneas 22-23 se calcula la posición del eje X e Y para el sistema de coordenadas Cartesianas en el cuadro de la imagen y, finalmente, en las líneas 25-28, se calculan los puntos superior izquierdo e inferior derecho para las esquinas que definen el rectángulo central.

La función get_target_coordinates(vid_cam) comienza a definirse en la línea 32 del Listado de Código 2. La línea 39 invoca la función 'read ()' del objeto 'vid_cam' pasado como argumento, el cual hace referencia a la cámara web conectada a nuestra computadora. La función 'read ()' devolverá en la variable 'frame' una matriz multidimensional que contiene los valores de píxel BGR (azul, verde, rojo) de la imagen. A continuación, en las líneas 41-43 se cambiará el tamaño de la imagen si el parámetro 'scaling_factor' es distinto de 1. En la línea 45 se aplica el filtro OpenCV 'GaussianBlur' (desenfoque Gaussiano) a la imagen; el cual es un filtro paso bajo que eliminará el ruido en la imagen. De manera más general, eliminará el contenido de alta frecuencia y hará que la imagen se vea más suave.

Una vez que la imagen está desenfocada, en la línea 46 la convertimos del espacio de color BGR ("Blue, Green, Red" - Azul, Rojo Verde) al espacio de color HSV ("Hue, Saturation, Value"- Tono, Saturación, Valor). Generalmente, es más fácil segmentar un color en el espacio de color HSV que en BGR, porque en HSV, el color que queremos segmentar depende solo de un canal (Hue). En el espacio de color BGR, el color deseado será una combinación de tres canales (azul, verde, rojo). En la Figura 4 se ve un ejemplo de color con valores en ambos espacios de color. Consulta el archivo 'Appendix.pdf' incluido con el código fuente del artículo para una breve explicación sobre espacios de color BGR y HSV.

Espacios de color

Figura 4: Espacios de color. (Fuente para la imagen: AlloyUI)

A continuación, en la línea 47, llamamos a la función OpenCV inRange(hsv, HSV_LOWER_BOUND, HSV_UPPER_BOUND) para obtener segmentos de imagen de todos los píxeles con valores en el rango de color HSV definido por las tuplas HSV_LOWER_BOUND y HSV_UPPER_BOUND. La función recibe como primer argumento el cuadro de imagen que queremos segmentar (llamado 'hsv' en el código); el segundo y tercer argumento son las tuplas de límite inferior y superior (tono, saturación, valor) que definen el rango de color. Esta función devolverá una imagen binaria (blanco y negro) llamda 'mask' (máscara) en la que todos los píxeles de nuestra gama de colores definida se representarán como píxeles blancos y el resto se representará como píxeles negros.  La Figura 5 muestra el cuadro de imagen en cuatro diferentes pasos del proceso.

Detección del objetivo

Figura 5: Detección del objetivo. a) Cuadro original, b) Cuadro desenfocado, c) Cuadro con máscara, d) Cuadro erosionado y dilatado.

Hay un script Python que forma parte de los archivos de los tutoriales oficiales pertenecientes al repositorio de código de la librería OpenCV, el cual ejemplifica la segmentación de color con la función 'inRange' [Referencia 2]. El ejemplo se llama 'threshold_inRange.py' y no solo es útil para aprender sobre el tópico en cuestión, sino que también puede ayudarnos a obtener los valores del rango de color para el objeto que queremos rastrear. La Figura 6 muestra cómo obtuve el rango de color para mi objetivo al ejecutar este script. Incluí el script con el código fuente. Consulta el archivo 'run_track_and_follow.md' para una descripción detallada acerca de cómo usar el script para obtener tu propio rango de color para tu objetivo.

Definiendo tu propio rango de color para tu objetivo

Figura 6: Definiendo tu propio rango de color para tu objetivo

Una vez que obtenemos la segmentación de color, en las líneas 48-49 aplicamos erosión y dilatación a la imagen tres veces cada una ('iterations = 3'). 'erode ()' erosionará los límites de la máscara blanca en la imagen, disminuyendo o eliminando pequeñas características (ruido) en los límites y separando los elementos conectados. Esto reducirá el área de la máscara y reducirá también su tamaño. 'dilate()', por otro lado, aumentará el tamaño de la máscara para contrarrestar el efecto de la erosión y volverá a conectar algunas características aún presentes.

En la línea 51, llamamos a la función findContours(), la cual devolverá una lista de todos los contornos detectados (los objetos "isla" desconectados) en la imagen 'mask' (máscara). Luego, en la línea 57 comprobamos que se haya encontrado al menos un contorno. En la línea 58 obtenemos el contorno con el área más grande de todos, y en la línea 59 calculamos el radio del círculo mínimo circundante para ese contorno. Este radio será utilizado a continuación (línea 61) para comprobar si el objeto detectado es lo suficientemente grande para ser rastreado por el dron, comparándolo con el parámetro 'min_tgt_radius' (radio de objetivo mínimo).

La línea 62 calcula los "raw moments" ("momentos originales") del contorno más grande y los devuelve en un diccionario Python (llamado 'M' en el código), del cual se pueden derivar propiedades clave de la imagen; como ser, el área del contorno (el elemento del diccionario M["m00"]) y el centroide del contorno (x = M["m10"] / M["m00"], y = M["m01"] / M["m00 "]). No daré más detalles sobre los momentos y por qué exactamente obtenemos el centroide del objeto de esta manera, pero puse un enlace en la sección "Recursos" en caso de que desees profundizar en este tópico. Finalmente, en la línea 66, la función devuelve un diccionario Python con las coordenadas "imagen de cámara" del centroide objetivo (ancho, alto), el cuadro de imagen escalado utilizado en el proceso de detección y el contorno del objetivo detectado.

Flitro Pasa Bajo de Promedio Móvil

La siempre variable cantidad luz, balance de color y enfoque de la imagen, hará que varíe de cuadro a cuadro el número de píxeles detectados como parte del objetivo. Eso a su vez, variará la forma detectada, el área y las coordenadas del centroide. Esto produce un efecto de "temblor" de alta frecuencia del centroide del objeto en la imagen de video del proceso de detección. Además, en un dron real se producirá también una cierta cantidad de vibración debido a los motores y las hélices; lo cual ampliará a su vez el temblor del punto centroide. Para minimizar este efecto, pasaremos las coordenadas del centroide a través de un filtro pasa bajo de promedio móvil; uno de los métodos más fáciles para filtrar ruido de alta frecuencia en mediciones de sensores. Explicar cómo funciona este tipo de filtro está fuera del alcance de este artículo, consulta el archivo 'Appendix.pdf ' incluido con el código fuente de este artículo para una explicación suficientemente detallada sobre este filtro. Las líneas 1-19 en el Listado de Código 3 muestran la definición de la función moving_average_filter(coord).

async def moving_average_filter(coord):
    """ Applies Low-Pass Moving Average Filter to a pair of (x, y) coordinates."""

    filt_buffer['width'].append(coord['width'])
    filt_buffer['height'].append(coord['height'])

    if len(filt_buffer['width']) > NUM_FILT_POINTS:
        filt_buffer['width'] = filt_buffer['width'][1:]
        filt_buffer['height'] = filt_buffer['height'][1:]
    
    N = len(filt_buffer['width'])

    w_sum = sum( filt_buffer['width'] )
    h_sum = sum( filt_buffer['height'] )

    w_filt = int(round(w_sum / N))
    h_filt = int(round(h_sum / N))

    return {'width':w_filt, 'height':h_filt}


async def draw_objects(cam_coord, filt_cam_coord, frame, contour):
    """ Draws visualization objects from the detection process.
        Position coordinates of every object are always in 'camera pixel' units"""

    cv2.line(frame, (0, params['x_ax_pos']), (params['resized_width'], params['x_ax_pos']), (0, 128, 255), 1)
    cv2.line(frame, (params['y_ax_pos'], 0), (params['y_ax_pos'], params['resized_height']), (0, 128, 255), 1)
    cv2.circle(frame, (params['y_ax_pos'], params['x_ax_pos']), 1, (255, 255, 255), -1)
    
    cv2.rectangle(frame, params['cent_rect_p1'], params['cent_rect_p2'], (0, 178, 255), 1)

    cv2.drawContours(frame, [contour], -1, (0, 255, 0), 2)

    x_cart_coord = cam_coord['width'] - params['y_ax_pos']
    y_cart_coord = params['x_ax_pos'] - cam_coord['height']

    x_filt_cart_coord = filt_cam_coord['width'] - params['y_ax_pos']
    y_filt_cart_coord = params['x_ax_pos'] - filt_cam_coord['height']

    cv2.circle(frame, (cam_coord['width'], cam_coord['height']), 5, (0, 0, 255), -1) 
    cv2.putText(frame, str(x_cart_coord) + ", " + str(y_cart_coord), 
        (cam_coord['width'] + 25, cam_coord['height'] - 25), cv2.FONT_HERSHEY_SIMPLEX, 0.5, (0, 0, 255), 1)

    cv2.circle(frame, (filt_cam_coord['width'], filt_cam_coord['height']), 5, (255, 30, 30), -1)
    cv2.putText(frame, str(x_filt_cart_coord) + ", " + str(y_filt_cart_coord), 
        (filt_cam_coord['width'] + 25, filt_cam_coord['height'] - 25), cv2.FONT_HERSHEY_SIMPLEX, 0.5, (255, 30, 30), 1)

    return frame

Listado de Código 2: Funciones auxiliares 2

Si recuerdas, después de filtrar las coordenadas en la función principal llamamos a la función draw_objects() para dibujar los objetos de visualización de la detección en el cuadro de imagen (ver Figura 3). Usamos las funciones de OpenCV 'line()', 'circle()', 'rectangle()' , 'drawContours( )' y 'putText()' para dibujar líneas, círculos, rectángulos , el contorno y el texto respectivamente. Las líneas 26-46 del Listado de Código 3 muestran el código que se encarga de dibujar esos elementos en la imagen. Hay tutoriales sobre estas funciones de dibujo de OpenCV en muchos sitios (incluido el sitio oficial de OpenCV) si deseas comprender mejor cómo funcionan las mismas. Ve la sección de "Recursos" para un tutorial recomendado en este tema.

Controlando el Dron con MAVSDK

Para controlar el dron usamos la función drone.offboard.set_position_ned() (ve la línea 48 en el Listado de Código 1), que recibe coordenadas en el sistema "North, East, Down" (NED), más un ángulo "Yaw". "North" es la distancia al punto objetivo en el eje Norte, "East" es la distancia en el eje Este y "Down" es la altitud. "Yaw" es el ángulo del dron alrededor de su eje vertical en sentido horario (medido desde la línea Norte) que el dron debe tener cuando llega a la pose de destino. Ten en cuenta que para altitudes positivas, la coordenada "Down" (Abajo) debe ser negativa. Por ejemplo, para mandar el dron a una altitud de 10 metros, la coordenada "Down" debe ser igual a -10 ('Arriba' es en realidad '-Abajo ' ).

En mi artículo anterior "Escribiendo Aplicaciones MAVSDK/PX4 Para Drones", discutí con más detalle cómo controlar la posición de un dron enviando puntos de ajuste de posición NED en el modo de vuelo "offboard" de PX4. En el ciclo 'while', las coordenadas Cartesianas del objetivo detectado se convierten en coordenadas NED, como se explica al principio, y se envían al dron para controlar su posición y hacer que siga al objetivo.

Pruebas en Simulación

Para probar el código de ejemplo en simulación sigue los siguientes pasos: Primero, ejecuta la simulación PX4 con Gazebo, o PX4 con JMAVSim. Segundo, abre QGroundControl y tercero, corre el script 'track_and_follow.py'. Si la cámara detecta un objeto azul dentro del rango de color HSV definido en el código, verás al dron moverse sobre el mapa de QGroundControl en la dirección del objetivo detectado. Además, si mueves el objetivo azul frente a la cámara, el dron se moverá en la misma dirección, rastreando al objetivo solo cuando esté fuera del rectángulo central. El archivo de texto 'run_track_and_follow.md' incluido con el código fuente resume todos los pasos detallados para ejecutar el ejemplo en simulación. La Figura 7 muestra una captura de pantalla del script 'track_and_follow.py' en ejecución.

Ejemplo

Figura 7: Ejemplo "track_and_follow.py" en ejecución.

Conclusión

Como dije al principio, la segmentación de color no es la mejor estrategia para detectar y rastrear objetos con visión por computador. Por otra parte, el enfoque usado aquí para encontrar las coordenadas "reales" del objetivo tampoco es el mejor. Por ejemplo, deberíamos haber tenido en cuenta el hecho de que una toma de cámara desde un dron arriba en el aire es una proyección en perspectiva 2D del mundo real en 3D, en el campo de visión de la cámara. Para hacer las cosas bien, sería necesario calcular la inversa de esa proyección, del sistema de coordenadas 2D de la imagen al sistema de coordenadas 3D del mundo real, para obtener las coordenadas de destino (x, y) del mundo real. Obviamente, perdemos una dimensión en el proceso de pasar de 3D a 2D y luego volver de 2D a 3D. La implementación de un algoritmo de seguimiento como ese estaba definitivamente fuera del alcance de este artículo, cuyo objetivo principal era familiarizarte con visión por computador básica y programación de vuelo autónomo de drones.

Por otro lado, existen otras técnicas de detección de visión por computador más robustas, mucho mejores que la que usamos aquí; que permiten detectar y clasificar muchos tipos de elementos como automóviles, animales o personas. Como ejemplo, podemos nombrar algunos enfoques de "Machine Learning", como el Clasificador en Cascada de Haar o el Histograma de Gradientes Orientados y Clasificador SVM; así como otros enfoques de Deep Learning incluso más efectivos y, hoy por hoy, más populares. En un próximo artículo retomaremos este mismo tema para escribir una aplicación de detección y seguimiento autónomo con drones usando detección de objetos por inferencia "Deep Learning". ¡Manténte al tanto!
-------------------

REFERENCIAS
[Reference 1] “Quadrotor Autonomous Flight with PX4 and MAVSDK”, Circuit Cellar #361, September 2020
[Reference 2] Thresholding Operations using inRange, https://docs.opencv.org/master/da/d97/tutorial_threshold_inRange.html
Note: [Reference 1] is the reference to my article “Quadrotor Autonomous Flight with PX4 and MAVSDK”, which at the time of this writing is pending publication.

RECURSOS
‘track_and_follow.py’ Demo Videos
 https://www.youtube.com/playlist?list=PLLNS5tnQ-zCAlB3t2TxAxn3K95RLTqfhX

Smoothing Images
https://docs.opencv.org/master/d4/d13/tutorial_py_filtering.html

Thresholding Operations using inRange
https://docs.opencv.org/master/da/d97/tutorial_threshold_inRange.html

The Ultimate Guide to Understanding Hue, Tint, Tone and Shade
https://color-wheel-artist.com/hue/

Moments: Find the Center of a Blob (Centroid) using OpenCV (C++/Python)
https://www.learnopencv.com/find-center-of-blob-centroid-using-opencv-cpp-python/

Drawing Functions in OpenCV
https://docs.opencv.org/master/dc/da5/tutorial_py_drawing_functions.html

-----------------------------

Suscríbete a Nuestro Boletín de Noticias

Para recibir anuncios de otros talleres cursos similares.

Pregunta anti spam. Ingresa abajo las últimas 4 letras de: asteroide
Nombre:
Email:

Productos Relacionados en Nuestra Tienda Virtual

Placa Controladora de Vuelo ArduPilot Mega APM 2.6

placa-controladora-de-vuelo-ardupilot-mega-apm-2.6-(2)

Detalles del Producto

$us 52.00

Controladora de Vuelo Pixhawk 2.4.8, GPS NEO-6M, Tarjeta TF 4GB, Módulo de Potencia, PPM, I2C Splitter, OSD, Botón, Buzzer

pixhawk

Detalles del Producto

$us 260.00

Kit Cuadricóptero F450 APM Básico Completo

kit_cuadricóptero_f450_apm_básico_completo

Detalles del Producto

$us 361.36

Kit Cuadricóptero S500 (Tren Largo) APM DJI Compatible Básico Completo

kit_s500l_basico_completo

Detalles del Producto

$us 513.00

Kit Cuadricóptero de Carrera QAV250 (Clone) Básico Completo

imagen-4

Detalles del Producto

$us 371.40