modified.

This commit is contained in:
ROBOTIS-zerom
2016-04-29 16:18:25 +09:00
parent 738b68b6e4
commit c72bab42ba
59 changed files with 1987 additions and 789 deletions

View File

@ -19,7 +19,7 @@ find_package(catkin REQUIRED COMPONENTS
## DEPENDS: system dependencies of this project that dependent projects also need
catkin_package(
INCLUDE_DIRS include
# LIBRARIES robotis_device
LIBRARIES robotis_device
CATKIN_DEPENDS roscpp rospy
# DEPENDS system_lib
)
@ -56,6 +56,5 @@ add_dependencies(robotis_device ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXP
## Specify libraries to link a library or executable target against
target_link_libraries(robotis_device
dynamixel_sdk
${catkin_LIBRARIES}
)

View File

@ -1,6 +1,6 @@
[device info]
model_name = GRIPPER
device_type = Dynamixel
device_type = dynamixel
[type info]
value_of_0_radian_position = 0
@ -8,17 +8,17 @@ value_of_min_radian_position = 0
value_of_max_radian_position = 750
min_radian = 0
max_radian = 1.150767
torque_enable_address = 562
position_d_gain_address =
position_i_gain_address =
position_p_gain_address = 594
goal_position_address = 596
goal_velocity_address = 600
goal_torque_address = 604
present_position_address = 611
present_velocity_address = 615
present_load_address = 621
is_moving_address = 610
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_torque
position_d_gain_item_name =
position_i_gain_item_name =
position_p_gain_item_name = position_p_gain
[control table]
# addr | item name | length | access | memory | min value | max value | signed
@ -47,9 +47,9 @@ is_moving_address = 610
563 | LED_RED | 1 | RW | RAM | 0 | 255 | N
564 | LED_GREEN | 1 | RW | RAM | 0 | 255 | N
565 | LED_BLUE | 1 | RW | RAM | 0 | 255 | N
586 | velocity_I_gain | 2 | RW | RAM | 0 | 2047 | N
588 | velocity_P_gain | 2 | RW | RAM | 0 | 2047 | N
594 | position_P_gain | 2 | RW | RAM | 0 | 2047 | N
586 | velocity_i_gain | 2 | RW | RAM | 0 | 2047 | N
588 | velocity_p_gain | 2 | RW | RAM | 0 | 2047 | N
594 | position_p_gain | 2 | RW | RAM | 0 | 2047 | N
596 | goal_position | 4 | RW | RAM | -2147483648 | 2147483647 | Y
600 | goal_velocity | 4 | RW | RAM | -2147483648 | 2147483647 | Y
604 | goal_torque | 2 | RW | RAM | -32768 | 32767 | Y

View File

@ -1,24 +1,26 @@
[device info]
model_name = H42-20-S300-R
device_type = Dynamixel
device_type = dynamixel
[type info]
current_ratio = 4.0283203125
value_of_0_radian_position = 0
value_of_min_radian_position = -151900
value_of_max_radian_position = 151900
min_radian = -3.14159265
max_radian = 3.14159265
torque_enable_address = 562
position_d_gain_address =
position_i_gain_address =
position_p_gain_address = 594
goal_position_address = 596
goal_velocity_address = 600
goal_torque_address = 604
present_position_address = 611
present_velocity_address = 615
present_load_address = 621
is_moving_address = 610
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_torque
position_d_gain_item_name =
position_i_gain_item_name =
position_p_gain_item_name = position_p_gain
[control table]
# addr | item name | length | access | memory | min value | max value | signed
@ -48,9 +50,9 @@ is_moving_address = 610
563 | LED_RED | 1 | RW | RAM | 0 | 255 | N
564 | LED_GREEN | 1 | RW | RAM | 0 | 255 | N
565 | LED_BLUE | 1 | RW | RAM | 0 | 255 | N
586 | velocity_I_gain | 2 | RW | RAM | 0 | 2047 | N
588 | velocity_P_gain | 2 | RW | RAM | 0 | 2047 | N
594 | position_P_gain | 2 | RW | RAM | 0 | 2047 | N
586 | velocity_i_gain | 2 | RW | RAM | 0 | 2047 | N
588 | velocity_p_gain | 2 | RW | RAM | 0 | 2047 | N
594 | position_p_gain | 2 | RW | RAM | 0 | 2047 | N
596 | goal_position | 4 | RW | RAM | -2147483648 | 2147483647 | Y
600 | goal_velocity | 4 | RW | RAM | -2147483648 | 2147483647 | Y
604 | goal_torque | 2 | RW | RAM | -32768 | 32767 | Y

View File

@ -1,24 +1,26 @@
[device info]
model_name = H54-100-S500-R
device_type = Dynamixel
device_type = dynamixel
[type info]
current_ratio = 16.11328125
value_of_0_radian_position = 0
value_of_min_radian_position = -250950
value_of_max_radian_position = 250950
min_radian = -3.14159265
max_radian = 3.14159265
torque_enable_address = 562
position_d_gain_address =
position_i_gain_address =
position_p_gain_address = 594
goal_position_address = 596
goal_velocity_address = 600
goal_torque_address = 604
present_position_address = 611
present_velocity_address = 615
present_load_address = 621
is_moving_address = 610
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_torque
position_d_gain_item_name =
position_i_gain_item_name =
position_p_gain_item_name = position_p_gain
[control table]
# addr | item name | length | access | memory | min value | max value | signed
@ -48,9 +50,9 @@ is_moving_address = 610
563 | LED_RED | 1 | RW | RAM | 0 | 255 | N
564 | LED_GREEN | 1 | RW | RAM | 0 | 255 | N
565 | LED_BLUE | 1 | RW | RAM | 0 | 255 | N
586 | velocity_I_gain | 2 | RW | RAM | 0 | 2047 | N
588 | velocity_P_gain | 2 | RW | RAM | 0 | 2047 | N
594 | position_P_gain | 2 | RW | RAM | 0 | 2047 | N
586 | velocity_i_gain | 2 | RW | RAM | 0 | 2047 | N
588 | velocity_p_gain | 2 | RW | RAM | 0 | 2047 | N
594 | position_p_gain | 2 | RW | RAM | 0 | 2047 | N
596 | goal_position | 4 | RW | RAM | -2147483648 | 2147483647 | Y
600 | goal_velocity | 4 | RW | RAM | -2147483648 | 2147483647 | Y
604 | goal_torque | 2 | RW | RAM | -32768 | 32767 | Y

View File

@ -1,24 +1,26 @@
[device info]
model_name = H54-200-B500-R
device_type = Dynamixel
device_type = dynamixel
[type info]
current_ratio = 16.11328125
value_of_0_radian_position = 0
value_of_min_radian_position = -250950
value_of_max_radian_position = 250950
min_radian = -3.14159265
max_radian = 3.14159265
torque_enable_address = 562
position_d_gain_address =
position_i_gain_address =
position_p_gain_address = 594
goal_position_address = 596
goal_velocity_address = 600
goal_torque_address = 604
present_position_address = 611
present_velocity_address = 615
present_load_address = 621
is_moving_address = 610
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_torque
position_d_gain_item_name =
position_i_gain_item_name =
position_p_gain_item_name = position_p_gain
[control table]
# addr | item name | length | access | memory | min value | max value | signed
@ -48,9 +50,9 @@ is_moving_address = 610
563 | LED_RED | 1 | RW | RAM | 0 | 255 | N
564 | LED_GREEN | 1 | RW | RAM | 0 | 255 | N
565 | LED_BLUE | 1 | RW | RAM | 0 | 255 | N
586 | velocity_I_gain | 2 | RW | RAM | 0 | 2047 | N
588 | velocity_P_gain | 2 | RW | RAM | 0 | 2047 | N
594 | position_P_gain | 2 | RW | RAM | 0 | 2047 | N
586 | velocity_i_gain | 2 | RW | RAM | 0 | 2047 | N
588 | velocity_p_gain | 2 | RW | RAM | 0 | 2047 | N
594 | position_p_gain | 2 | RW | RAM | 0 | 2047 | N
596 | goal_position | 4 | RW | RAM | -2147483648 | 2147483647 | Y
600 | goal_velocity | 4 | RW | RAM | -2147483648 | 2147483647 | Y
604 | goal_torque | 2 | RW | RAM | -32768 | 32767 | Y

View File

@ -1,24 +1,26 @@
[device info]
model_name = H54-200-S500-R
device_type = Dynamixel
device_type = dynamixel
[type info]
current_ratio = 16.11328125
value_of_0_radian_position = 0
value_of_min_radian_position = -250950
value_of_max_radian_position = 250950
min_radian = -3.14159265
max_radian = 3.14159265
torque_enable_address = 562
position_d_gain_address =
position_i_gain_address =
position_p_gain_address = 594
goal_position_address = 596
goal_velocity_address = 600
goal_torque_address = 604
present_position_address = 611
present_velocity_address = 615
present_load_address = 621
is_moving_address = 610
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_torque
position_d_gain_item_name =
position_i_gain_item_name =
position_p_gain_item_name = position_p_gain
[control table]
# addr | item name | length | access | memory | min value | max value | signed
@ -48,9 +50,9 @@ is_moving_address = 610
563 | LED_RED | 1 | RW | RAM | 0 | 255 | N
564 | LED_GREEN | 1 | RW | RAM | 0 | 255 | N
565 | LED_BLUE | 1 | RW | RAM | 0 | 255 | N
586 | velocity_I_gain | 2 | RW | RAM | 0 | 2047 | N
588 | velocity_P_gain | 2 | RW | RAM | 0 | 2047 | N
594 | position_P_gain | 2 | RW | RAM | 0 | 2047 | N
586 | velocity_i_gain | 2 | RW | RAM | 0 | 2047 | N
588 | velocity_p_gain | 2 | RW | RAM | 0 | 2047 | N
594 | position_p_gain | 2 | RW | RAM | 0 | 2047 | N
596 | goal_position | 4 | RW | RAM | -2147483648 | 2147483647 | Y
600 | goal_velocity | 4 | RW | RAM | -2147483648 | 2147483647 | Y
604 | goal_torque | 2 | RW | RAM | -32768 | 32767 | Y

View File

@ -1,6 +1,6 @@
[device info]
model_name = L42-10-S300-R
device_type = Dynamixel
device_type = dynamixel
[type info]
value_of_0_radian_position = 0
@ -8,17 +8,17 @@ value_of_min_radian_position = -2047
value_of_max_radian_position = 2048
min_radian = -3.14159265
max_radian = 3.14159265
torque_enable_address = 562
position_d_gain_address =
position_i_gain_address =
position_p_gain_address = 594
goal_position_address = 596
goal_velocity_address = 600
goal_torque_address = 604
present_position_address = 611
present_velocity_address = 615
present_load_address = 621
is_moving_address = 610
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_torque
position_d_gain_item_name =
position_i_gain_item_name =
position_p_gain_item_name = position_p_gain
[control table]
# addr | item name | length | access | memory | min value | max value | signed
@ -47,9 +47,9 @@ is_moving_address = 610
563 | LED_RED | 1 | RW | RAM | 0 | 255 | N
564 | LED_GREEN | 1 | RW | RAM | 0 | 255 | N
565 | LED_BLUE | 1 | RW | RAM | 0 | 255 | N
586 | velocity_I_gain | 2 | RW | RAM | 0 | 2047 | N
588 | velocity_P_gain | 2 | RW | RAM | 0 | 2047 | N
594 | position_P_gain | 2 | RW | RAM | 0 | 2047 | N
586 | velocity_i_gain | 2 | RW | RAM | 0 | 2047 | N
588 | velocity_p_gain | 2 | RW | RAM | 0 | 2047 | N
594 | position_p_gain | 2 | RW | RAM | 0 | 2047 | N
596 | goal_position | 4 | RW | RAM | -2147483648 | 2147483647 | Y
600 | goal_velocity | 4 | RW | RAM | -2147483648 | 2147483647 | Y
604 | goal_torque | 2 | RW | RAM | -32768 | 32767 | Y

View File

@ -1,24 +1,26 @@
[device info]
model_name = L54-30-S400-R
device_type = Dynamixel
device_type = dynamixel
[type info]
current_ratio = 16.11328125
value_of_0_radian_position = 0
value_of_min_radian_position = -144198
value_of_max_radian_position = 144198
min_radian = -3.14159265
max_radian = 3.14159265
torque_enable_address = 562
position_d_gain_address =
position_i_gain_address =
position_p_gain_address = 594
goal_position_address = 596
goal_velocity_address = 600
goal_torque_address = 604
present_position_address = 611
present_velocity_address = 615
present_load_address = 621
is_moving_address = 610
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_torque
position_d_gain_item_name =
position_i_gain_item_name =
position_p_gain_item_name = position_p_gain
[control table]
# addr | item name | length | access | memory | min value | max value | signed
@ -48,9 +50,9 @@ is_moving_address = 610
563 | LED_RED | 1 | RW | RAM | 0 | 255 | N
564 | LED_GREEN | 1 | RW | RAM | 0 | 255 | N
565 | LED_BLUE | 1 | RW | RAM | 0 | 255 | N
586 | velocity_I_gain | 2 | RW | RAM | 0 | 2047 | N
588 | velocity_P_gain | 2 | RW | RAM | 0 | 2047 | N
594 | position_P_gain | 2 | RW | RAM | 0 | 2047 | N
586 | velocity_i_gain | 2 | RW | RAM | 0 | 2047 | N
588 | velocity_p_gain | 2 | RW | RAM | 0 | 2047 | N
594 | position_p_gain | 2 | RW | RAM | 0 | 2047 | N
596 | goal_position | 4 | RW | RAM | -2147483648 | 2147483647 | Y
600 | goal_velocity | 4 | RW | RAM | -2147483648 | 2147483647 | Y
604 | goal_torque | 2 | RW | RAM | -32768 | 32767 | Y

View File

@ -1,24 +1,26 @@
[device info]
model_name = L54-30-S500-R
device_type = Dynamixel
device_type = dynamixel
[type info]
current_ratio = 16.11328125
value_of_0_radian_position = 0
value_of_min_radian_position = -180684
value_of_max_radian_position = 180684
min_radian = -3.14159265
max_radian = 3.14159265
torque_enable_address = 562
position_d_gain_address =
position_i_gain_address =
position_p_gain_address = 594
goal_position_address = 596
goal_velocity_address = 600
goal_torque_address = 604
present_position_address = 611
present_velocity_address = 615
present_load_address = 621
is_moving_address = 610
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_torque
position_d_gain_item_name =
position_i_gain_item_name =
position_p_gain_item_name = position_p_gain
[control table]
# addr | item name | length | access | memory | min value | max value | signed
@ -48,9 +50,9 @@ is_moving_address = 610
563 | LED_RED | 1 | RW | RAM | 0 | 255 | N
564 | LED_GREEN | 1 | RW | RAM | 0 | 255 | N
565 | LED_BLUE | 1 | RW | RAM | 0 | 255 | N
586 | velocity_I_gain | 2 | RW | RAM | 0 | 2047 | N
588 | velocity_P_gain | 2 | RW | RAM | 0 | 2047 | N
594 | position_P_gain | 2 | RW | RAM | 0 | 2047 | N
586 | velocity_i_gain | 2 | RW | RAM | 0 | 2047 | N
588 | velocity_p_gain | 2 | RW | RAM | 0 | 2047 | N
594 | position_p_gain | 2 | RW | RAM | 0 | 2047 | N
596 | goal_position | 4 | RW | RAM | -2147483648 | 2147483647 | Y
600 | goal_velocity | 4 | RW | RAM | -2147483648 | 2147483647 | Y
604 | goal_torque | 2 | RW | RAM | -32768 | 32767 | Y

View File

@ -1,24 +1,26 @@
[device info]
model_name = L54-50-S290-R
device_type = Dynamixel
device_type = dynamixel
[type info]
current_ratio = 16.11328125
value_of_0_radian_position = 0
value_of_min_radian_position = -103860
value_of_max_radian_position = 103860
min_radian = -3.14159265
max_radian = 3.14159265
torque_enable_address = 562
position_d_gain_address =
position_i_gain_address =
position_p_gain_address = 594
goal_position_address = 596
goal_velocity_address = 600
goal_torque_address = 604
present_position_address = 611
present_velocity_address = 615
present_load_address = 621
is_moving_address = 610
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_torque
position_d_gain_item_name =
position_i_gain_item_name =
position_p_gain_item_name = position_p_gain
[control table]
# addr | item name | length | access | memory | min value | max value | signed
@ -48,9 +50,9 @@ is_moving_address = 610
563 | LED_RED | 1 | RW | RAM | 0 | 255 | N
564 | LED_GREEN | 1 | RW | RAM | 0 | 255 | N
565 | LED_BLUE | 1 | RW | RAM | 0 | 255 | N
586 | velocity_I_gain | 2 | RW | RAM | 0 | 2047 | N
588 | velocity_P_gain | 2 | RW | RAM | 0 | 2047 | N
594 | position_P_gain | 2 | RW | RAM | 0 | 2047 | N
586 | velocity_i_gain | 2 | RW | RAM | 0 | 2047 | N
588 | velocity_p_gain | 2 | RW | RAM | 0 | 2047 | N
594 | position_p_gain | 2 | RW | RAM | 0 | 2047 | N
596 | goal_position | 4 | RW | RAM | -2147483648 | 2147483647 | Y
600 | goal_velocity | 4 | RW | RAM | -2147483648 | 2147483647 | Y
604 | goal_torque | 2 | RW | RAM | -32768 | 32767 | Y

View File

@ -1,24 +1,26 @@
[device info]
model_name = L54-50-S500-R
device_type = Dynamixel
device_type = dynamixel
[type info]
current_ratio = 16.11328125
value_of_0_radian_position = 0
value_of_min_radian_position = -180684
value_of_max_radian_position = 180684
min_radian = -3.14159265
max_radian = 3.14159265
torque_enable_address = 562
position_d_gain_address =
position_i_gain_address =
position_p_gain_address = 594
goal_position_address = 596
goal_velocity_address = 600
goal_torque_address = 604
present_position_address = 611
present_velocity_address = 615
present_load_address = 621
is_moving_address = 610
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_torque
position_d_gain_item_name =
position_i_gain_item_name =
position_p_gain_item_name = position_p_gain
[control table]
# addr | item name | length | access | memory | min value | max value | signed
@ -48,9 +50,9 @@ is_moving_address = 610
563 | LED_RED | 1 | RW | RAM | 0 | 255 | N
564 | LED_GREEN | 1 | RW | RAM | 0 | 255 | N
565 | LED_BLUE | 1 | RW | RAM | 0 | 255 | N
586 | velocity_I_gain | 2 | RW | RAM | 0 | 2047 | N
588 | velocity_P_gain | 2 | RW | RAM | 0 | 2047 | N
594 | position_P_gain | 2 | RW | RAM | 0 | 2047 | N
586 | velocity_i_gain | 2 | RW | RAM | 0 | 2047 | N
588 | velocity_p_gain | 2 | RW | RAM | 0 | 2047 | N
594 | position_p_gain | 2 | RW | RAM | 0 | 2047 | N
596 | goal_position | 4 | RW | RAM | -2147483648 | 2147483647 | Y
600 | goal_velocity | 4 | RW | RAM | -2147483648 | 2147483647 | Y
604 | goal_torque | 2 | RW | RAM | -32768 | 32767 | Y

View File

@ -1,24 +1,26 @@
[device info]
model_name = M42-10-S260-R
device_type = Dynamixel
device_type = dynamixel
[type info]
current_ratio = 4.0283203125
value_of_0_radian_position = 0
value_of_min_radian_position = -131584
value_of_max_radian_position = 131584
min_radian = -3.14159265
max_radian = 3.14159265
torque_enable_address = 562
position_d_gain_address =
position_i_gain_address =
position_p_gain_address = 594
goal_position_address = 596
goal_velocity_address = 600
goal_torque_address = 604
present_position_address = 611
present_velocity_address = 615
present_load_address = 621
is_moving_address = 610
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_torque
position_d_gain_item_name =
position_i_gain_item_name =
position_p_gain_item_name = position_p_gain
[control table]
# addr | item name | length | access | memory | min value | max value | signed
@ -48,9 +50,9 @@ is_moving_address = 610
563 | LED_RED | 1 | RW | RAM | 0 | 255 | N
564 | LED_GREEN | 1 | RW | RAM | 0 | 255 | N
565 | LED_BLUE | 1 | RW | RAM | 0 | 255 | N
586 | velocity_I_gain | 2 | RW | RAM | 0 | 2047 | N
588 | velocity_P_gain | 2 | RW | RAM | 0 | 2047 | N
594 | position_P_gain | 2 | RW | RAM | 0 | 2047 | N
586 | velocity_i_gain | 2 | RW | RAM | 0 | 2047 | N
588 | velocity_p_gain | 2 | RW | RAM | 0 | 2047 | N
594 | position_p_gain | 2 | RW | RAM | 0 | 2047 | N
596 | goal_position | 4 | RW | RAM | -2147483648 | 2147483647 | Y
600 | goal_velocity | 4 | RW | RAM | -2147483648 | 2147483647 | Y
604 | goal_torque | 2 | RW | RAM | -32768 | 32767 | Y

View File

@ -1,24 +1,26 @@
[device info]
model_name = M54-40-S250-R
device_type = Dynamixel
device_type = dynamixel
[type info]
current_ratio = 16.11328125
value_of_0_radian_position = 0
value_of_min_radian_position = -125700
value_of_max_radian_position = 125700
min_radian = -3.14159265
max_radian = 3.14159265
torque_enable_address = 562
position_d_gain_address =
position_i_gain_address =
position_p_gain_address = 594
goal_position_address = 596
goal_velocity_address = 600
goal_torque_address = 604
present_position_address = 611
present_velocity_address = 615
present_load_address = 621
is_moving_address = 610
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_torque
position_d_gain_item_name =
position_i_gain_item_name =
position_p_gain_item_name = position_p_gain
[control table]
# addr | item name | length | access | memory | min value | max value | signed
@ -48,9 +50,9 @@ is_moving_address = 610
563 | LED_RED | 1 | RW | RAM | 0 | 255 | N
564 | LED_GREEN | 1 | RW | RAM | 0 | 255 | N
565 | LED_BLUE | 1 | RW | RAM | 0 | 255 | N
586 | velocity_I_gain | 2 | RW | RAM | 0 | 2047 | N
588 | velocity_P_gain | 2 | RW | RAM | 0 | 2047 | N
594 | position_P_gain | 2 | RW | RAM | 0 | 2047 | N
586 | velocity_i_gain | 2 | RW | RAM | 0 | 2047 | N
588 | velocity_p_gain | 2 | RW | RAM | 0 | 2047 | N
594 | position_p_gain | 2 | RW | RAM | 0 | 2047 | N
596 | goal_position | 4 | RW | RAM | -2147483648 | 2147483647 | Y
600 | goal_velocity | 4 | RW | RAM | -2147483648 | 2147483647 | Y
604 | goal_torque | 2 | RW | RAM | -32768 | 32767 | Y

View File

@ -1,24 +1,26 @@
[device info]
model_name = M54-60-S250-R
device_type = Dynamixel
device_type = dynamixel
[type info]
current_ratio = 16.11328125
value_of_0_radian_position = 0
value_of_min_radian_position = -125700
value_of_max_radian_position = 125700
min_radian = -3.14159265
max_radian = 3.14159265
torque_enable_address = 562
position_d_gain_address =
position_i_gain_address =
position_p_gain_address = 594
goal_position_address = 596
goal_velocity_address = 600
goal_torque_address = 604
present_position_address = 611
present_velocity_address = 615
present_load_address = 621
is_moving_address = 610
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_torque
position_d_gain_item_name =
position_i_gain_item_name =
position_p_gain_item_name = position_p_gain
[control table]
# addr | item name | length | access | memory | min value | max value | signed
@ -48,9 +50,9 @@ is_moving_address = 610
563 | LED_RED | 1 | RW | RAM | 0 | 255 | N
564 | LED_GREEN | 1 | RW | RAM | 0 | 255 | N
565 | LED_BLUE | 1 | RW | RAM | 0 | 255 | N
586 | velocity_I_gain | 2 | RW | RAM | 0 | 2047 | N
588 | velocity_P_gain | 2 | RW | RAM | 0 | 2047 | N
594 | position_P_gain | 2 | RW | RAM | 0 | 2047 | N
586 | velocity_i_gain | 2 | RW | RAM | 0 | 2047 | N
588 | velocity_p_gain | 2 | RW | RAM | 0 | 2047 | N
594 | position_p_gain | 2 | RW | RAM | 0 | 2047 | N
596 | goal_position | 4 | RW | RAM | -2147483648 | 2147483647 | Y
600 | goal_velocity | 4 | RW | RAM | -2147483648 | 2147483647 | Y
604 | goal_torque | 2 | RW | RAM | -32768 | 32767 | Y

View File

@ -1,6 +1,6 @@
[device info]
model_name = MX-28
device_type = Dynamixel
device_type = dynamixel
[type info]
value_of_0_radian_position = 2048
@ -8,17 +8,17 @@ value_of_min_radian_position = 0
value_of_max_radian_position = 4095
min_radian = -3.14159265
max_radian = 3.14159265
torque_enable_address = 24
position_d_gain_address = 26
position_i_gain_address = 27
position_p_gain_address = 28
goal_position_address = 30
goal_velocity_address = 32
goal_torque_address = 34
present_position_address = 36
present_velocity_address = 38
present_load_address = 40
is_moving_address = 46
torque_enable_item_name = torque_enable
present_position_item_name = present_position
present_velocity_item_name = present_velocity
present_current_item_name =
goal_position_item_name = goal_position
goal_velocity_item_name = goal_velocity
goal_current_item_name =
position_d_gain_item_name = position_d_gain
position_i_gain_item_name = position_i_gain
position_p_gain_item_name = position_p_gain
[control table]
# addr | item name | length | access | memory | min value | max value | signed
@ -41,9 +41,9 @@ is_moving_address = 46
22 | resolution_dividor | 1 | RW | EEPROM | 1 | 255 | N
24 | torque_enable | 1 | RW | RAM | 0 | 1 | N
25 | LED | 1 | RW | RAM | 0 | 1 | N
26 | position_D_gain | 1 | RW | RAM | 0 | 254 | N
27 | position_I_gain | 1 | RW | RAM | 0 | 254 | N
28 | position_P_gain | 1 | RW | RAM | 0 | 254 | N
26 | position_d_gain | 1 | RW | RAM | 0 | 254 | N
27 | position_i_gain | 1 | RW | RAM | 0 | 254 | N
28 | position_p_gain | 1 | RW | RAM | 0 | 254 | N
30 | goal_position | 2 | RW | RAM | -28672 | 28672 | Y
32 | goal_velocity | 2 | RW | RAM | 0 | 1023 | N
34 | goal_torque | 2 | RW | RAM | 0 | 1023 | N

View File

@ -27,6 +27,7 @@ enum MEMORY_TYPE {
class ControlTableItem
{
public:
std::string item_name;
UINT16_T address;
ACCESS_TYPE access_type;
MEMORY_TYPE memory_type;
@ -36,7 +37,8 @@ public:
bool is_signed;
ControlTableItem()
: address(0),
: item_name(""),
address(0),
access_type(READ),
memory_type(RAM),
data_length(0),

View File

@ -10,6 +10,7 @@
#include <map>
#include <vector>
#include <string>
#include "DynamixelState.h"
#include "ControlTableItem.h"
@ -30,28 +31,36 @@ public:
std::string ctrl_module_name;
DynamixelState *dxl_state;
double current_ratio;
double velocity_ratio;
INT32_T value_of_0_radian_position;
INT32_T value_of_min_radian_position;
INT32_T value_of_max_radian_position;
double min_radian;
double max_radian;
UINT16_T torque_enable_address;
UINT16_T position_d_gain_address;
UINT16_T position_i_gain_address;
UINT16_T position_p_gain_address;
UINT16_T goal_position_address;
UINT16_T goal_velocity_address;
UINT16_T goal_torque_address;
UINT16_T present_position_address;
UINT16_T present_velocity_address;
UINT16_T present_load_address;
UINT16_T is_moving_address;
ControlTableItem *torque_enable_item;
ControlTableItem *present_position_item;
ControlTableItem *present_velocity_item;
ControlTableItem *present_current_item;
ControlTableItem *goal_position_item;
ControlTableItem *goal_velocity_item;
ControlTableItem *goal_current_item;
std::vector<ControlTableItem *> bulk_read_items;
std::map<std::string, UINT16_T> indirect_address_table;
Dynamixel(int id, std::string model_name, float protocol_version);
double ConvertValue2Radian(INT32_T value);
INT32_T ConvertRadian2Value(double radian);
double ConvertValue2Velocity(INT32_T value);
INT32_T ConvertVelocity2Value(double velocity);
double ConvertValue2Current(INT16_T value);
INT16_T ConvertCurrent2Value(double torque);
};
}

View File

@ -11,6 +11,9 @@
#include <stdint.h>
#include <robotis_framework_common/RobotisDef.h>
#define INDIRECT_DATA_1 "indirect_data_1"
#define INDIRECT_ADDRESS_1 "indirect_address_1"
namespace ROBOTIS
{
@ -26,47 +29,28 @@ class DynamixelState
public:
TimeStamp update_time_stamp;
bool torque_enable;
UINT16_T position_d_gain;
UINT16_T position_i_gain;
UINT16_T position_p_gain;
UINT16_T velocity_d_gain;
UINT16_T velocity_i_gain;
UINT16_T velocity_p_gain;
double goal_position;
double goal_velocity;
double goal_torque;
double present_position;
double present_velocity;
double present_load;
bool is_moving;
double present_current;
double goal_position;
double goal_velocity;
double goal_current;
UINT16_T ext_port_data[4];
std::map<std::string, UINT32_T> bulk_read_table;
double position_offset;
DynamixelState()
: update_time_stamp(0, 0),
torque_enable(false),
position_d_gain(0),
position_i_gain(0),
position_p_gain(0),
velocity_d_gain(0),
velocity_i_gain(0),
velocity_p_gain(0),
goal_position(0.0),
goal_velocity(0.0),
goal_torque(0.0),
present_position(0.0),
present_velocity(0.0),
present_load(0.0),
is_moving(false),
present_current(0.0),
goal_position(0.0),
goal_velocity(0.0),
goal_current(0.0),
position_offset(0.0)
{
ext_port_data[0] = 2048;
ext_port_data[1] = 2048;
ext_port_data[2] = 2048;
ext_port_data[3] = 2048;
bulk_read_table.clear();
}
};

View File

@ -21,6 +21,8 @@ class Robot
{
public:
std::map<std::string, PortHandler *> ports; // string: port name
std::map<std::string, std::string> port_default_joint; // port name, default joint name
std::map<std::string, Dynamixel *> dxls; // string: joint name
std::map<std::string, Sensor *> sensors; // string: sensor name

View File

@ -15,25 +15,26 @@ Dynamixel::Dynamixel(int id, std::string model_name, float protocol_version)
port_name(""),
ctrl_module_name("none"),
protocol_version(protocol_version),
current_ratio(1.0),
velocity_ratio(1.0),
value_of_0_radian_position(0),
value_of_min_radian_position(0),
value_of_max_radian_position(0),
min_radian(-3.14),
max_radian(3.14),
torque_enable_address(0),
position_d_gain_address(0),
position_i_gain_address(0),
position_p_gain_address(0),
goal_position_address(0),
goal_velocity_address(0),
goal_torque_address(0),
present_position_address(0),
present_velocity_address(0),
present_load_address(0),
is_moving_address(0)
min_radian(-3.14159265),
max_radian(3.14159265),
torque_enable_item(0),
present_position_item(0),
present_velocity_item(0),
present_current_item(0),
goal_position_item(0),
goal_velocity_item(0),
goal_current_item(0)
{
ctrl_table.clear();
dxl_state = new DynamixelState();
bulk_read_items.clear();
indirect_address_table.clear();
}
double Dynamixel::ConvertValue2Radian(INT32_T value)
@ -87,3 +88,23 @@ INT32_T Dynamixel::ConvertRadian2Value(double radian)
return _value;
}
double Dynamixel::ConvertValue2Velocity(INT32_T value)
{
return (double)value * velocity_ratio;
}
INT32_T Dynamixel::ConvertVelocity2Value(double velocity)
{
return (INT32_T)(velocity / velocity_ratio);;
}
double Dynamixel::ConvertValue2Current(INT16_T value)
{
return (double)value * current_ratio;
}
INT16_T Dynamixel::ConvertCurrent2Value(double torque)
{
return (INT16_T)(torque / current_ratio);
}

View File

@ -71,18 +71,19 @@ Robot::Robot(std::string robot_file_path, std::string dev_desc_dir_path)
if(session == "port info")
{
std::vector<std::string> tokens = split(input_str, '|');
if(tokens.size() != 2)
if(tokens.size() != 3)
continue;
std::cout << tokens[0] << " added. (baudrate: " << tokens[1] << ")" << std::endl;
ports[tokens[0]] = (PortHandler*)PortHandler::GetPortHandler(tokens[0].c_str());
ports[tokens[0]]->SetBaudRate(std::atoi(tokens[1].c_str()));
port_default_joint[tokens[0]] = tokens[2];
}
else if(session == "device info")
{
std::vector<std::string> tokens = split(input_str, '|');
if(tokens.size() != 6)
if(tokens.size() != 7)
continue;
if(tokens[0] == "dynamixel")
@ -94,6 +95,39 @@ Robot::Robot(std::string robot_file_path, std::string dev_desc_dir_path)
std::string _dev_name = tokens[5];
dxls[_dev_name] = getDynamixel(_file_path, _id, _port, _protocol);
Dynamixel *_dxl = dxls[_dev_name];
std::vector<std::string> sub_tokens = split(tokens[6], ',');
if(sub_tokens.size() > 0)
{
std::map<std::string, ControlTableItem *>::iterator _indirect_it = _dxl->ctrl_table.find(INDIRECT_ADDRESS_1);
if(_indirect_it != _dxl->ctrl_table.end()) // INDIRECT_ADDRESS_1 exist
{
UINT16_T _indirect_data_addr = _dxl->ctrl_table[INDIRECT_DATA_1]->address;
for(int _i = 0; _i < sub_tokens.size(); _i++)
{
_dxl->bulk_read_items.push_back(new ControlTableItem());
ControlTableItem *_dest_item = _dxl->bulk_read_items[_i];
ControlTableItem *_src_item = _dxl->ctrl_table[sub_tokens[_i]];
_dest_item->item_name = _src_item->item_name;
_dest_item->address = _indirect_data_addr;
_dest_item->access_type = _src_item->access_type;
_dest_item->memory_type = _src_item->memory_type;
_dest_item->data_length = _src_item->data_length;
_dest_item->data_min_value = _src_item->data_min_value;
_dest_item->data_max_value = _src_item->data_max_value;
_dest_item->is_signed = _src_item->is_signed;
_indirect_data_addr += _dest_item->data_length;
}
}
else // INDIRECT_ADDRESS_1 exist
{
for(int _i = 0; _i < sub_tokens.size(); _i++)
_dxl->bulk_read_items.push_back(_dxl->ctrl_table[sub_tokens[_i]]);
}
}
}
}
}
@ -112,47 +146,61 @@ Dynamixel *Robot::getDynamixel(std::string path, int id, std::string port, float
std::ifstream file(path.c_str());
if(file.is_open())
{
std::string session = "";
std::string input_str;
std::string _session = "";
std::string _input_str;
std::string _torque_enable_item_name = "";
std::string _present_position_item_name = "";
std::string _present_velocity_item_name = "";
std::string _present_current_item_name = "";
std::string _goal_position_item_name = "";
std::string _goal_velocity_item_name = "";
std::string _goal_current_item_name = "";
while(!file.eof())
{
std::getline(file, input_str);
std::getline(file, _input_str);
// remove comment ( # )
std::size_t pos = input_str.find("#");
std::size_t pos = _input_str.find("#");
if(pos != std::string::npos)
input_str = input_str.substr(0, pos);
_input_str = _input_str.substr(0, pos);
// trim
input_str = trim(input_str);
if(input_str == "")
_input_str = trim(_input_str);
if(_input_str == "")
continue;
// find session
if(!input_str.compare(0, 1, "[") && !input_str.compare(input_str.size()-1, 1, "]"))
// find _session
if(!_input_str.compare(0, 1, "[") && !_input_str.compare(_input_str.size()-1, 1, "]"))
{
input_str = input_str.substr(1, input_str.size()-2);
std::transform(input_str.begin(), input_str.end(), input_str.begin(), ::tolower);
session = trim(input_str);
_input_str = _input_str.substr(1, _input_str.size()-2);
std::transform(_input_str.begin(), _input_str.end(), _input_str.begin(), ::tolower);
_session = trim(_input_str);
continue;
}
if(session == "device info")
if(_session == "device info")
{
std::vector<std::string> tokens = split(input_str, '=');
std::vector<std::string> tokens = split(_input_str, '=');
if(tokens.size() != 2)
continue;
if(tokens[0] == "model_name")
dxl = new Dynamixel(id, tokens[1], protocol_version);
}
else if(session == "type info")
else if(_session == "type info")
{
std::vector<std::string> tokens = split(input_str, '=');
std::vector<std::string> tokens = split(_input_str, '=');
if(tokens.size() != 2)
continue;
if(tokens[0] == "value_of_0_radian_position")
if(tokens[0] == "current_ratio")
dxl->current_ratio = std::atof(tokens[1].c_str());
else if(tokens[0] == "velocity_ratio")
dxl->velocity_ratio = std::atof(tokens[1].c_str());
else if(tokens[0] == "value_of_0_radian_position")
dxl->value_of_0_radian_position = std::atoi(tokens[1].c_str());
else if(tokens[0] == "value_of_min_radian_position")
dxl->value_of_min_radian_position = std::atoi(tokens[1].c_str());
@ -162,36 +210,30 @@ Dynamixel *Robot::getDynamixel(std::string path, int id, std::string port, float
dxl->min_radian = std::atof(tokens[1].c_str());
else if(tokens[0] == "max_radian")
dxl->max_radian = std::atof(tokens[1].c_str());
else if(tokens[0] == "torque_enable_address")
dxl->torque_enable_address = std::atoi(tokens[1].c_str());
else if(tokens[0] == "position_d_gain_address")
dxl->position_d_gain_address = std::atoi(tokens[1].c_str());
else if(tokens[0] == "position_i_gain_address")
dxl->position_i_gain_address = std::atoi(tokens[1].c_str());
else if(tokens[0] == "position_p_gain_address")
dxl->position_p_gain_address = std::atoi(tokens[1].c_str());
else if(tokens[0] == "goal_position_address")
dxl->goal_position_address = std::atoi(tokens[1].c_str());
else if(tokens[0] == "goal_velocity_address")
dxl->goal_velocity_address = std::atoi(tokens[1].c_str());
else if(tokens[0] == "goal_torque_address")
dxl->goal_torque_address = std::atoi(tokens[1].c_str());
else if(tokens[0] == "present_position_address")
dxl->present_position_address = std::atoi(tokens[1].c_str());
else if(tokens[0] == "present_velocity_address")
dxl->present_velocity_address = std::atoi(tokens[1].c_str());
else if(tokens[0] == "present_load_address")
dxl->present_load_address = std::atoi(tokens[1].c_str());
else if(tokens[0] == "is_moving_address")
dxl->is_moving_address = std::atoi(tokens[1].c_str());
else if(tokens[0] == "torque_enable_item_name")
_torque_enable_item_name = tokens[1];
else if(tokens[0] == "present_position_item_name")
_present_position_item_name = tokens[1];
else if(tokens[0] == "present_velocity_item_name")
_present_velocity_item_name = tokens[1];
else if(tokens[0] == "present_current_item_name")
_present_current_item_name = tokens[1];
else if(tokens[0] == "goal_position_item_name")
_goal_position_item_name = tokens[1];
else if(tokens[0] == "goal_velocity_item_name")
_goal_velocity_item_name = tokens[1];
else if(tokens[0] == "goal_current_item_name")
_goal_current_item_name = tokens[1];
}
else if(session == "control table")
else if(_session == "control table")
{
std::vector<std::string> tokens = split(input_str, '|');
std::vector<std::string> tokens = split(_input_str, '|');
if(tokens.size() != 8)
continue;
ControlTableItem *item = new ControlTableItem();
item->item_name = tokens[1];
item->address = std::atoi(tokens[0].c_str());
item->data_length = std::atoi(tokens[2].c_str());
if(tokens[3] == "R")
@ -213,6 +255,21 @@ Dynamixel *Robot::getDynamixel(std::string path, int id, std::string port, float
}
dxl->port_name = port;
if(dxl->ctrl_table[_torque_enable_item_name] != NULL)
dxl->torque_enable_item = dxl->ctrl_table[_torque_enable_item_name];
if(dxl->ctrl_table[_present_position_item_name] != NULL)
dxl->present_position_item = dxl->ctrl_table[_present_position_item_name];
if(dxl->ctrl_table[_present_velocity_item_name] != NULL)
dxl->present_velocity_item = dxl->ctrl_table[_present_velocity_item_name];
if(dxl->ctrl_table[_present_current_item_name] != NULL)
dxl->present_current_item = dxl->ctrl_table[_present_current_item_name];
if(dxl->ctrl_table[_goal_position_item_name] != NULL)
dxl->goal_position_item = dxl->ctrl_table[_goal_position_item_name];
if(dxl->ctrl_table[_goal_velocity_item_name] != NULL)
dxl->goal_velocity_item = dxl->ctrl_table[_goal_velocity_item_name];
if(dxl->ctrl_table[_goal_current_item_name] != NULL)
dxl->goal_current_item = dxl->ctrl_table[_goal_current_item_name];
fprintf(stderr, "(%s) [ID:%3d] %14s added. \n", port.c_str(), dxl->id, dxl->model_name.c_str());
//std::cout << "[ID:" << (int)(dxl->id) << "] " << dxl->model_name << " added. (" << port << ")" << std::endl;
file.close();