PyNiryo API Documentation

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

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

NiryoRobot.connect(ip_address)[source]

Connect to the TCP Server

Parameters

ip_address (str) – IP Address

Return type

None

NiryoRobot.close_connection()[source]

Close connection with robot

Return type

None

Main purpose functions

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

NiryoRobot.calibrate_auto()[source]

Start a automatic motors calibration if motors are not calibrated yet

Return type

None

NiryoRobot.need_calibration()[source]

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

Return type

bool

NiryoRobot.get_learning_mode()[source]

Get learning mode state

Returns

True if learning mode is on

Return type

bool

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

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

NiryoRobot.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 NiryoRobot.wait(duration)[source]

Wait for a certain time

Parameters

duration (float) – duration in seconds

Return type

None

Joints & Pose

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

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

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

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

NiryoRobot.move_pose(*args)[source]

Move robot end effector pose to a (x, y, z, roll, pitch, yaw, frame_name) pose in a particular frame (frame_name) if defined. 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(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")
Parameters

args (Union[tuple[float], list[float], PoseObject, [tuple[float], str], [list[float], str], [PoseObject, str]]) – either 7 args (1 for each coordinates and 1 for the name of the frame) or a list of 6 coordinates or a PoseObject and 1 for the frame name

Return type

None

NiryoRobot.move_linear_pose(*args)[source]

Move robot end effector pose to a (x, y, z, roll, pitch, yaw) pose with a linear trajectory, in a particular frame (frame_name) if defined

Parameters

args (Union[tuple[float], list[float], PoseObject, [tuple[float], str], [list[float], str], [PoseObject, str]]) – either 7 args (1 for each coordinates and 1 for the name of the frame) or a list of 6 coordinates or a PoseObject and 1 for the frame name

Return type

None

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

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

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

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

NiryoRobot.move_to_home_pose()[source]

Move to a position where the forearm lays on shoulder

Return type

None

NiryoRobot.go_to_sleep()[source]

Go to home pose and activate learning mode

Return type

None

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

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

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

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

NiryoRobot.delete_pose(pose_name)[source]

Delete pose from robot’s memory

Return type

None

NiryoRobot.get_saved_pose_list()[source]

Get list of poses’ name saved in robot memory

Return type

list[str]

Pick & Place

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

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

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

NiryoRobot.get_trajectory_saved(trajectory_name)[source]

Get trajectory saved in Ned’s memory

Returns

Trajectory

Return type

list[Joints]

NiryoRobot.get_saved_trajectory_list()[source]

Get list of trajectories’ name saved in robot memory

Return type

list[str]

NiryoRobot.execute_registered_trajectory(trajectory_name)[source]

Execute trajectory from Ned’s memory

Return type

None

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

NiryoRobot.execute_trajectory_from_poses_and_joints(list_pose_joints, list_type=None, dist_smoothing=0.0)[source]

Execute trajectory from list of poses and joints

Example:

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
)
Parameters
  • list_pose_joints (list[list[float]]) – List of [x,y,z,qx,qy,qz,qw] or list of [x,y,z,roll,pitch,yaw] or a list of [j1,j2,j3,j4,j5,j6]

  • list_type (list[string]) – List of string ‘pose’ or ‘joint’, or [‘pose’] (if poses only) or [‘joint’] (if joints only). If None, it is assumed there are only poses in the list.

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

Return type

None

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

Save trajectory in robot memory

Parameters
  • trajectory (list[list[float]]) – list of Joints [j1, j2, j3, j4, j5, j6] as waypoints to create the trajectory

  • trajectory_name (str) – Name you want to give to the trajectory

  • trajectory_description – Description you want to give to the trajectory

Return type

None

NiryoRobot.save_last_learned_trajectory(name, description)[source]

Save last user executed trajectory

Return type

None

NiryoRobot.delete_trajectory(trajectory_name)[source]

Delete trajectory from robot’s memory

Return type

None

NiryoRobot.clean_trajectory_memory()[source]

Delete trajectory from robot’s memory

Return type

None

Dynamic frames

NiryoRobot.get_saved_dynamic_frame_list()[source]

Get list of saved dynamic frames

Example:

list_frame, list_desc = robot.get_saved_dynamic_frame_list()
print(list_frame)
print(list_desc)
Returns

list of dynamic frames name, list of description of dynamic frames

Return type

list[str], list[str]

NiryoRobot.get_saved_dynamic_frame(frame_name)[source]

Get name, description and pose of a dynamic frame

Example:

frame = robot.get_saved_dynamic_frame("default_frame")
Parameters

frame_name (str) – name of the frame

Returns

name, description, position and orientation of a frame

Return type

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]

Create a dynamic frame with 3 poses (origin, x, y)

Example:

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)
Parameters
  • frame_name (str) – name of the frame

  • description (str) – description of the frame

  • pose_origin (list[float] [x, y, z, roll, pitch, yaw]) – pose of the origin of the frame

  • pose_x (list[float] [x, y, z, roll, pitch, yaw]) – pose of the point x of the frame

  • pose_y (list[float] [x, y, z, roll, pitch, yaw]) – pose of the point y of the frame

  • belong_to_workspace (boolean) – indicate if the frame belong to a workspace

Returns

status, message

Return type

(int, str)

NiryoRobot.save_dynamic_frame_from_points(frame_name, description, point_origin, point_x, point_y, belong_to_workspace=False)[source]

Create a dynamic frame with 3 points (origin, x, y)

Example:

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)
Parameters
  • frame_name (str) – name of the frame

  • description (str) – description of the frame

  • point_origin (list[float] [x, y, z]) – origin point of the frame

  • point_x (list[float] [x, y, z]) – point x of the frame

  • point_y (list[float] [x, y, z]) – point y of the frame

  • belong_to_workspace (boolean) – indicate if the frame belong to a workspace

Returns

status, message

Return type

(int, str)

NiryoRobot.edit_dynamic_frame(frame_name, new_frame_name, new_description)[source]

Modify a dynamic frame

Example:

robot.edit_dynamic_frame("name", "new_name", "new description")
Parameters
  • frame_name (str) – name of the frame

  • new_frame_name (str) – new name of the frame

  • new_description (str) – new description of the frame

Returns

status, message

Return type

(int, str)

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

Delete a dynamic frame

Example:

robot.delete_saved_dynamic_frame("name")
Parameters
  • frame_name (str) – name of the frame to remove

  • belong_to_workspace (boolean) – indicate if the frame belong to a workspace

Returns

status, message

Return type

(int, str)

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

Move robot end of a offset in a frame

Example:

robot.move_relative([0.05, 0.05, 0.05, 0.3, 0, 0], frame="default_frame")
Parameters
  • offset (list[float]) – list which contains offset of x, y, z, roll, pitch, yaw

  • frame (str) – name of local frame

Returns

status, message

Return type

(int, str)

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

Move robot end of a offset by a linear movement in a frame

Example:

robot.move_linear_relative([0.05, 0.05, 0.05, 0.3, 0, 0], frame="default_frame")
Parameters
  • offset (list[float]) – list which contains offset of x, y, z, roll, pitch, yaw

  • frame (str) – name of local frame

Returns

status, message

Return type

(int, str)

Tools

NiryoRobot.get_current_tool_id()[source]

Get equipped tool Id

Return type

ToolID

NiryoRobot.update_tool()[source]

Update equipped tool

Return type

None

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

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

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

Open gripper

Parameters
  • speed (int) – Between 100 & 1000 (only for Niryo One and Ned1)

  • max_torque_percentage (int) – Closing torque percentage (only for Ned2)

  • hold_torque_percentage (int) – Hold torque percentage after closing (only for Ned2)

Return type

None

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

Close gripper

Parameters
  • speed (int) – Between 100 & 1000 (only for Niryo One and Ned1)

  • max_torque_percentage (int) – Opening torque percentage (only for Ned2)

  • hold_torque_percentage (int) – Hold torque percentage after opening (only for Ned2)

Return type

None

NiryoRobot.pull_air_vacuum_pump()[source]

Pull air of vacuum pump

Return type

None

NiryoRobot.push_air_vacuum_pump()[source]

Push air of vacuum pump

Return type

None

NiryoRobot.setup_electromagnet(pin_id)[source]

Setup electromagnet on pin

Parameters

pin_id (PinID or str) –

Return type

None

NiryoRobot.activate_electromagnet(pin_id)[source]

Activate electromagnet associated to electromagnet_id on pin_id

Parameters

pin_id (PinID or str) –

Return type

None

NiryoRobot.deactivate_electromagnet(pin_id)[source]

Deactivate electromagnet associated to electromagnet_id on pin_id

Parameters

pin_id (PinID or str) –

Return type

None

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

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

NiryoRobot.reset_tcp()[source]

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

Return type

None

NiryoRobot.tool_reboot()[source]

Reboot the motor of the tool equparam_list = [workspace_name]

Example:

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)
Return type

None

Hardware

NiryoRobot.set_pin_mode(pin_id, pin_mode)[source]

Set pin number pin_id to mode pin_mode

Parameters
  • pin_id (PinID or str) –

  • pin_mode (PinMode) –

Return type

None

NiryoRobot.digital_write(pin_id, digital_state)[source]

Set pin_id state to digital_state

Parameters
  • pin_id (PinID or str) –

  • digital_state (PinState) –

Return type

None

NiryoRobot.digital_read(pin_id)[source]

Read pin number pin_id and return its state

Parameters

pin_id (PinID or str) –

Return type

PinState

NiryoRobot.get_hardware_status()[source]

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

Returns

Infos contains in a HardwareStatusObject

Return type

HardwareStatusObject

NiryoRobot.get_digital_io_state()[source]

Get Digital IO state : Names, modes, states.

Example:

digital_io_state = robot.digital_io_state
digital_io_state = robot.get_digital_io_state()
Returns

List of DigitalPinObject instance

Return type

list[DigitalPinObject]

NiryoRobot.get_analog_io_state()[source]

Get Analog IO state : Names, modes, states

Example:

analog_io_state = robot.analog_io_state
analog_io_state = robot.get_analog_io_state()
Returns

List of AnalogPinObject instance

Return type

list[AnalogPinObject]

NiryoRobot.analog_write(pin_id, value)[source]

Set and analog pin_id state to a value

Parameters
  • pin_id (PinID or str) –

  • value (float) – voltage between 0 and 5V

Return type

None

NiryoRobot.analog_read(pin_id)[source]

Read the analog pin value

Parameters

pin_id (PinID or str) –

Return type

float

NiryoRobot.get_custom_button_state()[source]

Get the Ned2’s custom button state

Returns

True if pressed, False else

Return type

bool

Conveyor

NiryoRobot.set_conveyor()[source]

Activate a new conveyor and return its ID

Returns

New conveyor ID

Return type

ConveyorID

NiryoRobot.unset_conveyor(conveyor_id)[source]

Remove specific conveyor.

Parameters

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

NiryoRobot.run_conveyor(conveyor_id, speed=50, direction=<ConveyorDirection.FORWARD: 1>)[source]

Run conveyor at id ‘conveyor_id’

Parameters
  • conveyor_id (ConveyorID) –

  • speed (int) –

  • direction (ConveyorDirection) –

Return type

None

NiryoRobot.stop_conveyor(conveyor_id)[source]

Stop conveyor at id ‘conveyor_id’

Parameters

conveyor_id (ConveyorID) –

Return type

None

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

NiryoRobot.get_connected_conveyors_id()[source]
Returns

List of the connected conveyors’ ID

Return type

list[ConveyorID]

Vision

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

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

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

NiryoRobot.set_saturation(saturation_factor)[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

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

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

NiryoRobot.get_target_pose_from_cam(workspace_name, height_offset=0.0, shape=<ObjectShape.ANY: 'ANY'>, color=<ObjectColor.ANY: '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)

NiryoRobot.vision_pick(workspace_name, height_offset=0.0, shape=<ObjectShape.ANY: 'ANY'>, color=<ObjectColor.ANY: 'ANY'>)[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)

NiryoRobot.move_to_object(workspace_name, height_offset, shape, color)[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)

NiryoRobot.detect_object(workspace_name, shape=<ObjectShape.ANY: 'ANY'>, color=<ObjectColor.ANY: 'ANY'>)[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)

NiryoRobot.get_camera_intrinsics()[source]

Get calibration object: camera intrinsics, distortions coefficients

Returns

camera intrinsics, distortions coefficients

Return type

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

NiryoRobot.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
Return type

None

NiryoRobot.save_workspace_from_points(workspace_name, point_origin, point_2, point_3, point_4)[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
Return type

None

NiryoRobot.delete_workspace(workspace_name)[source]

Delete workspace from robot’s memory

Parameters

workspace_name (str) –

Return type

None

NiryoRobot.get_workspace_ratio(workspace_name)[source]

Get workspace ratio from robot’s memory

Parameters

workspace_name (str) –

Return type

float

NiryoRobot.get_workspace_list()[source]

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

Return type

list[str]

Led Ring

NiryoRobot.set_led_color(led_id, color)[source]

Lights up an LED in one colour. RGB colour between 0 and 255.

Example:

robot.set_led_color(5, [15, 50, 255])
Parameters
  • led_id (int) – Id of the led: between 0 and 29

  • color (list[float]) – Led color in a list of size 3[R, G, B]. RGB channels from 0 to 255.

Returns

status, message

Return type

(int, str)

NiryoRobot.led_ring_solid(color)[source]

Set the whole Led Ring to a fixed color.

Example:

robot.led_ring_solid([15, 50, 255])
Parameters

color (list[float]) – Led color in a list of size 3[R, G, B]. RGB channels from 0 to 255.

Returns

status, message

Return type

(int, str)

NiryoRobot.led_ring_turn_off()[source]

Turn off all LEDs

Example:

robot.led_ring_turn_off()
Returns

status, message

Return type

(int, str)

NiryoRobot.led_ring_flashing(color, period=0, iterations=0, wait=False)[source]

Flashes a color according to a frequency. The frequency is equal to 1 / period.

Examples:

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)
Parameters
  • color (list[float]) – Led color in a list of size 3[R, G, B]. RGB channels from 0 to 255.

  • period (float) – Execution time for a pattern in seconds. If 0, the default time will be used.

  • iterations (int) – Number of consecutive flashes. If 0, the Led Ring flashes endlessly.

  • wait (bool) – The service wait for the animation to finish all iterations or not to answer. If iterations is 0, the service answers immediately.

Returns

status, message

Return type

(int, str)

NiryoRobot.led_ring_alternate(color_list, period=0, iterations=0, wait=False)[source]

Several colors are alternated one after the other.

Examples:

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)
Parameters
  • color_list (list[list[float]]) – Led color list of lists of size 3[R, G, B]. RGB channels from 0 to 255.

  • period (float) – Execution time for a pattern in seconds. If 0, the default time will be used.

  • iterations (int) – Number of consecutive alternations. If 0, the Led Ring alternates endlessly.

  • wait (bool) – The service wait for the animation to finish all iterations or not to answer. If iterations is 0, the service answers immediately.

Returns

status, message

Return type

(int, str)

NiryoRobot.led_ring_chase(color, period=0, iterations=0, wait=False)[source]

Movie theater light style chaser animation.

Examples:

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)
Parameters
  • color (list[float]) – Led color in a list of size 3[R, G, B]. RGB channels from 0 to 255.

  • period (float) – Execution time for a pattern in seconds. If 0, the default time will be used.

  • iterations (int) – Number of consecutive chase. If 0, the animation continues endlessly. One chase just lights one Led every 3 LEDs.

  • wait (bool) – The service wait for the animation to finish all iterations or not to answer. If iterations is 0, the service answers immediately.

Returns

status, message

Return type

(int, str)

NiryoRobot.led_ring_wipe(color, period=0, wait=False)[source]

Wipe a color across the Led Ring, light a Led at a time.

Examples:

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)
Parameters
  • color (list[float]) – Led color in a list of size 3[R, G, B]. RGB channels from 0 to 255.

  • period (float) – Execution time for a pattern in seconds. If 0, the default time will be used.

  • wait (bool) – The service wait for the animation to finish or not to answer.

Returns

status, message

Return type

(int, str)

NiryoRobot.led_ring_rainbow(period=0, iterations=0, wait=False)[source]

Draw rainbow that fades across all LEDs at once.

Examples:

robot.led_ring_rainbow()
robot.led_ring_rainbow(5, 2, True)
robot.led_ring_rainbow(wait=True)
Parameters
  • period (float) – Execution time for a pattern in seconds. If 0, the default time will be used.

  • iterations (int) – Number of consecutive rainbows. If 0, the animation continues endlessly.

  • wait (bool) – The service wait for the animation to finish or not to answer. If iterations is 0, the service answers immediately.

Returns

status, message

Return type

(int, str)

NiryoRobot.led_ring_rainbow_cycle(period=0, iterations=0, wait=False)[source]

Draw rainbow that uniformly distributes itself across all LEDs.

Examples:

robot.led_ring_rainbow_cycle()
robot.led_ring_rainbow_cycle(5, 2, True)
robot.led_ring_rainbow_cycle(wait=True)
Parameters
  • period (float) – Execution time for a pattern in seconds. If 0, the default time will be used.

  • iterations (int) – Number of consecutive rainbow cycles. If 0, the animation continues endlessly.

  • wait (bool) – The service wait for the animation to finish or not to answer. If iterations is 0, the service answers immediately.

Returns

status, message

Return type

(int, str)

NiryoRobot.led_ring_rainbow_chase(period=0, iterations=0, wait=False)[source]

Rainbow chase animation, like the led_ring_chase method.

Examples:

robot.led_ring_rainbow_chase()
robot.led_ring_rainbow_chase(5, 2, True)
robot.led_ring_rainbow_chase(wait=True)
Parameters
  • period (float) – Execution time for a pattern in seconds. If 0, the default time will be used.

  • iterations (int) – Number of consecutive rainbow cycles. If 0, the animation continues endlessly.

  • wait (bool) – The service wait for the animation to finish or not to answer. If iterations is 0, the service answers immediately.

Returns

status, message

Return type

(int, str)

NiryoRobot.led_ring_go_up(color, period=0, iterations=0, wait=False)[source]

LEDs turn on like a loading circle, and are then all turned off at once.

Examples:

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)
Parameters
  • color (list[float]) – Led color in a list of size 3[R, G, B]. RGB channels from 0 to 255.

  • period (float) – Execution time for a pattern in seconds. If 0, the default time will be used.

  • iterations (int) – Number of consecutive turns around the Led Ring. If 0, the animation continues endlessly.

  • wait (bool) – The service wait for the animation to finish or not to answer. If iterations is 0, the service answers immediately.

Returns

status, message

Return type

(int, str)

NiryoRobot.led_ring_go_up_down(color, period=0, iterations=0, wait=False)[source]

LEDs turn on like a loading circle, and are turned off the same way.

Examples:

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)
Parameters
  • color (list[float]) – Led color in a list of size 3[R, G, B]. RGB channels from 0 to 255.

  • period (float) – Execution time for a pattern in seconds. If 0, the default time will be used.

  • iterations (int) – Number of consecutive turns around the Led Ring. If 0, the animation continues endlessly.

  • wait (bool) – The service wait for the animation to finish or not to answer. If iterations is 0, the service answers immediately.

Returns

status, message

Return type

(int, str)

NiryoRobot.led_ring_breath(color, period=0, iterations=0, wait=False)[source]

Variation of the light intensity of the LED ring, similar to human breathing.

Examples:

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)
Parameters
  • color (list[float]) – Led color in a list of size 3[R, G, B]. RGB channels from 0 to 255.

  • period (float) – Execution time for a pattern in seconds. If 0, the default time will be used.

  • iterations (int) – Number of consecutive turns around the Led Ring. If 0, the animation continues endlessly.

  • wait (bool) – The service wait for the animation to finish or not to answer. If iterations is 0, the service answers immediately.

Returns

status, message

Return type

(int, str)

NiryoRobot.led_ring_snake(color, period=0, iterations=0, wait=False)[source]

A small coloured snake (certainly a python :D ) runs around the LED ring.

Examples:

robot.led_ring_snake([15, 50, 255])
robot.led_ring_snake([15, 50, 255], 1, 100, True)
Parameters
  • color (list[float]) – Led color in a list of size 3[R, G, B]. RGB channels from 0 to 255.

  • period (float) – Execution time for a pattern in seconds. If 0, the default duration will be used.

  • iterations (int) – Number of consecutive turns around the Led Ring. If 0, the animation continues endlessly.

  • wait (bool) – The service wait for the animation to finish or not to answer. If iterations is 0, the service answers immediately.

Returns

status, message

Return type

(int, str)

NiryoRobot.led_ring_custom(led_colors)[source]

Sends a colour command to all LEDs of the LED ring. The function expects a list of colours for the 30 LEDs of the robot.

Example:

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

led_colors (list[list[float]]) – List of size 30 of led color in a list of size 3[R, G, B]. RGB channels from 0 to 255.

Returns

status, message

Return type

(int, str)

Sound

NiryoRobot.get_sounds()[source]

Get sound name list

Returns

list of the sounds of the robot

Return type

list[string]

NiryoRobot.play_sound(sound_name, wait_end=True, start_time_sec=0, end_time_sec=0)[source]

Play a sound from the robot

Parameters
  • sound_name (string) – Name of the sound to play

  • wait_end (bool) – wait for the end of the sound before exiting the function

  • start_time_sec (float) – start the sound from this value in seconds

  • end_time_sec (float) – end the sound at this value in seconds

Return type

None

NiryoRobot.set_volume(sound_volume)[source]

Set the volume percentage of the robot.

Parameters

sound_volume (int) – volume percentage of the sound (0: no sound, 100: max sound)

Return type

None

NiryoRobot.stop_sound()[source]

Stop a sound being played.

Return type

None

NiryoRobot.get_sound_duration(sound_name)[source]

Returns the duration in seconds of a sound stored in the robot database raise SoundRosWrapperException if the sound doesn’t exists

Parameters

sound_name (string) – name of sound

Returns

sound duration in seconds

Return type

float

NiryoRobot.say(text, language=0)[source]

Use gtts (Google Text To Speech) to interprete a string as sound Languages available are: * English: 0 * French: 1 * Spanish: 2 * Mandarin: 3 * Portuguese: 4

Example

robot.say("Hello", 0)
robot.say("Bonjour", 1)
robot.say("Hola", 2)
Parameters
  • text (string) – Text that needs to be spoken < 100 char

  • language (int) – language of the text

Return type

None

Enums

Enums are used to pass specific parameters to functions.

For instance, shift_pose() will need a parameter from RobotAxis enum

robot.shift_pose(RobotAxis.Y, 0.15)

List of enums:

  • CalibrateMode

  • RobotAxis

  • ToolID

  • PinMode

  • PinState

  • PinID

  • ConveyorID

  • ConveyorDirection

  • ObjectColor

  • ObjectShape

class CalibrateMode(value)[source]

Enumeration of Calibration Modes

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

Enumeration of Robot Axis : it used for Shift command

X = 0
Y = 1
Z = 2
ROLL = 3
PITCH = 4
YAW = 5
class ToolID(value)[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(value)[source]

Enumeration of Pin Modes

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

Pin State is either LOW or HIGH

LOW = False
HIGH = True
class PinID(value)[source]

Enumeration of Robot Pins

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]

Enumeration of Conveyor IDs used for Conveyor control

NONE = 0
ID_1 = -1
ID_2 = -2
class ConveyorDirection(value)[source]

Enumeration of Conveyor Directions used for Conveyor control

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

Enumeration of Colors available for image processing

RED = 'RED'
BLUE = 'BLUE'
GREEN = 'GREEN'
ANY = 'ANY'
class ObjectShape(value)[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

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

Object used to store information on digital pins