Documentation de l’API PyNiryo
Ce document présente les différentes Fonctions de commande, Enums (énumérations) & les Classes d’objets Python disponibles avec l’API
Les Fonctions de commande sont utilisées pour intéragir directement avec le robot. Elles peuvent être
move_joints()
,get_hardware_status()
vision_pick()
, ou encorerun_conveyor()
Enums (énumérations) sont utilisées pour passer des arguments spécifiques aux fonctions. Par exemple
PinState
,ConveyorDirection
, …Les objets Python, tels que
PoseObject
, facilitent certaines opérations.
Fonctions de commande
Cette section référence toutes les fonctions existantes permettant de contrôler votre robot, incluant :
Bouger le robot
Utiliser la Vision
Contrôler le convoyeur
Utiliser le hardware
Toutes les fonctions permettant de contrôler le robot sont disponibles depuis une instance de la classe NiryoRobot
:
robot = NiryoRobot(<robot_ip_address>)
Voir un exemple dans la section Exemples
Liste des sous-sections des fonctions :
Connexion TCP
Fonctions principales
- NiryoRobot.calibrate(calibrate_mode)[source]
Calibrer (manuellement ou automatiquement) les moteurs. La calibration automatique ne provoquera rien si les moteurs sont déjà calibrés
- Paramètres
calibrate_mode (CalibrateMode) – Auto ou Manuel
- Type renvoyé
- NiryoRobot.calibrate_auto()[source]
Démarre une calibration automatique des moteurs si les moteurs n’ont pas encore été calibrés
- Type renvoyé
- NiryoRobot.need_calibration()[source]
Renvoie un booléen indiquant si les moteurs du robot ont besoin d’être calibrés
- Type renvoyé
- NiryoRobot.get_learning_mode()[source]
Afficher l’état du mode apprentissage
- Renvoie
Vrai
si le mode apprentissage est activé- Type renvoyé
- NiryoRobot.set_learning_mode(enabled)[source]
Allumer le mode apprentissage si param est
Vrai
, sinon l’arrêter
- NiryoRobot.set_arm_max_velocity(percentage_speed)[source]
Limiter la vitesse maximum du bras à un pourcentage de sa vitesse maximum
Axe & Pose
- NiryoRobot.get_joints()[source]
Obtenir la valeur des axes en radians. Vous pouvez également utiliser un getter
joints = robot.get_joints() joints = robot.joints
- NiryoRobot.get_pose()[source]
Obtenir la position de l’effecteur en [w, y, z, roll, pitch, yaw]. x, y & z sont exprimés en mètres / roll, pitch & yaw sont exprimés en radians. Il est également possible d’utiliser un getter
pose = robot.get_pose() pose = robot.pose
- Type renvoyé
- NiryoRobot.move_joints(*args)[source]
Bouger les axes du robots. Les axes sont exprimés en radians.
L’ensemble des lignes du prochain exemple réalisent la même opération :
robot.joints = [0.2, 0.1, 0.3, 0.0, 0.5, 0.0] robot.move_joints([0.2, 0.1, 0.3, 0.0, 0.5, 0.0]) robot.move_joints(0.2, 0.1, 0.3, 0.0, 0.5, 0.0)
- NiryoRobot.move_pose(*args)[source]
Modifie la position de l’effecteur du robot à une position (x, y, z,roll, pitch, yaw), dans un repère particulier si défini. x, y & z sont exprimés en mètres / roll, pitch, yaw sont exprimés en radians
L’ensemble des lignes du prochain exemple réalisent la même opération :
robot.pose = [0.2, 0.1, 0.3, 0.0, 0.5, 0.0] robot.move_pose([0.2, 0.1, 0.3, 0.0, 0.5, 0.0]) robot.move_pose(0.2, 0.1, 0.3, 0.0, 0.5, 0.0) robot.move_pose(0.2, 0.1, 0.3, 0.0, 0.5, 0.0) robot.move_pose(PoseObject(0.2, 0.1, 0.3, 0.0, 0.5, 0.0)) robot.move_pose([0.2, 0.1, 0.3, 0.0, 0.5, 0.0], "frame") robot.move_pose(PoseObject(0.2, 0.1, 0.3, 0.0, 0.5, 0.0), "frame")
- NiryoRobot.move_linear_pose(*args)[source]
Modifie la position de l’effecteur du robot à une position (x, y, z,roll, pitch, yaw), dans un repère particulier si défini, avec une trajectoire linéaire
- NiryoRobot.shift_pose(axis, shift_value)[source]
Glisser la position de l’effecteur du robot le long d’un axe
- NiryoRobot.shift_linear_pose(axis, shift_value)[source]
Glisser la position de l’effecteur du robot le long d’un axe, avec une trajectoire linéaire
- NiryoRobot.jog_joints(*args)[source]
Translation des axes du robot. La translation correspond à un glissement sans plannification de mouvement. Les valeurs sont exprimées en radians.
- NiryoRobot.jog_pose(*args)[source]
Les arguments sont [dx, dy, dz, d_roll, d_pitch, d_yaw] dx, dy & dz sont exprimés en mètres / d_roll, d_pitch & d_yaw sont exprimés en radians
- NiryoRobot.move_to_home_pose()[source]
Bouger le robot à une position dans laquelle l’avant bras du robot repose sur son épaule
- Type renvoyé
- NiryoRobot.go_to_sleep()[source]
Retourner à la position de départ et activer le mode apprentissage
- Type renvoyé
Positions sauvegardées
- NiryoRobot.get_pose_saved(pose_name)[source]
Utiliser une position sauvegardée depuis la mémoire de Ned
- Paramètres
pose_name (str) – Nom de la position dans la mémoire du robot
- Renvoie
Position associée au pose_name
- Type renvoyé
Pick & Place
- NiryoRobot.pick_from_pose(*args)[source]
Exécuter un prélèvement depuis une position
Un prélèvement est décrit comme :
* descendre en direction de l’objet* descendre jusque hauteur = z* attraper avec un outil* retourner au dessus de l’objet
- NiryoRobot.place_from_pose(*args)[source]
Exécuter un placement depuis une position
Un placement est décrit comme :
* aller en direction d’un emplacement* descendre jusque hauteur = z* relâcher l’objet avec un outil* retourner au dessus de l’emplacement
- NiryoRobot.pick_and_place(pick_pose, place_pos, dist_smoothing=0.0)[source]
Exécuter un prélèvement puis un placement
- Paramètres
pick_pose (Union[list[float], PoseObject]) – Position de prélèvement : [x, y, z, roll, pitch, yaw] ou PoseObject
place_pos (Union[list[float], PoseObject]) – Position de placement : [x, y, z, roll, pitch, yaw] ou PoseObject
dist_smoothing (float) – Distance entre les points de passage avant le lissage de la trajectoire
- Type renvoyé
Trajectoires
- NiryoRobot.get_trajectory_saved(trajectory_name)[source]
Obtenir la trajectoire sauvegardée dans la mémoire de Ned
- Renvoie
Trajectoires
- Type renvoyé
list[Joints]
- NiryoRobot.get_saved_trajectory_list()[source]
Obtenir la liste des noms des trajectoires sauvegardées dans la mémoire du robot
- NiryoRobot.execute_registered_trajectory(trajectory_name)[source]
Exécuter la trajectoire depuis la mémoire de Ned
- Type renvoyé
- NiryoRobot.execute_trajectory_from_poses(list_poses, dist_smoothing=0.0)[source]
Exécuter une trajectoire depuis une liste de positions
- NiryoRobot.execute_trajectory_from_poses_and_joints(list_pose_joints, list_type=None, dist_smoothing=0.0)[source]
Exécuter la trajectoire à partir de la liste de positions cartésiennes et depositions des joints
Exemple
robot.execute_trajectory_from_poses_and_joints( list_pose_joints = [[0.0, 0.0, 0.0, 0.0, 0.0, 0.0], [0.25, 0.0, 0.0, 0.0, 0.0, 0.0]], list_type = ['joint', 'pose'], dist_smoothing = 0.01 )
- Paramètres
list_pose_joints (list[list[float]]) – Liste contenant [x,y,z,qx,qy,qz,qw] ou [x,y,z,roll,pitch,yaw]
list_type (list[string]) – Liste de string contenant “pose” ou “joint”, ou [“pose”] (si uniquement des “pose”) ou [“joint”] (si uniquement des “joint”). Si l’argument est None, le type est mis à [“Pose”] par défaut.
dist_smoothing (float) – Distance entre les points de passage avant le lissage de la trajectoire
- Type renvoyé
- NiryoRobot.save_trajectory(trajectory, trajectory_name, trajectory_description)[source]
Sauvegarder la trajectoire dans la mémoire du robot
- NiryoRobot.save_last_learned_trajectory(name, description)[source]
Sauvegarde la dernière trajectoire exécutée par l’utilisateur
- Type renvoyé
Repères dynamiques
- NiryoRobot.get_saved_dynamic_frame_list()[source]
Obtient la liste des repères sauvegardés
Exemple
list_frame, list_desc = robot.get_saved_dynamic_frame_list() print(list_frame) print(list_desc)
- NiryoRobot.get_saved_dynamic_frame(frame_name)[source]
Obtient le nom, la description et la position d’un repère dynamique
Exemple
frame = robot.get_saved_dynamic_frame("default_frame")
- NiryoRobot.save_dynamic_frame_from_poses(frame_name, description, pose_origin, pose_x, pose_y, belong_to_workspace=False)[source]
Créer un repère dynamique avec 3 positions (origine, x, y)
Exemple
pose_o = [0.1, 0.1, 0.1, 0, 0, 0] pose_x = [0.2, 0.1, 0.1, 0, 0, 0] pose_y = [0.1, 0.2, 0.1, 0, 0, 0] robot.save_dynamic_frame_from_poses("name", "une description test", pose_o, pose_x, pose_y)
- Paramètres
frame_name (str) – nom du repère
description (str) – description du repère
pose_origin (list[float] [x, y, z, roll, pitch, yaw]) – position d’origine du repère
pose_x (list[float] [x, y, z, roll, pitch, yaw]) – position du point x du repère
pose_y (list[float] [x, y, z, roll, pitch, yaw]) – position du point y du repère
belong_to_workspace (boolean) – indique si le repère appartient à un espace de travail
- Renvoie
status, message
- Type renvoyé
- NiryoRobot.save_dynamic_frame_from_points(frame_name, description, point_origin, point_x, point_y, belong_to_workspace=False)[source]
Créer un repère dynamique avec 3 points (origine, x, y)
Exemple
point_o = [-0.1, -0.1, 0.1] point_x = [-0.2, -0.1, 0.1] point_y = [-0.1, -0.2, 0.1] robot.save_dynamic_frame_from_points("name", "une description test", point_o, point_x, point_y)
- NiryoRobot.edit_dynamic_frame(frame_name, new_frame_name, new_description)[source]
Modifie un repère dynamique
Exemple
robot.edit_dynamic_frame("name", "new_name", "new description")
- NiryoRobot.delete_dynamic_frame(frame_name, belong_to_workspace=False)[source]
Supprime un repère dynamique
Exemple
robot.delete_saved_dynamic_frame("name")
- NiryoRobot.move_relative(offset, frame='world')[source]
Déplace l’effecteur du robot d’un offset dans un repère
Exemple
robot.move_relative([0.05, 0.05, 0.05, 0.3, 0, 0], frame="default_frame")
Outils
- NiryoRobot.grasp_with_tool()[source]
Saisir avec l’outil | Cette action correspond à | - Close gripper pour les grippers | - Pull Air pour la pompe à vide | - Activate pour l’électroaimant
- Type renvoyé
- NiryoRobot.release_with_tool()[source]
Relâcher avec l’outil | Cette action correspond à | - Open gripper pour les grippers | - Push Air pour la pompe à vide | - Deactivate pour l’électroaimant
- Type renvoyé
- NiryoRobot.open_gripper(speed=500, max_torque_percentage=100, hold_torque_percentage=30)[source]
Ouvrir la pince
- NiryoRobot.close_gripper(speed=500, max_torque_percentage=100, hold_torque_percentage=20)[source]
Fermer la pince
- NiryoRobot.activate_electromagnet(pin_id)[source]
Activer l’électroaimant associé à electromagnet_id sur pin_id
- NiryoRobot.deactivate_electromagnet(pin_id)[source]
Désactiver l’électroaimant associé à electromagnet_id sur pin_id
- NiryoRobot.enable_tcp(enable=True)[source]
Active ou désactive la fonction PCO (Point Central de l’Outil). Si une activation est demandée, la dernière valeur pour le PCO va être appliquée. Par défaut la valeur dépend de la pince équipée. Si la désactivation est demandée, le PCO va coincider avec le repère “tool_link”.
- Paramètres
enable (Bool) – True pour activer, False pour désactiver.
- Type renvoyé
- NiryoRobot.set_tcp(*args)[source]
Active la fonction de PCO (Point Central de l’Outil) et définit la transformation entre le repère “tool_link” et le repère du PCO.
Matériel
- NiryoRobot.set_pin_mode(pin_id, pin_mode)[source]
Régler le numéro de broche pin_id sur le mode pin_mode
- NiryoRobot.digital_read(pin_id)[source]
Lire le numéro de broche pin_id et retourne à son état
- Paramètres
pin_id (PinID or str) –
- Type renvoyé
PinState
- NiryoRobot.get_hardware_status()[source]
Obtenir le statut hardware : température, version hardware, noms et types des moteurs …
- Renvoie
Informations contenues dans un HardwareStatusObject
- Type renvoyé
- NiryoRobot.get_digital_io_state()[source]
Obtenir l’état des IO digitaux : noms, modes, états
Exemple
digital_io_state = robot.digital_io_state digital_io_state = robot.get_digital_io_state()
- Renvoie
Liste des instances DigitalPinObject
- Type renvoyé
- NiryoRobot.get_analog_io_state()[source]
Obtenir l’état des IO analogiques : noms, modes, états
Exemple
analog_io_state = robot.analog_io_state analog_io_state = robot.get_analog_io_state()
- Renvoie
Liste des instances AnalogPinObject
- Type renvoyé
Convoyeur
- NiryoRobot.set_conveyor()[source]
Activer un nouveau convoyeur et renvoyer son ID
- Renvoie
Nouvel ID du convoyeur
- Type renvoyé
ConveyorID
- NiryoRobot.unset_conveyor(conveyor_id)[source]
Retirer un convoyeur spécifique
- Paramètres
conveyor_id (ConveyorID) – Généralement, ConveyorID.ONE ou ConveyorID.TWO
- NiryoRobot.run_conveyor(conveyor_id, speed=50, direction=<ConveyorDirection.FORWARD: 1>)[source]
Activer le convoyeur avec l’id “conveyor_id”
- NiryoRobot.stop_conveyor(conveyor_id)[source]
Arrêter le convoyeur avec l’id “conveyor_id”
- Paramètres
conveyor_id (ConveyorID) –
- Type renvoyé
Vision
- NiryoRobot.get_img_compressed()[source]
Obtenir l’image du flux vidéo dans un format compressé. Utiliser
uncompress_image
du package vision pour les décompresser- Renvoie
Chaîne contenant une image JPEG compressée
- Type renvoyé
- NiryoRobot.get_image_parameters()[source]
Retourne les paramètres de la dernière image publiées: facteurs de luminosité, contraste et saturation.
Comment ajuster le facteur de luminosité: 0.5 donnera une image assombrie, 1 l’image d’origine et 2 augmentera la luminosité par un facteur de 2.
Comment ajuster le facteur de contraste: 1 équivaut à l’image d’origine. Plus le multiplicateur se rapproche de 0 et plus l’image deviendra grise, « tandis qu’un facteur > 1 augmentera le contraste de l’image.
Comment ajuster le facteur de saturation: 0 donnera une image en noir et blanc, 1 équivaut à l’image d’origine, tandis que 2 va augmenter la saturation par un facteur de 2.
- NiryoRobot.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ètres) définit à quelle hauteur l’outil va passer au dessus du workspace. Si height_offset = 0, alors l’outil touchera presque l’espace de travail.
- NiryoRobot.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)
- NiryoRobot.vision_pick(workspace_name, height_offset=0.0, shape=<ObjectShape.ANY: 'ANY'>, color=<ObjectColor.ANY: 'ANY'>)[source]
Attrape l’objet spécifié sur le workspace. Cette fonction est composée de plusieurs phases :
1. détecte l’objet en utilisant la caméra2. prépare l’outil utilisé pour la saisie3. approche l’objet4. descend jusque la bonne position de saisie5. actionne l’outil utilisé6. soulève l’objetExemple
robot = NiryoRobot(ip_address="x.x.x.x") robot.calibrate_auto() robot.move_pose(<observation_pose>) obj_found, shape_ret, color_ret = robot.vision_pick(<workspace_name>, height_offset=0.0, shape=ObjectShape.ANY, color=ObjectColor.ANY)
- NiryoRobot.move_to_object(workspace_name, height_offset, shape, color)[source]
Même fonction que get_target_pose_from_cam mais bouge directement à cette position
- NiryoRobot.detect_object(workspace_name, shape=<ObjectShape.ANY: 'ANY'>, color=<ObjectColor.ANY: 'ANY'>)[source]
Détecter l’objet sur le workspace et renvoyer 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)
- NiryoRobot.get_camera_intrinsics()[source]
Obtenir la calibration de l’objet : paramètres instrinsèques de la caméra, taux de distorsion
- NiryoRobot.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 peuvent également être une liste [x, y, z, roll, pitch, yaw] ou un PoseObject.
- Paramètres
workspace_name (str) – nom du workspace, maximum 30 caractères
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é
- NiryoRobot.save_workspace_from_points(workspace_name, point_origin, point_2, point_3, point_4)[source]
Sauvegarder le workspace en donnant les points des 4 coins du workspaces. Ces points sont écrits [x, y, z]. Les coins doivent être dans le bon ordre.
Anneau Led
- NiryoRobot.set_led_color(led_id, color)[source]
Allume une LED d’une seule couleur. Couleur RVB entre 0 et 255.
Exemple
robot.set_led_color(5, [15, 50, 255])
- NiryoRobot.led_ring_solid(color)[source]
Réglez l’ensemble de l’anneau LED sur une couleur fixe.
Exemple
robot.led_ring_solid([15, 50, 255])
- NiryoRobot.led_ring_flashing(color, period=0, iterations=0, wait=False)[source]
Clignote d’une couleur selon une fréquence. La fréquence est égaleà 1/période.
Exemple
robot.led_ring_flashing([15, 50, 255]) robot.led_ring_flashing([15, 50, 255], 1, 100, True) robot.led_ring_flashing([15, 50, 255], iterations=20, wait=True) frequency = 20 # Hz total_duration = 10 # seconds robot.flashing([15, 50, 255], 1./frequency, total_duration * frequency , True)
- Paramètres
color (list[float]) – Couleur du led dans une liste de taille 3[R, G, B]. Les canaux RVB ont une valeur comprise entre 0 et 255.
period (float) – Temps d’exécution d’un motif en secondes. Si 0, la période par défautsera utilisée.
iterations (int) – Nombre de clignotements consécutifs. Si 0, la Led Ring clignoteindéfiniment.
wait (bool) – Le service attend que l’animation termine toutes les itérationsou ne réponde pas. Si le nombre d’itérations vaut 0, le service répond immédiatement.
- Renvoie
status, message
- Type renvoyé
- NiryoRobot.led_ring_alternate(color_list, period=0, iterations=0, wait=False)[source]
Plusieurs couleurs s’alternéent les unes après les autres.
Exemple
color_list = [ [15, 50, 255], [255, 0, 0], [0, 255, 0], ] robot.led_ring_alternate(color_list) robot.led_ring_alternate(color_list, 1, 100, True) robot.led_ring_alternate(color_list, iterations=20, wait=True)
- Paramètres
color_list (list[list[float]]) – Liste des couleurs des leds de taille 3[R, G, B]. Canaux RVBde 0 à 255.
period (float) – Temps d’exécution d’un motif en secondes. Si 0, la période par défautsera utilisée.
iterations (int) – Nombre d’alternances consécutives. Si 0, le Led Ring alterneindéfiniment.
wait (bool) – Le service attend que l’animation termine toutes les itérationsou ne réponde pas. Si le nombre d’itérations vaut 0, le service répond immédiatement.
- Renvoie
status, message
- Type renvoyé
- NiryoRobot.led_ring_chase(color, period=0, iterations=0, wait=False)[source]
Animation de Chase de style lumière de cinéma.
Exemple
robot.led_ring_chase([15, 50, 255]) robot.led_ring_chase([15, 50, 255], 1, 100, True) robot.led_ring_chase([15, 50, 255], iterations=20, wait=True)
- Paramètres
color (list[float]) – Couleur du led dans une liste de taille 3[R, G, B]. Les canaux RVB ont une valeur comprise entre 0 et 255.
period (float) – Temps d’exécution d’un motif en secondes. Si 0, la période par défautsera utilisée.
iterations (int) – Nombre de poursuites consécutives. Si 0, l’animation continueindéfiniment. Un Chase allume juste une LED sur 3.
wait (bool) – Le service attend que l’animation termine toutes les itérationsou ne réponde pas. Si le nombre d’itérations vaut 0, le service répond immédiatement.
- Renvoie
status, message
- Type renvoyé
- NiryoRobot.led_ring_wipe(color, period=0, wait=False)[source]
Essuyez une couleur sur l’anneau LED, allume une LED à la fois.
Exemple
robot.led_ring_wipe([15, 50, 255]) robot.led_ring_wipe([15, 50, 255], 1, True) robot.led_ring_wipe([15, 50, 255], wait=True)
- Paramètres
color (list[float]) – Couleur du led dans une liste de taille 3[R, G, B]. Les canaux RVB ont une valeur comprise entre 0 et 255.
period (float) – Temps d’exécution d’un motif en secondes. Si 0, la période par défautsera utilisée.
wait (bool) – Le service attend que l’animation se termine ou ne réponde pas.
- Renvoie
status, message
- Type renvoyé
- NiryoRobot.led_ring_rainbow(period=0, iterations=0, wait=False)[source]
Dessinez un arc-en-ciel qui s’estompe sur toutes les LED à lafois.
Exemple
robot.led_ring_rainbow() robot.led_ring_rainbow(5, 2, True) robot.led_ring_rainbow(wait=True)
- Paramètres
period (float) – Temps d’exécution d’un motif en secondes. Si 0, la période par défautsera utilisée.
iterations (int) – Nombre d’arcs-en-ciel consécutifs. Si 0, l’animation continueindéfiniment.
wait (bool) – Le service attend que l’animation se termine ou ne réponde pas.Si itérations vaut 0, le service répond immédiatement.
- Renvoie
status, message
- Type renvoyé
- NiryoRobot.led_ring_rainbow_cycle(period=0, iterations=0, wait=False)[source]
Dessinez un arc-en-ciel qui se répartit uniformément sur toutesles LED.
Exemple
robot.led_ring_rainbow_cycle() robot.led_ring_rainbow_cycle(5, 2, True) robot.led_ring_rainbow_cycle(wait=True)
- Paramètres
period (float) – Temps d’exécution d’un motif en secondes. Si 0, la période par défautsera utilisée.
iterations (int) – Nombre de cycles arc-en-ciel consécutifs. Si 0, l’animation continueindéfiniment.
wait (bool) – Le service attend que l’animation se termine ou ne réponde pas.Si itérations vaut 0, le service répond immédiatement.
- Renvoie
status, message
- Type renvoyé
- NiryoRobot.led_ring_rainbow_chase(period=0, iterations=0, wait=False)[source]
Animation de Chase arc-en-ciel, comme la méthode led_ring_chase.
Exemple
robot.led_ring_rainbow_chase() robot.led_ring_rainbow_chase(5, 2, True) robot.led_ring_rainbow_chase(wait=True)
- Paramètres
period (float) – Temps d’exécution d’un motif en secondes. Si 0, la période par défautsera utilisée.
iterations (int) – Nombre de cycles arc-en-ciel consécutifs. Si 0, l’animation continueindéfiniment.
wait (bool) – Le service attend que l’animation se termine ou ne réponde pas.Si itérations vaut 0, le service répond immédiatement.
- Renvoie
status, message
- Type renvoyé
- NiryoRobot.led_ring_go_up(color, period=0, iterations=0, wait=False)[source]
Les LED s’allument comme un cercle de chargement, puis s’éteignenttoutes en même temps.
Exemple
robot.led_ring_go_up([15, 50, 255]) robot.led_ring_go_up([15, 50, 255], 1, 100, True) robot.led_ring_go_up([15, 50, 255], iterations=20, wait=True)
- Paramètres
color (list[float]) – Couleur du led dans une liste de taille 3[R, G, B]. Les canaux RVB ont une valeur comprise entre 0 et 255.
period (float) – Temps d’exécution d’un motif en secondes. Si 0, la période par défautsera utilisée.
iterations (int) – Nombre de tours consécutifs autour du Led Ring. Si 0, l’animationcontinue indéfiniment.
wait (bool) – Le service attend que l’animation se termine ou ne réponde pas.Si itérations vaut 0, le service répond immédiatement.
- Renvoie
status, message
- Type renvoyé
- NiryoRobot.led_ring_go_up_down(color, period=0, iterations=0, wait=False)[source]
Les LED s’allument comme un cercle de chargement et s’éteignentde la même manière.
Exemple
robot.led_ring_go_up_down([15, 50, 255]) robot.led_ring_go_up_down([15, 50, 255], 1, 100, True) robot.led_ring_go_up_down([15, 50, 255], iterations=20, wait=True)
- Paramètres
color (list[float]) – Couleur du led dans une liste de taille 3[R, G, B]. Les canaux RVB ont une valeur comprise entre 0 et 255.
period (float) – Temps d’exécution d’un motif en secondes. Si 0, la période par défautsera utilisée.
iterations (int) – Nombre de tours consécutifs autour du Led Ring. Si 0, l’animationcontinue indéfiniment.
wait (bool) – Le service attend que l’animation se termine ou ne réponde pas.Si itérations vaut 0, le service répond immédiatement.
- Renvoie
status, message
- Type renvoyé
- NiryoRobot.led_ring_breath(color, period=0, iterations=0, wait=False)[source]
Variation de l’intensité lumineuse de l’anneau LED, similaireà la respiration humaine.
Exemple
robot.led_ring_breath([15, 50, 255]) robot.led_ring_breath([15, 50, 255], 1, 100, True) robot.led_ring_breath([15, 50, 255], iterations=20, wait=True)
- Paramètres
color (list[float]) – Couleur du led dans une liste de taille 3[R, G, B]. Les canaux RVB ont une valeur comprise entre 0 et 255.
period (float) – Temps d’exécution d’un motif en secondes. Si 0, la période par défautsera utilisée.
iterations (int) – Nombre de tours consécutifs autour du Led Ring. Si 0, l’animationcontinue indéfiniment.
wait (bool) – Le service attend que l’animation se termine ou ne réponde pas.Si itérations vaut 0, le service répond immédiatement.
- Renvoie
status, message
- Type renvoyé
- NiryoRobot.led_ring_snake(color, period=0, iterations=0, wait=False)[source]
Un petit serpent coloré (certainement un python :D ) court autourde l’anneau LED.
Exemple
robot.led_ring_snake([15, 50, 255]) robot.led_ring_snake([15, 50, 255], 1, 100, True)
- Paramètres
color (list[float]) – Couleur du led dans une liste de taille 3[R, G, B]. Les canaux RVB ont une valeur comprise entre 0 et 255.
period (float) – Temps d’exécution d’un motif en secondes. Si 0, la durée pardéfaut sera utilisée.
iterations (int) – Nombre de tours consécutifs autour du Led Ring. Si 0, l’animationcontinue indéfiniment.
wait (bool) – Le service attend que l’animation se termine ou ne réponde pas.Si itérations vaut 0, le service répond immédiatement.
- Renvoie
status, message
- Type renvoyé
Son
- NiryoRobot.get_sounds()[source]
Obtenir la liste des noms de son
- Renvoie
liste des sons du robot
- Type renvoyé
list[string]
- NiryoRobot.play_sound(sound_name, wait_end=True, start_time_sec=0, end_time_sec=0)[source]
Jouer un son du robot
- NiryoRobot.get_sound_duration(sound_name)[source]
Renvoie la durée en secondes d’un son stocké dans la base dedonnées du robot. Lève SoundRosWrapperException si le son n’existepas
- Paramètres
sound_name (string) – nom du son
- Renvoie
durée du son en secondes
- Type renvoyé
- NiryoRobot.say(text, language=0)[source]
Utilisez gtts (Google Text To Speech) pour interpréter une chaîne de caractèrescomme un son. Les langues disponibles sont : * Anglais : 0 * Français: 1 * Espagnol : 2 * Mandarin : 3 * Portugais : 4
Exemple
robot.say("Hello", 0) robot.say("Bonjour", 1) robot.say("Hola", 2)
Enums (énumérations)
Les énumérations sont utilisées pour passer des paramètres spécifiques aux fonctions.
Par exemple, shift_pose()
aura besoin d’un paramètre de type l’enum RobotAxis
robot.shift_pose(RobotAxis.Y, 0.15)
Liste des énumérations
CalibrateMode
RobotAxis
ToolID
PinMode
PinState
PinID
ConveyorID
ConveyorDirection
ObjectColor
ObjectShape
- class CalibrateMode(value)[source]
Énumération des modes de calibration
- AUTO = 0
- MANUAL = 1
- class RobotAxis(value)[source]
Énumération des axes du robot : utilisé pour la commande shift
- X = 0
- Y = 1
- Z = 2
- ROLL = 3
- PITCH = 4
- YAW = 5
- class ToolID(value)[source]
Énumération des ID des outils
- NONE = 0
- GRIPPER_1 = 11
- GRIPPER_2 = 12
- GRIPPER_3 = 13
- ELECTROMAGNET_1 = 30
- VACUUM_PUMP_1 = 31
- class PinMode(value)[source]
Énumération des modes des broches
- OUTPUT = 0
- INPUT = 1
- class PinState(value)[source]
L’état des broches est soit LOW ou HIGH
- LOW = False
- HIGH = True
- class PinID(value)[source]
Énumération des broches du robot
- GPIO_1A = '1A'
- GPIO_1B = '1B'
- GPIO_1C = '1C'
- GPIO_2A = '2A'
- GPIO_2B = '2B'
- GPIO_2C = '2C'
- SW_1 = 'SW1'
- SW_2 = 'SW2'
- DO1 = 'DO1'
- DO2 = 'DO2'
- DO3 = 'DO3'
- DO4 = 'DO4'
- DI1 = 'DI1'
- DI2 = 'DI2'
- DI3 = 'DI3'
- DI4 = 'DI4'
- DI5 = 'DI5'
- AI1 = 'AI1'
- AI2 = 'AI2'
- AO1 = 'AO1'
- AO2 = 'AO2'
- class ConveyorID(value)[source]
Énumération des ID du convoyeur utilisés pour le contrôle du convoyeur
- NONE = 0
- ID_1 = -1
- ID_2 = -2
- class ConveyorDirection(value)[source]
Énumération des directions du convoyeur utilisés pour le contrôle du convoyeur
- FORWARD = 1
- BACKWARD = -1
- class ObjectColor(value)[source]
Énumération des couleurs disponibles pour le traitement d’images
- RED = 'RED'
- BLUE = 'BLUE'
- GREEN = 'GREEN'
- ANY = 'ANY'
- class ObjectShape(value)[source]
Énumération des formes disponibles pour le traitement d’images
- SQUARE = 'SQUARE'
- CIRCLE = 'CIRCLE'
- ANY = 'ANY'
Classes d’objets Python
Objets spéciaux
- class PoseObject(x, y, z, roll, pitch, yaw)[source]
Pose object qui stocke les paramètres x, y, z, roll, pitch & yaw
- class HardwareStatusObject(rpi_temperature, hardware_version, connection_up, error_message, calibration_needed, calibration_in_progress, motor_names, motor_types, motors_temperature, motors_voltage, hardware_errors)[source]
Objet utilisé pour stocker toutes les informations matérielles