Bras

Ce fichier présente les différentes Bras - Fonctions de contrôle, Bras - Enumerations, Bras - Topics Niryo & Bras - Objets disponible avec l’API du Bras

Bras - Fonctions de contrôle

Cette section fait reference à toutes les fonctions de contrôle du bras existantes, ce qui inclut

  • Obtenir l’état du robot

  • Bouger le bras

  • Obtenir la cinématique inverse et directe

  • Calibrer le robot

Toutes les fonctions de contôle du bras sont accessibles grâce à une instance de la classe NiryoRobot

robot = NiryoRobot(<robot_ip_address>)

robot.arm.calibrate_auto()
robot.arm.move_joints([0.0, 0.0, 0.0, 0.0, 0.0, 0.0])
...

Voir des exemples dans la Section Exemples

Liste des sous-sections des fonctions :

class Arm(client)[source]

Fonction du robot

Exemples:

ros_instance = NiryoRos("10.10.10.10") # Hotspot
arm_interface = Arm(ros_instance)
Paramètres

client (NiryoRos) – Client Niryo ROS

Fonctions de calibration

Arm.calibrate(calibrate_mode, callback=None, errback=None, timeout=None)[source]

Calibre (manuellement ou automatiquement) les moteurs. La calibration automatique n’aura pas d’effet si les moteurs sont déjà calibrés

Exemples:

# Synchronous use
arm.calibrate(CalibrateMode.MANUAL)
arm.calibrate(CalibrateMode.AUTO)

# Asynchronous use
def calibration_callback(result):
    if result["status"] < RobotErrors.SUCCESS.value:
        print("Calibration failed")
    else:
        print("Calibration completed with success")

arm.calibrate(CalibrateMode.AUTO, calibration_callback)
Paramètres
  • calibrate_mode (CalibrateMode) – Automatique ou Manuel

  • callback (function) – Fonction de rappel lancée en cas de réussite lors de l’exécution

  • errback (function) – Fonction de rappel lancée en cas d’erreur lors de l’exécution

  • timeout (float) – Délai d’exécution de l’opération, en secondes. Utilisé seulement en cas de blocage

Type renvoyé

None

Arm.calibrate_auto(callback=None, errback=None, timeout=None)[source]

Démarre une calibration automatique des moteurs s’ils ne sont pas déjà calibrés.

Exemples:

# Synchronous use
arm.calibrate_auto()

# Asynchronous use
def calibration_callback(result):
    if result["status"] < RobotErrors.SUCCESS.value:
        print("Calibration failed")
    else:
        print("Calibration completed with success")

arm.calibrate_auto(calibration_callback)
Paramètres
  • callback (function) – Fonction de rappel lancée en cas de réussite lors de l’exécution

  • errback (function) – Fonction de rappel lancée en cas d’erreur lors de l’exécution

  • timeout (float) – Délai d’exécution de l’opération, en secondes. Utilisé seulement en cas de blocage

Type renvoyé

None

Arm.request_new_calibration(callback=None, errback=None, timeout=None)[source]

Démarre une calibration automatique des moteurs même s’ils sont déjà calibrés.

Exemples:

# Synchronous use
arm.request_new_calibration()

# Asynchronous use
def calibration_callback(result):
    if result["status"] < RobotErrors.SUCCESS.value:
        print("Calibration failed")
    else:
        print("Calibration completed with success")

arm.request_new_calibration(calibration_callback)
Paramètres
  • callback (function) – Fonction de rappel lancée en cas de réussite lors de l’exécution

  • errback (function) – Fonction de rappel lancée en cas d’erreur lors de l’exécution

  • timeout (float) – Délai d’exécution de l’opération, en secondes. Utilisé seulement en cas de blocage

Type renvoyé

None

Arm.reset_calibration(timeout=2)[source]

Réinitialise le status de la calibration courante. Une nouvelle calibration est alors nécessaire.

Paramètres

timeout (float) – Délai d’exécution de l’opération, en secondes.

Type renvoyé

None

Arm.need_calibration()[source]

Retourne un booléen indiquant si les moteurs doivent être calibrés

Renvoie

Vrai si la calibration est nécessaire, Faux le cas contraire

Type renvoyé

bool

Fonction de mouvement du robot

Arm.set_arm_max_velocity(percentage_speed)[source]

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

Paramètres

percentage_speed (int) – Doit être entre 1 et 100

Type renvoyé

None

Arm.go_to_sleep()[source]

Bouge le bras jusqu’a la position home et active le mode d’apprentissage

Type renvoyé

None

Arm.stop_move(callback=None, errback=None, timeout=None)[source]

Arrête l’exécution du mouvement actuel de move_pose, move_joint ou de move_linear_pose. Le robot va s’arrêter à sa position actuelle. Si une fonction de retour n’est pas passée en paramètre, la fonction sera bloquante. Sinon la fonction de retour sera appelée quand l’exécution de la fonction sera terminée.

Exemples:

# Synchronous use
arm.stop_move()

# Asynchronous use
def stop_callback(result):
    if result["status"] < RobotErrors.SUCCESS.value:
        print("Succeeded")
    else:
        print("Failed")

arm.stop_move(stop_callback)
Paramètres
  • callback (function) – Fonction de rappel lancée en cas de réussite lors de l’exécution

  • errback (function) – Fonction de rappel lancée en cas d’erreur lors de l’exécution

  • timeout (float) – Délai d’exécution de l’opération, en secondes. Utilisé seulement en cas de blocage

Type renvoyé

None

Arm.move_to_home_pose(callback=None)[source]

Bouge le robot à une position dans laquelle l’avant bras du robot repose sur son épaule. Si une fonction de retour n’est pas passée en paramètre, la fonction sera bloquante. Sinon la fonction de retour sera appelée quand l’exécution de la fonction sera terminée.

Paramètres

callback (function) – Fonction de rappel lancée en cas de réussite lors de l’exécution

Type renvoyé

None

Arm.move_joints(joints, callback=None)[source]

Réalise une action de mouvement d’axes. Les axes sont exprimés en radian. Réalise une action de déplacement de l’effecteur par glissement.

Toutes les lignes de l’exemple suivant réalisent la même action:

arm.joints = [0.2, 0.1, 0.3, 0.0, 0.5, 0.0]
arm.move_joints([0.2, 0.1, 0.3, 0.0, 0.5, 0.0])

def move_callback(_):
    print("Move completed")

arm.move_joints([0chronous use
arm.calibrate(CalibrateMode.MANUAL)
arm.calibrate(CalibrateMode.AUTO)

# Asynchronous use
def calibration_callback(result):
    if result["status"] < RobotErrors.SUCCESS.value:
        print("Calibration failed")
    else:
        print("Calibration completed with success")

arm.calibrate(CalibrateMode.AUTO, calibration_callback)
Paramètres
  • callback (function) – Fonction de rappel lancée en cas de réussite lors de l’exécution

  • joints (Union[list[float], tuple[float]]) – Liste des noms des axes

Type renvoyé

None

Arm.move_pose(pose, frame='', callback=None)[source]

Déplace l’effecteur à la position [x, y, z, roll, pitch, yaw], dans un repère particulier si précisé. x, y, z sont exprimés en mètres / roll, pitch & yaw sont exprimés en radian. Si une fonction de retour n’est pas passée en paramètre, la fonction sera bloquante. Sinon la fonction de retour sera appelée quand l’exécution de la fonction sera terminée.

Toutes les lignes de l’exemple suivant réalisent la même action:

arm.pose = [0.2, 0.1, 0.3, 0.0, 0.5, 0.0]
arm.move_pose([0.2, 0.1, 0.3, 0.0, 0.5, 0.0])
arm.move_pose(PoseObject(0.2, 0.1, 0.3, 0.0, 0.5, 0.0))
arm.move_pose([0.2, 0.1, 0.3, 0.0, 0.5, 0.0], "default_frame")
arm.move_pose(PoseObject(0.2, 0.1, 0.3, 0.0, 0.5, 0.0), "default_frame")

def move_callback(_):
    print("Move completed")

arm.move_joints([0.2, 0.1, 0.3, 0.0, 0.5, 0.0], callback=move_callback)
Paramètres
  • callback (function) – Fonction de rappel lancée en cas de réussite lors de l’exécution

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

  • frame – nom du repère

Type renvoyé

None

Arm.move_linear_pose(pose, frame='', callback=None)[source]

Déplace l’effecteur à la position [x, y, z, roll, pitch, yaw], d’une manière linéaire, dans un repère particulier si précisé. x, y, z sont exprimés en mètres / roll, pitch & yaw sont exprimés en radian. Si une fonction de retour n’est pas passée en paramètre, la fonction sera bloquante. Sinon la fonction de retour sera appelée quand l’exécution de la fonction sera terminée.

Toutes les lignes de l’exemple suivant réalisent la même action:

arm.move_linear_pose([0.2, 0.1, 0.3, 0.0, 0.5, 0.0])
arm.move_linear_pose(PoseObject(0.2, 0.1, 0.3, 0.0, 0.5, 0.0))
arm.move_linear_pose([0.2, 0.1, 0.3, 0.0, 0.5, 0.0], "default_frame")
arm.move_linear_pose(PoseObject(0.2, 0.1, 0.3, 0.0, 0.5, 0.0), "default_frame")

def move_callback(_):
    print("Move completed")

arm.move_linear_pose([0.2, 0.1, 0.3, 0.0, 0.5, 0.0], callback=move_callback)
Paramètres
  • callback (function) – Fonction de rappel lancée en cas de réussite lors de l’exécution

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

  • frame – nom du repère

Type renvoyé

None

Arm.shift_pose(axis, shift_value, callback=None)[source]

Réalise une action de déplacement de l’effecteur par glissement. Réalise une action de déplacement de l’effecteur par glissement.

Exemples:

self.arm.shift_pose(RobotAxis.X, 0.05)
self.arm.shift_pose(RobotAxis.Y, -0.05)
self.arm.shift_pose(RobotAxis.Z, 0.1)
self.arm.shift_pose(RobotAxis.ROLL, 1.57)
self.arm.shift_pose(RobotAxis.PITCH, -1.57)
self.arm.shift_pose(RobotAxis.YAW, 0.78)

def move_callback(_):
    print("Move completed")

self.arm.shift_pose(RobotAxis.X, 0.1, move_callback)
Paramètres
  • axis (RobotAxis) – Valeur de l’énumérations correspondant à l’axe de glissement

  • shift_value (float) – En mètre pour X, Y, Z et en radian pour roll, pitch, yaw

  • callback (function) – Fonction de rappel lancée en cas de réussite lors de l’exécution

Type renvoyé

None

Arm.move_relative(offset, frame='world')[source]

Déplace l’effecteur d’un offset dans un repère

Exemples:

arm.move_relative([0.05, 0.05, 0.05, 0.3, 0, 0], "default_frame")
Paramètres
  • offset (list[float]) – la liste qui contient les paramètres x, y, z, roulis, tangage et lacet

  • frame (str) – nom du repère

Renvoie

status, message

Type renvoyé

(int, str)

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

Déplace l’effecteur d’un offset dans un repère de manière linéaire

Exemples:

arm.move_linear_relative([0.05, 0.05, 0.05, 0.3, 0, 0], "default_frame")
Paramètres
  • offset (list[float]) – la liste qui contient les paramètres x, y, z, roulis, tangage et lacet

  • frame (str) – nom du repère

Renvoie

status, message

Type renvoyé

(int, str)

Arm.set_jog_control(enabled)[source]

Active le mode de contrôle direct si le paramètre est Vrai, l’éteint le cas contraire

Paramètres

enabled (Bool) – Vrai ou Faux

Type renvoyé

None

Arm.jog_joints(joints_offset, callback=None, errback=None, timeout=None)[source]

Réalise un control direct sur la position des axes. Les valeurs sont exprimées en radians. Si une fonction de retour n’est pas passée en paramètre, la fonction sera bloquante. Sinon la fonction de retour sera appelée quand l’exécution de la fonction sera terminée.

Exemples:

arm.jog_joints([0.1, 0.0, 0.5, 0.0, 0.0, -1.57])

def jog_callback(_):
    print("Jog completed")
    arm.set_jog_control(False) # Disable Jog interface

arm.jog_joints([0.1, 0.0, 0.5, 0.0, 0.0, -1.57], jog_callback)
Paramètres
  • joints_offset (Union[list[float], tuple[float]]) – la liste des 6 offset des axes

  • callback (function) – Fonction de rappel lancée en cas de réussite lors de l’exécution

  • errback (function) – Fonction de rappel lancée en cas d’erreur lors de l’exécution

  • timeout (float) – Délai d’exécution de l’opération, en secondes. Utilisé seulement en cas de blocage

Type renvoyé

None

Arm.jog_pose(pose_offset, callback=None, errback=None, timeout=None)[source]

Réalise un control direct sur l’effecteur. 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. Si une fonction de retour n’est pas passée en paramètre, la fonction sera bloquante. Sinon la fonction de retour sera appelée quand l’exécution de la fonction sera terminée.

Exemples:

arm.jog_pose([0.01, 0.0, 0.05, 0.0, 0.0, -1.57])

def jog_callback(_):
    print("Jog completed")
    arm.set_jog_control(False) # Disable Jog interface

arm.jog_pose([0.1, 0.0, 0.5, 0.0, 0.0, -1.57], jog_callback)
Paramètres
  • pose_offset (Union[list[float], tuple[float]]) – la liste des 6 offset

  • callback (function) – Fonction de rappel lancée en cas de réussite lors de l’exécution

  • errback (function) – Fonction de rappel lancée en cas d’erreur lors de l’exécution

  • timeout (float) – Délai d’exécution de l’opération, en secondes. Utilisé seulement en cas de blocage

Type renvoyé

None

Fonction de statut du robot

property Arm.hardware_status

Retourne le client de l’état hardware qui peut être utilisé de manière synchrone ou asynchrone pour obtenir l’état hardware

Exemples:

# Get last value
arm.hardware_status()
arm.hardware_status.value

# Subscribe a callback
def hs_callback(msg):
    print msg.voltage

arm.hardware_status.subscribe(hs_callback)
arm.hardware_status.unsubscribe()
Renvoie

Instance de topic d’état hardware

Type renvoyé

NiryoTopic

property Arm.joints_state

Obtient le topic d’état des joints qui peut être utilisé de manière synchrone ou asynchrone pour obtenir l’état des joints. Le topic d’état des joints retourne un JointStateObject

Cela peut être utilisé comme ceci::

# Get last joint state
joint_state = arm.joints_state()
joint_state = arm.joints_state.value

joint_names = arm.joints_state().name
joint_positions = arm.joints_state().position
joint_velocities = arm.joints_state.value.velocity

# Raise a callback at each new value
from __future__ import print_function

arm.joints_state.subscribe(lambda message: print(message.position))
arm.joints_state.unsubscribe()
Renvoie

Topic de l’état des joints

Type renvoyé

NiryoTopic

Arm.get_joints()[source]

Obtient la valeur des axes en radians. Vous pouvez également utiliser un getter

joints = arm.get_joints()
joints = arm.joints
Renvoie

Liste des valeurs des axes

Type renvoyé

list[float]

property Arm.joints

Obtient la valeur des axes en radians.

Renvoie

Liste des valeurs des axes

Type renvoyé

list[float]

property Arm.pose

Obtient la position de l’effecteur sous la forme [x, 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 = arm.pose
pose_list = arm.pose.to_list()
x, y, z, roll, pitch, yaw = arm.pose.to_list()
Renvoie

Position de l’effecteur

Type renvoyé

PoseObject

property Arm.get_pose

Obtient le topic de la postion de l’effecteur qui peut être utilisé de manière synchrone ou asynchrone pour obtenir la position de l’effecteur. Le topic de l’état des axes retourne un PoseObject. x, y & z sont exprimés en mètres / roll, pitch & yaw sont exprimés en radians

Voir ci-dessous quelques utilisations

pose = arm.get_pose()
pose = arm.get_pose.value
pose_list = arm.get_pose().to_list()
x, y, z, roll, pitch, yaw = arm.get_pose().to_list()

arm.get_pose.subscribe(callback)
arm.get_pose.unsubscribe()
Renvoie

Topic de position de l’effecteur

Type renvoyé

NiryoTopic

Arm.get_pose_quat()[source]

Obtient la positon de l’effecteur en coordonnées quaternion

Renvoie

Positions et coordonnées quaternion concaténées dans une liste [x, y, z, qx, qy, qz, qw]

Type renvoyé

list[float]

Fonctions du mode apprentissage

property Arm.learning_mode

Retourne le client du mode apprentissage qui peut être utilisé de manière synchrone ou asynchrone pour obtenir l’état du mode apprentissage. Le client du mode apprentissage retourne une valeur booléene

Exemples:

# Get last value
arm.learning_mode()
if arm.learning_mode.value:
    print("Learning mode enabled"))

# Subscribe a callback
def lm_callback(is_learning_mode_enabled):
    print is_learning_mode_enabled

arm.learning_mode.subscribe(lm_callback)
arm.learning_mode.unsubscribe()
Renvoie

Instance du topic du mode apprentissage

Type renvoyé

NiryoTopic

Arm.get_learning_mode()[source]

Obtient l’état du mode apprentissage

Renvoie

Vrai si le mode apprentissage est activé

Type renvoyé

bool

Arm.set_learning_mode(enabled)[source]

Active le mode apprentissage si le paramètre est Vrai, l’éteint le cas contraire

Paramètres

enabled (bool) – Vrai ou Faux

Type renvoyé

None

Fonctions cinématiques

Arm.forward_kinematics(*args)[source]

Cacule la cinématique directe pour une configuration d’axes donnée et donne la position spatiale associé

Exemples:

pose_obj = arm.forward_kinematics(1.57, 0.0, 0.0, 0.78, 0.0, -1.57)
pose_obj = arm.forward_kinematics([1.57, 0.0, 0.0, 0.78, 0.0, -1.57])
Paramètres

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

Type renvoyé

PoseObject

Arm.inverse_kinematics(*args)[source]

Calcule la cinématique inverse

Exemples:

joint_list = arm.inverse_kinematics(0.2, 0.0, 0.3, 0.0, 1.57, 0.0)
joint_list = arm.inverse_kinematics([0.2, 0.0, 0.3, 0.0, 1.57, 0.0])
joint_list = arm.inverse_kinematics(PoseObject(0.2, 0.0, 0.3, 0.0, 1.57, 0.0))
Paramètres

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

Renvoie

Liste des valeurs des axes

Type renvoyé

list[float]

Bras - Topics Niryo

L’utilisation de ces fonctions est expliquée dans la section NiryoTopic. Elles permettent l’acquisition de données en temps réel par des fonctions de rappel ou des appels directs.

Topics du bras Niryo

Nom

Fonctions

Type Retour

/joint_states

joints_state

JointStateObject

/niryo_robot/robot_state

get_pose

PoseObject

/niryo_robot_hardware_interface/hardware_status

hardware_status

HardwareStatusObject

/niryo_robot/learning_mode/state

learning_mode

bool

/niryo_robot/max_velocity_scaling_factor

get_arm_max_velocity

float

Bras - Enumerations

Liste d’enumerations

  • CalibrateMode

  • RobotAxis

  • JogShift

class CalibrateMode(value)[source]

Enumerations des modes de calibration

AUTO = 1
MANUAL = 2
class RobotAxis(value)[source]

Enumeration des axes du robot : utilsé pour les commandes par glissement

X = 0
Y = 1
Z = 2
ROLL = 3
PITCH = 4
YAW = 5
class JogShift(value)[source]

Enumeration des translations : utilisée pour les commandes par translations

JOINTS_SHIFT = 1
POSE_SHIFT = 2

Bras - Objets

  • HardwareStatusObject

class HardwareStatusObject[source]

Objet utilisé pour sauvegarder toute les informations hardware

Attributs
  • rpi_temperature (float) – Nombre représentant la température de la raspberry

  • hardware_version (str) – Nombre représentant la version du matériel

  • connection_up (bool) – Booléen indicant si la connection avec le robot est faite

  • error_message (str) – Message du status d’erreur

  • calibration_needed (bool) – Booléen

  • calibration_in_progress (bool) – Booléen indicant une la calibration est en cours

  • motor_names (list[str]) – Liste des noms des moteurs

  • motor_types (list[str]) – Liste des types de moteurs

  • motors_temperature (list[float]) – Liste de la température des moteurs en degrés celsius

  • motors_voltage (list[float]) – Liste de la tension des moteurs en volt

  • hardware_errors (list[int]) – Liste des codes erreurs moteur

  • hardware_error_messages (list[str]) – Liste des textes d’erreurs moteurs

  • JointStateObject

class JointStateObject[source]

Objet utilisé pour sauvegarder toute les informations des axes

Attributs
  • name (list[str]) – Liste des noms des axes

  • position (list[float]) – Liste des positions des axes

  • velocity (list[float]) – Liste des vitesses des axes

  • effort (list[float]) – Liste des effors des axes

class PoseObject(x, y, z, roll, pitch, yaw)[source]

Objet Pose qui contient les paramètres x, y, z, roulis, tangage et lacet.

Attributs
  • x (float) – X (mètres)

  • y (float) – Y (mètres)

  • z (float) – Z (mètres)

  • roll (float) – Roulis (radian)

  • pitch (float) – Tangage (radian)

  • yaw (float) – Lacet (radian)