Merge pull request #56 from ROBOTIS-GIT/master
merge for sync kinetic-devel and master branch
This commit is contained in:
		| @@ -22,7 +22,7 @@ find_package(catkin REQUIRED COMPONENTS | ||||
| ) | ||||
|  | ||||
| find_package(PkgConfig REQUIRED) | ||||
| pkg_check_modules(YAML_CPP REQUIRED yaml-cpp) | ||||
| pkg_check_modules(yaml_cpp yaml-cpp REQUIRED) | ||||
|  | ||||
| ################################################################################ | ||||
| # Declare ROS messages, services and actions | ||||
|   | ||||
							
								
								
									
										73
									
								
								robotis_device/devices/dynamixel/RH-P12-RN.device
									
									
									
									
									
										Executable file
									
								
							
							
						
						
									
										73
									
								
								robotis_device/devices/dynamixel/RH-P12-RN.device
									
									
									
									
									
										Executable file
									
								
							| @@ -0,0 +1,73 @@ | ||||
| [device info] | ||||
| model_name  = RH-P12-RN | ||||
| device_type = dynamixel | ||||
|  | ||||
| [type info] | ||||
| value_of_0_radian_position      = 0 | ||||
| value_of_min_radian_position    = 0 | ||||
| value_of_max_radian_position    = 740 | ||||
| min_radian                      = 0 | ||||
| max_radian                      = 1.150767 | ||||
|  | ||||
| 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_p_gain_item_name       = | ||||
|  | ||||
| [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             | 8           | N | ||||
|    9   | return_delay_time        | 1      | RW     | EEPROM | 0             | 254         | N | ||||
|    11  | operating_mode           | 1      | RW     | EEPROM | 0             | 4           | N | ||||
|    17  | moving_threshold         | 4      | RW     | EEPROM | 0             | 2147483647  | N | ||||
|    21  | max_temperature_limit    | 1      | RW     | EEPROM | 0             | 100         | N | ||||
|    22  | max_voltage_limit        | 2      | RW     | EEPROM | 0             | 400         | N | ||||
|    24  | min_voltage_limit        | 2      | RW     | EEPROM | 0             | 400         | N | ||||
|    26  | acceleration_limit       | 4      | RW     | EEPROM | 0             | 2147483647  | N | ||||
|    30  | current_limit            | 2      | RW     | EEPROM | 0             | 32767       | N | ||||
|    32  | velocity_limit           | 4      | RW     | EEPROM | 0             | 2147483647  | N | ||||
|    36  | max_position_limit       | 4      | RW     | EEPROM | -2147483648   | 2147483647  | Y | ||||
|    40  | min_position_limit       | 4      | RW     | EEPROM | -2147483648   | 2147483647  | Y | ||||
|    44  | external_port_mod_1      | 1      | RW     | EEPROM | 0             | 3           | N | ||||
|    45  | external_port_mod_2      | 1      | RW     | EEPROM | 0             | 3           | N | ||||
|    46  | external_port_mod_3      | 1      | RW     | EEPROM | 0             | 3           | N | ||||
|    47  | external_port_mod_4      | 1      | RW     | EEPROM | 0             | 3           | N | ||||
|    48  | shutdown                 | 1      | RW     | EEPROM | 0             | 255         | N | ||||
|    49  | indirect_address_1       | 2      | RW     | EEPROM | 0             | 65535       | N | ||||
|    562 | torque_enable            | 1      | RW     | RAM    | 0             | 1           | N | ||||
|    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 | ||||
|    590 | position_d_gain          | 2      | RW     | RAM    | 0             | 2047        | N | ||||
|    592 | position_i_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_current             | 2      | RW     | RAM    | -32768        | 32767       | Y | ||||
|    606 | goal_acceleration        | 4      | RW     | RAM    | 0             | 2147483647  | N | ||||
|    610 | is_moving                | 1      | R      | RAM    | 0             | 1           | N | ||||
|    611 | present_position         | 4      | R      | RAM    | -2147483648   | 2147483647  | Y | ||||
|    615 | present_velocity         | 4      | R      | RAM    | -2147483648   | 2147483647  | Y | ||||
|    621 | present_current          | 2      | R      | RAM    | -32768        | 32767       | Y | ||||
|    623 | present_voltage          | 2      | R      | RAM    | 0             | 500         | N | ||||
|    625 | present_temperature      | 1      | R      | RAM    | 0             | 200         | N | ||||
|    626 | external_port_data_1     | 2      | RW     | RAM    | 0             | 4095        | N | ||||
|    628 | external_port_data_2     | 2      | RW     | RAM    | 0             | 4095        | N | ||||
|    630 | external_port_data_3     | 2      | RW     | RAM    | 0             | 4095        | N | ||||
|    632 | external_port_data_4     | 2      | RW     | RAM    | 0             | 4095        | N | ||||
|    634 | indirect_data_1          | 1      | RW     | RAM    | 0             | 255         | N | ||||
|    890 | registerd_instruction    | 1      | R      | RAM    | 0             | 1           | N | ||||
|    891 | status_return_level      | 1      | RW     | RAM    | 0             | 2           | N | ||||
|    892 | hardware_error_status    | 2      | R      | RAM    | 0             | 31          | N | ||||
		Reference in New Issue
	
	Block a user
	 Pyo
					Pyo