Joints Interface
This package acts as an interface for the robot’s joints controller.
It provides an interface to the ROS control package.
Joints interface node
It is instantiated by the Niryo Robot Hardware Interface node.
- The node:
interfaces robot’s motors to the joint trajectory controller, from the ROS control package.
creates a controller manager, from the ROS control package, that provides the infrastructure to load, unload, start and stop controllers.
interfaces with motors calibration.
initializes motors parameters.
It belongs to the ROS namespace: /joints_interface
.
Joints motors configuration
Here are the configurations for each robot joint motor. They contain the name of the joint, its ID on the TTL bus and its type.
For the Ned2 robot:
1joint_1:
2 name: "joint_1"
3 id: 2
4 type: "stepper"
5 bus: "ttl"
6
7joint_2:
8 name: "joint_2"
9 id: 3
10 type: "stepper"
11 bus: "ttl"
12
13joint_3:
14 name: "joint_3"
15 id: 4
16 type: "stepper"
17 bus: "ttl"
18
19joint_4:
20 name: "joint_4"
21 id: 5
22 type: "xl430"
23 bus: "ttl"
24
25joint_5:
26 name: "joint_5"
27 id: 6
28 type: "xl430"
29 bus: "ttl"
30
31joint_6:
32 name: "joint_6"
33 id: 7
34 type: "xl330"
35 bus: "ttl"
For the Ned3pro robot:
1joint_1:
2 name: "joint_1"
3 id: 2
4 type: "ned3pro_stepper"
5 bus: "ttl"
6
7joint_2:
8 name: "joint_2"
9 id: 3
10 type: "ned3pro_stepper"
11 bus: "ttl"
12
13joint_3:
14 name: "joint_3"
15 id: 4
16 type: "ned3pro_stepper"
17 bus: "ttl"
18
19joint_4:
20 name: "joint_4"
21 id: 5
22 type: "xh430"
23 bus: "ttl"
24
25joint_5:
26 name: "joint_5"
27 id: 6
28 type: "xh430"
29 bus: "ttl"
30
31joint_6:
32 name: "joint_6"
33 id: 7
34 type: "xh430"
35 bus: "ttl"
The stepper motors profiles
Ned robots use stepper motors for the first 3 axis. The velocity and acceleration profiles for the stepper motors are defined in the steppers_params.yaml config file.
For the Ned2 robot:
1#
2# Stepper caracteristics for Ned's hardware
3#
4
5steppers:
6 stepper_1:
7 # gear_ratio, max_effort and micro_steps not used for ttl steppers
8 motor_ratio: 0.0872
9 # assembly offset position (rad)
10 offset_position: -2.90
11 # home position (rad)
12 default_home_position: 0.0
13 limit_position_min: -2.90 # joint limit min
14 limit_position_max: 2.90 # joint limit max
15 # assembly direction (1 or -1)
16 direction: 1
17 v_start: 0.0
18 a_1: 2.199
19 v_1: 0.628
20 a_max: 4.363
21 v_max: 1.571
22 d_max: 4.363
23 d_1: 2.143
24 v_stop: 0.0209
25 torque_percentage: 100 # For Ned2's steppers, it only takes either 0 or 1. 100 by default means 1.
26
27 stepper_2:
28 motor_ratio: 0.0868
29 offset_position: 0.61
30 default_home_position: 0.5
31 limit_position_max: 0.61
32 limit_position_min: -2.09
33 direction: -1
34 v_start: 0.0
35 a_1: 1.0996
36 v_1: 0.251
37 a_max: 2.18
38 v_max: 1.047
39 d_max: 2.18
40 d_1: 1.07
41 v_stop: 0.0209
42 torque_percentage: 100 # For Ned2's steppers, it only takes either 0 or 1. 100 by default means 1.
43
44 stepper_3:
45 motor_ratio: 0.0868
46 offset_position: -1.34
47 default_home_position: -1.25
48 limit_position_min: -1.34
49 limit_position_max: 1.54
50 direction: 1
51 v_start: 0.0
52 a_1: 2.199
53 v_1: 0.628
54 a_max: 4.363
55 v_max: 1.571
56 d_max: 4.363
57 d_1: 2.143
58 v_stop: 0.0209
59 torque_percentage: 100 # For Ned2's steppers, it only takes either 0 or 1. 100 by default means 1.
For the Ned3pro robot:
1#
2# Stepper caracteristics for Ned's hardware
3#
4
5steppers:
6 stepper_1:
7 # gear_ratio, max_effort and micro_steps not used for ttl steppers
8 motor_ratio: 0.001
9 # assembly offset position (rad)
10 offset_position: 0.0
11 # home position (rad)
12 default_home_position: 0.0
13 limit_position_min: -2.96 # joint limit min
14 limit_position_max: 2.96 # joint limit max
15 # assembly direction (1 or -1)
16 direction: 1
17 a_max: 4.363
18 v_max: 2.45
19 torque_percentage: 40
20
21 stepper_2:
22 motor_ratio: 0.001
23 offset_position: 0.0
24 default_home_position: 0.44
25 limit_position_max: 0.44
26 limit_position_min: -1.75
27 direction: 1
28 a_max: 2.18
29 v_max: 1.047
30 torque_percentage: 60
31
32 stepper_3:
33 motor_ratio: 0.001
34 offset_position: 0.0
35 default_home_position: -1.22
36 limit_position_min: -1.22
37 limit_position_max: 1.57
38 direction: 1
39 a_max: 4.363
40 v_max: 1.5
41 torque_percentage: 40
These parameters allows us to define this kind of velocity profile for the Ned robot’s motors:

The dynamixel motors parameters
Ned robots use dynamixels servomotors for the last 3 axis. The parameters for the dynamixel motors are defined in the dynamixels_params.yaml config file.
For the Ned2 robot:
1dynamixels:
2 dxl_1:
3 # assembly offset position (rad)
4 offset_position: -3.1415
5 # home position (rad)
6 default_home_position: 0.0
7 direction: 1
8 # assembly direction (1 or -1)
9 limit_position_max: 2.089
10 limit_position_min: -2.093
11 position_P_gain: 1292
12 position_I_gain: 163
13 position_D_gain: 0
14 velocity_P_gain: 0
15 velocity_I_gain: 0
16 FF1_gain: 0
17 FF2_gain: 0
18 acceleration_profile: 100 # profile acc and vel used by dxl motors
19 velocity_profile: 200
20
21 dxl_2:
22 offset_position: 3.1415
23 default_home_position: 0.0
24 direction: -1
25 limit_position_max: 1.919
26 limit_position_min: -1.919
27 position_P_gain: 1292
28 position_I_gain: 13
29 position_D_gain: 0
30 velocity_P_gain: 0
31 velocity_I_gain: 0
32 FF1_gain: 0
33 FF2_gain: 0
34 acceleration_profile: 75 # profile acc and vel used by dxl motors
35 velocity_profile: 150
36
37 dxl_3:
38 offset_position: -3.1415
39 default_home_position: 0.0
40 direction: 1
41 limit_position_max: 2.53
42 limit_position_min: -2.529
43 position_P_gain: 1536
44 position_I_gain: 0
45 position_D_gain: 480
46 velocity_P_gain: 0
47 velocity_I_gain: 0
48 FF1_gain: 0
49 FF2_gain: 0
50 acceleration_profile: 50 # profile acc and vel used by dxl motors
51 velocity_profile: 100
For the Ned3pro robot:
1dynamixels:
2 dxl_1:
3 # assembly offset position (rad)
4 offset_position: -3.1415
5 # home position (rad)
6 default_home_position: 0.0
7 direction: 1
8 # assembly direction (1 or -1)
9 limit_position_max: 2.09
10 limit_position_min: -2.09
11 position_P_gain: 1500
12 position_I_gain: 4000
13 position_D_gain: 50
14 velocity_P_gain: 0
15 velocity_I_gain: 0
16 FF1_gain: 0
17 FF2_gain: 0
18 acceleration_profile: 80 # profile acc and vel used by dxl motors
19 velocity_profile: 170
20
21 dxl_2:
22 offset_position: 2.35619
23 default_home_position: 0.0
24 direction: -1
25 limit_position_max: 1.92
26 limit_position_min: -1.92
27 position_P_gain: 1000
28 position_I_gain: 4000
29 position_D_gain: 50
30 velocity_P_gain: 0
31 velocity_I_gain: 0
32 FF1_gain: 0
33 FF2_gain: 0
34 acceleration_profile: 70 # profile acc and vel used by dxl motors
35 velocity_profile: 140
36
37 dxl_3:
38 offset_position: -3.1415
39 default_home_position: 0.0
40 direction: 1
41 limit_position_max: 3.1415
42 limit_position_min: -3.1415
43 position_P_gain: 1500
44 position_I_gain: 4000
45 position_D_gain: 50
46 velocity_P_gain: 0
47 velocity_I_gain: 0
48 FF1_gain: 0
49 FF2_gain: 0
50 acceleration_profile: 105 # profile acc and vel used by dxl motors
51 velocity_profile: 210
These parameters allows us to configure some features, like the PID control gains, for the Ned robot’s dynamixel motors following the dynamixel control table of the current motor.
Package Documentation
For more informations about ROS topics, services and parameters, check the Niryo robot hardware interface documentation.
ROS Services
Service Name |
Type |
Description |
---|---|---|
/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 |
ROS Parameters
Parameter Name |
Default value |
Simulation value |
Unit |
Description |
---|---|---|---|---|
/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 |
ROS Action
Namespace: None