Common interfaces
The Niryo robot msgs package
This package is used to define custom shared Niryo ROS interfaces.
ROS messages
Name |
Definition |
---|---|
float64 x
float64 y
float64 z
float64 roll
float64 pitch
float64 yaw
|
|
geometry_msgs/Point position
niryo_robot_msgs/RPY rpy
geometry_msgs/Quaternion orientation
geometry_msgs/Twist twist
float64 tcp_speed
|
|
int32 val
# overall behavior
int32 SUCCESS = 1
int32 CANCELLED = 2
int32 PREEMPTED = 3
int32 REJECTED = 4
int32 NO_CONNECTION = 5
int32 GOAL_TIMEOUT = 6
int32 FAILURE = -1
int32 ABORTED = -3
int32 STOPPED = -4
int32 BAD_HARDWARE_VERSION = -10
int32 ROS_ERROR = -20
int32 FILE_ALREADY_EXISTS = -30
int32 FILE_NOT_FOUND = -31
int32 UNKNOWN_COMMAND = -50
int32 NOT_IMPLEMENTED_COMMAND = -51
int32 INVALID_PARAMETERS = -52
# - Hardware
int32 HARDWARE_FAILURE = -110
int32 HARDWARE_NOT_OK = -111
int32 LEARNING_MODE_ON = -112
int32 CALIBRATION_NOT_DONE = -113
int32 DIGITAL_IO_PANEL_ERROR = -114
int32 LED_MANAGER_ERROR = -115
int32 BUTTON_ERROR = -116
int32 WRONG_MOTOR_TYPE = -117
int32 TTL_WRITE_ERROR = -118
int32 TTL_READ_ERROR = -119
int32 CAN_WRITE_ERROR = -120
int32 CAN_READ_ERROR = -121
int32 NO_CONVEYOR_LEFT = -122
int32 NO_CONVEYOR_FOUND = -123
int32 CONVEYOR_ID_INVALID = -124
int32 CALIBRATION_IN_PROGRESS = -125
int32 HARDWARE_NOT_SUPPORTED = -126
# - Vision
int32 VIDEO_STREAM_ON_OFF_FAILURE = -170
int32 VIDEO_STREAM_NOT_RUNNING = -171
int32 OBJECT_NOT_FOUND = -172
int32 MARKERS_NOT_FOUND = -173
# - Commander
# Arm Commander
int32 ARM_COMMANDER_FAILURE = -220
int32 GOAL_STILL_ACTIVE = -221
int32 JOG_CONTROLLER_ENABLED = -222
int32 CONTROLLER_PROBLEMS = -223
int32 SHOULD_RESTART = -224
int32 JOG_CONTROLLER_FAILURE = -225
int32 COLLISION = -226
int32 PAUSE_TIMEOUT= -227
int32 CANCEL_PAUSE= -228
int32 PLAN_FAILED = -230
int32 NO_PLAN_AVAILABLE = -231
int32 INVERT_KINEMATICS_FAILURE = -232
int32 FORWARD_KINEMATICS_FAILURE = -233
# Tool Commander
int32 TOOL_FAILURE = -251
int32 TOOL_ID_INVALID = -252
int32 TOOL_NOT_CONNECTED = -253
int32 TOOL_ROS_INTERFACE_ERROR = -254
# - Pose Handlers
int32 POSES_HANDLER_CREATION_FAILED = -300
int32 POSES_HANDLER_REMOVAL_FAILED = -301
int32 POSES_HANDLER_READ_FAILURE = -302
int32 POSES_HANDLER_COMPUTE_FAILURE = -303
int32 DYNAMIC_FRAME_DOES_NOT_EXISTS = -304
int32 DYNAMIC_FRAME_EDIT_FAILED = -305
int32 DYNAMIC_FRAME_CREATION_FAILED = -306
int32 CONVERT_FAILED = -307
int32 WORKSPACE_CREATION_FAILED = -308
int32 TF_ERROR = -309
# - Trajectory Handler
int32 TRAJECTORY_HANDLER_CREATION_FAILED = -310
int32 TRAJECTORY_HANDLER_REMOVAL_FAILED = -311
int32 TRAJECTORY_HANDLER_RENAME_FAILURE = -312
int32 TRAJECTORY_HANDLER_EXECUTE_REGISTERED_FAILURE = -313
int32 TRAJECTORY_HANDLER_EXECUTE_FAILURE = -314
int32 TRAJECTORY_HANDLER_GET_TRAJECTORY_FAILURE = -315
int32 TRAJECTORY_HANDLER_GET_TRAJECTORY_LIST_FAILURE = -316
# - Programs Manager
int32 PROGRAMS_MANAGER_FAILURE = -320
int32 PROGRAMS_MANAGER_READ_FAILURE = -321
int32 PROGRAMS_MANAGER_PROGRAM_ALREADY_RUNNING = -324
int32 PROGRAMS_MANAGER_UNKNOWN_LANGUAGE = -325
int32 PROGRAMS_MANAGER_NOT_RUNNABLE_LANGUAGE = -326
int32 PROGRAMS_MANAGER_EXECUTION_FAILED = -327
int32 PROGRAMS_MANAGER_STOPPING_FAILED = -328
int32 PROGRAMS_MANAGER_AUTORUN_FAILURE = -329
int32 PROGRAMS_MANAGER_WRITING_FAILURE = -330
int32 PROGRAMS_MANAGER_FILE_ALREADY_EXISTS = -331
int32 PROGRAMS_MANAGER_FILE_DOES_NOT_EXIST = -332
# - Credentials
int32 CREDENTIALS_FILE_ERROR = -400
int32 CREDENTIALS_UNKNOWN_ERROR = -401
# - System Api Client
int32 SYSTEM_API_CLIENT_UNKNOWN_ERROR = -440
int32 SYSTEM_API_CLIENT_INVALID_ROBOT_NAME = -441
int32 SYSTEM_API_CLIENT_REQUEST_FAILED = -442
int32 SYSTEM_API_CLIENT_UNKNOWN_COMMAND = -443
int32 SYSTEM_API_CLIENT_COMMAND_FAILED = -444
# - Database
int32 DATABASE_DB_ERROR = -460
int32 DATABASE_SETTINGS_UNKNOWN = -461
int32 DATABASE_SETTINGS_TYPE_MISMATCH = -462
int32 DATABASE_FILE_PATH_UNKNOWN = -463
# - Reports
int32 REPORTS_UNABLE_TO_SEND = -470
int32 REPORTS_SENDING_FAIL = -471
int32 REPORTS_FETCHING_FAIL = -472
int32 REPORTS_SERVICE_UNREACHABLE = -473
# - Sound interface
int32 SOUND_FILE_NOT_FOUND = -500
int32 PROTECTED_SOUND_NAME = -501
int32 INVALID_SOUND_NAME = -502
int32 INVALID_SOUND_FORMAT = -503
int32 SOUND_TIMEOUT = -504
# - I2C interface
int32 MISSING_I2C = -510
|
|
# roll, pitch and yaw
float64 roll
float64 pitch
float64 yaw
|
|
string rpi_image_version
string ros_niryo_robot_version
string robot_version
string[] motor_names
string[] stepper_firmware_versions
|
|
string name
string description
|
|
std_msgs/Header header
# Raspberry Pi board
int32 rpi_temperature
# Ned, One, ....
string hardware_version
# Hardware State
int8 ERROR = -1
int8 NORMAL = 0
int8 DEBUG = 1
int8 REBOOT = 2
int8 hardware_state
# Motors
bool connection_up
string error_message
bool calibration_needed
bool calibration_in_progress
string[] motor_names
string[] motor_types
int32[] temperatures
float64[] voltages
int32[] hardware_errors
string[] hardware_errors_message
|
|
uint8 motor_id
uint8 motor_type
uint8 MOTOR_TYPE_STEPPER=1
uint8 MOTOR_TYPE_XL430=2
uint8 MOTOR_TYPE_XL320=3
uint8 MOTOR_TYPE_XL330=4
uint8 MOROR_TYPE_XC430=5
uint8 MOTOR_TYPE_END_EFFECTOR=10
|
|
niryo_robot_msgs/BasicObject[] objects
|
|
std_msgs/Header header
bool connection_status
uint8[] motor_id_connected
string error
|
ROS services
Name |
Definition |
---|---|
---
int32 status
string message
# this service embed both old and new way to structure the datas in order to stay compatible with NS1/2
string[] name_list
string[] description_list
BasicObject[] objects
|
|
---
int32 status
string message
|
|
int8 SHUTDOWN=1
int8 REBOOT=2
int8 UPDATE=3
int8 value
---
int32 status
string message
|
|
string value
---
int32 status
string message
|
|
int32 value
---
int32 status
string message
|
|
---
float32[] values
int32 status
string message
|
|
float32 value
---
int32 status
string message
|
|
string name
bool state
---
|
|
bool value
---
int32 status
string message
|
|
float32[] values
---
int32 status
string message
|
|
---
bool value
|
|
---
string[] string_list
|
|
---
int32 value
|
|
---
string value
|
The /niryo_robot
namespace
In Ned robots, most of the ROS interfaces and parameters are bound to a specific package and, therefore, to a specific namespace.
However, some of them are considered global for the robot and take the namespace /niryo_robot
.
Here is an overview of the common interfaces available in the robot:
ROS topics
Publishers
Topic Name |
Type |
Description |
---|---|---|
/niryo_robot/end_effector_interface/collision_detected |
Whether a collision is detected or not |
|
/niryo_robot/blockly/save_current_point |
Save current robot pose in blockly block when user is in Blockly page in Niyro Studio |
|
/niryo_robot/rpi/is_button_pressed |
Publish the button state (true if pressed) |
|
/niryo_robot/max_velocity_scaling_factor |
Publish the maximum velocity percentage scaling factor |
|
/niryo_robot/max_acceleration_scaling_factor |
Publish the maximum acceleration percentage scaling factor |
|
/niryo_robot/learning_mode/state |
Whether the robot is in freemotion mode or not |
|
/niryo_robot/conveyor/feedback |
conveyor_interface/ConveyorFeedbackArray |
Publish the conveyor feedback |
/niryo_robot/robot_state |
Publish the robot state (TCP pose with x-axis forward and TCP speed) (deprecated) |
|
/niryo_robot/robot_state_v2 |
Publish the robot state (TCP pose with z-axis forward and TCP speed) |
|
/niryo_robot/collision_detected |
Whether a collision is detected or not |
|
/niryo_robot/blockly/save_trajectory |
Whether a recorded trajectory can be saved to blockly |
|
/niryo_robot/jog_interface/is_enabled |
Whether the jog interface is enabled or not |
|
/niryo_robot/jog_interface/errors |
Publish jog error message when using the jog interface |
Subscribers
Topic Name |
Type |
Description |
---|---|---|
/niryo_robot/jog_interface/is_enabled |
Whether the jog interface is enabled or not |
|
/niryo_robot/learning_mode/state |
Whether the robot is in freemotion mode or not |
|
/niryo_robot/collision_detected |
Whether a collision is detected or not |
|
/niryo_robot/robot_state_v2 |
Publish the robot state (TCP pose with z-axis forward and TCP speed) |
|
/niryo_robot/blockly/save_current_point |
Save current robot pose in blockly block when user is in Blockly page in Niyro Studio |
|
/niryo_robot/hotspot_button_state |
niryo_robot_rpi/HotspotButtonStatus |
Publish the state of the hotspot button |
/niryo_robot/hardware_interface/collision_detected |
Whether a collision is detected or not |
ROS Services
Service Name |
Type |
Description |
---|---|---|
/niryo_robot/ttl_driver/set_dxl_leds |
Set the LEDs of the Dynamixel motors |
|
/niryo_robot/ttl_driver/send_custom_value |
ttl_driver/WriteCustomValue |
Send a custom value to a given device ID on the TTL bus |
/niryo_robot/ttl_driver/read_custom_value |
ttl_driver/ReadCustomValue |
Read a custom value from a given device ID on the TTL bus |
/niryo_robot/ttl_driver/read_pid_value |
ttl_driver/ReadPIDValue |
Read the PID values of the Dynamixel motors |
/niryo_robot/ttl_driver/write_pid_value |
ttl_driver/WritePIDValue |
Write the PID values to the Dynamixel motors |
/niryo_robot/ttl_driver/read_velocity_profile |
ttl_driver/ReadVelocityProfile |
Read the velocity profile of the Dynamixel motors |
/niryo_robot/ttl_driver/write_velocity_profile |
ttl_driver/WriteVelocityProfile |
Write the velocity profile to the Dynamixel motors |
/niryo_robot/tools/ping_and_set_dxl_tool |
tools_interface/PingDxlTool |
Ping the given device ID on the bus and set the corresponding tool if found |
/niryo_robot/tools/open_gripper |
tools_interface/ToolCommand |
Open the gripper |
/niryo_robot/tools/close_gripper |
tools_interface/ToolCommand |
Close the gripper |
/niryo_robot/tools/pull_air_vacuum_pump |
tools_interface/ToolCommand |
Pull air from the vacuum pump |
/niryo_robot/tools/push_air_vacuum_pump |
tools_interface/ToolCommand |
Push air to the vacuum pump |
/niryo_robot/tools/reboot |
Reboot the tool’s motor |
|
/niryo_robot/joints_interface/calibrate_motors |
Calibrate the motors |
|
/niryo_robot/joints_interface/request_new_calibration |
Request a new calibration (Ned2 only) |
|
/niryo_robot/learning_mode/activate |
Activate the learning mode |
|
/niryo_robot/joints_interface/steppers_reset_controller |
Reset the steppers controller |
|
/niryo_robot/joints_interface/factory_calibrate_motors |
joints_interface/FactoryCalibration |
Factory calibrate the motors (Ned3pro only) |
/niryo_robot/conveyor/ping_and_set_conveyor |
conveyor_interface/SetConveyor |
Ping for a conveyor ID on the bus and set the conveyor if found |
/niryo_robot/conveyor/control_conveyor |
conveyor_interface/ControlConveyor |
Control the conveyor |
/niryo_robot/conveyor/get_hardware_id |
conveyor_interface/GetHardwareId |
Get the ID of the conveyor on the TTL bus |
/niryo_robot/kinematics/forward |
niryo_robot_arm_commander/GetFK |
Get TCP pose from joint values with x axis forward (deprecated) |
/niryo_robot/kinematics/inverse |
niryo_robot_arm_commander/GetIK |
Get joints configuration from TCP pose with x axis forward (deprecated) |
/niryo_robot/kinematics/forward_v2 |
niryo_robot_arm_commander/GetFK |
Get TCP pose from joint values with z axis forward |
/niryo_robot/kinematics/inverse_v2 |
niryo_robot_arm_commander/GetIK |
Get joints configuration from TCP pose with z axis forward |
/niryo_robot/jog_interface/enable |
Enable/disable the jog interface |
|
/niryo_robot/jog_interface/jog_shift_commander |
niryo_robot_arm_commander/JogShift |
Send a jog command to shift robot’s joints or TCP |
ROS Parameters
Parameter Name |
Default value |
Simulation value |
Unit |
Description |
---|---|---|---|---|
/niryo_robot/hardware_version |
ned2 |
N/A |
string |
Hardware version of the robot |
/niryo_robot/info/robot_type |
niryo_ned2 |
N/A |
N/A |
N/A |
/niryo_robot/info/ros_version |
noetic |
N/A |
string |
ROS distribution used by the robot |
/niryo_robot/python_ros_wrapper/action_connection_timeout |
20 |
N/A |
seconds |
Timeout for the action server connection by the python ROS wrapper |
/niryo_robot/python_ros_wrapper/action_execute_timeout |
3600 |
N/A |
seconds |
Timeout for the action server execution by the python ROS wrapper |
/niryo_robot/python_ros_wrapper/action_preempt_timeout |
60 |
N/A |
seconds |
Timeout for the action server preemption by the python ROS wrapper |
/niryo_robot/python_ros_wrapper/service_timeout |
2 |
N/A |
seconds |
Timeout for the service call by the python ROS wrapper |
/niryo_robot/robot_command_validation/joint_limits/joint_1/max |
2.999871918328051 |
N/A |
radians |
Maximum value for joint 1 when validating move commands |
/niryo_robot/robot_command_validation/joint_limits/joint_1/min |
-2.999871918328051 |
N/A |
radians |
Minimum value for joint 1 when validating move commands |
/niryo_robot/robot_command_validation/joint_limits/joint_2/max |
0.6101671064972578 |
N/A |
radians |
Maximum value for joint 2 when validating move commands |
/niryo_robot/robot_command_validation/joint_limits/joint_2/min |
-1.8325957145941667 |
N/A |
radians |
Minimum value for joint 2 when validating move commands |
/niryo_robot/robot_command_validation/joint_limits/joint_3/max |
1.5700981950942021 |
N/A |
radians |
Maximum value for joint 3 when validating move commands |
/niryo_robot/robot_command_validation/joint_limits/joint_3/min |
-1.3400637996813345 |
N/A |
radians |
Minimum value for joint 3 when validating move commands |
/niryo_robot/robot_command_validation/joint_limits/joint_4/max |
2.090031779263347 |
N/A |
radians |
Maximum value for joint 4 when validating move commands |
/niryo_robot/robot_command_validation/joint_limits/joint_4/min |
-2.090031779263347 |
N/A |
radians |
Minimum value for joint 4 when validating move commands |
/niryo_robot/robot_command_validation/joint_limits/joint_5/max |
1.9228292369222795 |
N/A |
radians |
Maximum value for joint 5 when validating move commands |
/niryo_robot/robot_command_validation/joint_limits/joint_5/min |
-1.9200367101190883 |
N/A |
radians |
Minimum value for joint 5 when validating move commands |
/niryo_robot/robot_command_validation/joint_limits/joint_6/max |
2.530029283691147 |
N/A |
radians |
Maximum value for joint 6 when validating move commands |
/niryo_robot/robot_command_validation/joint_limits/joint_6/min |
-2.530029283691147 |
N/A |
radians |
Minimum value for joint 6 when validating move commands |
/niryo_robot/robot_command_validation/position_limits/x/max |
0.5 |
N/A |
meters |
Maximum value for TCP x position when validating move commands |
/niryo_robot/robot_command_validation/position_limits/x/min |
-0.5 |
N/A |
meters |
Minimum value for TCP x position when validating move commands |
/niryo_robot/robot_command_validation/position_limits/y/max |
0.5 |
N/A |
meters |
Maximum value for TCP y position when validating move commands |
/niryo_robot/robot_command_validation/position_limits/y/min |
-0.5 |
N/A |
meters |
Minimum value for TCP y position when validating move commands |
/niryo_robot/robot_command_validation/position_limits/z/max |
0.6 |
N/A |
meters |
Maximum value for TCP z position when validating move commands |
/niryo_robot/robot_command_validation/position_limits/z/min |
-0.15 |
N/A |
meters |
Minimum value for TCP z position when validating move commands |
/niryo_robot/robot_command_validation/rpy_limits/pitch/max |
3.142 |
N/A |
radians |
Maximum value for TCP pitch when validating move commands |
/niryo_robot/robot_command_validation/rpy_limits/pitch/min |
-3.142 |
N/A |
radians |
Minimum value for TCP pitch when validating move commands |
/niryo_robot/robot_command_validation/rpy_limits/roll/max |
3.142 |
N/A |
radians |
Maximum value for TCP roll when validating move commands |
/niryo_robot/robot_command_validation/rpy_limits/roll/min |
-3.142 |
N/A |
radians |
Minimum value for TCP roll when validating move commands |
/niryo_robot/robot_command_validation/rpy_limits/yaw/max |
3.142 |
N/A |
radians |
Maximum value for TCP yaw when validating move commands |
/niryo_robot/robot_command_validation/rpy_limits/yaw/min |
-3.142 |
N/A |
radians |
Minimum value for TCP yaw when validating move commands |
/niryo_robot/robot_state/rate_publish_state |
5.0 |
N/A |
Hz |
Rate at which the robot state is published |
/niryo_robot/simulation_mode |
True |
N/A |
bool |
Whether the robot is in simulation mode or not |
ROS Action
Namespace: None