Tools Interface

This package handles Niryo’s tools.

Tools interface node (For Development and Debugging)

The ROS Node is made to:
  • Initialize Tool Interface with configuration parameters.
  • Start ROS stuffs like services, topics.

Tools Interface Core

It is instantiated in Niryo Robot Hardware Interface package.

It has been conceived to:
  • Initialize the Tool Interface.
  • Provide services for setting and controlling tools.
  • Publish tool connection state.

It belongs to the ROS namespace: /tools_interface/.

Tool Interface’s default Parameters

default.yaml
Name Description
check_tool_connection_frequency
The frequency where tool interface check and publish the state of the tool connected,
or remove tool if it is disconnected.
Default: ‘2.0’

Tool Interface’s hardware specific Parameters

These parameters are specific to the hardware version (Ned, One or Ned2). This file comes in a different version for each hardware version, located in a directory of the hardware version name.

tools_params.yaml
Name Description Supported Hardware versions
id_list
List of default IDs of each tool supported by Niryo
Default: ‘[11,12,13,30,31]’
All Versions
type_list
List of motor tools type
Default: ‘xl320’ for NED and ONE
Default: ‘xl330’ for NED2
Default: ‘fakeDxl’ for simulation
All Versions
name_list
List of tools’s name corresponds to ID list and type list above
Default: ‘[“Standard Gripper”, “Large Gripper”, “Adaptive Gripper”, “Vacuum Pump”, “Electromagnet”]’
All Versions

Services, Topics and Messages

Published topics

Tools Interface’s Published Topics
Name Message Type Description
/niryo_robot_hardware/tools/current_id std_msgs/Int32 Current tool ID

Services

Tool Interface Package Services
Name Message Type Description
niryo_robot/tools/ping_and_set_dxl_tool tools_interface/PingDxlTool Scans and sets for a tool plugged
niryo_robot/tools/open_gripper tools_interface/OpenGripper Opens the gripper
niryo_robot/tools/close_gripper tools_interface/OpenGripper Closes the gripper
niryo_robot/tools/pull_air_vacuum_pump tools_interface/OpenGripper Pulls air with the vacuum pump
niryo_robot/tools/push_air_vacuum_pump tools_interface/OpenGripper Pushes air with the vacuum pump
niryo_robot/tools/reboot std_srvs/Trigger Reboots the motor of the equipped tool

PingDxlTool (Service)

---
int8 state
tools_interface/Tool tool

ToolCommand (Service)

uint8 id

uint16 position
uint16 speed
int16 hold_torque
int16 max_torque
---
uint8 state