Python ROS Wrapper API documentation

This document presents the different Functions, Classes & Enums available with the ROS wrapper API.

Main class

class niryo_robot_python_ros_wrapper.ros_wrapper.NiryoRosWrapper(collision_policy=CollisionPolicy.HARD)

Bases: AbstractNiryoRosWrapper

activate_electromagnet(pin_id)

Activates electromagnet associated to electromagnet_id on pin_id

Parameters:

pin_id (PinID) – Pin ID

Returns:

status, message

Return type:

(int, str)

analog_read(pin_id)

Reads pin number pin_id and returns its state

Parameters:

pin_id (Union[ PinID, str]) – The name of the pin

Returns:

pin voltage

Return type:

float

analog_write(pin_id, analog_state)

Sets pin_id state to pin_state

Parameters:
  • pin_id (Union[ PinID, str]) – The name of the pin

  • analog_state (float) –

Returns:

status, message

Return type:

(int, str)

break_point()
calibrate_auto()

Calls service to calibrate motors then waits for its end. If failed, raises NiryoRosWrapperException

Returns:

status, message

Return type:

(int, str)

calibrate_manual()

Calls service to calibrate motors then waits for its end. If failed, raises NiryoRosWrapperException

Returns:

status, message

Return type:

(int, str)

clean_trajectory_memory()

Sends delete all trajectory command to the trajectory manager service

Returns:

status, message

Return type:

(int, str)

clear_collision_detected()
close_gripper(speed=500, max_torque_percentage=100, hold_torque_percentage=50)

Closes gripper with a speed ‘speed’

Parameters:
  • speed (int) – Default -> 500

  • max_torque_percentage (int) – Default -> 100

  • hold_torque_percentage (int) – Default -> 20

Returns:

status, message

Return type:

(int, str)

property collision_detected
compute_trajectory(robot_positions: List[JointsPosition | Pose], dist_smoothing=0.0)

Generate a trajectory from a list of poses and joints. :param robot_positions: a list of poses and / or joints :type robot_positions: list[RobotPosition] :param dist_smoothing: Distance from waypoints before smoothing trajectory :type dist_smoothing: float

Returns:

a trajectory

Return type:

JointTrajectory

compute_trajectory_from_poses(list_poses_raw, dist_smoothing=0.0)

Deprecated since version 5.5.0: You should use compute_trajectory() with Pose objects.

Generate a trajectory from a list of robot positions. :param list_poses_raw: a list of poses :type list_poses_raw: list[list[float]] :param dist_smoothing: Distance from waypoints before smoothing trajectory :type dist_smoothing: float

Returns:

a trajectory

Return type:

JointTrajectory

compute_trajectory_from_poses_and_joints(list_pose_joints, list_type=None, dist_smoothing=0.0)

Deprecated since version 5.5.0: You should use compute_trajectory() with JointsPosition and Pose objects.

Generate a trajectory from a list of poses and joints. :param list_pose_joints: a list of poses and / or joints :type list_pose_joints: list[list[float]] :param list_type: a list indicating if the corresponding element is a pose or joints :type list_type: list[str] :param dist_smoothing: Distance from waypoints before smoothing trajectory :type dist_smoothing: float

Returns:

a trajectory

Return type:

JointTrajectory

control_conveyor(conveyor_id, bool_control_on, speed, direction)

Controls conveyor associated to conveyor_id. Then stops it if bool_control_on is False, else refreshes it speed and direction

Parameters:
  • conveyor_id (ConveyorID) – ConveyorID.ID_1 or ConveyorID.ID_2

  • bool_control_on (bool) – True for activate, False for deactivate

  • speed (int) – target speed

  • direction (ConveyorDirection) – Target direction

Returns:

status, message

Return type:

(int, str)

control_video_stream(stream_on)

Control if the video stream should be activated or not :param stream_on: if True, activate the video stream. Deactivate it otherwise :return: None

property custom_button

Manages the custom button

Example:

from niryo_robot_python_ros_wrapper.ros_wrapper import *
import rospy

rospy.init_node('ros_wrapper_node')
robot = NiryoRosWrapper()
print(robot.custom_button.state)
Returns:

CustomButtonRosWrapper API instance

Return type:

CustomButtonRosWrapper

property database
deactivate_electromagnet(pin_id)

Deactivates electromagnet associated to electromagnet_id on pin_id

Parameters:

pin_id (PinID) – Pin ID

Returns:

status, message

Return type:

(int, str)

delete_dynamic_frame(frame_name, belong_to_workspace=False)

Delete a dynamic frame

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)

delete_pose(name)

Sends delete command to the pose manager service

Parameters:

name (str) –

Returns:

status, message

Return type:

(int, str)

delete_trajectory(trajectory_name)

Sends delete command to the trajectory manager service

Parameters:

trajectory_name (str) – name

Returns:

status, message

Return type:

(int, str)

delete_workspace(name)

Calls workspace manager to delete a certain workspace

Parameters:

name (str) – workspace name

Returns:

status, message

Return type:

(int, str)

detect_object(workspace_name, shape, color)
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, ObjectPose, str, str)

digital_read(pin_id)

Reads pin number pin_id and returns its state

Parameters:

pin_id (Union[ PinID, str]) – The name of the pin

Returns:

state

Return type:

PinState

digital_write(pin_id, digital_state)

Sets pin_id state to pin_state

Parameters:
  • pin_id (Union[ PinID, str]) – The name of the pin

  • digital_state (Union[ PinState, bool]) –

Returns:

status, message

Return type:

(int, str)

edit_dynamic_frame(frame_name, new_frame_name, new_description)

Modify a dynamic frame

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)

enable_tcp(enable=True)

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.

Returns:

status, message

Return type:

(int, str)

execute_moveit_robot_trajectory(moveit_robot_trajectory)
execute_registered_trajectory(trajectory_name: str)

Sends execution command to the trajectory manager service

Parameters:

trajectory_name (str) – name

Returns:

status, message

Return type:

(int, str)

execute_trajectory(robot_positions: List[JointsPosition | Pose], dist_smoothing=0.0)

Executes trajectory from list of poses and joints

Parameters:
  • robot_positions (list[RobotPosition]) – List of poses and / or joints

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

Returns:

status, message

Return type:

(int, str)

execute_trajectory_from_poses(list_poses_raw: List[List[float] | Pose], dist_smoothing=0.0)

Deprecated since version 5.5.0: You should use execute_trajectory() with Pose objects.

Executes trajectory from a list of pose

Parameters:
  • list_poses_raw (List[Union[List[float], Pose]]) – 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

Returns:

status, message

Return type:

(int, str)

execute_trajectory_from_poses_and_joints(list_pose_joints, list_type=None, dist_smoothing=0.0)

Deprecated since version 5.5.0: You should use execute_trajectory() with JointsPosition and Pose objects.

Executes trajectory from list of poses and joints

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

Returns:

status, message

Return type:

(int, str)

forward_kinematics(j1: float, j2: float, j3: float, j4: float, j5: float, j6: float) Pose
forward_kinematics(joints_position: JointsPosition) Pose

Deprecated since version 5.5.0: You should use forward_kinematics_v2().

Computes the forward kinematics given joint positions. The end effector pose is given for an end effector frame following the right hand rule and with the x axis pointing forward.

This function is overloaded to accept multiple forms of input:

Parameters:
  • args (tuple) – Variable-length positional arguments. This can be either individual joint angles (j1, j2, j3, j4, j5, j6) or a single JointsPosition object.

  • kwargs (dict) – Arbitrary keyword arguments.

Returns:

The pose of the end effector in the robot’s workspace.

Return type:

Pose

forward_kinematics_v2(joints_position: JointsPosition) Pose

Computes the forward kinematics given joint positions. The end effector pose is given for an end effector frame following the right hand rule and with the z axis pointing forward.

This function is overloaded to accept multiple forms of input:

Parameters:

joints_position (JointsPosition) – the joints position to be used for the forward kinematics computation

Returns:

The pose of the end effector in the robot’s workspace.

Return type:

Pose

get_analog_io_state()
get_available_disk_size()

Get the RPI available space on the SD card :return: the number of MegaBytes available :rtype: int

static get_axis_limits()

Returns the joints and positions min and max values

Returns:

An object containing all the values

Return type:

dict

get_camera_intrinsics()

Gets calibration object: camera intrinsics, distortions coefficients

Returns:

raw camera intrinsics, distortions coefficients

Return type:

(list, list)

get_compressed_image(with_seq=False)

Gets last stream image in a compressed format

Returns:

string containing a JPEG compressed image

Return type:

str

get_conveyors_feedback()

Gives conveyors feedback

Returns:

for each conveyor, its id, connection_state, running, speed and direction

Return type:

list[dict] with the following keys: conveyor_id: ConveyorID, connection_state: bool, speed: int, direction: ConveyorDirection

get_conveyors_number()
get_current_tool_id()

Uses /niryo_robot_tools_commander/current_id topic to get current tool id

Returns:

Tool Id

Return type:

Union[ToolID, int]

get_current_tool_state()

Return the hardware state of the tool :return: the hardware state :rtype: int

get_debug_colors(color)
get_debug_markers()
get_digital_io_mode(pin_id)

Get a digital IO mode

Parameters:

pin_id (str) – the pin id of a digital io

Returns:

The mode of the digital io (Input or Output)

Return type:

PinMode

get_digital_io_state()

Gets Digital IO state : Names, modes, states

Returns:

Infos contains in a IOsState object (see niryo_robot_msgs)

Return type:

IOsState

get_hardware_status()

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

Returns:

Infos contains in a HardwareStatus object (see niryo_robot_msgs)

Return type:

HardwareStatus

get_hardware_version()

Gets the robot hardware version

static get_image_parameters()

Gets 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: 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.

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_joint_names()

Uses /joint_states topic to get the name of the joints

Returns:

list of the name of the joints

Return type:

list[string]

get_joints()

Uses /joint_states topic to get joints status

Returns:

A JointsPosition object containing the joints values

Return type:

JointsPosition

get_learning_mode()

Uses /niryo_robot/learning_mode/state topic subscriber to get learning mode status

Returns:

True if activate else False

Return type:

bool

get_max_velocity_scaling_factor()

Gets the max velocity scaling factor :return: max velocity scaling factor :rtype: Int32

get_pose()

Deprecated since version 5.5.0: You should use get_pose_v2().

Return the legacy pose of the robot (i.e the legacy TCP orientation) Uses /niryo_robot/robot_state topic to get pose status

Returns:

RobotState object (position.x/y/z && rpy.roll/pitch/yaw && orientation.x/y/z/w)

Return type:

RobotState

get_pose_as_list()

Deprecated since version 5.5.0: You should use get_pose_v2_as_list().

Return the legacy pose of the robot (i.e the legacy TCP orientation) as a list Uses /niryo_robot/robot_state topic to get pose status

Returns:

list corresponding to [x, y, z, roll, pitch, yaw]

Return type:

list[float]

get_pose_saved(pose_name: str) Pose

Gets saved pose from robot intern storage Will raise error if position does not exist

Parameters:

pose_name (str) – Pose Name

Returns:

x, y, z, roll, pitch, yaw

Return type:

Pose

get_pose_v2()

Return the pose of the robot (i.e the legacy TCP orientation) Uses /niryo_robot/robot_state_v2 topic to get pose status

Returns:

RobotState object (position.x/y/z && rpy.roll/pitch/yaw && orientation.x/y/z/w)

Return type:

RobotState

get_pose_v2_as_list()

Return the pose of the robot (i.e the legacy TCP orientation) as a list Uses /niryo_robot/robot_state_v2 topic to get pose status

Returns:

list corresponding to [x, y, z, roll, pitch, yaw]

Return type:

list[float]

static get_robot_status()
get_ros_logs_size()

Get the ros logs size on the SD card :return: the size of the ros logs in MB :rtype: int

get_saved_dynamic_frame(frame_name)

Get name, description and pose of a dynamic 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]]

static get_saved_dynamic_frame_list()

Get list of saved dynamic frames

Returns:

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

Return type:

list[str], list[str]

static get_saved_pose_list(with_desc=False)

Asks the pose manager service which positions are available

Parameters:

with_desc (bool) – If True it returns the poses descriptions

Returns:

list of positions name

Return type:

list[str]

static get_saved_trajectory_list() List[str]

Asks the pose trajectory service which trajectories are available

Returns:

list of trajectory name

Return type:

list[str]

get_simulation_mode()

The simulation mode

get_sleep_pose() JointsPosition

Get current robot’s home position

Returns:

the sleep pose

Return type:

JointsPosition

get_software_version()

Get the robot software version

Returns:

rpi_image_version, ros_niryo_robot_version, motor_names, stepper_firmware_versions

Return type:

(str, str, list[str], list[str])

get_target_pose_from_cam(workspace_name, height_offset, shape, color, as_list=False)

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

  • as_list (bool) – whether return the pose as a list or a Pose object

Returns:

object_found, object_pose, object_shape, object_color

Return type:

(bool, RobotState, str, str)

get_target_pose_from_rel(workspace_name, height_offset, x_rel, y_rel, yaw_rel, as_list=False)

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

  • y_rel (float) –

  • yaw_rel (float) –

  • as_list (bool) – whether return the pose as a list or a Pose object

Returns:

target_pose

Return type:

RobotState

get_tcp(as_list=False)

Returns the TCP state :param as_list: True to return the tcp position as a list of float :type as_list: bool :return: the tcp (enabled, position and orientation) :rtype: Tool msg object

get_trajectory_saved(trajectory_name) List[JointsPosition]

Gets saved trajectory from robot intern storage Will raise error if position does not exist

Parameters:

trajectory_name (str) –

Raises:

NiryoRosWrapperException – If trajectory file doesn’t exist

Returns:

list of [x, y, z, qx, qy, qz, qw]

Return type:

list[list[float]]

static get_workspace_list(with_desc=False)

Asks the workspace manager service names of the available workspace

Returns:

list of workspaces name

Return type:

list[str]

get_workspace_poses(name)

Gets the 4 workspace poses of the workspace called ‘name’

Parameters:

name (str) – workspace name

Returns:

List of the 4 workspace poses

Return type:

list[list]

get_workspace_ratio(name)

Gives the length over width ratio of a certain workspace

Parameters:

name (str) – workspace name

Returns:

ratio

Return type:

float

grasp_with_tool(pin_id='')

Grasps with the tool linked to tool_id This action corresponds to - Close gripper for Grippers - Pull Air for Vacuum pump - Activate for Electromagnet

Parameters:

pin_id (PinID) – [Only required for electromagnet] Pin ID of the electromagnet

Returns:

status, message

Return type:

(int, str)

highlight_block(block_id)
classmethod init_with_node(*args, **kwargs)

Initialize a ros node before returning a new instance of the class

inverse_kinematics(x: float, y: float, z: float, roll: float, pitch: float, yaw: float) JointsPosition
inverse_kinematics(pose: Pose) JointsPosition

Deprecated since version 5.6.0: You should use inverse_kinematics_v2().

Computes the inverse kinematics given a pose.

This function is overloaded to accept multiple forms of input:

Parameters:
  • args (tuple) – Variable-length positional arguments. This can be either individual pose components (x, y, z, roll, pitch, yaw) or a single Pose object.

  • kwargs (dict) – Arbitrary keyword arguments.

Returns:

The joint position of the robot.

Return type:

JointsPosition

inverse_kinematics_v2(pose: Pose) JointsPosition

Computes the inverse kinematics given a pose.

This function is overloaded to accept multiple forms of input:

Parameters:
  • pose – Variable-length positional arguments. This can be either individual pose components (x, y, z, roll, pitch, yaw) or a single Pose object.

  • kwargs (dict) – Arbitrary keyword arguments.

Returns:

The joint position of the robot.

Return type:

JointsPosition

jog_joints_shift(shift_values)

Deprecated since version 5.5.0: You should use jog_shift() with a JointsPosition object.

Makes a Jog on joints position

Parameters:

shift_values (list[float]) – list corresponding to the shift to be applied to each joint

Returns:

status, message

Return type:

(int, str)

jog_pose_shift(shift_values)

Deprecated since version 5.5.0: You should use jog_shift() with a Pose object.

Makes a Jog on end-effector position

Parameters:

shift_values (list[float]) – list corresponding to the shift to be applied to the position

Returns:

status, message

Return type:

(int, str)

jog_shift(shift_values: JointsPosition | Pose)

Makes a Jog oof the robot position

Parameters:

shift_values (RobotPosition) – robot position corresponding to the shift to be applied to the current position

Returns:

status, message

Return type:

(int, str)

property led_ring

Manages the LED ring

Example:

from niryo_robot_python_ros_wrapper.ros_wrapper import *
import rospy

rospy.init_node('ros_wrapper_node')
robot = NiryoRosWrapper()
robot.led_ring.solid(color=[255, 255, 255])
Returns:

LedRingRosWrapper API instance

Return type:

LedRingRosWrapper

move(robot_position: Pose, move_cmd: int = ArmMoveCommand.POSE)
move(robot_position: JointsPosition, move_cmd: int = ArmMoveCommand.JOINTS)

Moves the robot end effector to the given goal position. The goal position can be either a joint position or a pose

Parameters:
  • robot_position (Union[Pose, JointsPosition]) – Position of the goal position

  • move_cmd – Command used to move the robot. If not provided, the command will be the basic move (either

joint or pose depending on the robot_position type) :type move_cmd: int :return: status, message :rtype: (int, str)

move_circle(x, y, z)
move_joints(j1, j2, j3, j4, j5, j6)

Deprecated since version 5.5.0: You should use move() with a JointsPosition object.

Executes Move joints action

Parameters:
  • j1 (float) –

  • j2 (float) –

  • j3 (float) –

  • j4 (float) –

  • j5 (float) –

  • j6 (float) –

Returns:

status, message

Return type:

(int, str)

move_linear_pose(x, y, z, roll, pitch, yaw, frame='')

Deprecated since version 5.5.0: You should use move() with a Pose object and move_cmd=ArmMoveCommand.LINEAR_POSE

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

Parameters:
  • x (float) –

  • y (float) –

  • z (float) –

  • roll (float) –

  • pitch (float) –

  • yaw (float) –

  • frame (str) –

Returns:

status, message

Return type:

(int, str)

move_linear_relative(offset, frame='world')

Deprecated since version 5.5.0: You should use move with a frame in the pose metadata and linear=True.

Move robot end of an offset by a linear movement in a 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)

move_pose(x, y, z, roll, pitch, yaw, frame='')

Deprecated since version 5.5.0: You should use move() with a Pose object.

Moves robot end effector pose to a (x, y, z, roll, pitch, yaw) pose, in a particular frame if defined

Parameters:
  • x (float) –

  • y (float) –

  • z (float) –

  • roll (float) –

  • pitch (float) –

  • yaw (float) –

  • frame (str) –

Returns:

status, message

Return type:

(int, str)

move_pose_saved(pose_name)

Moves robot end effector pose to a pose saved

Parameters:

pose_name (str) –

Returns:

status, message

Return type:

(int, str)

move_relative(offset, frame='world')

Deprecated since version 5.5.0: You should use move with a frame in the pose metadata.

Move robot end of an offset in a 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)

move_spiral(radius=0.2, angle_step=5, nb_steps=72, plan=1)

Calls robot action service to draw a spiral trajectory

Parameters:
  • radius – maximum distance between the spiral and the starting point

  • angle_step – rotation between each waypoint creation

  • nb_steps – number of waypoints from the beginning to the end of the spiral

  • plan (int) – xyz plan of the spiral: 1 = yz plan, 2 = xz plan, 3 = xy plan

Returns:

status, message

Return type:

(int, str)

move_to_object(workspace, height_offset, shape, color)

Same as get_target_pose_from_cam but directly moves to this position

Parameters:
  • workspace (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_sleep_pose()

Moves the robot to a predefined home position

Returns:

status, message

Return type:

(int, str)

move_without_moveit(joints_target, duration)
static msg_from_pose(pose: ~niryo_robot_utils.dataclasses.Pose.Pose, msg_type=<class 'niryo_robot_msgs.msg._RobotState.RobotState'>, normalize=True)

Convert a Pose object to a ROS message.

Parameters:
  • pose (Pose) – the pose to convert

  • msg_type (any ROS message which has position and rpy attributes) – the type of the ROS message to create

  • normalize (bool) – whether to normalize the pose before converting it or not. Default is True.

Returns:

ROS message

Return type:

RobotState

open_gripper(speed=500, max_torque_percentage=100, hold_torque_percentage=20)

Opens gripper with a speed ‘speed’

Parameters:
  • speed (int) – Default -> 500

  • max_torque_percentage (int) – Default -> 100

  • hold_torque_percentage (int) – Default -> 20

Returns:

status, message

Return type:

(int, str)

pick(robot_position: JointsPosition | Pose)
pick_and_place(pick_pose: list, place_pose: list, dist_smoothing=0.0)
pick_and_place(pick_pose: JointsPosition | Pose, place_pose: JointsPosition | Pose, dist_smoothing=0.0)

Executes a pick and place. If an error happens during the movement, error will be raised -> Args param is for development purposes

Parameters:
  • pick_pose (list[float]) –

  • place_pose (list[float]) –

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

Returns:

status, message

Return type:

(int, str)

pick_from_pose(x, y, z, roll, pitch, yaw)

Deprecated since version 5.5.0: You should use pick() with a Pose or JointsPosition object instead

Executes a picking from a position. If an error happens during the movement, error will be raised A picking is described as : - going over the object - going down until height = z - grasping with tool - going back over the object

Parameters:
  • x (float) –

  • y (float) –

  • z (float) –

  • roll (float) –

  • pitch (float) –

  • yaw (float) –

Returns:

status, message

Return type:

(int, str)

place(robot_position: JointsPosition | Pose)
place_from_pose(x, y, z, roll, pitch, yaw)

Deprecated since version 5.5.0: You should use place() with a Pose or JointsPosition object instead

Executes a placing from a position. If an error happens during the movement, error will be raised 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:
  • x (float) –

  • y (float) –

  • z (float) –

  • roll (float) –

  • pitch (float) –

  • yaw (float) –

Returns:

status, message

Return type:

(int, str)

static point_to_list(point)
static pose_from_msg(msg) Pose
pull_air_vacuum_pump()

Pulls air

Returns:

status, message

Return type:

(int, str)

push_air_vacuum_pump()

Pulls air

Returns:

status, message

Return type:

(int, str)

static quaternion_to_list(quaternion)
reboot_motors()

Reboots the robots motors

Raises:

NiryoRosWrapperException

Returns:

status, message

Return type:

(int, str)

release_with_tool(pin_id='')

Releases with the tool associated to tool_id This action corresponds to - Open gripper for Grippers - Push Air for Vacuum pump - Deactivate for Electromagnet

Parameters:

pin_id (PinID) – [Only required for electromagnet] Pin ID of the electromagnet

Returns:

status, message

Return type:

(int, str)

request_new_calibration()

Calls service to set the request calibration value. If failed, raises NiryoRosWrapperException

Returns:

status, message

Return type:

(int, str)

reset_sleep_pose()

Reset robot’s home position to factory default

Returns:

status, message

Return type:

(int, str)

reset_tcp()

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

Returns:

status, message

Return type:

(int, str)

property robot_status
save_dynamic_frame_from_points(frame_name, description, list_points, belong_to_workspace=False)

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

Parameters:
  • frame_name (str) – name of the frame

  • description (str) – description of the frame

  • list_points (list[list[float]]) – 3 points needed to create the frame

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

Returns:

status, message

Return type:

(int, str)

save_dynamic_frame_from_poses(frame_name, description, list_robot_poses: List[List[float] | Pose], belong_to_workspace=False)

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

Parameters:
  • frame_name (str) – name of the frame

  • description (str) – description of the frame

  • list_robot_poses (list[list[float]]) – 3 poses needed to create the frame

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

Returns:

status, message

Return type:

(int, str)

save_last_learned_trajectory(trajectory_name, trajectory_description)

Saves trajectory object and sends it to the trajectory manager service

Parameters:
  • trajectory_name (str) – name which will have the trajectory

  • trajectory_description (str) – description which will have the trajectory

Returns:

status, message

Return type:

(int, str)

save_pose(name: str, x: float, y: float, z: float, roll: float, pitch: float, yaw: float)
save_pose(name: str, pose: Pose)

Saves pose in robot’s memory

save_trajectory(trajectory_points, trajectory_name, trajectory_description)

Saves trajectory object and sends it to the trajectory manager service

Parameters:
  • trajectory_points (Union[List[float], JointsPosition]) – list of waypoints that constitute the trajectory

  • trajectory_name (str) – name which will have the trajectory

  • trajectory_description (str) – A short text describing the trajectory

Returns:

status, message

Return type:

(int, str)

save_workspace_from_points(name, list_points_raw)

Saves workspace by giving the poses of its 4 corners in the good order

Parameters:
  • name (str) – workspace name, max 30 char.

  • list_points_raw (list[list[float]]) – list of 4 corners [x, y, z]

Returns:

status, message

Return type:

(int, str)

save_workspace_from_poses(name, list_poses_raw: List[List[float] | Pose])

Saves workspace by giving the poses of the robot to point its 4 corners with the calibration Tip. Corners should be in the good order

Parameters:
  • name (str) – workspace name, max 30 char.

  • list_poses_raw (list[list]) – list of 4 corners pose

Returns:

status, message

Return type:

(int, str)

set_arm_max_acceleration(percentage)

Sets relative max acceleration (in %)

Parameters:

percentage (int) – Percentage of max acceleration

Returns:

status, message

Return type:

(int, str)

set_arm_max_velocity(percentage)

Sets relative max velocity (in %)

Parameters:

percentage (int) – Percentage of max velocity

Returns:

status, message

Return type:

(int, str)

set_brightness(brightness_factor)

Modifies image 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.

Returns:

status, message

Return type:

(int, str)

set_contrast(contrast_factor)

Modifies image 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.

Returns:

status, message

Return type:

(int, str)

set_conveyor()

Scans for conveyor on can bus. If conveyor detected, returns the conveyor ID

Raises:

NiryoRosWrapperException

Returns:

ID

Return type:

ConveyorID

set_jog_use_state(state)

Turns jog controller On or Off

Parameters:

state (bool) – True to turn on, else False

Returns:

status, message

Return type:

(int, str)

set_learning_mode(set_bool)

Calsl service to set_learning_mode according to set_bool. If failed, raises NiryoRosWrapperException

Parameters:

set_bool (bool) – True to activate, False to deactivate

Returns:

status, message

Return type:

(int, str)

set_pin_mode(pin_id, pin_mode)

Sets pin number pin_id to mode pin_mode

Parameters:
  • pin_id (str) –

  • pin_mode (int) –

Returns:

status, message

Return type:

(int, str)

set_saturation(saturation_factor)

Modifies image 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.

Returns:

status, message

Return type:

(int, str)

set_sleep_pose(joints_position: JointsPosition)

Set user defined robot’s home position in the database. Raises NiryoRosWrapperException if the number of joint values does not match the robot’s joints number or if failed.

Parameters:

joints_position (JointsPosition) – joint position of the sleep pose

Returns:

status, message

Return type:

(int, str)

set_tcp(x, y, z, roll, pitch, yaw)

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

Parameters:
  • x (float) –

  • y (float) –

  • z (float) –

  • roll (float) –

  • pitch (float) –

  • yaw (float) –

Returns:

status, message

Return type:

(int, str)

setup_electromagnet(pin_id)

Setups electromagnet on pin

Parameters:

pin_id (PinID) – Pin ID

Returns:

status, message

Return type:

(int, str)

shift_linear_pose(axis, value)

Deprecated since version 5.5.0: You should use shift_pose() with linear=True.

Executes Shift pose action with a linear trajectory

Parameters:
  • axis (ShiftPose) – Value of RobotAxis enum corresponding to where the shift happens

  • value (float) – shift value

Returns:

status, message

Return type:

(int, str)

shift_pose(axis, value, linear=False)

Executes Shift pose action

Parameters:
  • axis (ShiftPose) – Value of RobotAxis enum corresponding to where the shift happens

  • value (float) – shift value

  • linear (bool) – Whether the movement has to be linear or not

Returns:

status, message

Return type:

(int, str)

property sound

Manages sound

Example:

from niryo_robot_python_ros_wrapper.ros_wrapper import *
import rospy

rospy.init_node('ros_wrapper_node')
robot = NiryoRosWrapper()
robot.sound.play(sound.sounds[0])
Returns:

SoundRosWrapper API instance

Return type:

SoundRosWrapper

stop_move()

Stops the robot movement

Returns:

list of joints value

Return type:

list[float]

tool_reboot()

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

Returns:

success, message

Return type:

(bool, str)

unset_conveyor(conveyor_id)

Removes specific conveyor

Parameters:

conveyor_id (ConveyorID) – Basically, ConveyorID.ID_1 or ConveyorID.ID_2

Raises:

NiryoRosWrapperException

Returns:

status, message

Return type:

(int, str)

update_tool()

Calls service niryo_robot_tools_commander/update_tool to update tool

Returns:

status, message

Return type:

(int, str)

update_trajectory_infos(name, new_name, new_description)
vision_pick(workspace_name, height_offset, shape, color, obs_pose: JointsPosition | Pose | None = None)

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

  1. move to the observation pose (if specified)

  2. detects object using the camera

  3. prepares the current tool for picking

  4. approaches the object

  5. moves down to the correct picking pose

  6. actuates the current tool

  7. lifts the object

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

  • obs_pose (RobotPosition) – The observation pose

Returns:

object_found, object_shape, object_color

Return type:

(bool, ObjectShape, ObjectColor)

vision_pick_w_obs_joints(workspace_name, height_offset, shape, color, observation_joints: list | JointsPosition)

Deprecated since version 5.5.0: You should use vision_pick() by setting obs_pose with a JointsPosition object.

Move Joints to observation_joints, then executes a vision pick

vision_pick_w_obs_pose(workspace_name, height_offset, shape, color, observation_pose_list: list | Pose)

Deprecated since version 5.5.0: You should use vision_pick() by setting obs_pose with a Pose object.

Move Pose to observation_pose, then executes a vision pick

static wait(time_sleep)
classmethod wait_for_node_initialization(node_name, timeout=30, sleep_time=0.1)
classmethod wait_for_nodes_initialization(simulation_mode=False)
niryo_robot_python_ros_wrapper.ros_wrapper.move_command(move_function)
class niryo_robot_python_ros_wrapper.ros_wrapper_enums.AutorunMode

Bases: object

DISABLE = 0
LOOP = 2
ONE_SHOT = 1
class niryo_robot_python_ros_wrapper.ros_wrapper_enums.ButtonAction

Bases: object

DOUBLE_PUSH_ACTION = 3
HANDLE_HELD_ACTION = 0
LONG_PUSH_ACTION = 1
NO_ACTION = 100
SINGLE_PUSH_ACTION = 2
class niryo_robot_python_ros_wrapper.ros_wrapper_enums.CommandEnum(value)

Bases: Enum

Enumeration of all commands used

ACTIVATE_ELECTROMAGNET = 126
ANALOG_READ = 156
ANALOG_WRITE = 155
CALIBRATE = 0
CLEAN_TRAJECTORY_MEMORY = 89
CLEAR_COLLISION_DETECTED = 6
CLOSE_GRIPPER = 122
CONTROL_CONVEYOR = 182
CUSTOM_BUTTON_STATE = 158
DEACTIVATE_ELECTROMAGNET = 127
DELETE_DYNAMIC_FRAME = 100
DELETE_POSE = 52
DELETE_SOUND = 243
DELETE_TRAJECTORY = 88
DELETE_WORKSPACE = 222
DETECT_OBJECT = 204
DIGITAL_READ = 152
DIGITAL_WRITE = 151
EDIT_DYNAMIC_FRAME = 99
ENABLE_TCP = 140
EXECUTE_REGISTERED_TRAJECTORY = 82
EXECUTE_TRAJECTORY = 90
EXECUTE_TRAJECTORY_FROM_POSES = 83
EXECUTE_TRAJECTORY_FROM_POSES_AND_JOINTS = 84
FORWARD_KINEMATICS = 27
FORWARD_KINEMATICS_V2 = 31
GET_ANALOG_IO_STATE = 157
GET_CAMERA_INTRINSICS = 210
GET_COLLISION_DETECTED = 5
GET_CONNECTED_CONVEYORS_ID = 183
GET_CONVEYORS_FEEDBACK = 184
GET_CURRENT_TOOL_ID = 128
GET_DIGITAL_IO_STATE = 153
GET_HARDWARE_STATUS = 154
GET_IMAGE_COMPRESSED = 200
GET_IMAGE_PARAMETERS = 235
GET_JOINTS = 10
GET_LEARNING_MODE = 2
GET_POSE = 11
GET_POSE_QUAT = 12
GET_POSE_SAVED = 50
GET_POSE_V2 = 13
GET_SAVED_DYNAMIC_FRAME = 96
GET_SAVED_DYNAMIC_FRAME_LIST = 95
GET_SAVED_POSE_LIST = 53
GET_SAVED_TRAJECTORY_LIST = 81
GET_SOUNDS = 245
GET_SOUND_DURATION = 246
GET_TARGET_POSE_FROM_CAM = 202
GET_TARGET_POSE_FROM_REL = 201
GET_TCP = 146
GET_TRAJECTORY_SAVED = 80
GET_WORKSPACE_LIST = 224
GET_WORKSPACE_RATIO = 223
GRASP_WITH_TOOL = 129
HANDSHAKE = 7
IMPORT_SOUND = 244
INVERSE_KINEMATICS = 28
INVERSE_KINEMATICS_V2 = 32
JOG = 30
JOG_JOINTS = 25
JOG_POSE = 26
LED_RING_ALTERNATE = 253
LED_RING_BREATH = 261
LED_RING_CHASE = 254
LED_RING_CUSTOM = 263
LED_RING_FLASH = 252
LED_RING_GO_UP = 259
LED_RING_GO_UP_DOWN = 260
LED_RING_RAINBOW = 256
LED_RING_RAINBOW_CHASE = 258
LED_RING_RAINBOW_CYCLE = 257
LED_RING_SET_LED = 264
LED_RING_SNAKE = 262
LED_RING_SOLID = 250
LED_RING_TURN_OFF = 251
LED_RING_WIPE = 255
MOVE = 29
MOVE_JOINTS = 20
MOVE_LINEAR_POSE = 23
MOVE_LINEAR_RELATIVE = 102
MOVE_POSE = 21
MOVE_RELATIVE = 101
MOVE_TO_OBJECT = 205
OPEN_GRIPPER = 121
PICK = 63
PICK_AND_PLACE = 62
PICK_FROM_POSE = 60
PLACE = 64
PLACE_FROM_POSE = 61
PLAY_SOUND = 240
PULL_AIR_VACUUM_PUMP = 123
PUSH_AIR_VACUUM_PUMP = 124
RELEASE_WITH_TOOL = 130
RESET_TCP = 142
SAVE_DYNAMIC_FRAME_FROM_POINTS = 98
SAVE_DYNAMIC_FRAME_FROM_POSES = 97
SAVE_LAST_LEARNED_TRAJECTORY = 86
SAVE_POSE = 51
SAVE_TRAJECTORY = 85
SAVE_WORKSPACE_FROM_POINTS = 221
SAVE_WORKSPACE_FROM_POSES = 220
SAY = 247
SETUP_ELECTROMAGNET = 125
SET_ARM_MAX_VELOCITY = 3
SET_CONVEYOR = 180
SET_IMAGE_BRIGHTNESS = 230
SET_IMAGE_CONTRAST = 231
SET_IMAGE_SATURATION = 232
SET_JOG_CONTROL = 4
SET_LEARNING_MODE = 1
SET_PIN_MODE = 150
SET_TCP = 141
SET_VOLUME = 241
SHIFT_LINEAR_POSE = 24
SHIFT_POSE = 22
STOP_SOUND = 242
TOOL_REBOOT = 145
UNSET_CONVEYOR = 181
UPDATE_TOOL = 120
UPDATE_TRAJECTORY_INFOS = 87
VISION_PICK = 203
class niryo_robot_python_ros_wrapper.ros_wrapper_enums.ConveyorCan(value)

Bases: Enum

ConveyorID to control conveyors with CAN interface

ID_1 = 12
ID_2 = 13
NONE = 0
class niryo_robot_python_ros_wrapper.ros_wrapper_enums.ConveyorDirection

Bases: object

BACKWARD = -1
FORWARD = 1
class niryo_robot_python_ros_wrapper.ros_wrapper_enums.ConveyorID(value)

Bases: Enum

ConveyorID to be able to have CAN (id 12 and 13) and TTL (id 9 and 10) conveyor in any possible combination

ID_1 = 12 # One, Ned ID_2 = 13 # One, Ned ID_3 = 9 # Ned2 ID_4 = 10 # Ned2

ID_1 = -1
ID_2 = -2
NONE = 0
class niryo_robot_python_ros_wrapper.ros_wrapper_enums.ConveyorTTL(value)

Bases: Enum

ConveyorID to control conveyors with TTL interface

ID_1 = 9
ID_2 = 10
NONE = 0
class niryo_robot_python_ros_wrapper.ros_wrapper_enums.ObjectColor

Bases: object

ANY = 'ANY'
BLUE = 'BLUE'
GREEN = 'GREEN'
RED = 'RED'
class niryo_robot_python_ros_wrapper.ros_wrapper_enums.ObjectShape

Bases: object

ANY = 'ANY'
CIRCLE = 'CIRCLE'
SQUARE = 'SQUARE'
class niryo_robot_python_ros_wrapper.ros_wrapper_enums.PinID

Bases: object

Pins ID

AI1 = 'AI1'
AI2 = 'AI2'
AO1 = 'AO1'
AO2 = 'AO2'
DI1 = 'DI1'
DI2 = 'DI2'
DI3 = 'DI3'
DI4 = 'DI4'
DI5 = 'DI5'
DO1 = 'DO1'
DO2 = 'DO2'
DO3 = 'DO3'
DO4 = 'DO4'
GPIO_1A = '1A'
GPIO_1B = '1B'
GPIO_1C = '1C'
GPIO_2A = '2A'
GPIO_2B = '2B'
GPIO_2C = '2C'
SW_1 = 'SW1'
SW_2 = 'SW2'
class niryo_robot_python_ros_wrapper.ros_wrapper_enums.PinMode

Bases: object

Pin Mode is either OUTPUT or INPUT

INPUT = 1
OUTPUT = 0
class niryo_robot_python_ros_wrapper.ros_wrapper_enums.PinState

Bases: object

Pin State is either LOW or HIGH

HIGH = True
LOW = False
class niryo_robot_python_ros_wrapper.ros_wrapper_enums.ProgramLanguage

Bases: object

ALL = 0
BLOCKLY = 66
NONE = -1
PYTHON2 = 1
PYTHON3 = 2
class niryo_robot_python_ros_wrapper.ros_wrapper_enums.ShiftPose

Bases: object

AXIS_X = 0
AXIS_Y = 1
AXIS_Z = 2
ROT_PITCH = 4
ROT_ROLL = 3
ROT_YAW = 5
class niryo_robot_python_ros_wrapper.ros_wrapper_enums.ToolID

Bases: object

Tools IDs (need to match tools ids in niryo_robot_tools_commander package)

ELECTROMAGNET_1 = 30
GRIPPER_1 = 11
GRIPPER_2 = 12
GRIPPER_3 = 13
GRIPPER_4 = 14
NONE = 0
VACUUM_PUMP_1 = 31
VACUUM_PUMP_2 = 32

Data Classes

class niryo_robot_utils.dataclasses.JointsPosition.JointsPosition(*joints: float, metadata: JointsPositionMetadata | None = None)

Bases: ABCSerializable

classmethod from_dict(d) JointsPosition

Creates a new JointsPosition object from a dictionary representing the object.

Parameters:

d (dict) – A dictionary representing the object.

insert(index: int, value: float)
to_dict() Dict[str, Any]
to_list() List[int]
class niryo_robot_utils.dataclasses.Pose.Pose(x: float, y: float, z: float, roll: float, pitch: float, yaw: float, metadata: PoseMetadata | None = None)

Bases: ABCSerializable

convert_to_dh_convention() None
convert_to_meters() None
classmethod from_dict(d: Dict) Pose
normalize() None
quaternion() Tuple[float, float, float, float]
to_dict() Dict
to_list() List[float]

Tools

For more informations, please refer to: Niryo robot tools commander

class niryo_robot_tools_commander.api.tools_ros_wrapper.ToolsRosWrapper(service_timeout=0.2)

Bases: AbstractNiryoRosWrapper

activate_electromagnet(pin_id)

Activates electromagnet associated to electromagnet_id on pin_id

Parameters:

pin_id (PinID) – Pin ID

Returns:

status, message

Return type:

(int, str)

close_gripper(speed=500, max_torque_percentage=100, hold_torque_percentage=50)

Closes gripper with a speed ‘speed’

Parameters:
  • speed (int) – Default -> 500

  • max_torque_percentage (int) – Default -> 100

  • hold_torque_percentage (int) – Default -> 20

Returns:

status, message

Return type:

(int, str)

deactivate_electromagnet(pin_id)

Deactivates electromagnet associated to electromagnet_id on pin_id

Parameters:

pin_id (PinID) – Pin ID

Returns:

status, message

Return type:

(int, str)

enable_tcp(enable=True)

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.

Returns:

status, message

Return type:

(int, str)

get_current_tool_id()

Uses /niryo_robot_tools_commander/current_id topic to get current tool id

Returns:

Tool Id

Return type:

ToolID

get_tcp()

Returns the TCP state :return: the tcp (enabled, position and orientation) :rtype: Tool msg object

grasp_with_tool(pin_id='')

Grasps with the tool linked to tool_id. This action corresponds to - Close gripper for Grippers - Pull Air for Vacuum pump - Activate for Electromagnet

Parameters:

pin_id (PinID) – [Only required for electromagnet] Pin ID of the electromagnet

Returns:

status, message

Return type:

(int, str)

open_gripper(speed=500, max_torque_percentage=100, hold_torque_percentage=20)

Opens gripper with a speed ‘speed’

Parameters:
  • speed (int) – Default -> 500

  • max_torque_percentage (int) – Default -> 100

  • hold_torque_percentage (int) – Default -> 20

Returns:

status, message

Return type:

(int, str)

pull_air_vacuum_pump()

Pulls air

Returns:

status, message

Return type:

(int, str)

push_air_vacuum_pump()

Pulls air

Returns:

status, message

Return type:

(int, str)

release_with_tool(pin_id='')

Releases with the tool associated to tool_id. This action corresponds to - Open gripper for Grippers - Push Air for Vacuum pump - Deactivate for Electromagnet

Parameters:

pin_id (PinID) – [Only required for electromagnet] Pin ID of the electromagnet

Returns:

status, message

Return type:

(int, str)

reset_tcp()

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

Returns:

status, message

Return type:

(int, str)

set_tcp(x, y, z, roll, pitch, yaw)

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

Parameters:
  • x (float) –

  • y (float) –

  • z (float) –

  • roll (float) –

  • pitch (float) –

  • yaw (float) –

Returns:

status, message

Return type:

(int, str)

setup_electromagnet(pin_id)

Setups electromagnet on pin

Parameters:

pin_id (PinID) – Pin ID

Returns:

status, message

Return type:

(int, str)

tool_reboot()

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

Returns:

status, message

Return type:

(int, str)

update_tool()

Calls service niryo_robot_tools_commander/update_tool to update tool

Returns:

status, message

Return type:

(int, str)

class niryo_robot_tools_commander.api.tools_ros_wrapper_enums.ToolID

Bases: object

Tools IDs (need to match tools ids in niryo_robot_tools_commander package)

ELECTROMAGNET_1 = 30
GRIPPER_1 = 11
GRIPPER_2 = 12
GRIPPER_3 = 13
GRIPPER_4 = 14
NONE = 0
VACUUM_PUMP_1 = 31
VACUUM_PUMP_2 = 32

Database

For more informations, please refer to: Niryo robot database

class niryo_robot_database.api.database_ros_wrapper.DatabaseRosWrapper(service_timeout=1)

Bases: object

get_setting(name)

Retrieve a setting from the database

Example

database.get_setting('purge_ros_logs_on_startup')
Parameters:

name (str) – the name of the setting

Returns:

the value of the setting

Return type:

object

set_setting(name, value)

Set a setting in the database

Example

database.set_setting('purge_ros_logs_on_startup', True)
Parameters:
  • name (str) – the name of a setting

  • value (object) – the value of the setting

Returns:

status, message

Return type:

(int, str)

exception niryo_robot_database.api.database_ros_wrapper.DatabaseRosWrapperException

Bases: Exception

Sound

For more informations, please refer to: Niryo robot sound

class niryo_robot_sound.api.sound_ros_wrapper.SoundRosWrapper(hardware_version='ned2', service_timeout=1)

Bases: object

property current_sound

Get the current sound being played

Returns:

current sound name

Return type:

Optional[str]

delete_sound(sound_name)

Delete a sound on the RaspberryPi of the robot. If failed, raise NiryoRosWrapperException

Parameters:

sound_name (str) – name of the sound which needs to be deleted

Returns:

status, message

Return type:

(int, str)

get_sound_duration(sound_name)

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

Parameters:

sound_name (str) – name of sound

Returns:

sound duration in seconds

Return type:

float

property hardware_version
import_sound(sound_name, sound_data)

Delete a sound on the RaspberryPi of the robot. If failed, raise NiryoRosWrapperException

Parameters:
  • sound_name (str) – name of the sound which needs to be deleted

  • sound_data (str) – String containing the encoded data of the sound file (wav or mp3)

Returns:

status, message

Return type:

(int, str)

play(sound_name, wait_end=True, start_time_sec=0, end_time_sec=0)

Play a sound from the robot If failed, raise NiryoRosWrapperException

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

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

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

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

Returns:

status, message

Return type:

(int, str)

say(text, language=0)

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

Parameters:
  • text (string) – text to speek < 100 char

  • language (int) – language of the text

Returns:

status, message

Return type:

(int, str)

set_volume(sound_volume)

Set the volume percentage of the robot. If failed, raise NiryoRosWrapperException

Parameters:

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

Returns:

status, message

Return type:

(int, str)

property sounds

Get sound name list

Returns:

list of the sounds of the robot

Return type:

list[string]

stop()

Stop a sound being played. If failed, raise NiryoRosWrapperException

Returns:

status, message

Return type:

(int, str)

exception niryo_robot_sound.api.sound_ros_wrapper.SoundRosWrapperException

Bases: Exception

niryo_robot_sound.api.sound_ros_wrapper.check_ned2_version(func)

Decorator that check the robot version

Led Ring

For more informations, please refer to: Niryo robot led ring

class niryo_robot_led_ring.api.led_ring_ros_wrapper.LedRingRosWrapper(hardware_version='ned2', service_timeout=1)

Bases: object

alternate(color_list, period=0, iterations=0, wait=False)

Several colors are alternated one after the other.

Examples:

from std_msgs.msg import ColorRGBA

color_list = [
    ColorRGBA(r=15, g=50, b=255),
    [255, 0, 0],
    [0, 255, 0],
]

led_ring.alternate(color_list)
led_ring.alternate(color_list, 1, 100, True)
led_ring.alternate(color_list, iterations=20, wait=True)
Parameters:
  • color_list (list[list[float] or ColorRGBA]) – Led color list of lists of size 3[R, G, B] or ColorRGBA objects. 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)

property animation_mode

Get the current animation mode of the Led Ring. :return: The current animation mode. One of LedRingAnimation values. :rtype: int

breath(color, period=0, iterations=0, wait=False)

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

Examples:

from std_msgs.msg import ColorRGBA

led_ring.breath(ColorRGBA(r=15, g=50, b=255))
led_ring.breath([15, 50, 255], 1, 100, True)
led_ring.breath(ColorRGBA(r=15, g=50, b=255), iterations=20, wait=True)
Parameters:
  • color (list[float] or ColorRGBA) – Led color in a list of size 3[R, G, B] or in an ColorRGBA object. 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)

chase(color, period=0, iterations=0, wait=False)

Movie theater light style chaser animation.

Examples:

from std_msgs.msg import ColorRGBA

led_ring.chase(ColorRGBA(r=15, g=50, b=255))
led_ring.chase([15, 50, 255], 1, 100, True)
led_ring.chase(ColorRGBA(r=15, g=50, b=255), iterations=20, wait=True)
Parameters:
  • color (list or ColorRGBA) – Led color in a list of size 3[R, G, B] or in an ColorRGBA object. 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)

property color

Get the current color of the Led Ring. :return: The current color of the Led Ring in RGB format. :rtype: list(int, int, int)

custom(led_colors)

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)]
led_ring.custom(led_list)
Parameters:

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

Returns:

status, message

Return type:

(int, str)

flashing(color, period=0, iterations=0, wait=False)

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

Examples:

from std_msgs.msg import ColorRGBA

led_ring.flashing([15, 50, 255])
led_ring.flashing([15, 50, 255], 1, 100, True)
led_ring.flashing([15, 50, 255], iterations=20, wait=True)

frequency = 20  # Hz
total_duration = 10 # seconds
led_ring.flashing(ColorRGBA(r=15, g=50, b=255), 1./frequency, total_duration * frequency , True)
Parameters:
  • color (list[float] or ColorRGBA) – Led color in a list of size 3[R, G, B] or in an ColorRGBA object. 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)

go_up(color, period=0, iterations=0, wait=False)

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

Examples:

from std_msgs.msg import ColorRGBA

led_ring.go_up(ColorRGBA(r=15, g=50, b=255))
led_ring.go_up([15, 50, 255], 1, 100, True)
led_ring.go_up(ColorRGBA(r=15, g=50, b=255), iterations=20, wait=True)
Parameters:
  • color (list[float] or ColorRGBA) – Led color in a list of size 3[R, G, B] or in an ColorRGBA object. 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)

go_up_down(color, period=0, iterations=0, wait=False)

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

Examples:

from std_msgs.msg import ColorRGBA

led_ring.go_up_down(ColorRGBA(r=15, g=50, b=255))
led_ring.go_up_down([15, 50, 255], 1, 100, True)
led_ring.go_up_down(ColorRGBA(r=15, g=50, b=255), iterations=20, wait=True)
Parameters:
  • color (list[float] or ColorRGBA) – Led color in a list of size 3[R, G, B] or in an ColorRGBA object. 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)

property hardware_version
property is_autonomous

Return whether the led ring is in autonomous mode or not. :return: True if the led ring is in autonomous mode, False otherwise. :rtype: bool

rainbow(period=0, iterations=0, wait=False)

Draws rainbow that fades across all LEDs at once.

Examples:

led_ring.rainbow()
led_ring.rainbow(5, 2, True)
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)

rainbow_chase(period=0, iterations=0, wait=False)

Rainbow chase animation, like the led_ring_chase method.

Examples:

led_ring.rainbow_chase()
led_ring.rainbow_chase(5, 2, True)
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)

rainbow_cycle(period=0, iterations=0, wait=False)

Draws rainbow that uniformly distributes itself across all LEDs.

Examples:

led_ring.rainbow_cycle()
led_ring.rainbow_cycle(5, 2, True)
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)

set_led_color(led_id, color)

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

Example:

from std_msgs.msg import ColorRGBA

led_ring.set_led_color(5, [15, 50, 255])
led_ring.set_led_color(5, ColorRGBA(r=15, g=50, b=255))
Parameters:
  • led_id (int) – Id of the led: between 0 and 29

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

Returns:

status, message

Return type:

(int, str)

set_user_animation(animation_mode, colors, period=0, iterations=0, wait_end=False)

Low level function to set an animation on the Led Ring. Prefer using the high level functions.

Parameters:
  • animation_mode (int) – Animation mode to set. One of LedRingAnimation values.

  • colors (list[list[float] or ColorRGBA]) – List of colors for the animation. 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 animations. If 0, the animation continues endlessly.

  • wait_end (bool) – Wait for the end of the animation before exiting the function.

Returns:

status, message

Return type:

(int, str)

snake(color, period=0, iterations=0, wait=False)

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

Examples:

from std_msgs.msg import ColorRGBA

led_ring.snake(ColorRGBA(r=15, g=50, b=255))
led_ring.snake([15, 50, 255], 1, 100, True)
led_ring.snake(ColorRGBA(r=15, g=50, b=255), iterations=20, wait=True)
Parameters:
  • color (list[float] or ColorRGBA) – Led color in a list of size 3[R, G, B] or in an ColorRGBA object. 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)

solid(color, wait=False)

Sets the whole Led Ring to a fixed color.

Example:

from std_msgs.msg import ColorRGBA

led_ring.solid([15, 50, 255])
led_ring.solid(ColorRGBA(r=15, g=50, b=255), True)
Parameters:
  • color (list[float] or ColorRGBA) – Led color in a list of size 3[R, G, B] or in an ColorRGBA object. RGB channels from 0 to 255.

  • wait (bool) – The service wait for the animation to finish or not to answer. For this method, the action is quickly done, so waiting doesn’t take a lot of time.

Returns:

status, message

Return type:

(int, str)

turn_off(wait=False)

Turns off all Leds

Example:

led_ring.turn_off()
Parameters:

wait (bool) – The service wait for the animation to finish or not to answer. For this method, the action is quickly done, so waiting doesn’t take a lot of time.

Returns:

status, message

Return type:

(int, str)

wipe(color, period=0, wait=False)

Wipes a color across the LED Ring, light a LED at a time.

Examples:

from std_msgs.msg import ColorRGBA

led_ring.wipe(ColorRGBA(r=15, g=50, b=255))
led_ring.wipe([15, 50, 255], 1, True)
led_ring.wipe(ColorRGBA(r=15, g=50, b=255), wait=True)
Parameters:
  • color (list[float] or ColorRGBA) – Led color in a list of size 3[R, G, B] or in an ColorRGBA object. 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)

exception niryo_robot_led_ring.api.led_ring_ros_wrapper.LedRingRosWrapperException

Bases: Exception

niryo_robot_led_ring.api.led_ring_ros_wrapper.check_ned2_version(func)

Decorator that check the robot version

Robot Status

For more informations, please refer to: Niryo robot status

class niryo_robot_status.api.robot_status_ros_wrapper.RobotStatusRosWrapper(service_timeout=1)

Bases: object

prepare_update()
reboot()
shutdown()
exception niryo_robot_status.api.robot_status_ros_wrapper.RobotStatusRosWrapperException

Bases: Exception

Custom Button

class niryo_robot_python_ros_wrapper.custom_button_ros_wrapper.CustomButtonRosWrapper(hardware_version='ned2')

Bases: object

get_and_wait_press_duration(timeout=0)

Waits for the button to be pressed and returns the press time. Returns 0 if no press is detected after the timeout duration.

Return type:

float

property hardware_version
is_pressed()

Button press state

Return type:

bool

property state

Get the button state from the ButtonAction class

Returns:

int value from the ButtonAction class

Return type:

int

wait_for_action(action, timeout=0)

Waits until a specific action occurs and returns true. Returns false if the timeout is reached.

Parameters:

action (int) – int value from the ButtonAction class

Returns:

True if the action has occurred, false otherwise

Return type:

bool

wait_for_any_action(timeout=0)

Returns the detected action. Returns ButtonAction.NO_ACTION if the timeout is reached without action.

Returns:

Returns the detected action, or ButtonAction.NO_ACTION if the timeout is reached without any action.

Return type:

int

exception niryo_robot_python_ros_wrapper.custom_button_ros_wrapper.CustomButtonRosWrapperException

Bases: Exception

niryo_robot_python_ros_wrapper.custom_button_ros_wrapper.check_ned2_version(func)

Decorator that check the robot version