Tool

This file presents the different Tool - Command Functions, Tool - Enums & Tool - Niryo Topics available with the Tool API

Tool - Command Functions

This section reference all existing functions to control your robot, which include

  • Using tools

  • Using grippers

  • Using the vacuum pump

  • Using the electromagnet

  • Management of the TCP

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

robot = NiryoRobot(<robot_ip_address>)

robot.tool.update_tool()
robot.tool.grasp_with_tool()
robot.tool.release_with_tool()
...

See examples on Examples Section

List of functions subsections:

class Tool(client)[source]

Tool robot functions

Example:

ros_instance = NiryoRos("10.10.10.10") # Hotspot
tool_interface = Tool(ros_instance)
Parameters

client (NiryoRos) – Niryo ROS client

Tool functions

Tool.update_tool(callback=None, errback=None, timeout=None)[source]

Update equipped tool

Examples:

# Synchronous use
tool.update_tool()

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

tool.update_tool(update_tool_callback)
Parameters
  • callback (function) – Callback invoked on successful execution.

  • errback (function) – Callback invoked on error.

  • timeout – Timeout for the operation, in seconds. Only used if blocking.

Return type

None

property Tool.tool
Returns

The equipped tool ID

Return type

ToolID

property Tool.get_current_tool_id

Returns the equipped tool Id client which can be used synchronously or asynchronously to obtain the equipped tool Id. The topic returns a attribute of the ToolID enum.

Examples:

# Get last value
tool.get_current_tool_id()
tool.get_current_tool_id.value

# Subscribe a callback
def tool_id_callback(tool_id_object):
    print tool_id_object

tool.get_current_tool_id.subscribe(tool_id_callback)
tool.get_current_tool_id.unsubscribe()
Returns

the equipped tool Id topic instance.

Return type

NiryoTopic

Tool.grasp_with_tool(callback=None)[source]

Grasp with tool This action correspond to * Close gripper for Grippers * Pull Air for Vacuum pump * Activate for Electromagnet If a callback function is not passed in parameter, the function will be blocking. Otherwise, the callback will be called when the execution of the function is finished.

Examples:

tool.update_tool()
tool.grasp_with_tool()

def tool_callback(_msg)
    print("Grasped") 

tool.grasp_with_tool(callback=tool_callback)
Parameters

callback (function) – Callback invoked on successful execution.

Return type

None

Tool.release_with_tool(callback=None)[source]

Release with tool This action correspond to * Open gripper for Grippers * Push Air for Vacuum pump * Deactivate for Electromagnet If a callback function is not passed in parameter, the function will be blocking. Otherwise, the callback will be called when the execution of the function is finished.

Examples:

tool.update_tool()
tool.release_with_tool()

def tool_callback(_msg)
    print("Released")

tool.release_with_tool(callback=tool_callback)
Parameters

callback (function) – Callback invoked on successful execution.

Return type

None

Grippers functions

Tool.open_gripper(speed=500, max_torque_percentage=100, hold_torque_percentage=30, callback=None)[source]

Open gripper associated to the equipped gripper. If a callback function is not passed in parameter, the function will be blocking. Otherwise, the callback will be called when the execution of the function is finished.

Examples:

tool.update_tool()
tool.open_gripper()

# Niryo One and Ned
tool.open_gripper(speed=850)

# Ned2
tool.open_gripper(max_torque_percentage=100, hold_torque_percentage=50)

def tool_callback(_msg)
    print("Released")

tool.open_gripper(callback=tool_callback)
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)

  • callback (function) – Callback invoked on successful execution.

Return type

None

Tool.close_gripper(speed=500, max_torque_percentage=100, hold_torque_percentage=30, callback=None)[source]

Close gripper associated to ‘gripper_id’ with a speed ‘speed’ If a callback function is not passed in parameter, the function will be blocking. Otherwise, the callback will be called when the execution of the function is finished.

Examples:

tool.update_tool()
tool.close_gripper()

# Niryo One and Ned
tool.close_gripper(speed=850)

# Ned2
tool.close_gripper(max_torque_percentage=100, hold_torque_percentage=50)

def tool_callback(_msg)
    print("Grasped")

tool.close_gripper(callback=tool_callback)
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)

  • callback (function) – Callback invoked on successful execution.

Return type

None

Vacuum pump functions

Tool.pull_air_vacuum_pump(callback=None)[source]

Pull air of vacuum pump If a callback function is not passed in parameter, the function will be blocking. Otherwise, the callback will be called when the execution of the function is finished.

Examples:

tool.update_tool()
tool.pull_air_vacuum_pump()

def tool_callback(_msg)
    print("Grasped")

tool.pull_air_vacuum_pump(callback=tool_callback)
Parameters

callback (function) – Callback invoked on successful execution.

Return type

None

Tool.push_air_vacuum_pump(callback=None)[source]

Push air of vacuum pump If a callback function is not passed in parameter, the function will be blocking. Otherwise, the callback will be called when the execution of the function is finished.

Examples:

tool.update_tool()
tool.push_air_vacuum_pump()

def tool_callback(_msg)
    print("Released")

tool.push_air_vacuum_pump(callback=tool_callback)
Parameters

callback (function) – Callback invoked on successful execution.

Return type

None

Electromagnet functions

Tool.setup_electromagnet(pin_id)[source]

Setup electromagnet on pin

Example:

tool.setup_electromagnet(PinID.GPIO_1A)
Parameters

pin_id (PinID) –

Return type

None

Tool.activate_electromagnet(pin_id=None, callback=None)[source]

Activate electromagnet associated to electromagnet_id on pin_id If a callback function is not passed in parameter, the function will be blocking. Otherwise, the callback will be called when the execution of the function is finished.

Examples:

tool.setup_electromagnet(PinID.GPIO_1A)
tool.activate_electromagnet()
tool.activate_electromagnet(PinID.GPIO_1A)

def tool_callback(_msg)
    print("Grasped") 

tool.activate_electromagnet(callback=tool_callback)
Parameters
  • pin_id (PinID) –

  • callback (function) – Callback invoked on successful execution.

Return type

None

Tool.deactivate_electromagnet(pin_id=None, callback=None)[source]

Deactivate electromagnet associated to electromagnet_id on pin_id If a callback function is not passed in parameter, the function will be blocking. Otherwise, the callback will be called when the execution of the function is finished.

Examples:

tool.setup_electromagnet(PinID.GPIO_1A)
tool.deactivate_electromagnet()
tool.deactivate_electromagnet(PinID.GPIO_1A)

def tool_callback(_msg)
    print("Deactivated")

tool.deactivate_electromagnet(callback=tool_callback)
Parameters
  • pin_id (PinID) –

  • callback (function) – Callback invoked on successful execution.

Return type

None

TCP functions

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

Tool.set_tcp(*args)[source]

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

Examples:

tool.set_tcp(0.02, 0.0, 0.03, 0.0, 1.57, 0.0)
tool.set_tcp([0.02, 0.0, 0.03, 0.0, 1.57, 0.0])
tool.set_tcp(PoseObject(0.02, 0.0, 0.03, 0.0, 1.57, 0.0))
Parameters

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

Return type

None

Tool.reset_tcp()[source]

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

Return type

None

Tool - Niryo Topics

The use of these functions is explained in the NiryoTopic section. They allow the acquisition of data in real time by callbacks or by direct call.

Tool’s Niryo Topics

Name

Function

Return type

/niryo_robot_tools_commander/current_id

get_current_tool_id

ToolID

Tool - Enums

List of enums:

  • ToolID

  • ToolCommand

class ToolID(value)[source]

Enumeration of Tools IDs

NONE = 0
GRIPPER_1 = 11
GRIPPER_2 = 12
GRIPPER_3 = 13
GRIPPER_4 = 14
ELECTROMAGNET_1 = 30
VACUUM_PUMP_1 = 31
class ToolCommand(value)[source]

An enumeration.

OPEN_GRIPPER = 1
CLOSE_GRIPPER = 2
PULL_AIR_VACUUM_PUMP = 10
PUSH_AIR_VACUUM_PUMP = 11
SETUP_DIGITAL_IO = 20
ACTIVATE_DIGITAL_IO = 21
DEACTIVATE_DIGITAL_IO = 22