Documentation Status

Cannot load information on name: dynamixel_workbench_toolbox, distro: electric, which means that it is not yet in our index. Please see this page for information on how to submit your repository to our index.
Cannot load information on name: dynamixel_workbench_toolbox, distro: fuerte, which means that it is not yet in our index. Please see this page for information on how to submit your repository to our index.
Cannot load information on name: dynamixel_workbench_toolbox, distro: groovy, which means that it is not yet in our index. Please see this page for information on how to submit your repository to our index.
Cannot load information on name: dynamixel_workbench_toolbox, distro: hydro, which means that it is not yet in our index. Please see this page for information on how to submit your repository to our index.
Cannot load information on name: dynamixel_workbench_toolbox, distro: indigo, which means that it is not yet in our index. Please see this page for information on how to submit your repository to our index.
Cannot load information on name: dynamixel_workbench_toolbox, distro: jade, which means that it is not yet in our index. Please see this page for information on how to submit your repository to our index.
dynamixel_workbench: dynamixel_workbench_controllers | dynamixel_workbench_operators | dynamixel_workbench_single_manager | dynamixel_workbench_single_manager_gui | dynamixel_workbench_toolbox

Package Summary

Released Continuous integration Documented

This package is composed of 'dynamixel_tool', 'dynamixel_driver' and 'dynamixel_multi_driver' class. The 'dynamixel_tool' class loads the information of Dynamixel stored in '.device' files. The 'dynamixel_driver' class which is based on dynamixel_sdk provides functions to control an Dynamixel. The 'dynamixel_multi_driver' class which is inherited by 'dynamixel_driver' class provides functions to control Dynamixels.

Cannot load information on name: dynamixel_workbench_toolbox, distro: lunar, which means that it is not yet in our index. Please see this page for information on how to submit your repository to our index.

Library

dynamixel_tool

dynamixel_tool is library for obtaining Dynamixel information (e.g. model name, model number, baudrate and control table).

Function

* DynamixelTool(uint8_t id, uint16_t model_number) - It helps find Dynamixel's information using id, model_number

* DynamixelTool(uint8_t id, std::string model_name) - It helps find Dynamixel's information using id, model_name

* bool getModelName(uint16_t model_number) - It helps find model name using model_number

* bool getModelPath() - It finds model information file(~.device) path

* bool getModelItem() - It arranges model information in model information file(~.device)

For example of model information(~.device):

[device info]
model_number = 1030
model_name  = XM430_W210_R

[type info]
torque_to_current_value_ratio   = 235.53647082
velocity_to_value_ratio         = 41.71

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

[baud rate]
# baud rate | value
9600        | 0
57600       | 1
115200      | 2
1000000     | 3
2000000     | 4
3000000     | 5
4000000     | 6
4500000     | 7

[control table]
# addr | item name                | length | access | memory
   0   | model_number             | 2      | R      | EEPROM
   6   | version_of_firmware      | 1      | R      | EEPROM
   7   | id                       | 1      | RW     | EEPROM
   8   | baud_rate                | 1      | RW     | EEPROM
   9   | return_delay_time        | 1      | RW     | EEPROM
   11  | operating_mode           | 1      | RW     | EEPROM
   13  | protocol_version         | 1      | RW     | EEPROM
   20  | homing_offset            | 4      | RW     | EEPROM
   24  | moving_threshold         | 4      | RW     | EEPROM
   31  | max_temperature_limit    | 1      | RW     | EEPROM
   32  | max_voltage_limit        | 2      | RW     | EEPROM
   34  | min_voltage_limit        | 2      | RW     | EEPROM
   36  | pwm_limit                | 2      | RW     | EEPROM
   38  | current_limit            | 2      | RW     | EEPROM
   40  | acceleration_limit       | 4      | RW     | EEPROM
   44  | velocity_limit           | 4      | RW     | EEPROM
   48  | max_position_limit       | 4      | RW     | EEPROM
   52  | min_position_limit       | 4      | RW     | EEPROM
   63  | shutdown                 | 1      | RW     | EEPROM
   64  | torque_enable            | 1      | RW     | RAM
   65  | led                      | 1      | RW     | RAM
   68  | status_return_level      | 1      | RW     | RAM
   69  | registered_instruction   | 1      | R      | RAM
   70  | hardware_error_status    | 1      | R      | RAM
   76  | velocity_i_gain          | 2      | RW     | RAM
   78  | velocity_p_gain          | 2      | RW     | RAM
   80  | position_d_gain          | 2      | RW     | RAM
   82  | position_i_gain          | 2      | RW     | RAM
   84  | position_p_gain          | 2      | RW     | RAM
   88  | feedforward_2nd_gain     | 2      | RW     | RAM
   90  | feedforward_1st_gain     | 2      | RW     | RAM
   100 | goal_pwm                 | 2      | RW     | RAM
   102 | goal_current             | 2      | RW     | RAM
   104 | goal_velocity            | 4      | RW     | RAM
   108 | profile_acceleration     | 4      | RW     | RAM
   112 | profile_velocity         | 4      | RW     | RAM
   116 | goal_position            | 4      | RW     | RAM
   120 | realtime_tick            | 2      | R      | RAM
   122 | moving                   | 1      | R      | RAM
   123 | moving_status            | 1      | R      | RAM
   124 | present_pwm              | 2      | R      | RAM
   126 | present_current          | 2      | R      | RAM
   128 | present_velocity         | 4      | R      | RAM
   132 | present_position         | 4      | R      | RAM
   136 | velocity_trajectory      | 4      | R      | RAM
   140 | position_trajectory      | 4      | R      | RAM
   144 | present_input_voltage    | 2      | R      | RAM
   146 | present_temperature      | 1      | R      | RAM
   168 | indirect_address_1       | 2      | RW     | RAM
   224 | indirect_data_1          | 1      | RW     | RAM
   578 | indirect_address_29      | 2      | RW     | RAM
   634 | indirect_data_29         | 1      | RW     | RAM

dynamixel_driver

dynamixel_driver is library to control a Dynamixel. It is based on Dynamixel SDK.

Function

* DynamixelDriver(std::string device_name, int baud_rate, float protocol_version) - It helps connect USB port and Dynamixel

* bool setPortHandler(std::string device_name) - It helps set porthandler (device_name : /tty/USBx)

* bool setPacketHandler(float protocol_version) - It helps set packethandler (protocol version : 1.0 or 2.0)

* bool scan() - It helps search Dynamixel ID and make Dynamixel instance.

* bool ping(uint8_t id) - It helps make Dynamixel instance.

* bool reboot() - Reboot Dynamixel (It only applies protocol version 2.0)

* bool reset() - Reset Dynamixel (ID : 1, BAUD RATE : 57600 or 1000000)

* bool setBaudrate(uint32_t baud_rate) - It helps set baudrate

* char* getPortName() - It helps get device name

* float getProtocolVersion() - It helps get protocol version

* uint32_t getBaudrate() - It helps get baudrate

* bool writeRegister(std::string addr_name, uint32_t value) - It helps write register

* bool readRegister(std::string addr_name, int32_t *value) - It helps read register

dynamixel_multi_driver

dynamixel_multi_driver is library to control multiple Dynamixels. It is inherited by dynamixel_driver.

Function

* DynamixelMultiDriver(std::string device_name, int baud_rate, float protocol_version) - It helps connect USB port and Dynamixel

* bool loadDynamixel(std::vector<dynamixel_driver::DynamixelInfo *> dynamixel_info) - It helps load multiple Dynamixel instances

* bool initSyncWrite() - It helps init sync write handler

* bool initSyncRead() - It helps init sync read handler

* dynamixel::GroupSyncWrite* setSyncWrite(std::string addr_name) - It helps set sync write handler

* dynamixel::GroupSyncRead* setSyncRead(std::string addr_name) - It helps set sync read handler

* bool readMultiRegister(std::string addr_name) - It helps read multiple information about dynamixel

* bool syncWrite[address_name](std::vector<xxx> &xxx) - It helps write value using sync write handler

* bool syncRead[address_name](std::vector<xxx> &xxx) - It helps read value using sync read handler

Wiki: dynamixel_workbench_toolbox (last edited 2017-06-23 01:02:16 by Darby Lim)