Vue d’ensemble et exemples

Ce document illustre quelques pipelines de traitement d’image utilisation de module de vision du package niryo_edu. Ce module est basé sur OpenCV et ses fonctions sont détaillées dans Documentation des fonctions.

Le package niryo_edu est fourni avec un module vision qui contient des fonctions de traitement d’images incluant du seuillage, la détection de zones d’intérêt (blobs), …
Afin de l’utiliser, ajoutez à vous importations from pyniryo.vision import *.

Note

Il est également possible de fusionner les lignes des deux importations en utilisant from pyniryo import *

Interagir avec le flux vidéo du robot

Nous allons commencer par étudier les fonctions du robot qui peuvent être trouvées dans API - Vision.

Obtenir et afficher une image depuis le flux

Ned peut partager son flux vidéo par le biais de TCP. Envoyer des images brutes est à l’origine de lourds paquets qui peuvent faire saturer le réseau, alors il envoie des images compressées. Vous pouvez y accéder depuis la fonction du robot suivante : get_img_compressed(). Une fois l’image reçue, vous aurez besoin de la décompresser avec uncompress_image(). Vous pouvez désormais l’afficher avec la fonction show_img_and_wait_close().

from pyniryo import *

# Connecting to robot
robot = NiryoRobot("10.10.10.10")

# Getting image
img_compressed = robot.get_img_compressed()
# Uncompressing image
img = uncompress_image(img_compressed)

# Displaying
show_img_and_wait_close("img_stream", img)

Note

La fonction show_img_and_wait_close() attendra que l’utilisateur appuie sur la touche Q ou Esc avant de fermer la fenêtre.

Rectifier la déformation et afficher le flux vidéo

Dans cette section, nous afficherons le flux vidéo brut ainsi que le flux vidéo non distordu.

Puisque la caméra du Set Vision envoie à Ned des images brutes, ces images sont déformées à cause de la lentille de la caméra. Afin de rectifier leur déformation, nous avons besoin d’utiliser les paramètres intrinsèques de la caméra de Ned.

Afin de rectifier la déformation de l’image brute, nous utilisons la fonction undistort_image() qui doit être appelée avec les paramètres donnés à Ned par get_camera_intrinsics().

Une fois que vous avez l’image brute et l’image non distordue, on peut les concaténer afin de les afficher en une fois avec concat_imgs(). Enfin, on affiiche l’image show_img().

from pyniryo import *

observation_pose = PoseObject(
    x=0.18, y=0.0, z=0.35,
    roll=0.0, pitch=1.57, yaw=-0.2,
)

# Connecting to robot
robot = NiryoRobot("10.10.10.10")
robot.calibrate_auto()

# Getting calibration param
mtx, dist = robot.get_camera_intrinsics()
# Moving to observation pose
robot.move_pose(observation_pose)

while "User do not press Escape neither Q":
    # Getting image
    img_compressed = robot.get_img_compressed()
    # Uncompressing image
    img_raw = uncompress_image(img_compressed)
    # Undistorting
    img_undistort = undistort_image(img_raw, mtx, dist)

    # - Display
    # Concatenating raw image and undistorted image
    concat_ims = concat_imgs((img_raw, img_undistort))

    # Showing images
    key = show_img("Images raw & undistorted", concat_ims, wait_ms=30)
    if key in [27, ord("q")]:  # Will break loop if the user press Escape or Q
        break

Note

Pour en découvrir davantage à propos de la distortion / correction de distortion, rendez vous sur la documentation OpenCV à propos de la calibration de la caméra.

Fonctions de traitement d’images simple

Afin d’illuster les fonctions, nous allons utiliser l’image suivante.

Image illustration

Attention

Dans cette section, il est supposé que :

  • Vous avez importé pyniryo.vision

  • La variable img contient l’image sur laquelle le traitement d’images est appliqué

Seuillage de couleurs

Le seuillage de couleurs est très utile pour détecter un objet avec une couleur uniforme. La fonction implémentée pour réaliser cette opération est threshold_hsv().

Le code suivant utilise les paramètres de l’enum ColorHSV afin de seuiller les éléments rouges ainsi que des paramètres réalisés à la main pour extraire la couleur bleue.

img_threshold_red = threshold_hsv(img_test, *ColorHSV.RED.value)

blue_min_hsv = [90, 85, 70]
blue_max_hsv = [125, 255, 255]

img_threshold_blue = threshold_hsv(img_test, list_min_hsv=blue_min_hsv,
                                   list_max_hsv=blue_max_hsv, reverse_hue=False)

show_img("img_threshold_red", img_threshold_red)

show_img_and_wait_close("img_threshold_blue", img_threshold_blue)
Images obtenues

Couleur seuillée

Images obtenues

Bleu

Image Threshold Blue

Rouge

Image Threshold Red

Transformations morphologiques

Les transformations morphologiques sont des opérations simples basées sur la forme de l’image. Elles sont normalement réalisée sur des images binaires. Elles nécessitent deux entrées, l’une est notre image originale, l’autre est appelée élément structurant ou noyau et décide de la nature de l’opération. Les deux opérateurs morphologiques communs sont l’érosion et la dilatation.

Ensuite ses variantes comme l’ouverture, la fermeture sont sont également à prendre en compte. Apprenez-en plus sur la page Wikipédia.

Afin de réaliser ses opérations, la fonction implémentée est morphological_transformations(). Elle utilise MorphoType et KernelType afin de déterminer quelle opération doit être appliquée à l’image.

Le code montre comment réaliser une fermeture et une érosion :

img_threshold = threshold_hsv(img_test, *ColorHSV.ANY.value)

img_close = morphological_transformations(img_threshold, morpho_type=MorphoType.CLOSE,
                                          kernel_shape=(11, 11), kernel_type=KernelType.ELLIPSE)

img_erode = morphological_transformations(img_threshold, morpho_type=MorphoType.ERODE,
                                          kernel_shape=(9, 9), kernel_type=KernelType.RECT)

show_img("img_threshold", img_threshold)
show_img("img_erode", img_erode)
show_img_and_wait_close("img_close", img_close)
Images obtenues

Morphotype

Images obtenues

Aucun

Image Threshold Any

Érodé

Images obtenues

Fermé

Image Close

Détection de contours

Les contours peuvent être expliqués par une courbe reliant tous les points ayant la même couleur ou intensité. La détection de contours est un outil utile pour l’analyse de formes et la détection et reconnaissance d’objets. Apprenez en plus sur la Documentation OpenCV.

Afin de réaliser ces opérations, la fonction implémentée est biggest_contours_finder() qui prend une image en noir et blanc et en extrait le plus grand (en terme de surface) contour.

Le code permettant d’extraire et dessiner les 3 plus grands contours d’une image sont les suivants :

img_threshold = threshold_hsv(img_test, *ColorHSV.ANY.value)
img_threshold = morphological_transformations(img_threshold, morpho_type=MorphoType.OPEN,
                                              kernel_shape=(11, 11), kernel_type=KernelType.ELLIPSE)

cnts = biggest_contours_finder(img_threshold, 3)

img_contours = draw_contours(img_threshold, cnts)

show_img("init", img_threshold)
show_img_and_wait_close("img with contours", img_contours)
Images obtenues

Seuil + ouverture

Image Threshold Any & Open

3 contours

3 contours

Trouve le centre l’objet

Afin d’attraper un objet, nous avons besoin de trouver une position depuis laquelle l’effecteur peut saisir l’objet. La méthode qui suit utilise les contours qui ont été trouvés dans la section précedente et trouve ainsi leur barycentre et leur orientation via les fonctions get_contour_barycenter() & get_contour_angle().

img_threshold = threshold_hsv(img_test, *ColorHSV.ANY.value)
img_threshold = morphological_transformations(img_threshold, morpho_type=MorphoType.OPEN,
                                              kernel_shape=(11, 11), kernel_type=KernelType.ELLIPSE)

cnt = biggest_contour_finder(img_threshold)

cnt_barycenter = get_contour_barycenter(cnt)
cx, cy = cnt_barycenter
cnt_angle = get_contour_angle(cnt)

img_debug = draw_contours(img_threshold, [cnt])
img_debug = draw_barycenter(img_debug, cx, cy)
img_debug = draw_angle(img_debug, cx, cy, cnt_angle)
show_img("Image with contours, barycenter and angle", img_debug, wait_ms=30)
Images obtenues

Seuil + ouverture

Image Threshold Any & Open

Barycentre + Angle

Barycentre + Angle

Note

Le vecteur dessiné est normal à la longueur du contour, car nous voulons que Ned attrape l’objet dans sa largeur plutôt que dans sa longueur. En effet, cela permet de réduire le nombre de cas dans lequel le gripper ne peut pas s’ouvrir de manière suffisante.

Extraction des marqueurs

Puisque le traitement d’images à lieu dans un espace de travail, il est important d’extraire cet espace de travail avant tout ! Pour cela, vous pouvez utiliser la fonction extract_img_workspace().

status, im_work = extract_img_workspace(img, workspace_ratio=1.0)
show_img("init", img_test)
show_img_and_wait_close("img_workspace", img_workspace)
Images obtenues

Original

Original Image

Extraite

Extraite

Mode debogage

Si les fonctions de Ned échouent, vous pouvez utiliser les fonctions de debogage qui sont debug_threshold_color() & debug_markers(), afin d’afficher sur l’écran ce que le robot voit.

Vous pouvez utiliser les fonctions qui suivent :

debug_color = debug_threshold_color(img_test, ColorHSV.RED)
_status, debug_markers_im = debug_markers(img_test, workspace_ratio=1.0)

show_img("init", img_test)
show_img("debug_color", debug_color)
show_img_and_wait_close("debug_markers", debug_markers_im)
Images obtenues

Original

Original Image

Debogage rouge

Debogage rouge

Debogage marqueurs

Debogage marqueurs

Créer votre propre traitement d’images !

Maintenant que vous êtes un professionnel en traitement d’images, regardons des exemples complets.

Affiche le flux vidéo avec le workspace extrait

Dans l’état actuel, le code suivant affichera le flux vidéo et extraira l’image de l’espace de travail. Vous pouvez ajouter vos propres fonctions de traitement d’images afin d’appliquer des process additionnels.

from pyniryo import *

# Connecting to robot
robot = NiryoRobot("10.10.10.10")
robot.calibrate_auto()

# Getting calibration param
mtx, dist = robot.get_camera_intrinsics()
# Moving to observation pose
robot.move_pose(*observation_pose.to_list())

while "User do not press Escape neither Q":
    # Getting image
    img_compressed = robot.get_img_compressed()
    # Uncompressing image
    img_raw = uncompress_image(img_compressed)
    # Undistorting
    img_undistort = undistort_image(img_raw, mtx, dist)
    # Trying to find markers
    workspace_found, res_img_markers = debug_markers(img_undistort)
    # Trying to extract workspace if possible
    if workspace_found:
        img_workspace = extract_img_workspace(img_undistort, workspace_ratio=1.0)
    else:
        img_workspace = None

    # --- --------- --- #
    # --- YOUR CODE --- #
    # --- --------- --- #

    # - Display
    # Concatenating raw image and undistorted image
    concat_ims = concat_imgs((img_raw, img_undistort))
    # Concatenating extracted workspace with markers annotation
    if img_workspace is not None:
        resized_img_workspace = resize_img(img_workspace, height=res_img_markers.shape[0])
        res_img_markers = concat_imgs((res_img_markers, resized_img_workspace))
    # Showing images
    show_img("Images raw & undistorted", concat_ims)
    key = show_img("Markers", res_img_markers, wait_ms=30)
    if key in [27, ord("q")]:  # Will break loop if the user press Escape or Q
        break

Saisie par la vision avec votre pipeline de traitement d’images.

Si vous souhaitez envoyer des coordonnées à Ned afin qu’il saisisse l’objet de votre choix, utilisez la fonction get_target_pose_from_rel(), qui convertit une position relative sur le workspace en une position dans l’environnement du robot !

from pyniryo import *

# -- MUST Change these variables
simulation_mode = True
if simulation_mode:
    robot_ip_address, workspace_name = "127.0.0.1", "gazebo_1"
else:
    robot_ip_address, workspace_name = "10.10.10.10", "workspace_1"

# -- Can Change these variables
grid_dimension = (3, 3)  # conditioning grid dimension
vision_process_on_robot = False  # boolean to indicate if the image processing append on the Robot
display_stream = True  # Only used if vision on computer

# -- Should Change these variables
# The pose from where the image processing happens
observation_pose = PoseObject(
    x=0.17, y=0., z=0.35,
    roll=0.0, pitch=1.57, yaw=0.0,
)

# Center of the conditioning area
center_conditioning_pose = PoseObject(
    x=0.0, y=-0.25, z=0.12,
    roll=-0., pitch=1.57, yaw=-1.57
)


# -- MAIN PROGRAM

def process(niryo_robot):
    """

    :type niryo_robot: NiryoRobot
    :rtype: None
    """
    # Initializing variables
    obj_pose = None
    try_without_success = 0
    count = 0
    if not vision_process_on_robot:
        mtx, dist = niryo_robot.get_camera_intrinsics()
    else:
        mtx = dist = None
    # Loop
    while try_without_success < 5:
        # Moving to observation pose
        niryo_robot.move_pose(observation_pose)

        if vision_process_on_robot:
            ret = niryo_robot.get_target_pose_from_cam(workspace_name,
                                                       height_offset=0.0,
                                                       shape=ObjectShape.ANY,
                                                       color=ObjectColor.ANY)
            obj_found, obj_pose, shape, color = ret

        else:  # Home made image processing
            img_compressed = niryo_robot.get_img_compressed()
            img = uncompress_image(img_compressed)
            img = undistort_image(img, mtx, dist)
            # extracting working area
            im_work = extract_img_workspace(img, workspace_ratio=1.0)
            if im_work is None:
                print("Unable to find markers")
                try_without_success += 1
                if display_stream:
                    cv2.imshow("Last image saw", img)
                    cv2.waitKey(25)
                continue

            # Applying Threshold on ObjectColor
            color_hsv_setting = ColorHSV.ANY.value
            img_thresh = threshold_hsv(im_work, *color_hsv_setting)

            if display_stream:
                show_img("Last image saw", img, wait_ms=100)
                show_img("Image thresh", img_thresh, wait_ms=100)
            # Getting biggest contour/blob from threshold image
            contour = biggest_contour_finder(img_thresh)
            if contour is None or len(contour) == 0:
                print("No blob found")
                obj_found = False
            else:
                img_thresh_rgb_w_contour = draw_contours(img_thresh, [contour])

                # Getting contour/blob center and angle
                cx, cy = get_contour_barycenter(contour)
                img_thresh_rgb_w_contour = draw_barycenter(img_thresh_rgb_w_contour, cx, cy)
                cx_rel, cy_rel = relative_pos_from_pixels(im_work, cx, cy)

                angle = get_contour_angle(contour)
                img_thresh_rgb_w_contour = draw_angle(img_thresh_rgb_w_contour, cx, cy, angle)

                show_img("Image thresh", img_thresh_rgb_w_contour, wait_ms=30)

                # Getting object world pose from relative pose
                obj_pose = niryo_robot.get_target_pose_from_rel(workspace_name,
                                                                height_offset=0.0,
                                                                x_rel=cx_rel, y_rel=cy_rel,
                                                                yaw_rel=angle)
                obj_found = True
        if not obj_found:
            try_without_success += 1
            continue
        # Everything is good, so we going to object
        niryo_robot.pick_from_pose(obj_pose)

        # Computing new place pose
        offset_x = count % grid_dimension[0] - grid_dimension[0] // 2
        offset_y = (count // grid_dimension[1]) % 3 - grid_dimension[1] // 2
        offset_z = count // (grid_dimension[0] * grid_dimension[1])
        place_pose = center_conditioning_pose.copy_with_offsets(0.05 * offset_x, 0.05 * offset_y, 0.025 * offset_z)

        # Placing
        niryo_robot.place_from_pose(place_pose)

        try_without_success = 0
        count += 1


if __name__ == '__main__':
    # Connect to robot
    robot = NiryoRobot(robot_ip_address)
    # Changing tool
    robot.update_tool()
    # Calibrate robot if robot needs calibration
    robot.calibrate_auto()
    # Launching main process
    process(robot)
    # Ending
    robot.go_to_sleep()
    # Releasing connection
    robot.close_connection()