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

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

NiryoRobot.connect(ip_address)[source]

Se connecter au serveur TCP

Paramètres

ip_address (str) – Adresse IP

Type renvoyé

None

NiryoRobot.close_connection()[source]

Couper la connexion avec le robot

Type renvoyé

None

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é

None

NiryoRobot.calibrate_auto()[source]

Démarre une calibration automatique des moteurs si les moteurs n’ont pas encore été calibrés

Type renvoyé

None

NiryoRobot.need_calibration()[source]

Renvoie un booléen indiquant si les moteurs du robot ont besoin d’être calibrés

Type renvoyé

bool

NiryoRobot.get_learning_mode()[source]

Afficher l’état du mode apprentissage

Renvoie

Vrai si le mode apprentissage est activé

Type renvoyé

bool

NiryoRobot.set_learning_mode(enabled)[source]

Allumer le mode apprentissage si param est Vrai, sinon l’arrêter

Paramètres

enabled (bool) – Vrai ou Faux

Type renvoyé

None

NiryoRobot.set_arm_max_velocity(percentage_speed)[source]

Limiter la vitesse maximum du bras à un pourcentage de sa vitesse maximum

Paramètres

percentage_speed (int) – Peut être entre 1 & 100

Type renvoyé

None

NiryoRobot.set_jog_control(enabled)[source]

Allumer le mode de contrôle par translation si param est Vrai, sinon l’arrêter

Paramètres

enabled (bool) – Vrai ou Faux

Type renvoyé

None

static NiryoRobot.wait(duration)[source]

Attendre pendant un certain temps

Paramètres

duration (float) – durée en secondes

Type renvoyé

None

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
Renvoie

Liste de la valeur des joints

Type renvoyé

list[float]

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é

PoseObject

NiryoRobot.get_pose_quat()[source]

Obtenir la position de l’effecteur en coordonnées Quaternion

Renvoie

Position and quaternion coordinates concatenated in a list : [x, y, z, qx, qy, qz, qw]

Type renvoyé

list[float]

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)
Paramètres

args (Union[list[float], tuple[float]]) – soit 6 args (1 pour chaque axe) ou une liste de 6 axes

Type renvoyé

None

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")
Paramètres

args (Union[tuple[float], list[float], PoseObject, [tuple[float], str], [list[float], str], [PoseObject, str]]) – soit 6 args (1 pour chaque coordonnées et 1 pour le nom du repère) ou une liste de 6 coordonnées, ou un PoseObject et 1 pour le nom du repère

Type renvoyé

None

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

Paramètres

args (Union[tuple[float], list[float], PoseObject, [tuple[float], str], [list[float], str], [PoseObject, str]]) – soit 6 args (1 pour chaque coordonnées et 1 pour le nom du repère) ou une liste de 6 coordonnées, ou un PoseObject et 1 pour le nom du repère

Type renvoyé

None

NiryoRobot.shift_pose(axis, shift_value)[source]

Glisser la position de l’effecteur du robot le long d’un axe

Paramètres
  • axis (RobotAxis) – Axe le long duquel l’effecteur du robot est déplacé

  • shift_value (float) – En mètres pour X/Y/Z et en radians pour roll/pitch/yaw

Type renvoyé

None

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

Paramètres
  • axis (RobotAxis) – Axe le long duquel l’effecteur du robot est déplacé

  • shift_value (float) – En mètres pour X/Y/Z et en radians pour roll/pitch/yaw

Type renvoyé

None

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.

Paramètres

args (Union[list[float], tuple[float]]) – soit 6 args (1 pour chaque axe) ou une liste des offsets des 6 axes

Type renvoyé

None

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

Paramètres

args (Union[list[float], tuple[float]]) – soit 6 args (1 pour chaque axe) ou une liste de 6 offset

Type renvoyé

None

NiryoRobot.move_to_home_pose()[source]

Bouger le robot à une position dans laquelle l’avant bras du robot repose sur son épaule

Type renvoyé

None

NiryoRobot.go_to_sleep()[source]

Retourner à la position de départ et activer le mode apprentissage

Type renvoyé

None

NiryoRobot.forward_kinematics(*args)[source]

Calculer la cinématique directe d’une configuration des axes donnée et donner la position dans l’espace qui y est associée

Paramètres

args (Union[list[float], tuple[float]]) – soit 6 args (1 pour chaque axe) ou une liste de 6 axes

Type renvoyé

PoseObject

NiryoRobot.inverse_kinematics(*args)[source]

Calculer la cinématique inverse

Paramètres

args (Union[tuple[float], list[float], PoseObject]) – soit 6 args (1 pour chaque coordonnées) ou une liste de 6 coordonnées, ou un PoseObject

Renvoie

Liste de la valeur des joints

Type renvoyé

list[float]

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é

PoseObject

NiryoRobot.save_pose(pose_name, *args)[source]

Sauvegarder une position dans la mémoire du robot

Paramètres

args (Union[list[float], tuple[float], PoseObject]) – soit 6 args (1 pour chaque coordonnées) ou une liste de 6 coordonnées, ou un PoseObject

Type renvoyé

None

NiryoRobot.delete_pose(pose_name)[source]

Supprimer une position dans la mémoire du robot

Type renvoyé

None

NiryoRobot.get_saved_pose_list()[source]

Afficher la liste de noms des positions sauvegardées dans la mémoire du robot

Type renvoyé

list[str]

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
Paramètres

args (Union[list[float], tuple[float], PoseObject]) – soit 6 args (1 pour chaque coordonnées) ou une liste de 6 coordonnées, ou un PoseObject

Type renvoyé

None

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
Paramètres

args (Union[list[float], tuple[float], PoseObject]) – soit 6 args (1 pour chaque coordonnées) ou une liste de 6 coordonnées, ou un PoseObject

Type renvoyé

None

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é

None

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

Type renvoyé

list[str]

NiryoRobot.execute_registered_trajectory(trajectory_name)[source]

Exécuter la trajectoire depuis la mémoire de Ned

Type renvoyé

None

NiryoRobot.execute_trajectory_from_poses(list_poses, dist_smoothing=0.0)[source]

Exécuter une trajectoire depuis une liste de positions

Paramètres
  • list_poses (list[list[float]]) – Liste de position [x,y,z,qx,qy,qz,qw] ou liste de posiiton [x,y,z,roll,pitch,yaw]

  • dist_smoothing (float) – Distance entre les points de passage avant le lissage de la trajectoire

Type renvoyé

None

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é

None

NiryoRobot.save_trajectory(trajectory, trajectory_name, trajectory_description)[source]

Sauvegarder la trajectoire dans la mémoire du robot

Paramètres
  • trajectory (list[list[float]]) – la liste des axes [j1, j2, j3, j4, j5, j6] comme point de passage pour créer la trajectoire

  • trajectory_name (str) – Nom de la trajectoire

  • trajectory_description – Description de la trajectoire

Type renvoyé

None

NiryoRobot.save_last_learned_trajectory(name, description)[source]

Sauvegarde la dernière trajectoire exécutée par l’utilisateur

Type renvoyé

None

NiryoRobot.delete_trajectory(trajectory_name)[source]

Supprimer la trajectoire de la mémoire du robot.

Type renvoyé

None

NiryoRobot.clean_trajectory_memory()[source]

Supprimer la trajectoire de la mémoire du robot.

Type renvoyé

None

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)
Renvoie

la liste des nom des repères, la liste des descriptions des repères

Type renvoyé

list[str], list[str]

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")
Paramètres

frame_name (str) – nom du repère

Renvoie

le nom, la description et la position d’un repère

Type renvoyé

list[str, str, list[float]]

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é

(int, str)

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)
Paramètres
  • frame_name (str) – nom du repère

  • description (str) – description du repère

  • point_origin (list[float] [x, y, z]) – point d’origine du repère

  • point_x (list[float] [x, y, z]) – point x du repère

  • point_y (list[float] [x, y, z]) – point y du repère

  • belong_to_workspace (boolean) – indique si le repère appartient à un espace de travail

Renvoie

status, message

Type renvoyé

(int, str)

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")
Paramètres
  • frame_name (str) – nom du repère

  • new_frame_name (str) – nouveau nom du repère

  • new_description (str) – nouvelle description du repère

Renvoie

status, message

Type renvoyé

(int, str)

NiryoRobot.delete_dynamic_frame(frame_name, belong_to_workspace=False)[source]

Supprime un repère dynamique

Exemple

robot.delete_saved_dynamic_frame("name")
Paramètres
  • frame_name (str) – nom du repère à supprimer

  • belong_to_workspace (boolean) – indique si le repère appartient à un espace de travail

Renvoie

status, message

Type renvoyé

(int, str)

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")
Paramètres
  • offset (list[float]) – list qui contient les paramètres x, y, z, roll, pitch & yaw

  • frame (str) – nom du repère

Renvoie

status, message

Type renvoyé

(int, str)

NiryoRobot.move_linear_relative(offset, frame='world')[source]

Déplace l’effecteur du robot d’un offset dans un repère par un mouvement linéaire

Exemple

robot.move_linear_relative([0.05, 0.05, 0.05, 0.3, 0, 0], frame="default_frame")
Paramètres
  • offset (list[float]) – list qui contient les paramètres x, y, z, roll, pitch & yaw

  • frame (str) – nom du repère

Renvoie

status, message

Type renvoyé

(int, str)

Outils

NiryoRobot.get_current_tool_id()[source]

Obtenir l’ID de l’outil installé

Type renvoyé

ToolID

NiryoRobot.update_tool()[source]

Mettre à jour l’outil installé

Type renvoyé

None

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é

None

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é

None

NiryoRobot.open_gripper(speed=500, max_torque_percentage=100, hold_torque_percentage=30)[source]

Ouvrir la pince

Paramètres
  • speed (int) – Entre 100 & 1000 (uniquement pour Niryo One et Ned1)

  • max_torque_percentage (int) – Pourcentage de couple de fermeture (uniquement pour Ned2)

  • hold_torque_percentage (int) – Pourcentage de couple de maintien après fermeture (uniquementpour Ned2)

Type renvoyé

None

NiryoRobot.close_gripper(speed=500, max_torque_percentage=100, hold_torque_percentage=20)[source]

Fermer la pince

Paramètres
  • speed (int) – Entre 100 & 1000 (uniquement pour Niryo One et Ned1)

  • max_torque_percentage (int) – Pourcentage de couple d’ouverture (uniquement pour Ned2)

  • hold_torque_percentage (int) – Pourcentage de couple de maintien ouverture (uniquementpour Ned2)

Type renvoyé

None

NiryoRobot.pull_air_vacuum_pump()[source]

Aspirer l’air de la pompe à vide

Type renvoyé

None

NiryoRobot.push_air_vacuum_pump()[source]

Souffler l’air de la pompe à vide

Type renvoyé

None

NiryoRobot.setup_electromagnet(pin_id)[source]

Installer l’électroaimant sur une broche

Paramètres

pin_id (PinID or str) –

Type renvoyé

None

NiryoRobot.activate_electromagnet(pin_id)[source]

Activer l’électroaimant associé à electromagnet_id sur pin_id

Paramètres

pin_id (PinID or str) –

Type renvoyé

None

NiryoRobot.deactivate_electromagnet(pin_id)[source]

Désactiver l’électroaimant associé à electromagnet_id sur pin_id

Paramètres

pin_id (PinID or str) –

Type renvoyé

None

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é

None

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.

Paramètres

args (Union[list[float], tuple[float], PoseObject]) – soit 6 args (1 pour chaque coordonnées) ou une liste de 6 coordonnées, ou un PoseObject

Type renvoyé

None

NiryoRobot.reset_tcp()[source]

Réinitialise la transformation appliquée au PCO (Point Central de l’Outil). La valeur par défaut dépend de l’outil actuellement équipé.

Type renvoyé

None

NiryoRobot.tool_reboot()[source]

Redémarre le moteur de l’outil equipé

Exemple

for pose in (pose_origin, pose_2, pose_3, pose_4):
    pose_list = self.__args_pose_to_list(pose)
    param_list.append(pose_list)ipped. Useful when an Overload error occurs. (cf HardwareStatus)
Type renvoyé

None

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

Paramètres
  • pin_id (PinID or str) –

  • pin_mode (PinMode) –

Type renvoyé

None

NiryoRobot.digital_write(pin_id, digital_state)[source]

Régler l’état de pin_id sur digital_state

Paramètres
  • pin_id (PinID or str) –

  • digital_state (PinState) –

Type renvoyé

None

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é

HardwareStatusObject

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é

list[DigitalPinObject]

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é

list[AnalogPinObject]

NiryoRobot.analog_write(pin_id, value)[source]

Régler la valeur de la sortie analogique pin_id

Paramètres
  • pin_id (PinID or str) –

  • value (float) – tension entre 0V et 5V

Type renvoyé

None

NiryoRobot.analog_read(pin_id)[source]

Lire la valeur d’un pin analogique

Paramètres

pin_id (PinID or str) –

Type renvoyé

float

NiryoRobot.get_custom_button_state()[source]

Optenir l’état du bouton Custom du Ned2

Renvoie

True si pressé, False sinon

Type renvoyé

bool

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”

Paramètres
  • conveyor_id (ConveyorID) –

  • speed (int) –

  • direction (ConveyorDirection) –

Type renvoyé

None

NiryoRobot.stop_conveyor(conveyor_id)[source]

Arrêter le convoyeur avec l’id “conveyor_id”

Paramètres

conveyor_id (ConveyorID) –

Type renvoyé

None

NiryoRobot.control_conveyor(conveyor_id, control_on, speed, direction)[source]

Contrôler le convoyeur avec l’id “conveyor_id”

Paramètres
  • conveyor_id (ConveyorID) –

  • control_on (bool) –

  • speed (int) – Nouvelle vitesse qui est un pourcentage de la vitesse maximum

  • direction (ConveyorDirection) – Direction du convoyeur

Type renvoyé

None

NiryoRobot.get_connected_conveyors_id()[source]
Renvoie

Liste des ID des convoyeurs connectés

Type renvoyé

list[ConveyorID]

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é

str

NiryoRobot.set_brightness(brightness_factor)[source]

Modifie la luminosité du stream vidéo

Paramètres

brightness_factor (float) – Comment ajuster la luminosité: 0.5 donnera une image assombrie, 1 l’image d’origine et 2 augmentera la luminosité par un facteur de 2.

Type renvoyé

None

NiryoRobot.set_contrast(contrast_factor)[source]

Modifie le contraste du stream vidéo

Paramètres

contrast_factor (float) – Un facteur de 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.

Type renvoyé

None

NiryoRobot.set_saturation(saturation_factor)[source]

Modifie la saturation du stream vidéo

Paramètres

saturation_factor (float) – Comment ajuster la 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.

Type renvoyé

None

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.

Renvoie

Facteur de luminosité, contraste et saturation

Type renvoyé

float, float, float

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.

Paramètres
  • workspace_name (str) – Nom du workspace

  • height_offset (float) – Offset entre le workspace sa hauteur cible

  • x_rel (float) – pose relative de x (entre 0 et 1)

  • y_rel (float) – pose relative de y (entre 0 et 1)

  • yaw_rel (float) – Angle en radians

Renvoie

target_pose

Type renvoyé

PoseObject

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
  • workspace_name (str) – Nom du workspace

  • height_offset (float) – Offset entre le workspace sa hauteur cible

  • 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, 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éra
2. prépare l’outil utilisé pour la saisie
3. approche l’objet
4. descend jusque la bonne position de saisie
5. actionne l’outil utilisé
6. soulève l’objet

Exemple

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)
Paramètres
  • workspace_name (str) – Nom du workspace

  • height_offset (float) – Offset entre le workspace sa hauteur cible

  • shape (ObjectShape) – Forme de la cible

  • color (ObjectColor) – Couleur de la cible

Renvoie

object_found, object_shape, object_color

Type renvoyé

(bool, ObjectShape, ObjectColor)

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

Paramètres
  • workspace_name (str) – Nom du workspace

  • height_offset (float) – Offset entre le workspace sa hauteur cible

  • shape (ObjectShape) – Forme de la cible

  • color (ObjectColor) – Couleur de la cible

Renvoie

object_found, object_shape, object_color

Type renvoyé

(bool, ObjectShape, ObjectColor)

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

Renvoie

paramètres instrinsèque de la caméra, taux de distorsion

Type renvoyé

(list[list[float]], list[list[float]])

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
Type renvoyé

None

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.

Paramètres
Type renvoyé

None

NiryoRobot.delete_workspace(workspace_name)[source]

Supprimer le workspace de la mémoire du robot

Paramètres

workspace_name (str) –

Type renvoyé

None

NiryoRobot.get_workspace_ratio(workspace_name)[source]

Obtenir le ratio du workspace depuis la mémoire du robot

Paramètres

workspace_name (str) –

Type renvoyé

float

NiryoRobot.get_workspace_list()[source]

Obtenir la liste des noms des workspaces stockés dans la mémoire du robot

Type renvoyé

list[str]

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])
Paramètres
  • led_id (int) – ID de la LED: entre 0 et 29

  • 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.

Renvoie

status, message

Type renvoyé

(int, str)

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])
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.

Renvoie

status, message

Type renvoyé

(int, str)

NiryoRobot.led_ring_turn_off()[source]

Éteignez toutes les LED

Exemple

robot.led_ring_turn_off()
Renvoie

status, message

Type renvoyé

(int, str)

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é

(int, str)

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é

(int, str)

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é

(int, str)

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é

(int, str)

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é

(int, str)

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é

(int, str)

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é

(int, str)

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é

(int, str)

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é

(int, str)

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é

(int, str)

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é

(int, str)

NiryoRobot.led_ring_custom(led_colors)[source]

Envoie une commande de couleur à toutes les LED de l’anneau LED.La fonction attend une liste de couleurs pour les 30 LED du robot.

Exemple

led_list = [[i / 30. * 255 , 0, 255 - i / 30.] for i in range(30)]
robot.led_ring_custom(led_list)
Paramètres

led_colors (list[list[float]]) – Liste de taille 30 de couleur led dans une liste de taille 3[R,G, B]. La valeur des canaux RVB est comprise entre de 0 et 255.

Renvoie

status, message

Type renvoyé

(int, str)

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

Paramètres
  • sound_name (string) – Nom du son à jouer

  • wait_end (bool) – attendre la fin du son avant de quitter la fonction

  • start_time_sec (float) – démarrer le son à partir de cette valeur en secondes

  • end_time_sec (float) – terminer le son à cette valeur en secondes

Type renvoyé

None

NiryoRobot.set_volume(sound_volume)[source]

Réglez le pourcentage de volume du robot.

Paramètres

sound_volume (int) – pourcentage de volume du son (0 : pas de son, 100 : son maximum)

Type renvoyé

None

NiryoRobot.stop_sound()[source]

Arrête un son en cours de lecture.

Type renvoyé

None

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é

float

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)
Paramètres
  • text (string) – Texte qui doit être prononcé < 100 caractères

  • language (int) – Langage du texte

Type renvoyé

None

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

copy_with_offsets(x_offset=0.0, y_offset=0.0, z_offset=0.0, roll_offset=0.0, pitch_offset=0.0, yaw_offset=0.0)[source]

Créer une nouvelle position en copiant a position actuelle avec des offsets

Type renvoyé

PoseObject

to_list()[source]

Retourne une liste [x, y, z, roll, pitch, yaw] correspondant aux paramètres de la position.

Type renvoyé

list[float]

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

class DigitalPinObject(pin_id, name, mode, state)[source]

Objet utilisé pour stocker toutes les informations relatives aux digital pins

class AnalogPinObject(pin_id, name, mode, value)[source]

Objet utilisé pour stocker toutes les informations relatives aux digital pins