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 alsorun_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
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
- NiryoRobot.calibrate_auto()[source]
Start a automatic motors calibration if motors are not calibrated yet
- Return type
- NiryoRobot.need_calibration()[source]
Return a bool indicating whereas the robot motors need to be calibrate
- Return type
- NiryoRobot.get_learning_mode()[source]
Get learning mode state
- Returns
True
if learning mode is on- Return type
- NiryoRobot.set_arm_max_velocity(percentage_speed)[source]
Limit arm max velocity to a percentage of its maximum velocity
Joints & Pose
- NiryoRobot.get_joints()[source]
Get joints value in radians You can also use a getter
joints = robot.get_joints() joints = robot.joints
- 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
- 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)
- 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")
- 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
- NiryoRobot.shift_linear_pose(axis, shift_value)[source]
Shift robot end effector pose along one axis, with a linear trajectory
- NiryoRobot.jog_joints(*args)[source]
Jog robot joints’. Jog corresponds to a shift without motion planning. Values are expressed in radians.
- 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
- NiryoRobot.move_to_home_pose()[source]
Move to a position where the forearm lays on shoulder
- Return type
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
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
- 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
- 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
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
- NiryoRobot.execute_registered_trajectory(trajectory_name)[source]
Execute trajectory from Ned’s memory
- Return type
- NiryoRobot.execute_trajectory_from_poses(list_poses, dist_smoothing=0.0)[source]
Execute trajectory from list of poses
- 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
- NiryoRobot.save_trajectory(trajectory, trajectory_name, trajectory_description)[source]
Save trajectory in robot memory
- NiryoRobot.save_last_learned_trajectory(name, description)[source]
Save last user executed trajectory
- Return type
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)
- 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")
- 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
- 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)
- 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")
- NiryoRobot.delete_dynamic_frame(frame_name, belong_to_workspace=False)[source]
Delete a dynamic frame
Example:
robot.delete_saved_dynamic_frame("name")
- 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")
Tools
- 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
- 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
- NiryoRobot.open_gripper(speed=500, max_torque_percentage=100, hold_torque_percentage=30)[source]
Open gripper
- NiryoRobot.close_gripper(speed=500, max_torque_percentage=100, hold_torque_percentage=20)[source]
Close gripper
- NiryoRobot.activate_electromagnet(pin_id)[source]
Activate electromagnet associated to electromagnet_id on pin_id
- NiryoRobot.deactivate_electromagnet(pin_id)[source]
Deactivate electromagnet associated to electromagnet_id on pin_id
- 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
- 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.
- NiryoRobot.reset_tcp()[source]
Reset the TCP (Tool Center Point) transformation. The TCP will be reset according to the tool equipped.
- Return type
- 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
Hardware
- 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
- 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
- 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
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’
- NiryoRobot.stop_conveyor(conveyor_id)[source]
Stop conveyor at id ‘conveyor_id’
- Parameters
conveyor_id (ConveyorID) –
- Return type
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
- 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.
- 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
- Returns
target_pose
- Return type
- 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
- 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 camera2. prepare the current tool for picking3. approach the object4. move down to the correct picking pose5. actuate the current tool6. lift the objectExample:
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
- 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
- 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
- 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
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
- 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.
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])
- NiryoRobot.led_ring_solid(color)[source]
Set the whole Led Ring to a fixed color.
Example:
robot.led_ring_solid([15, 50, 255])
- 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
- 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
- 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
- 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
- Returns
status, message
- Return type
- 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
- 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
- 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
- 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
- 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
- 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
- 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
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
- 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
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
- 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