- added XM540 device files
This commit is contained in:
89
robotis_device/devices/dynamixel/XM540-W150.device
Executable file
89
robotis_device/devices/dynamixel/XM540-W150.device
Executable file
@ -0,0 +1,89 @@
|
||||
[device info]
|
||||
model_name = XM540-W150
|
||||
device_type = dynamixel
|
||||
|
||||
[type info]
|
||||
torque_to_current_value_ratio = 289.13672036
|
||||
velocity_to_value_ratio = 41.707853
|
||||
|
||||
value_of_0_radian_position = 2048
|
||||
value_of_min_radian_position = 0
|
||||
value_of_max_radian_position = 4095
|
||||
min_radian = -3.14159265
|
||||
max_radian = 3.14159265
|
||||
|
||||
torque_enable_item_name = torque_enable
|
||||
present_position_item_name = present_position
|
||||
present_velocity_item_name = present_velocity
|
||||
present_current_item_name = present_current
|
||||
goal_position_item_name = goal_position
|
||||
goal_velocity_item_name = goal_velocity
|
||||
goal_current_item_name = goal_current
|
||||
position_d_gain_item_name = position_d_gain
|
||||
position_i_gain_item_name = position_i_gain
|
||||
position_p_gain_item_name = position_p_gain
|
||||
velocity_d_gain_item_name =
|
||||
velocity_i_gain_item_name = velocity_i_gain
|
||||
velocity_p_gain_item_name = velocity_p_gain
|
||||
|
||||
[control table]
|
||||
# addr | item name | length | access | memory | min value | max value | signed
|
||||
0 | model_number | 2 | R | EEPROM | 0 | 65535 | N
|
||||
6 | version_of_firmware | 1 | R | EEPROM | 0 | 254 | N
|
||||
7 | ID | 1 | RW | EEPROM | 0 | 252 | N
|
||||
8 | baudrate | 1 | RW | EEPROM | 0 | 7 | N
|
||||
9 | return_delay_time | 1 | RW | EEPROM | 0 | 254 | N
|
||||
11 | operating_mode | 1 | RW | EEPROM | 0 | 16 | N
|
||||
12 | secondary_id | 1 | RW | EEPROM | 0 | 255 | N
|
||||
20 | homing_offset | 4 | RW | EEPROM | -1044479 | 1044479 | Y
|
||||
24 | moving_threshold | 4 | RW | EEPROM | 0 | 1023 | N
|
||||
31 | max_temperature_limit | 1 | RW | EEPROM | 0 | 100 | N
|
||||
32 | max_voltage_limit | 2 | RW | EEPROM | 95 | 160 | N
|
||||
34 | min_voltage_limit | 2 | RW | EEPROM | 95 | 160 | N
|
||||
36 | pwm_limit | 2 | RW | EEPROM | 0 | 885 | N
|
||||
38 | current_limit | 2 | RW | EEPROM | 0 | 1193 | N
|
||||
40 | acceleration_limit | 4 | RW | EEPROM | 0 | 32767 | N
|
||||
44 | velocity_limit | 4 | RW | EEPROM | 0 | 1023 | N
|
||||
48 | max_position_limit | 4 | RW | EEPROM | 0 | 4095 | N
|
||||
52 | min_position_limit | 4 | RW | EEPROM | 0 | 4095 | N
|
||||
56 | external_port_mod_1 | 1 | RW | EEPROM | 0 | 3 | N
|
||||
57 | external_port_mod_2 | 1 | RW | EEPROM | 0 | 3 | N
|
||||
58 | external_port_mod_3 | 1 | RW | EEPROM | 0 | 3 | N
|
||||
63 | shutdown | 1 | RW | EEPROM | 0 | 255 | N
|
||||
64 | torque_enable | 1 | RW | RAM | 0 | 1 | N
|
||||
65 | LED | 1 | RW | RAM | 0 | 1 | N
|
||||
68 | status_return_level | 1 | RW | RAM | 0 | 2 | N
|
||||
69 | registered_instruction | 1 | R | RAM | 0 | 1 | N
|
||||
70 | hardware_error_status | 1 | R | RAM | 0 | 255 | N
|
||||
76 | velocity_i_gain | 2 | RW | RAM | 0 | 32767 | N
|
||||
78 | velocity_p_gain | 2 | RW | RAM | 0 | 32767 | N
|
||||
80 | position_d_gain | 2 | RW | RAM | 0 | 32767 | N
|
||||
82 | position_i_gain | 2 | RW | RAM | 0 | 32767 | N
|
||||
84 | position_p_gain | 2 | RW | RAM | 0 | 32767 | N
|
||||
88 | feedforward_2nd_gain | 2 | RW | RAM | 0 | 32767 | N
|
||||
90 | feedforward_1st_gain | 2 | RW | RAM | 0 | 32767 | N
|
||||
98 | bus_watchdog | 1 | RW | RAM | -1 | 127 | Y
|
||||
100 | goal_pwm | 2 | RW | RAM | 0 | 885 | N
|
||||
102 | goal_current | 2 | RW | RAM | 0 | 1193 | N
|
||||
104 | goal_velocity | 4 | RW | RAM | 0 | 1023 | N
|
||||
108 | profile_acceleration | 4 | RW | RAM | 0 | 32767 | N
|
||||
112 | profile_velocity | 4 | RW | RAM | 0 | 1023 | N
|
||||
116 | goal_position | 4 | RW | RAM | -1048575 | 1048575 | Y
|
||||
120 | realtime_tick | 2 | R | RAM | 0 | 32767 | N
|
||||
122 | moving | 1 | R | RAM | 0 | 1 | N
|
||||
123 | moving_status | 1 | R | RAM | 0 | 255 | N
|
||||
124 | present_pwm | 2 | R | RAM | 0 | 885 | N
|
||||
126 | present_current | 2 | R | RAM | 0 | 1193 | N
|
||||
128 | present_velocity | 4 | R | RAM | 0 | 1023 | N
|
||||
132 | present_position | 4 | R | RAM | -2147483648 | 2147483647 | Y
|
||||
136 | velocity_trajectory | 4 | R | RAM | 0 | 1023 | N
|
||||
140 | position_trajectory | 4 | R | RAM | 0 | 4095 | N
|
||||
144 | present_input_voltage | 2 | R | RAM | 95 | 160 | N
|
||||
146 | present_temperature | 1 | R | RAM | 0 | 100 | N
|
||||
152 | external_port_data_1 | 2 | RW | RAM | 0 | 4095 | N
|
||||
154 | external_port_data_2 | 2 | RW | RAM | 0 | 4095 | N
|
||||
156 | external_port_data_3 | 2 | RW | RAM | 0 | 4095 | N
|
||||
168 | indirect_address_1 | 2 | RW | RAM | 0 | 65535 | N
|
||||
224 | indirect_data_1 | 1 | RW | RAM | 0 | 255 | N
|
||||
578 | indirect_address_29 | 2 | RW | RAM | 0 | 65535 | N
|
||||
634 | indirect_data_29 | 1 | RW | RAM | 0 | 255 | N
|
89
robotis_device/devices/dynamixel/XM540-W270.device
Executable file
89
robotis_device/devices/dynamixel/XM540-W270.device
Executable file
@ -0,0 +1,89 @@
|
||||
[device info]
|
||||
model_name = XM540-W270
|
||||
device_type = dynamixel
|
||||
|
||||
[type info]
|
||||
torque_to_current_value_ratio = 156.133829
|
||||
velocity_to_value_ratio = 41.707853
|
||||
|
||||
value_of_0_radian_position = 2048
|
||||
value_of_min_radian_position = 0
|
||||
value_of_max_radian_position = 4095
|
||||
min_radian = -3.14159265
|
||||
max_radian = 3.14159265
|
||||
|
||||
torque_enable_item_name = torque_enable
|
||||
present_position_item_name = present_position
|
||||
present_velocity_item_name = present_velocity
|
||||
present_current_item_name = present_current
|
||||
goal_position_item_name = goal_position
|
||||
goal_velocity_item_name = goal_velocity
|
||||
goal_current_item_name = goal_current
|
||||
position_d_gain_item_name = position_d_gain
|
||||
position_i_gain_item_name = position_i_gain
|
||||
position_p_gain_item_name = position_p_gain
|
||||
velocity_d_gain_item_name =
|
||||
velocity_i_gain_item_name = velocity_i_gain
|
||||
velocity_p_gain_item_name = velocity_p_gain
|
||||
|
||||
[control table]
|
||||
# addr | item name | length | access | memory | min value | max value | signed
|
||||
0 | model_number | 2 | R | EEPROM | 0 | 65535 | N
|
||||
6 | version_of_firmware | 1 | R | EEPROM | 0 | 254 | N
|
||||
7 | ID | 1 | RW | EEPROM | 0 | 252 | N
|
||||
8 | baudrate | 1 | RW | EEPROM | 0 | 7 | N
|
||||
9 | return_delay_time | 1 | RW | EEPROM | 0 | 254 | N
|
||||
11 | operating_mode | 1 | RW | EEPROM | 0 | 16 | N
|
||||
12 | secondary_id | 1 | RW | EEPROM | 0 | 255 | N
|
||||
20 | homing_offset | 4 | RW | EEPROM | -1044479 | 1044479 | Y
|
||||
24 | moving_threshold | 4 | RW | EEPROM | 0 | 1023 | N
|
||||
31 | max_temperature_limit | 1 | RW | EEPROM | 0 | 100 | N
|
||||
32 | max_voltage_limit | 2 | RW | EEPROM | 95 | 160 | N
|
||||
34 | min_voltage_limit | 2 | RW | EEPROM | 95 | 160 | N
|
||||
36 | pwm_limit | 2 | RW | EEPROM | 0 | 885 | N
|
||||
38 | current_limit | 2 | RW | EEPROM | 0 | 1193 | N
|
||||
40 | acceleration_limit | 4 | RW | EEPROM | 0 | 32767 | N
|
||||
44 | velocity_limit | 4 | RW | EEPROM | 0 | 1023 | N
|
||||
48 | max_position_limit | 4 | RW | EEPROM | 0 | 4095 | N
|
||||
52 | min_position_limit | 4 | RW | EEPROM | 0 | 4095 | N
|
||||
56 | external_port_mod_1 | 1 | RW | EEPROM | 0 | 3 | N
|
||||
57 | external_port_mod_2 | 1 | RW | EEPROM | 0 | 3 | N
|
||||
58 | external_port_mod_3 | 1 | RW | EEPROM | 0 | 3 | N
|
||||
63 | shutdown | 1 | RW | EEPROM | 0 | 255 | N
|
||||
64 | torque_enable | 1 | RW | RAM | 0 | 1 | N
|
||||
65 | LED | 1 | RW | RAM | 0 | 1 | N
|
||||
68 | status_return_level | 1 | RW | RAM | 0 | 2 | N
|
||||
69 | registered_instruction | 1 | R | RAM | 0 | 1 | N
|
||||
70 | hardware_error_status | 1 | R | RAM | 0 | 255 | N
|
||||
76 | velocity_i_gain | 2 | RW | RAM | 0 | 32767 | N
|
||||
78 | velocity_p_gain | 2 | RW | RAM | 0 | 32767 | N
|
||||
80 | position_d_gain | 2 | RW | RAM | 0 | 32767 | N
|
||||
82 | position_i_gain | 2 | RW | RAM | 0 | 32767 | N
|
||||
84 | position_p_gain | 2 | RW | RAM | 0 | 32767 | N
|
||||
88 | feedforward_2nd_gain | 2 | RW | RAM | 0 | 32767 | N
|
||||
90 | feedforward_1st_gain | 2 | RW | RAM | 0 | 32767 | N
|
||||
98 | bus_watchdog | 1 | RW | RAM | -1 | 127 | Y
|
||||
100 | goal_pwm | 2 | RW | RAM | 0 | 885 | N
|
||||
102 | goal_current | 2 | RW | RAM | 0 | 1193 | N
|
||||
104 | goal_velocity | 4 | RW | RAM | 0 | 1023 | N
|
||||
108 | profile_acceleration | 4 | RW | RAM | 0 | 32767 | N
|
||||
112 | profile_velocity | 4 | RW | RAM | 0 | 1023 | N
|
||||
116 | goal_position | 4 | RW | RAM | -1048575 | 1048575 | Y
|
||||
120 | realtime_tick | 2 | R | RAM | 0 | 32767 | N
|
||||
122 | moving | 1 | R | RAM | 0 | 1 | N
|
||||
123 | moving_status | 1 | R | RAM | 0 | 255 | N
|
||||
124 | present_pwm | 2 | R | RAM | 0 | 885 | N
|
||||
126 | present_current | 2 | R | RAM | 0 | 1193 | N
|
||||
128 | present_velocity | 4 | R | RAM | 0 | 1023 | N
|
||||
132 | present_position | 4 | R | RAM | -2147483648 | 2147483647 | Y
|
||||
136 | velocity_trajectory | 4 | R | RAM | 0 | 1023 | N
|
||||
140 | position_trajectory | 4 | R | RAM | 0 | 4095 | N
|
||||
144 | present_input_voltage | 2 | R | RAM | 95 | 160 | N
|
||||
146 | present_temperature | 1 | R | RAM | 0 | 100 | N
|
||||
152 | external_port_data_1 | 2 | RW | RAM | 0 | 4095 | N
|
||||
154 | external_port_data_2 | 2 | RW | RAM | 0 | 4095 | N
|
||||
156 | external_port_data_3 | 2 | RW | RAM | 0 | 4095 | N
|
||||
168 | indirect_address_1 | 2 | RW | RAM | 0 | 65535 | N
|
||||
224 | indirect_data_1 | 1 | RW | RAM | 0 | 255 | N
|
||||
578 | indirect_address_29 | 2 | RW | RAM | 0 | 65535 | N
|
||||
634 | indirect_data_29 | 1 | RW | RAM | 0 | 255 | N
|
Reference in New Issue
Block a user