Niryo Robot Hardware Interface
This package is in charge for managing drivers and required hardware interfaces of the robot. It launches hardware interface nodes, motors communication and drivers.

Global overview of hardware stack packages organization.
The hardware interface node instantiates all the hardware interfaces we need to have a fully functional robot. The hardware interfaces use the TTL driver in order to communicate with all the devices (motors, end effector panel, accessories, …) on the robot.
- Among those interfaces we have:
Conveyor Interface
Joints Interface
Tools Interface
Cpu Interface
End Effector Panel Interface
TTL Driver
It belongs to the ROS namespace: /niryo_robot_hardware_interface
.
Hardware status
The robot exposes the status of its hardware on the topic /niryo_robot_hardware_interface/hardware_status
.
You can check the robot’s hardware current status by using the following command in a terminal launched on the robot:
rostopic echo /niryo_robot_hardware_interface/hardware_status
Message definition
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
Package Documentation
ROS topics
Publishers
Topic Name |
Type |
Description |
---|---|---|
/joint_states |
Position, velocity and effort of all the joints |
|
/niryo_robot/conveyor/feedback |
Publish the conveyor feedback |
|
/niryo_robot/end_effector_interface/collision_detected |
Whether a collision is detected or not |
|
/niryo_robot/learning_mode/state |
Whether the robot is in freemotion mode or not |
|
/niryo_robot_arm_commander/robot_action/cancel |
N/A |
|
/niryo_robot_follow_joint_trajectory_controller/follow_joint_trajectory/feedback |
N/A |
|
/niryo_robot_follow_joint_trajectory_controller/follow_joint_trajectory/result |
N/A |
|
/niryo_robot_follow_joint_trajectory_controller/follow_joint_trajectory/status |
N/A |
|
/niryo_robot_follow_joint_trajectory_controller/state |
N/A |
|
/niryo_robot_hardware/tools/motor |
tools_interface/Tool |
Publish informations about the tool’s motor (ID, motor type, position, state) |
/niryo_robot_hardware_interface/end_effector_interface/custom_button_status |
Publish Custom Button’s state |
|
/niryo_robot_hardware_interface/end_effector_interface/free_drive_button_status |
Publish Free Motion Button’s state |
|
/niryo_robot_hardware_interface/end_effector_interface/io_state |
States of the IOs on the end effector panel |
|
/niryo_robot_hardware_interface/end_effector_interface/save_pos_button_status |
Publish Save Button’s state |
|
/niryo_robot_hardware_interface/hardware_status |
Status of robot’s hardware devices (joints, tools, end effector panel, calibration, etc…) |
|
/niryo_robot_hardware_interface/software_version |
Publish the firmware version of hardware devices the robot |
|
/niryo_robot_hardware_interface/ttl_driver/calibration_status |
ttl_driver/CalibrationStatus |
Publish the calibration status of the stepper motors |
/niryo_robot_programs_manager_v2/execute_program/cancel |
N/A |
|
/niryo_robot_tools_commander/action_server/cancel |
N/A |
|
/rosout |
N/A |
Subscribers
Topic Name |
Type |
Description |
---|---|---|
/niryo_robot_follow_joint_trajectory_controller/command |
Command the arm through the FollowJointTrajectory controller via its command topic |
|
/niryo_robot_follow_joint_trajectory_controller/follow_joint_trajectory/cancel |
N/A |
|
/niryo_robot_follow_joint_trajectory_controller/follow_joint_trajectory/goal |
Command the arm through the FollowJointTrajectory controller via its action server |
|
/niryo_robot_follow_joint_trajectory_controller/follow_joint_trajectory/result |
N/A |
|
/niryo_robot_status/robot_status |
Publish the robot, log, overheating and joints out of bounds status |
ROS Services
Service Name |
Type |
Description |
---|---|---|
/controller_manager/list_controller_types |
N/A |
|
/controller_manager/list_controllers |
N/A |
|
/controller_manager/load_controller |
N/A |
|
/controller_manager/reload_controller_libraries |
N/A |
|
/controller_manager/switch_controller |
N/A |
|
/controller_manager/unload_controller |
N/A |
|
/niryo_robot/conveyor/control_conveyor |
Control the conveyor |
|
/niryo_robot/conveyor/get_hardware_id |
Get the ID of the conveyor on the TTL bus |
|
/niryo_robot/conveyor/ping_and_set_conveyor |
Ping for a conveyor ID on the bus and set the conveyor if found |
|
/niryo_robot/joints_interface/calibrate_motors |
Calibrate the motors |
|
/niryo_robot/joints_interface/factory_calibrate_motors |
Factory calibrate the motors (Ned3pro only) |
|
/niryo_robot/joints_interface/request_new_calibration |
Request a new calibration (Ned2 only) |
|
/niryo_robot/joints_interface/steppers_reset_controller |
Reset the steppers controller |
|
/niryo_robot/learning_mode/activate |
Activate the learning mode |
|
/niryo_robot/tools/close_gripper |
tools_interface/ToolCommand |
Close the gripper |
/niryo_robot/tools/open_gripper |
tools_interface/ToolCommand |
Open the gripper |
/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/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/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/read_velocity_profile |
ttl_driver/ReadVelocityProfile |
Read the velocity profile 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/set_dxl_leds |
Set the LEDs 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/write_velocity_profile |
ttl_driver/WriteVelocityProfile |
Write the velocity profile to the Dynamixel motors |
/niryo_robot_follow_joint_trajectory_controller/query_state |
N/A |
|
/niryo_robot_hardware_interface/end_effector_interface/set_ee_io_state |
N/A |
|
/niryo_robot_hardware_interface/get_loggers |
roscpp/GetLoggers |
N/A |
/niryo_robot_hardware_interface/launch_motors_report |
N/A |
|
/niryo_robot_hardware_interface/reboot_motors |
Reboot the motors |
|
/niryo_robot_hardware_interface/set_logger_level |
roscpp/SetLoggerLevel |
N/A |
/niryo_robot_hardware_interface/stop_motors_report |
N/A |
|
/niryo_robot_joints_interface/get_home_position |
Get the home position of the robot |
|
/niryo_robot_joints_interface/reset_home_position |
Reset the home position of the robot to its factory value |
|
/niryo_robot_joints_interface/set_home_position |
Set the home position of the robot |
ROS Parameters
Parameter Name |
Default value |
Simulation value |
Unit |
Description |
---|---|---|---|---|
/niryo_robot_hardware_interface/can_enabled |
False |
N/A |
N/A |
N/A |
/niryo_robot_hardware_interface/conveyor/publish_frequency |
2 |
N/A |
Hz |
Frequency at which the conveyor feedback is published |
/niryo_robot_hardware_interface/conveyor/ttl/default_id |
None |
8 |
int |
Default ID of the conveyor on the TTL bus before setup |
/niryo_robot_hardware_interface/conveyor/ttl/direction |
None |
1 |
string |
Direction of the conveyor (forward/backward) |
/niryo_robot_hardware_interface/conveyor/ttl/pool_id_list |
None |
[9, 10] |
string |
List of available IDs on the TTL bus dedicated to conveyors |
/niryo_robot_hardware_interface/conveyor/type |
None |
fakeStepper |
string |
Motor type of the conveyor |
/niryo_robot_hardware_interface/cpu_interface/read_rpi_diagnostics_frequency |
0.25 |
N/A |
Hz |
Frequency at which the Raspberry Pi diagnostics are read |
/niryo_robot_hardware_interface/cpu_interface/simulation_mode |
True |
N/A |
bool |
Whether the CPU interface is in simulation mode or not |
/niryo_robot_hardware_interface/cpu_interface/temperature_shutdown_threshold |
85 |
N/A |
°C |
CPU Temperature threshold at which the robot should shutdown |
/niryo_robot_hardware_interface/cpu_interface/temperature_warn_threshold |
75 |
N/A |
°C |
CPU Temperature threshold at which the robot should warn the user |
/niryo_robot_hardware_interface/debug |
False |
N/A |
N/A |
N/A |
/niryo_robot_hardware_interface/end_effector_interface/button_0/type |
None |
free_drive |
string |
Type of the button 0 on the end effector panel |
/niryo_robot_hardware_interface/end_effector_interface/button_1/type |
None |
save_position |
string |
Type of the button 1 on the end effector panel |
/niryo_robot_hardware_interface/end_effector_interface/button_2/type |
None |
custom |
string |
Type of the button 2 on the end effector panel |
/niryo_robot_hardware_interface/end_effector_interface/check_end_effector_status_frequency |
40.0 |
N/A |
Hz |
Frequency at which the end effector status is checked |
/niryo_robot_hardware_interface/end_effector_interface/collision_thresh |
None |
5 |
N/A |
N/A |
/niryo_robot_hardware_interface/end_effector_interface/end_effector_id |
0 |
N/A |
int |
ID of the end effector in the TTL bus |
/niryo_robot_hardware_interface/end_effector_interface/hardware_type |
None |
fake_end_effector |
string |
Type of the end effector |
/niryo_robot_hardware_interface/gazebo |
False |
N/A |
N/A |
N/A |
/niryo_robot_hardware_interface/hardware_version |
ned2 |
N/A |
string |
Hardware version of the robot |
/niryo_robot_hardware_interface/joints_interface/calibration_file |
None |
~/.niryo/simulation/stepper_motor_calibration_offsets.txt |
string |
Path to the calibration file |
/niryo_robot_hardware_interface/joints_interface/calibration_params/stepper_1/a_1 |
None |
450 |
N/A |
N/A |
/niryo_robot_hardware_interface/joints_interface/calibration_params/stepper_1/a_max |
None |
1200 |
N/A |
N/A |
/niryo_robot_hardware_interface/joints_interface/calibration_params/stepper_1/d_1 |
None |
450 |
N/A |
N/A |
/niryo_robot_hardware_interface/joints_interface/calibration_params/stepper_1/d_max |
None |
1200 |
N/A |
N/A |
/niryo_robot_hardware_interface/joints_interface/calibration_params/stepper_1/delay |
None |
200 |
N/A |
N/A |
/niryo_robot_hardware_interface/joints_interface/calibration_params/stepper_1/direction |
None |
1 |
N/A |
N/A |
/niryo_robot_hardware_interface/joints_interface/calibration_params/stepper_1/id |
None |
2 |
N/A |
N/A |
/niryo_robot_hardware_interface/joints_interface/calibration_params/stepper_1/stall_threshold |
None |
7 |
N/A |
N/A |
/niryo_robot_hardware_interface/joints_interface/calibration_params/stepper_1/v_1 |
None |
3 |
N/A |
N/A |
/niryo_robot_hardware_interface/joints_interface/calibration_params/stepper_1/v_max |
None |
7 |
N/A |
N/A |
/niryo_robot_hardware_interface/joints_interface/calibration_params/stepper_1/v_start |
None |
1 |
N/A |
N/A |
/niryo_robot_hardware_interface/joints_interface/calibration_params/stepper_1/v_stop |
None |
2 |
N/A |
N/A |
/niryo_robot_hardware_interface/joints_interface/calibration_params/stepper_2/a_1 |
None |
300 |
N/A |
N/A |
/niryo_robot_hardware_interface/joints_interface/calibration_params/stepper_2/a_max |
None |
600 |
N/A |
N/A |
/niryo_robot_hardware_interface/joints_interface/calibration_params/stepper_2/d_1 |
None |
300 |
N/A |
N/A |
/niryo_robot_hardware_interface/joints_interface/calibration_params/stepper_2/d_max |
None |
600 |
N/A |
N/A |
/niryo_robot_hardware_interface/joints_interface/calibration_params/stepper_2/delay |
None |
1000 |
N/A |
N/A |
/niryo_robot_hardware_interface/joints_interface/calibration_params/stepper_2/direction |
None |
1 |
N/A |
N/A |
/niryo_robot_hardware_interface/joints_interface/calibration_params/stepper_2/id |
None |
3 |
N/A |
N/A |
/niryo_robot_hardware_interface/joints_interface/calibration_params/stepper_2/stall_threshold |
None |
6 |
N/A |
N/A |
/niryo_robot_hardware_interface/joints_interface/calibration_params/stepper_2/v_1 |
None |
3 |
N/A |
N/A |
/niryo_robot_hardware_interface/joints_interface/calibration_params/stepper_2/v_max |
None |
6 |
N/A |
N/A |
/niryo_robot_hardware_interface/joints_interface/calibration_params/stepper_2/v_start |
None |
1 |
N/A |
N/A |
/niryo_robot_hardware_interface/joints_interface/calibration_params/stepper_2/v_stop |
None |
2 |
N/A |
N/A |
/niryo_robot_hardware_interface/joints_interface/calibration_params/stepper_3/a_1 |
None |
450 |
N/A |
N/A |
/niryo_robot_hardware_interface/joints_interface/calibration_params/stepper_3/a_max |
None |
750 |
N/A |
N/A |
/niryo_robot_hardware_interface/joints_interface/calibration_params/stepper_3/d_1 |
None |
450 |
N/A |
N/A |
/niryo_robot_hardware_interface/joints_interface/calibration_params/stepper_3/d_max |
None |
750 |
N/A |
N/A |
/niryo_robot_hardware_interface/joints_interface/calibration_params/stepper_3/delay |
None |
1000 |
N/A |
N/A |
/niryo_robot_hardware_interface/joints_interface/calibration_params/stepper_3/direction |
None |
-1 |
N/A |
N/A |
/niryo_robot_hardware_interface/joints_interface/calibration_params/stepper_3/id |
None |
4 |
N/A |
N/A |
/niryo_robot_hardware_interface/joints_interface/calibration_params/stepper_3/stall_threshold |
None |
6 |
N/A |
N/A |
/niryo_robot_hardware_interface/joints_interface/calibration_params/stepper_3/v_1 |
None |
3 |
N/A |
N/A |
/niryo_robot_hardware_interface/joints_interface/calibration_params/stepper_3/v_max |
None |
6 |
N/A |
N/A |
/niryo_robot_hardware_interface/joints_interface/calibration_params/stepper_3/v_start |
None |
1 |
N/A |
N/A |
/niryo_robot_hardware_interface/joints_interface/calibration_params/stepper_3/v_stop |
None |
2 |
N/A |
N/A |
/niryo_robot_hardware_interface/joints_interface/calibration_timeout |
None |
5 |
N/A |
N/A |
/niryo_robot_hardware_interface/joints_interface/dynamixels/dxl_1/FF1_gain |
None |
N/A |
N/A |
FF1 gain of the axe 4 Dynamixel motor |
/niryo_robot_hardware_interface/joints_interface/dynamixels/dxl_1/FF2_gain |
None |
400 |
N/A |
FF2 gain of the axe 4 Dynamixel motor |
/niryo_robot_hardware_interface/joints_interface/dynamixels/dxl_1/acceleration_profile |
None |
200 |
N/A |
Acceleration profile of the axe 4 Dynamixel motor |
/niryo_robot_hardware_interface/joints_interface/dynamixels/dxl_1/direction |
None |
1 |
N/A |
Direction of the axe 4 Dynamixel motor |
/niryo_robot_hardware_interface/joints_interface/dynamixels/dxl_1/home_position |
None |
N/A |
N/A |
N/A |
/niryo_robot_hardware_interface/joints_interface/dynamixels/dxl_1/limit_position_max |
None |
2.093 |
Radians |
Maximum position limit of the axe 4 Dynamixel motor |
/niryo_robot_hardware_interface/joints_interface/dynamixels/dxl_1/limit_position_min |
None |
-2.093 |
Radians |
Minimum position limit of the axe 4 Dynamixel motor |
/niryo_robot_hardware_interface/joints_interface/dynamixels/dxl_1/offset_position |
None |
-3.1415 |
Radians |
Offset position of the axe 4 Dynamixel motor |
/niryo_robot_hardware_interface/joints_interface/dynamixels/dxl_1/position_D_gain |
None |
9520 |
N/A |
D gain of the position PID of the axe 4 Dynamixel motor |
/niryo_robot_hardware_interface/joints_interface/dynamixels/dxl_1/position_I_gain |
None |
N/A |
N/A |
I gain of the position PID of the axe 4 Dynamixel motor |
/niryo_robot_hardware_interface/joints_interface/dynamixels/dxl_1/position_P_gain |
None |
3264 |
N/A |
P gain of the position PID of the axe 4 Dynamixel motor |
/niryo_robot_hardware_interface/joints_interface/dynamixels/dxl_1/velocity_I_gain |
None |
N/A |
N/A |
I gain of the velocity PID of the axe 4 Dynamixel motor |
/niryo_robot_hardware_interface/joints_interface/dynamixels/dxl_1/velocity_P_gain |
None |
N/A |
N/A |
P gain of the velocity PID of the axe 4 Dynamixel motor |
/niryo_robot_hardware_interface/joints_interface/dynamixels/dxl_1/velocity_profile |
None |
200 |
N/A |
Velocity profile of the axe 4 Dynamixel motor |
/niryo_robot_hardware_interface/joints_interface/dynamixels/dxl_2/FF1_gain |
None |
N/A |
N/A |
FF1 gain of the axe 5 Dynamixel motor |
/niryo_robot_hardware_interface/joints_interface/dynamixels/dxl_2/FF2_gain |
None |
N/A |
N/A |
FF2 gain of the axe 5 Dynamixel motor |
/niryo_robot_hardware_interface/joints_interface/dynamixels/dxl_2/acceleration_profile |
None |
200 |
N/A |
Acceleration profile of the axe 5 Dynamixel motor |
/niryo_robot_hardware_interface/joints_interface/dynamixels/dxl_2/direction |
None |
-1 |
N/A |
Direction of the axe 5 Dynamixel motor |
/niryo_robot_hardware_interface/joints_interface/dynamixels/dxl_2/home_position |
None |
N/A |
N/A |
N/A |
/niryo_robot_hardware_interface/joints_interface/dynamixels/dxl_2/limit_position_max |
None |
1.919 |
Radians |
Maximum position limit of the axe 5 Dynamixel motor |
/niryo_robot_hardware_interface/joints_interface/dynamixels/dxl_2/limit_position_min |
None |
-1.919 |
Radians |
Minimum position limit of the axe 5 Dynamixel motor |
/niryo_robot_hardware_interface/joints_interface/dynamixels/dxl_2/offset_position |
None |
3.1415 |
Radians |
Offset position of the axe 5 Dynamixel motor |
/niryo_robot_hardware_interface/joints_interface/dynamixels/dxl_2/position_D_gain |
None |
352 |
N/A |
D gain of the position PID of the axe 5 Dynamixel motor |
/niryo_robot_hardware_interface/joints_interface/dynamixels/dxl_2/position_I_gain |
None |
N/A |
N/A |
I gain of the position PID of the axe 5 Dynamixel motor |
/niryo_robot_hardware_interface/joints_interface/dynamixels/dxl_2/position_P_gain |
None |
2560 |
N/A |
P gain of the position PID of the axe 5 Dynamixel motor |
/niryo_robot_hardware_interface/joints_interface/dynamixels/dxl_2/velocity_I_gain |
None |
N/A |
N/A |
I gain of the velocity PID of the axe 5 Dynamixel motor |
/niryo_robot_hardware_interface/joints_interface/dynamixels/dxl_2/velocity_P_gain |
None |
N/A |
N/A |
P gain of the velocity PID of the axe 5 Dynamixel motor |
/niryo_robot_hardware_interface/joints_interface/dynamixels/dxl_2/velocity_profile |
None |
200 |
N/A |
Velocity profile of the axe 5 Dynamixel motor |
/niryo_robot_hardware_interface/joints_interface/dynamixels/dxl_3/FF1_gain |
None |
N/A |
N/A |
FF1 gain of the axe 6 Dynamixel motor |
/niryo_robot_hardware_interface/joints_interface/dynamixels/dxl_3/FF2_gain |
None |
N/A |
N/A |
FF2 gain of the axe 6 Dynamixel motor |
/niryo_robot_hardware_interface/joints_interface/dynamixels/dxl_3/acceleration_profile |
None |
200 |
N/A |
Acceleration profile of the axe 6 Dynamixel motor |
/niryo_robot_hardware_interface/joints_interface/dynamixels/dxl_3/direction |
None |
1 |
N/A |
Direction of the axe 6 Dynamixel motor |
/niryo_robot_hardware_interface/joints_interface/dynamixels/dxl_3/home_position |
None |
N/A |
N/A |
N/A |
/niryo_robot_hardware_interface/joints_interface/dynamixels/dxl_3/limit_position_max |
None |
2.53 |
Radians |
Maximum position limit of the axe 6 Dynamixel motor |
/niryo_robot_hardware_interface/joints_interface/dynamixels/dxl_3/limit_position_min |
None |
-2.53 |
Radians |
Minimum position limit of the axe 6 Dynamixel motor |
/niryo_robot_hardware_interface/joints_interface/dynamixels/dxl_3/offset_position |
None |
-3.1415 |
Radians |
Offset position of the axe 6 Dynamixel motor |
/niryo_robot_hardware_interface/joints_interface/dynamixels/dxl_3/position_D_gain |
None |
1424 |
N/A |
D gain of the position PID of the axe 6 Dynamixel motor |
/niryo_robot_hardware_interface/joints_interface/dynamixels/dxl_3/position_I_gain |
None |
N/A |
N/A |
I gain of the position PID of the axe 6 Dynamixel motor |
/niryo_robot_hardware_interface/joints_interface/dynamixels/dxl_3/position_P_gain |
None |
2560 |
N/A |
P gain of the position PID of the axe 6 Dynamixel motor |
/niryo_robot_hardware_interface/joints_interface/dynamixels/dxl_3/velocity_I_gain |
None |
N/A |
N/A |
I gain of the velocity PID of the axe 6 Dynamixel motor |
/niryo_robot_hardware_interface/joints_interface/dynamixels/dxl_3/velocity_P_gain |
None |
N/A |
N/A |
P gain of the velocity PID of the axe 6 Dynamixel motor |
/niryo_robot_hardware_interface/joints_interface/dynamixels/dxl_3/velocity_profile |
None |
200 |
N/A |
Velocity profile of the axe 6 Dynamixel motor |
/niryo_robot_hardware_interface/joints_interface/homing_offset_file |
None |
~/.niryo/simulation/stepper_motor_homing_offsets.txt |
N/A |
N/A |
/niryo_robot_hardware_interface/joints_interface/joint_1/bus |
None |
ttl |
string |
Field bus used by the joint 1 motor |
/niryo_robot_hardware_interface/joints_interface/joint_1/id |
None |
2 |
int |
ID of the joint 1 motor |
/niryo_robot_hardware_interface/joints_interface/joint_1/name |
None |
joint_1 |
string |
Name of the joint 1 motor |
/niryo_robot_hardware_interface/joints_interface/joint_1/type |
None |
fakeStepper |
string |
Type of the joint 1 motor |
/niryo_robot_hardware_interface/joints_interface/joint_2/bus |
None |
ttl |
string |
Field bus used by the joint 2 motor |
/niryo_robot_hardware_interface/joints_interface/joint_2/id |
None |
3 |
int |
ID of the joint 2 motor |
/niryo_robot_hardware_interface/joints_interface/joint_2/name |
None |
joint_2 |
string |
Name of the joint 2 motor |
/niryo_robot_hardware_interface/joints_interface/joint_2/type |
None |
fakeStepper |
string |
Type of the joint 2 motor |
/niryo_robot_hardware_interface/joints_interface/joint_3/bus |
None |
ttl |
string |
Field bus used by the joint 3 motor |
/niryo_robot_hardware_interface/joints_interface/joint_3/id |
None |
4 |
int |
ID of the joint 3 motor |
/niryo_robot_hardware_interface/joints_interface/joint_3/name |
None |
joint_3 |
string |
Name of the joint 3 motor |
/niryo_robot_hardware_interface/joints_interface/joint_3/type |
None |
fakeStepper |
string |
Type of the joint 3 motor |
/niryo_robot_hardware_interface/joints_interface/joint_4/bus |
None |
ttl |
string |
Field bus used by the joint 4 motor |
/niryo_robot_hardware_interface/joints_interface/joint_4/id |
None |
5 |
int |
ID of the joint 4 motor |
/niryo_robot_hardware_interface/joints_interface/joint_4/name |
None |
joint_4 |
string |
Name of the joint 4 motor |
/niryo_robot_hardware_interface/joints_interface/joint_4/type |
None |
fakeDxl |
string |
Type of the joint 4 motor |
/niryo_robot_hardware_interface/joints_interface/joint_5/bus |
None |
ttl |
string |
Field bus used by the joint 5 motor |
/niryo_robot_hardware_interface/joints_interface/joint_5/id |
None |
6 |
int |
ID of the joint 5 motor |
/niryo_robot_hardware_interface/joints_interface/joint_5/name |
None |
joint_5 |
string |
Name of the joint 5 motor |
/niryo_robot_hardware_interface/joints_interface/joint_5/type |
None |
fakeDxl |
string |
Type of the joint 5 motor |
/niryo_robot_hardware_interface/joints_interface/joint_6/bus |
None |
ttl |
string |
Field bus used by the joint 6 motor |
/niryo_robot_hardware_interface/joints_interface/joint_6/id |
None |
7 |
int |
ID of the joint 6 motor |
/niryo_robot_hardware_interface/joints_interface/joint_6/name |
None |
joint_6 |
string |
Name of the joint 6 motor |
/niryo_robot_hardware_interface/joints_interface/joint_6/type |
None |
fakeDxl |
string |
Type of the joint 6 motor |
/niryo_robot_hardware_interface/joints_interface/ros_control_loop_frequency |
100.0 |
N/A |
Hz |
Frequency of the ROS control loop |
/niryo_robot_hardware_interface/joints_interface/simulation_mode |
True |
N/A |
bool |
Whether the joints interface is in simulation mode or not |
/niryo_robot_hardware_interface/joints_interface/steppers/stepper_1/a_1 |
None |
1260 |
rad/s² |
First acceleration of the velocity profile for the stepper 1 |
/niryo_robot_hardware_interface/joints_interface/steppers/stepper_1/a_max |
None |
2500 |
rad/s² |
Maximum acceleration of the velocity profile for the stepper 1 |
/niryo_robot_hardware_interface/joints_interface/steppers/stepper_1/d_1 |
None |
1228 |
rad/s² |
First deceleration of the velocity profile for the stepper 1 |
/niryo_robot_hardware_interface/joints_interface/steppers/stepper_1/d_max |
None |
2500 |
rad/s² |
Maximum deceleration of the velocity profile for the stepper 1 |
/niryo_robot_hardware_interface/joints_interface/steppers/stepper_1/direction |
None |
1 |
string |
Direction of the stepper 1 |
/niryo_robot_hardware_interface/joints_interface/steppers/stepper_1/home_position |
None |
N/A |
N/A |
N/A |
/niryo_robot_hardware_interface/joints_interface/steppers/stepper_1/id |
None |
2 |
N/A |
N/A |
/niryo_robot_hardware_interface/joints_interface/steppers/stepper_1/limit_position_max |
None |
2.966 |
Radians |
Maximum position limit of the stepper 1 |
/niryo_robot_hardware_interface/joints_interface/steppers/stepper_1/limit_position_min |
None |
-2.966 |
Radians |
Minimum position limit of the stepper 1 |
/niryo_robot_hardware_interface/joints_interface/steppers/stepper_1/motor_ratio |
None |
0.0872 |
N/A |
Motor ratio of the stepper 1 |
/niryo_robot_hardware_interface/joints_interface/steppers/stepper_1/offset_position |
None |
-2.966 |
Radians |
Offset position of the stepper 1 |
/niryo_robot_hardware_interface/joints_interface/steppers/stepper_1/v_1 |
None |
500 |
rad/s |
First velocity of the velocity profile for the stepper 1 |
/niryo_robot_hardware_interface/joints_interface/steppers/stepper_1/v_max |
None |
1500 |
rad/s |
Maximum velocity of the velocity profile for the stepper 1 |
/niryo_robot_hardware_interface/joints_interface/steppers/stepper_1/v_start |
None |
N/A |
rad/s |
Starting velocity of the velocity profile for the stepper 1 |
/niryo_robot_hardware_interface/joints_interface/steppers/stepper_1/v_stop |
None |
20 |
rad/s |
Stopping velocity of the velocity profile for the stepper 1 |
/niryo_robot_hardware_interface/joints_interface/steppers/stepper_2/a_1 |
None |
860 |
rad/s² |
First acceleration of the velocity profile for the stepper 2 |
/niryo_robot_hardware_interface/joints_interface/steppers/stepper_2/a_max |
None |
1400 |
rad/s² |
Maximum acceleration of the velocity profile for the stepper 2 |
/niryo_robot_hardware_interface/joints_interface/steppers/stepper_2/d_1 |
None |
860 |
rad/s² |
First deceleration of the velocity profile for the stepper 2 |
/niryo_robot_hardware_interface/joints_interface/steppers/stepper_2/d_max |
None |
1400 |
rad/s² |
Maximum deceleration of the velocity profile for the stepper 2 |
/niryo_robot_hardware_interface/joints_interface/steppers/stepper_2/direction |
None |
-1 |
string |
Direction of the stepper 2 |
/niryo_robot_hardware_interface/joints_interface/steppers/stepper_2/home_position |
None |
0.5 |
N/A |
N/A |
/niryo_robot_hardware_interface/joints_interface/steppers/stepper_2/id |
None |
3 |
N/A |
N/A |
/niryo_robot_hardware_interface/joints_interface/steppers/stepper_2/limit_position_max |
None |
0.61 |
Radians |
Maximum position limit of the stepper 2 |
/niryo_robot_hardware_interface/joints_interface/steppers/stepper_2/limit_position_min |
None |
-2.09 |
Radians |
Minimum position limit of the stepper 2 |
/niryo_robot_hardware_interface/joints_interface/steppers/stepper_2/motor_ratio |
None |
0.0868 |
N/A |
Motor ratio of the stepper 2 |
/niryo_robot_hardware_interface/joints_interface/steppers/stepper_2/offset_position |
None |
0.61 |
Radians |
Offset position of the stepper 2 |
/niryo_robot_hardware_interface/joints_interface/steppers/stepper_2/v_1 |
None |
300 |
rad/s |
First velocity of the velocity profile for the stepper 2 |
/niryo_robot_hardware_interface/joints_interface/steppers/stepper_2/v_max |
None |
1000 |
rad/s |
Maximum velocity of the velocity profile for the stepper 2 |
/niryo_robot_hardware_interface/joints_interface/steppers/stepper_2/v_start |
None |
N/A |
rad/s |
Starting velocity of the velocity profile for the stepper 2 |
/niryo_robot_hardware_interface/joints_interface/steppers/stepper_2/v_stop |
None |
20 |
rad/s |
Stopping velocity of the velocity profile for the stepper 2 |
/niryo_robot_hardware_interface/joints_interface/steppers/stepper_3/a_1 |
None |
915 |
rad/s² |
First acceleration of the velocity profile for the stepper 3 |
/niryo_robot_hardware_interface/joints_interface/steppers/stepper_3/a_max |
None |
1700 |
rad/s² |
Maximum acceleration of the velocity profile for the stepper 3 |
/niryo_robot_hardware_interface/joints_interface/steppers/stepper_3/d_1 |
None |
983 |
rad/s² |
First deceleration of the velocity profile for the stepper 3 |
/niryo_robot_hardware_interface/joints_interface/steppers/stepper_3/d_max |
None |
1700 |
rad/s² |
Maximum deceleration of the velocity profile for the stepper 3 |
/niryo_robot_hardware_interface/joints_interface/steppers/stepper_3/direction |
None |
1 |
string |
Direction of the stepper 3 |
/niryo_robot_hardware_interface/joints_interface/steppers/stepper_3/home_position |
None |
-1.25 |
N/A |
N/A |
/niryo_robot_hardware_interface/joints_interface/steppers/stepper_3/id |
None |
4 |
N/A |
N/A |
/niryo_robot_hardware_interface/joints_interface/steppers/stepper_3/limit_position_max |
None |
1.57 |
Radians |
Maximum position limit of the stepper 3 |
/niryo_robot_hardware_interface/joints_interface/steppers/stepper_3/limit_position_min |
None |
-1.34 |
Radians |
Minimum position limit of the stepper 3 |
/niryo_robot_hardware_interface/joints_interface/steppers/stepper_3/motor_ratio |
None |
0.0868 |
N/A |
Motor ratio of the stepper 3 |
/niryo_robot_hardware_interface/joints_interface/steppers/stepper_3/offset_position |
None |
-1.34 |
Radians |
Offset position of the stepper 3 |
/niryo_robot_hardware_interface/joints_interface/steppers/stepper_3/v_1 |
None |
400 |
rad/s |
First velocity of the velocity profile for the stepper 3 |
/niryo_robot_hardware_interface/joints_interface/steppers/stepper_3/v_max |
None |
1200 |
rad/s |
Maximum velocity of the velocity profile for the stepper 3 |
/niryo_robot_hardware_interface/joints_interface/steppers/stepper_3/v_start |
None |
N/A |
rad/s |
Starting velocity of the velocity profile for the stepper 3 |
/niryo_robot_hardware_interface/joints_interface/steppers/stepper_3/v_stop |
None |
20 |
rad/s |
Stopping velocity of the velocity profile for the stepper 3 |
/niryo_robot_hardware_interface/publish_hw_status_frequency |
2.0 |
N/A |
Hz |
Frequency at which the hardware status is published |
/niryo_robot_hardware_interface/publish_software_version_frequency |
2.0 |
N/A |
Hz |
Frequency at which the software version is published |
/niryo_robot_hardware_interface/tools_interface/check_tool_connection_frequency |
2.0 |
N/A |
Hz |
Frequency at which the tool connection is checked |
/niryo_robot_hardware_interface/tools_interface/gripper_timeout |
3.0 |
N/A |
seconds |
Maximum waiting time before considering that the gripper cannot move anymore (due to contact with an object for example) |
/niryo_robot_hardware_interface/tools_interface/tools_params/id_list |
None |
[11, 12, 13, 31, 32] |
string |
List of tools IDs on the TTL bus |
/niryo_robot_hardware_interface/tools_interface/tools_params/name_list |
None |
[‘Standard Gripper’, ‘Large Gripper’, ‘Adaptive Gripper’, ‘Vacuum Pump’, ‘Vacuum Pump v2’] |
string |
List of tools names on the TTL bus |
/niryo_robot_hardware_interface/tools_interface/tools_params/params_list |
None |
[{‘velocity_profile’: 130, ‘acceleration_profile’: 60, ‘pid’: {‘p’: 400, ‘i’: 0, ‘d’: 50}}, {‘velocity_profile’: 130, ‘acceleration_profile’: 60, ‘pid’: {‘p’: 400, ‘i’: 0, ‘d’: 50}}, {‘velocity_profile’: 130, ‘acceleration_profile’: 60, ‘pid’: {‘p’: 400, ‘i’: 0, ‘d’: 50}}, {‘velocity_profile’: 0, ‘acceleration_profile’: 0, ‘pid’: {‘p’: 400, ‘i’: 0, ‘d’: 0}}, {‘velocity_profile’: 80, ‘acceleration_profile’: 40, ‘pid’: {‘p’: 400, ‘i’: 0, ‘d’: 0}}] |
string |
List of tools parameters on the TTL bus |
/niryo_robot_hardware_interface/tools_interface/tools_params/type_list |
None |
[‘fakeDxl’, ‘fakeDxl’, ‘fakeDxl’, ‘fakeDxl’, ‘fakeDxl’] |
string |
List of tools motor types on the TTL bus |
/niryo_robot_hardware_interface/tools_interface/vacuum_pump_timeout |
3.0 |
N/A |
seconds |
Maximum waiting time before considering that the vacuum pump motor cannot move anymore (due to contact with an object for example) |
/niryo_robot_hardware_interface/ttl_driver/bus_params/baudrate |
1000000 |
N/A |
bps |
Baudrate of the TTL bus |
/niryo_robot_hardware_interface/ttl_driver/bus_params/uart_device_name |
/dev/ttyAMA0 |
N/A |
N/A |
N/A |
/niryo_robot_hardware_interface/ttl_driver/fake_params/conveyors/firmware |
None |
[‘0.0.1’] |
N/A |
N/A |
/niryo_robot_hardware_interface/ttl_driver/fake_params/conveyors/id |
None |
[8] |
N/A |
N/A |
/niryo_robot_hardware_interface/ttl_driver/fake_params/conveyors/max_position |
None |
[4096] |
N/A |
N/A |
/niryo_robot_hardware_interface/ttl_driver/fake_params/conveyors/min_position |
None |
[0] |
N/A |
N/A |
/niryo_robot_hardware_interface/ttl_driver/fake_params/conveyors/model_number |
None |
[2] |
N/A |
N/A |
/niryo_robot_hardware_interface/ttl_driver/fake_params/conveyors/position |
None |
[0] |
N/A |
N/A |
/niryo_robot_hardware_interface/ttl_driver/fake_params/conveyors/temperature |
None |
[54] |
N/A |
N/A |
/niryo_robot_hardware_interface/ttl_driver/fake_params/conveyors/velocity |
None |
[0] |
N/A |
N/A |
/niryo_robot_hardware_interface/ttl_driver/fake_params/conveyors/voltage |
None |
[12300] |
N/A |
N/A |
/niryo_robot_hardware_interface/ttl_driver/fake_params/dynamixels/firmware |
None |
[‘0.0.1’, ‘0.0.1’, ‘0.0.1’] |
N/A |
N/A |
/niryo_robot_hardware_interface/ttl_driver/fake_params/dynamixels/id |
None |
[5, 6, 7] |
N/A |
N/A |
/niryo_robot_hardware_interface/ttl_driver/fake_params/dynamixels/max_position |
None |
[4096, 4096, 4096] |
N/A |
N/A |
/niryo_robot_hardware_interface/ttl_driver/fake_params/dynamixels/min_position |
None |
[0, 0, 0] |
N/A |
N/A |
/niryo_robot_hardware_interface/ttl_driver/fake_params/dynamixels/model_number |
None |
[1, 1, 1] |
N/A |
N/A |
/niryo_robot_hardware_interface/ttl_driver/fake_params/dynamixels/position |
None |
[2048, 2048, 2048] |
N/A |
N/A |
/niryo_robot_hardware_interface/ttl_driver/fake_params/dynamixels/temperature |
None |
[50, 52, 54] |
N/A |
N/A |
/niryo_robot_hardware_interface/ttl_driver/fake_params/dynamixels/velocity |
None |
[0, 0, 0] |
N/A |
N/A |
/niryo_robot_hardware_interface/ttl_driver/fake_params/dynamixels/voltage |
None |
[50, 50, 50] |
N/A |
N/A |
/niryo_robot_hardware_interface/ttl_driver/fake_params/end_effector/firmware |
None |
[‘0.0.1’] |
N/A |
N/A |
/niryo_robot_hardware_interface/ttl_driver/fake_params/end_effector/id |
None |
[0] |
N/A |
N/A |
/niryo_robot_hardware_interface/ttl_driver/fake_params/end_effector/temperature |
None |
[32] |
N/A |
N/A |
/niryo_robot_hardware_interface/ttl_driver/fake_params/end_effector/voltage |
None |
[5000] |
N/A |
N/A |
/niryo_robot_hardware_interface/ttl_driver/fake_params/steppers/firmware |
None |
[‘0.0.1’, ‘0.0.1’, ‘0.0.1’] |
N/A |
N/A |
/niryo_robot_hardware_interface/ttl_driver/fake_params/steppers/id |
None |
[2, 3, 4] |
N/A |
N/A |
/niryo_robot_hardware_interface/ttl_driver/fake_params/steppers/max_position |
None |
[4096, 4096, 4096] |
N/A |
N/A |
/niryo_robot_hardware_interface/ttl_driver/fake_params/steppers/min_position |
None |
[0, 0, 0] |
N/A |
N/A |
/niryo_robot_hardware_interface/ttl_driver/fake_params/steppers/model_number |
None |
[1, 1, 1] |
N/A |
N/A |
/niryo_robot_hardware_interface/ttl_driver/fake_params/steppers/position |
None |
[1950, 0, 0] |
N/A |
N/A |
/niryo_robot_hardware_interface/ttl_driver/fake_params/steppers/temperature |
None |
[50, 52, 54] |
N/A |
N/A |
/niryo_robot_hardware_interface/ttl_driver/fake_params/steppers/velocity |
None |
[0, 0, 0] |
N/A |
N/A |
/niryo_robot_hardware_interface/ttl_driver/fake_params/steppers/voltage |
None |
[12100, 12200, 12300] |
N/A |
N/A |
/niryo_robot_hardware_interface/ttl_driver/fake_params/tool/firmware |
None |
[‘0.0.1’] |
N/A |
N/A |
/niryo_robot_hardware_interface/ttl_driver/fake_params/tool/id |
None |
[11] |
N/A |
N/A |
/niryo_robot_hardware_interface/ttl_driver/fake_params/tool/max_position |
None |
[4096] |
N/A |
N/A |
/niryo_robot_hardware_interface/ttl_driver/fake_params/tool/min_position |
None |
[0] |
N/A |
N/A |
/niryo_robot_hardware_interface/ttl_driver/fake_params/tool/model_number |
None |
[1] |
N/A |
N/A |
/niryo_robot_hardware_interface/ttl_driver/fake_params/tool/position |
None |
[370] |
N/A |
N/A |
/niryo_robot_hardware_interface/ttl_driver/fake_params/tool/temperature |
None |
[56] |
N/A |
N/A |
/niryo_robot_hardware_interface/ttl_driver/fake_params/tool/velocity |
None |
[0] |
N/A |
N/A |
/niryo_robot_hardware_interface/ttl_driver/fake_params/tool/voltage |
None |
[50] |
N/A |
N/A |
/niryo_robot_hardware_interface/ttl_driver/hardware_version |
ned2 |
N/A |
string |
Hardware version of the robot |
/niryo_robot_hardware_interface/ttl_driver/led_motor |
None |
fakeDxl |
N/A |
N/A |
/niryo_robot_hardware_interface/ttl_driver/simu_conveyor |
True |
N/A |
N/A |
N/A |
/niryo_robot_hardware_interface/ttl_driver/simu_gripper |
True |
N/A |
N/A |
N/A |
/niryo_robot_hardware_interface/ttl_driver/simulation_mode |
True |
N/A |
bool |
Whether the TTL driver is in simulation mode or not |
/niryo_robot_hardware_interface/ttl_driver/ttl_hardware_control_loop_frequency |
240.0 |
N/A |
Hz |
Frequency of the TTL hardware control loop |
/niryo_robot_hardware_interface/ttl_driver/ttl_hardware_read_data_frequency |
120.0 |
N/A |
Hz |
Frequency at which the TTL hardware data is read |
/niryo_robot_hardware_interface/ttl_driver/ttl_hardware_read_end_effector_frequency |
13.0 |
N/A |
Hz |
Frequency at which the TTL hardware end effector data is read |
/niryo_robot_hardware_interface/ttl_driver/ttl_hardware_read_status_frequency |
0.7 |
N/A |
Hz |
Frequency at which the TTL hardware status is read |
/niryo_robot_hardware_interface/ttl_driver/ttl_hardware_write_frequency |
120.0 |
N/A |
Hz |
Frequency at which the TTL hardware data is written |
/niryo_robot_hardware_interface/ttl_enabled |
True |
N/A |
bool |
Whether the TTL bus is enabled or not |
ROS Action
Namespace: None