PyNiryo API Documentation

This file presents the different Command functions, Enums & Python object classes available with the API

  • Command functions are used to deal directly with the robot. It could be move_joints(), get_hardware_status() vision_pick(), or also run_conveyor()

  • Enums are used to pass specific arguments to functions. For instance PinState, ConveyorDirection, …

  • Python object classes, as PoseObject, ease some operations

Command functions

This section references all existing functions to control your robot, which includes

  • Moving the robot

  • Using Vision

  • Controlling Conveyor Belts

  • Playing with Hardware

All functions to control the robot are accessible via an instance of the class NiryoRobot

robot = NiryoRobot(<robot_ip_address>)

See examples on Examples: Basics

List of functions subsections:

TCP Connection

class NiryoRobot(ip_address=None)[source]
close_connection()[source]

Close connection with robot

Return type:

None

connect(ip_address)[source]

Connect to the TCP Server

Parameters:

ip_address (str) – IP Address

Return type:

None

Main purpose functions

class NiryoRobot(ip_address=None)[source]
calibrate(calibrate_mode)[source]

Calibrate (manually or automatically) motors. Automatic calibration will do nothing if motors are already calibrated

Parameters:

calibrate_mode (CalibrateMode) – Auto or Manual

Return type:

None

calibrate_auto()[source]

Start a automatic motors calibration if motors are not calibrated yet

Return type:

None

need_calibration()[source]

Return a bool indicating whereas the robot motors need to be calibrate

Return type:

bool

get_learning_mode()[source]

Get learning mode state

Returns:

True if learning mode is on

Return type:

bool

set_learning_mode(enabled)[source]

Set learning mode if param is True, else turn it off

Parameters:

enabled (bool) – True or False

Return type:

None

set_arm_max_velocity(percentage_speed)[source]

Limit arm max velocity to a percentage of its maximum velocity

Parameters:

percentage_speed (int) – Should be between 1 & 100

Return type:

None

set_jog_control(enabled)[source]

Set jog control mode if param is True, else turn it off

Parameters:

enabled (bool) – True or False

Return type:

None

static wait(duration)[source]

Wait for a certain time

Parameters:

duration (float) – duration in seconds

Return type:

None

Joints & Pose

class NiryoRobot(ip_address=None)[source]
get_joints()[source]

Get joints value in radians You can also use a getter

joints = robot.get_joints()
joints = robot.joints
Returns:

List of joints value

Return type:

list[float]

get_pose()[source]

Get end effector link pose as [x, y, z, roll, pitch, yaw]. x, y & z are expressed in meters / roll, pitch & yaw are expressed in radians You can also use a getter

pose = robot.get_pose()
pose = robot.pose
Return type:

PoseObject

get_pose_quat()[source]

Get end effector link pose in Quaternion coordinates

Returns:

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

Return type:

list[float]

move_joints(*args)[source]

Move robot joints. Joints are expressed in radians.

All lines of the next example realize the same operation:

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)
Parameters:

args (Union[list[float], tuple[float]]) – either 6 args (1 for each joints) or a list of 6 joints

Return type:

None

move_pose(*args)[source]

Move robot end effector pose to a (x, y, z, roll, pitch, yaw) pose. x, y & z are expressed in meters / roll, pitch & yaw are expressed in radians

All lines of the next example realize the same operation:

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(PoseObject(0.2, 0.1, 0.3, 0.0, 0.5, 0.0))
Parameters:

args (Union[tuple[float], list[float], PoseObject]) – either 6 args (1 for each coordinates) or a list of 6 coordinates or a PoseObject

Return type:

None

move_linear_pose(*args)[source]

Move robot end effector pose to a (x, y, z, roll, pitch, yaw) pose with a linear trajectory

Parameters:

args (Union[tuple[float], list[float], PoseObject]) – either 6 args (1 for each coordinates) or a list of 6 coordinates or a PoseObject

Return type:

None

shift_pose(axis, shift_value)[source]

Shift robot end effector pose along one axis

Parameters:
  • axis (RobotAxis) – Axis along which the robot is shifted

  • shift_value (float) – In meter for X/Y/Z and radians for roll/pitch/yaw

Return type:

None

shift_linear_pose(axis, shift_value)[source]

Shift robot end effector pose along one axis, with a linear trajectory

Parameters:
  • axis (RobotAxis) – Axis along which the robot is shifted

  • shift_value (float) – In meter for X/Y/Z and radians for roll/pitch/yaw

Return type:

None

jog_joints(*args)[source]

Jog robot joints’. Jog corresponds to a shift without motion planning. Values are expressed in radians.

Parameters:

args (Union[list[float], tuple[float]]) – either 6 args (1 for each joints) or a list of 6 joints offset

Return type:

None

jog_pose(*args)[source]

Jog robot end effector pose Jog corresponds to a shift without motion planning Arguments are [dx, dy, dz, d_roll, d_pitch, d_yaw] dx, dy & dz are expressed in meters / d_roll, d_pitch & d_yaw are expressed in radians

Parameters:

args (Union[list[float], tuple[float]]) – either 6 args (1 for each coordinates) or a list of 6 offset

Return type:

None

move_to_home_pose()[source]

Move to a position where the forearm lays on shoulder

Return type:

None

go_to_sleep()[source]

Go to home pose and activate learning mode

Return type:

None

forward_kinematics(*args)[source]

Compute forward kinematics of a given joints configuration and give the associated spatial pose

Parameters:

args (Union[list[float], tuple[float]]) – either 6 args (1 for each joints) or a list of 6 joints

Return type:

PoseObject

inverse_kinematics(*args)[source]

Compute inverse kinematics

Parameters:

args (Union[tuple[float], list[float], PoseObject]) – either 6 args (1 for each coordinates) or a list of 6 coordinates or a PoseObject

Returns:

List of joints value

Return type:

list[float]

Saved Poses

class NiryoRobot(ip_address=None)[source]
get_pose_saved(pose_name)[source]

Get pose saved in from Ned’s memory

Parameters:

pose_name (str) – Pose name in robot’s memory

Returns:

Pose associated to pose_name

Return type:

PoseObject

save_pose(pose_name, *args)[source]

Save pose in robot’s memory

Parameters:

args (Union[list[float], tuple[float], PoseObject]) – either 6 args (1 for each coordinates) or a list of 6 coordinates or a PoseObject

Return type:

None

delete_pose(pose_name)[source]

Delete pose from robot’s memory

Return type:

None

get_saved_pose_list()[source]

Get list of poses’ name saved in robot memory

Return type:

list[str]

Pick & Place

class NiryoRobot(ip_address=None)[source]
pick_from_pose(*args)[source]

Execute a picking from a pose.

A picking is described as :

* going over the object
* going down until height = z
* grasping with tool
* going back over the object
Parameters:

args (Union[list[float], tuple[float], PoseObject]) – either 6 args (1 for each coordinates) or a list of 6 coordinates or a PoseObject

Return type:

None

place_from_pose(*args)[source]

Execute a placing from a position.

A placing is described as :

* going over the place
* going down until height = z
* releasing the object with tool
* going back over the place
Parameters:

args (Union[list[float], tuple[float], PoseObject]) – either 6 args (1 for each coordinates) or a list of 6 coordinates or a PoseObject

Return type:

None

pick_and_place(pick_pose, place_pos, dist_smoothing=0.0)[source]

Execute a pick then a place

Parameters:
  • pick_pose (Union[list[float], PoseObject]) – Pick Pose : [x, y, z, roll, pitch, yaw] or PoseObject

  • place_pos (Union[list[float], PoseObject]) – Place Pose : [x, y, z, roll, pitch, yaw] or PoseObject

  • dist_smoothing (float) – Distance from waypoints before smoothing trajectory

Return type:

None

Trajectories

class NiryoRobot(ip_address=None)[source]
get_trajectory_saved(trajectory_name)[source]

Get trajectory saved in Ned’s memory

Returns:

Trajectory

Return type:

list[list[float]]

execute_trajectory_saved(trajectory_name)[source]

Execute trajectory from Ned’s memory

Return type:

None

execute_trajectory_from_poses(list_poses, dist_smoothing=0.0)[source]

Execute trajectory from list of poses

Parameters:
  • list_poses (list[list[float]]) – List of [x,y,z,qx,qy,qz,qw] or list of [x,y,z,roll,pitch,yaw]

  • dist_smoothing (float) – Distance from waypoints before smoothing trajectory

Return type:

None

save_trajectory(trajectory_name, list_poses)[source]

Save trajectory in robot memory

Parameters:

list_poses (list[list[float]]) – List of [x,y,z,qx,qy,qz,qw] or list of [x,y,z,roll,pitch,yaw]

Return type:

None

delete_trajectory()[source]

Delete trajectory from robot’s memory

Return type:

None

get_saved_trajectory_list()[source]

Get list of trajectories’ name saved in robot memory

Return type:

list[str]

Tools

class NiryoRobot(ip_address=None)[source]
get_current_tool_id()[source]

Get equipped tool Id

Return type:

ToolID

update_tool()[source]

Update equipped tool

Return type:

None

grasp_with_tool()[source]

Grasp with tool | This action correspond to | - Close gripper for Grippers | - Pull Air for Vacuum pump | - Activate for Electromagnet

Return type:

None

release_with_tool()[source]

Release with tool | This action correspond to | - Open gripper for Grippers | - Push Air for Vacuum pump | - Deactivate for Electromagnet

Return type:

None

open_gripper()[source]

Open gripper associated to ‘gripper_id’ with a speed ‘speed’

Parameters:

speed (int) – Between 100 & 1000

Return type:

None

close_gripper(speed=500)[source]

Close gripper associated to ‘gripper_id’ with a speed ‘speed’

Parameters:

speed (int) – Between 100 & 1000

Return type:

None

pull_air_vacuum_pump()[source]

Pull air of vacuum pump

Return type:

None

push_air_vacuum_pump()[source]

Push air of vacuum pump

Return type:

None

setup_electromagnet()[source]

Setup electromagnet on pin

Parameters:

pin_id (PinID)

Return type:

None

activate_electromagnet()[source]

Activate electromagnet associated to electromagnet_id on pin_id

Parameters:

pin_id (PinID)

Return type:

None

deactivate_electromagnet()[source]

Deactivate electromagnet associated to electromagnet_id on pin_id

Parameters:

pin_id (PinID)

Return type:

None

enable_tcp(enable=True)[source]

Enables or disables the TCP function (Tool Center Point). If activation is requested, the last recorded TCP value will be applied. The default value depends on the gripper equipped. If deactivation is requested, the TCP will be coincident with the tool_link.

Parameters:

enable (Bool) – True to enable, False otherwise.

Return type:

None

set_tcp(*args)[source]

Activates the TCP function (Tool Center Point) and defines the transformation between the tool_link frame and the TCP frame.

Parameters:

args (Union[list[float], tuple[float], PoseObject]) – either 6 args (1 for each coordinates) or a list of 6 coordinates or a PoseObject

Return type:

None

reset_tcp()[source]

Reset the TCP (Tool Center Point) transformation. The TCP will be reset according to the tool equipped.

Return type:

None

tool_reboot()[source]

Reboot the motor of the tool equipped. Useful when an Overload error occurs. (cf HardwareStatus)

Return type:

None

Hardware

class NiryoRobot(ip_address=None)[source]
set_pin_mode()[source]

Set pin number pin_id to mode pin_mode

Parameters:
  • pin_id (PinID)

  • pin_mode (PinMode)

Return type:

None

digital_write(pin_id, digital_state)[source]

Set pin_id state to digital_state

Parameters:
  • pin_id (PinID)

  • digital_state (PinState)

Return type:

None

digital_read(pin_id)[source]

Read pin number pin_id and return its state

Parameters:

pin_id (PinID)

Return type:

PinState

get_hardware_status()[source]

Get hardware status : Temperature, Hardware version, motors names & types …

Returns:

Infos contains in a HardwareStatusObject

Return type:

HardwareStatusObject

get_digital_io_state()[source]

Get Digital IO state : Names, modes, states

Returns:

List of DigitalPinObject instance

Return type:

list[DigitalPinObject]

Conveyor

class NiryoRobot(ip_address=None)[source]
set_conveyor()[source]

Activate a new conveyor and return its ID

Returns:

New conveyor ID

Return type:

ConveyorID

unset_conveyor()[source]

Remove specific conveyor.

Parameters:

conveyor_id (ConveyorID) – Basically, ConveyorID.ONE or ConveyorID.TWO

run_conveyor()[source]

Run conveyor at id ‘conveyor_id’

Parameters:
  • conveyor_id (ConveyorID)

  • speed (int)

  • direction (ConveyorDirection)

Return type:

None

stop_conveyor(conveyor_id)[source]

Stop conveyor at id ‘conveyor_id’

Parameters:

conveyor_id (ConveyorID)

Return type:

None

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

Control conveyor at id ‘conveyor_id’

Parameters:
  • conveyor_id (ConveyorID)

  • control_on (bool)

  • speed (int) – New speed which is a percentage of maximum speed

  • direction (ConveyorDirection) – Conveyor direction

Return type:

None

get_connected_conveyors_id()[source]
Returns:

List of the connected conveyors’ ID

Return type:

list[ConveyorID]

Vision

class NiryoRobot(ip_address=None)[source]
get_img_compressed()[source]

Get image from video stream in a compressed format. Use uncompress_image from the vision package to uncompress it

Returns:

string containing a JPEG compressed image

Return type:

str

set_brightness(brightness_factor)[source]

Modify video stream brightness

Parameters:

brightness_factor (float) – How much to adjust the brightness. 0.5 will give a darkened image, 1 will give the original image while 2 will enhance the brightness by a factor of 2.

Return type:

None

set_contrast(contrast_factor)[source]

Modify video stream contrast

Parameters:

contrast_factor (float) – While a factor of 1 gives original image. Making the factor towards 0 makes the image greyer, while factor>1 increases the contrast of the image.

Return type:

None

set_saturation()[source]

Modify video stream saturation

Parameters:

saturation_factor (float) – How much to adjust the saturation. 0 will give a black and white image, 1 will give the original image while 2 will enhance the saturation by a factor of 2.

Return type:

None

get_image_parameters()[source]

Get last stream image parameters: Brightness factor, Contrast factor, Saturation factor.

Brightness factor: How much to adjust the brightness. 0.5 will give a darkened image, 1 will give the original image while 2 will enhance the brightness by a factor of 2.

Contrast factor: A factor of 1 gives original image. Making the factor towards 0 makes the image greyer, while factor>1 increases the contrast of the image.

Saturation factor: 0 will give a black and white image, 1 will give the original image while 2 will enhance the saturation by a factor of 2.

Returns:

Brightness factor, Contrast factor, Saturation factor

Return type:

float, float, float

get_target_pose_from_rel(workspace_name, height_offset, x_rel, y_rel, yaw_rel)[source]

Given a pose (x_rel, y_rel, yaw_rel) relative to a workspace, this function returns the robot pose in which the current tool will be able to pick an object at this pose.

The height_offset argument (in m) defines how high the tool will hover over the workspace. If height_offset = 0, the tool will nearly touch the workspace.

Parameters:
  • workspace_name (str) – name of the workspace

  • height_offset (float) – offset between the workspace and the target height

  • x_rel (float) – x relative pose (between 0 and 1)

  • y_rel (float) – y relative pose (between 0 and 1)

  • yaw_rel (float) – Angle in radians

Returns:

target_pose

Return type:

PoseObject

get_target_pose_from_cam(workspace_name, height_offset=0.0, shape=ObjectShape.ANY, color=ObjectColor.ANY)[source]

First detects the specified object using the camera and then returns the robot pose in which the object can be picked with the current tool

Parameters:
  • workspace_name (str) – name of the workspace

  • height_offset (float) – offset between the workspace and the target height

  • shape (ObjectShape) – shape of the target

  • color (ObjectColor) – color of the target

Returns:

object_found, object_pose, object_shape, object_color

Return type:

(bool, PoseObject, ObjectShape, ObjectColor)

vision_pick()[source]

Picks the specified object from the workspace. This function has multiple phases:

1. detect object using the camera
2. prepare the current tool for picking
3. approach the object
4. move down to the correct picking pose
5. actuate the current tool
6. lift the object

Example:

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)
Parameters:
  • workspace_name (str) – name of the workspace

  • height_offset (float) – offset between the workspace and the target height

  • shape (ObjectShape) – shape of the target

  • color (ObjectColor) – color of the target

Returns:

object_found, object_shape, object_color

Return type:

(bool, ObjectShape, ObjectColor)

move_to_object()[source]

Same as get_target_pose_from_cam but directly moves to this position

Parameters:
  • workspace_name (str) – name of the workspace

  • height_offset (float) – offset between the workspace and the target height

  • shape (ObjectShape) – shape of the target

  • color (ObjectColor) – color of the target

Returns:

object_found, object_shape, object_color

Return type:

(bool, ObjectShape, ObjectColor)

detect_object()[source]

Detect object in workspace and return its pose and characteristics

Parameters:
  • workspace_name (str) – name of the workspace

  • shape (ObjectShape) – shape of the target

  • color (ObjectColor) – color of the target

Returns:

object_found, object_pose, object_shape, object_color

Return type:

(bool, PoseObject, str, str)

get_camera_intrinsics()[source]

Get calibration object: camera intrinsics, distortions coefficients

Returns:

camera intrinsics, distortions coefficients

Return type:

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

save_workspace_from_robot_poses(workspace_name, pose_origin, pose_2, pose_3, pose_4)[source]

Save workspace by giving the poses of the robot to point its 4 corners with the calibration Tip. Corners should be in the good order. Markers’ pose will be deduced from these poses

Poses should be either a list [x, y, z, roll, pitch, yaw] or a PoseObject

Parameters:
  • workspace_name (str) – workspace name, maximum lenght 30 char.

  • pose_origin (Union[list[float], PoseObject])

  • pose_2 (Union[list[float], PoseObject])

  • pose_3 (Union[list[float], PoseObject])

  • pose_4 (Union[list[float], PoseObject])

Return type:

None

save_workspace_from_points()[source]

Save workspace by giving the points of worskpace’s 4 corners. Points are written as [x, y, z] Corners should be in the good order.

Parameters:
  • workspace_name (str) – workspace name, maximum lenght 30 char.

  • point_origin (list[float])

  • point_2 (list[float])

  • point_3 (list[float])

  • point_4 (list[float])

Return type:

None

delete_workspace(workspace_name)[source]

Delete workspace from robot’s memory

Parameters:

workspace_name (str)

Return type:

None

get_workspace_ratio(workspace_name)[source]

Get workspace ratio from robot’s memory

Parameters:

workspace_name (str)

Return type:

float

get_workspace_list()[source]

Get list of workspaces’ name store in robot’s memory

Return type:

list[str]

Enums

Enums are used to pass specific parameters to functions.

For instance, change_tool() will need a parameter from ToolID enum

robot.change_tool(ToolID.GRIPPER_1)

List of enums:

  • CalibrateMode

  • RobotAxis

  • ToolID

  • PinMode

  • PinState

  • PinID

  • ConveyorID

  • ConveyorDirection

  • ObjectColor

  • ObjectShape

class CalibrateMode(*values)[source]

Enumeration of Calibration Modes

AUTO = 0
MANUAL = 1
class RobotAxis(*values)[source]

Enumeration of Robot Axis : it used for Shift command

X = 0
Y = 1
Z = 2
ROLL = 3
PITCH = 4
YAW = 5
class ToolID(*values)[source]

Enumeration of Tools IDs

NONE = 0
GRIPPER_1 = 11
GRIPPER_2 = 12
GRIPPER_3 = 13
ELECTROMAGNET_1 = 30
VACUUM_PUMP_1 = 31
class PinMode(*values)[source]

Enumeration of Pin Modes

INPUT = 0
OUTPUT = 1
class PinState(*values)[source]

Pin State is either LOW or HIGH

LOW = 0
HIGH = 1
class PinID(*values)[source]

Enumeration of Robot Pins

GPIO_1A = 0
GPIO_1B = 1
GPIO_1C = 2
GPIO_2A = 3
GPIO_2B = 4
GPIO_2C = 5
class ConveyorID(*values)[source]

Enumeration of Conveyor IDs used for Conveyor control

NONE = 0
ID_1 = 12
ID_2 = 13
class ConveyorDirection(*values)[source]

Enumeration of Conveyor Directions used for Conveyor control

FORWARD = 1
BACKWARD = -1
class ObjectColor(*values)[source]

Enumeration of Colors available for image processing

RED = 'RED'
BLUE = 'BLUE'
GREEN = 'GREEN'
ANY = 'ANY'
class ObjectShape(*values)[source]

Enumeration of Shapes available for image processing

SQUARE = 'SQUARE'
CIRCLE = 'CIRCLE'
ANY = 'ANY'

Python object classes

Special objects

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

Pose object which stores x, y, z, roll, pitch & yaw parameters

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]

Create a new pose from copying from copying actual pose with offsets

Return type:

PoseObject

to_list()[source]

Return a list [x, y, z, roll, pitch, yaw] corresponding to the pose’s parameters

Return type:

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]

Object used to store every hardware information

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

Object used to store information on digital pins