Vision
Ce fichier présente les différentes Vision - Fonctions de contrôle, Vision - Enumerations, Vision - Topics Niryo & Vision - Namedtuple disponible avec l’API de Vision
Vision - Fonctions de contrôle
Cette section fait référence à toutes les fonctions de contrôle du bras robotique existantes, ce qui inclut
Obtient l’image de la caméra
Détecte les objets
Gère les workspaces
Toutes les fonctions de contrôle du bras sont accessibles grâce à une instance de classe NiryoRobot
robot = NiryoRobot(<robot_ip_address>)
robot.vision.vision_pick("workspace_1", 0.0, ObjectShape.ANY, ObjectColor.ANY)
robot.vision.detect_object("workspace_1", ObjectShape.ANY, ObjectColor.ANY)
...
Voir les exemples dans Examples Section
Liste des fonctions de sous-sections
- class Vision(client, arm=None, tool=None)[source]
Vision - Fonctions de contrôle
Exemples:
ros_instance = NiryoRos("10.10.10.10") # Hotspot vision_interface = Vision(ros_instance)
- Paramètres
client (NiryoRos) – Client Niryo Ros
Fonctions de la caméra
- property Vision.get_img_compressed
Obtient les images du flux vidéo en format compressé. Utilise
uncompress_image
du package vision pour le décompresserExemples:
import pyniryo img_compressed = vision.get_img_compressed() camera_info = vision.get_camera_intrinsics() img = pyniryo.uncompress_image(img_compressed) img = pyniryo.undistort_image(img, camera_info.intrinsics, camera_info.distortion)
- Renvoie
Chaîne contenant l’image compréssée au format JPEG
- Type renvoyé
- property Vision.get_camera_intrinsics
Obtient l’objet de type calibration: Paramètres intrinsèques de la caméra, coefficients de distortion. Le topic retourne un namedtuple(intrinsics: list[list[float]], distortion: list[list[float]])
Exemples:
vision.get_camera_intrinsics() vision.get_camera_intrinsics().value def camera_info_callback(camera_info): print(camera_info.intrinsics) print(camera_info.distortion) vision.get_camera_intrinsics.unsubscribe() vision.get_camera_intrinsics.subscribe(camera_info_callback)
- Type renvoyé
- property Vision.get_image_parameters
Retourne le NiryoTopic pour obtenir les Paramètres de la dernière image du flux vidéo: facteur de luminosité, facteur de contraste, facteur de saturation. Le topic retourne un namedtuple(brightness_factor: float, contrast_factor: float, saturation_factor: float)
Facteur de luminosité : comment ajuster la luminosité. 0.5 donnera une image assombrie, 1 donnera l’image originale tandis que 2 augmentera la luminosité par un facteur 2.
Facteur de contraste: un facteur 1 donne l’image originale.Plus le multiplicateur se rapproche de 0 et plus l’image deviendra grise, « tandis qu’un facteur > 1 augmentera le contraste de l’image.
Facteur de saturation: 0 donnera une image en noir et blanc, 1 donnera l’image originale tandis que 2 augmentera la saturation par un facteur 2
Exemples:
vision.get_image_parameters() vision.get_image_parameters.value def image_parameters_callback(image_parameters): print(image_parameters.brightness_factor) print(image_parameters.contrast_factor) print(image_parameters.saturation_factor) vision.get_image_parameters.unsubscribe() vision.get_image_parameters.subscribe(image_parameters_callback)
- Renvoie
ImageParameters namedtuple contient le facteur de luminosité, le facteur de contraste et le facteur de saturation
- Type renvoyé
Fonctions de détection
- Vision.get_target_pose_from_cam(workspace_name, height_offset=0.0, shape=<ObjectShape.ANY: 'ANY'>, color=<ObjectColor.ANY: 'ANY'>)[source]
Commence par détecter l’objet spécifié en utilisant la caméra puis renvoie la position du robot à laquelle l’objet peut être attrapé avec l’outil utilisé.
- Paramètres
- Renvoie
object_found, object_pose, object_shape, object_color
- Type renvoyé
(bool, PoseObject, ObjectShape, ObjectColor)
- Vision.vision_pick(workspace_name, height_offset=0.0, shape=<ObjectShape.ANY: 'ANY'>, color=<ObjectColor.ANY: 'ANY'>)[source]
Saisit l’objet spécifié sur le workspace. Cette fonction possède plusieurs phases:
1. detect object using the camera2. prepare the current tool for picking3. approach the object4. move down to the correct picking pose5. actuate the current tool6. lift the objectExemple:
robot = NiryoRobot(ip_address="x.x.x.x") robot.arm.calibrate_auto() robot.arm.move_pose(<observation_pose>) obj_found, shape_ret, color_ret = robot.vision.vision_pick(<workspace_name>, height_offset=0.0, shape=ObjectShape.ANY, color=ObjectColor.ANY)
- Paramètres
- Renvoie
object_found, object_shape, object_color
- Type renvoyé
(bool, ObjectShape, ObjectColor)
- Vision.move_to_object(workspace_name, height_offset, shape, color)[source]
Comme get_target_pose_from_cam mais se déplace directement à cette position
- Paramètres
- Renvoie
object_found, object_shape, object_color
- Type renvoyé
(bool, ObjectShape, ObjectColor)
- Vision.detect_object(workspace_name, shape=<ObjectShape.ANY: 'ANY'>, color=<ObjectColor.ANY: 'ANY'>)[source]
Détecte un objet dans le workspace et retourne sa position et ses caractéristiques
- Paramètres
workspace_name (str) – nom du workspace
shape (ObjectShape) – forme de la cible
color (ObjectColor) – couleur de la cible
- Renvoie
object_found, object_pose, object_shape, object_color
- Type renvoyé
(bool, PoseObject, str, str)
Fonctions du workspace
- Vision.get_target_pose_from_rel(workspace_name, height_offset, x_rel, y_rel, yaw_rel)[source]
Pour une pose (x_rel, y_rel, yaw_rel) donnée relative à un workspace, cette fonction retourne la position du robot dans laquelle l’outil actuel sera capable d’attraper un objet.
L’argument height_offset (en m) definit à quelle hauteur l’outil va passer au dessus du workspace. Si height_offset = 0, l’outil touchera presque le workspace.
- Paramètres
- Renvoie
target_pose
- Type renvoyé
- Vision.save_workspace_from_robot_poses(workspace_name, pose_origin, pose_2, pose_3, pose_4)[source]
Sauvegarder le workspace en donnant au robot les 4 positions lui permettant de pointer ses 4 coins avec la pointe de calibration. Les coins doivent être dans le bon ordre. La position de ces marqueurs sera déduite de ces positions.
Les Positions doivent être une liste [x, y, z, roll, pitch, yaw] ou une PoseObject
- Paramètres
workspace_name (str) – nom du workspace
pose_origin (Union[list[float], PoseObject]) –
pose_2 (Union[list[float], PoseObject]) –
pose_3 (Union[list[float], PoseObject]) –
pose_4 (Union[list[float], PoseObject]) –
- Type renvoyé
- Vision.save_workspace_from_points(workspace_name, point_origin, point_2, point_3, point_4)[source]
Sauvegarde le workspace en donnant les points des quatre coins du workspace. Les points sont écrit sous la forme [x, y, z]. Les coins doivent être donnés dans le bon ordre
Vision - Topics Niryo
L’utilisation de ces fonctions est expliqué dans la section NiryoTopic. Elle permettent d’obtenir les données en temps réel grâce aux fonctions de rappel ou par appel direct
Nom |
Fonctions |
Type de la variable de retour |
---|---|---|
|
|
|
|
|
Vision - Enumerations
Liste des enumerations
ObjectColor
ObjectShape
ManageWorkspace
- class ObjectColor(value)[source]
Enumeration des couleurs disponibles pour le traitement de l’image
- RED = 'RED'
- BLUE = 'BLUE'
- GREEN = 'GREEN'
- ANY = 'ANY'
- class ObjectShape(value)[source]
Enumeration des formes disponibles pour le traitement de l’image
- SQUARE = 'SQUARE'
- CIRCLE = 'CIRCLE'
- ANY = 'ANY'
- class ManageWorkspace(value)[source]
Enumeration des actions disponible pour la gestion des workspaces
- SAVE = 1
- SAVE_WITH_POINTS = 2
- DELETE = -1
Vision - Namedtuple
- class CameraInfo(intrinsics, distortion)
Crée une nouvelle instance de CameraInfo(intrinsics, distortion)
- distortion
Alias pour le champ numéro 1
- intrinsics
Alias pour le champ numéro 0
- class ImageParameters(brightness_factor, contrast_factor, saturation_factor)
Crée une nouvell instance de ImageParameters(brightness_factor, contrast_factor, saturation_factor
- brightness_factor
Alias pour le champ numéro 0
- contrast_factor
Alias pour le champ numéro 1
- saturation_factor
Alias pour le champ numéro 2