|
1 | | -%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% |
2 | | -% Copyright 2017 ROBOTIS CO., LTD. |
3 | | -% |
4 | | -% Licensed under the Apache License, Version 2.0 (the "License"); |
5 | | -% you may not use this file except in compliance with the License. |
6 | | -% You may obtain a copy of the License at |
7 | | -% |
8 | | -% http://www.apache.org/licenses/LICENSE-2.0 |
9 | | -% |
10 | | -% Unless required by applicable law or agreed to in writing, software |
11 | | -% distributed under the License is distributed on an "AS IS" BASIS, |
12 | | -% WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. |
13 | | -% See the License for the specific language governing permissions and |
14 | | -% limitations under the License. |
15 | | -%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% |
| 1 | +%{ |
| 2 | +Copyright 2017 ROBOTIS CO., LTD. |
| 3 | +
|
| 4 | +Licensed under the Apache License, Version 2.0 (the "License"); |
| 5 | +you may not use this file except in compliance with the License. |
| 6 | +You may obtain a copy of the License at |
| 7 | +
|
| 8 | + http://www.apache.org/licenses/LICENSE-2.0 |
| 9 | +
|
| 10 | +Unless required by applicable law or agreed to in writing, software |
| 11 | +distributed under the License is distributed on an "AS IS" BASIS, |
| 12 | +WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. |
| 13 | +See the License for the specific language governing permissions and |
| 14 | +limitations under the License. |
| 15 | +%} |
16 | 16 |
|
17 | 17 | % Author: Ryu Woon Jung (Leon) |
18 | 18 |
|
19 | | -% |
20 | | -% ********* Read and Write Example ********* |
21 | | -% |
22 | | -% |
23 | | -% Available Dynamixel model on this example : All models using Protocol 2.0 |
24 | | -% This example is designed for using a Dynamixel PRO 54-200, and an USB2DYNAMIXEL. |
25 | | -% To use another Dynamixel model, such as X series, see their details in E-Manual(emanual.robotis.com) and edit below variables yourself. |
26 | | -% Be sure that Dynamixel PRO properties are already set as %% ID : 1 / Baudnum : 1 (Baudrate : 57600) |
27 | | -% |
| 19 | +%{ |
| 20 | +********* Read and Write Example ****************** |
| 21 | +* Required Environment to run this example : |
| 22 | + - Protocol 2.0 supported DYNAMIXEL(X, P, PRO/PRO(A), MX 2.0 series) |
| 23 | + - DYNAMIXEL Starter Set (U2D2, U2D2 PHB, 12V SMPS) |
| 24 | +* How to use the example : |
| 25 | + - Use proper DYNAMIXEL Model definition from line #44 |
| 26 | + - Build and Run from proper architecture subdirectory. |
| 27 | + - For ARM based SBCs such as Raspberry Pi, use linux_sbc subdirectory to build and run. |
| 28 | + - https://emanual.robotis.com/docs/en/software/dynamixel/dynamixel_sdk/overview/ |
| 29 | +
|
| 30 | +* Author: Ryu Woon Jung (Leon) |
| 31 | +
|
| 32 | +* Maintainer : Zerom, Will Son |
| 33 | +*********************************************************** |
| 34 | +%} |
28 | 35 |
|
29 | 36 | clc; |
30 | 37 | clear all; |
|
48 | 55 | [notfound, warnings] = loadlibrary(lib_name, 'dynamixel_sdk.h', 'addheader', 'port_handler.h', 'addheader', 'packet_handler.h'); |
49 | 56 | end |
50 | 57 |
|
51 | | -% Control table address |
52 | | -ADDR_PRO_TORQUE_ENABLE = 562; % Control table address is different in Dynamixel model |
53 | | -ADDR_PRO_GOAL_POSITION = 596; |
54 | | -ADDR_PRO_PRESENT_POSITION = 611; |
| 58 | +%{ |
| 59 | +********* DYNAMIXEL Model ********* |
| 60 | +***** (Use only one definition at a time) ***** |
| 61 | +%} |
| 62 | + |
| 63 | + My_DXL = 'X_SERIES'; % X330, X430, X540, 2X430 |
| 64 | +% My_DXL = 'PRO_SERIES'; % H54, H42, M54, M42, L54, L42 |
| 65 | +% My_DXL = 'PRO_A_SERIES'; % PRO series with (A) firmware update. |
| 66 | +% My_DXL = 'P_SERIES'; % PH54, PH42, PM54 |
| 67 | +% My_DXL = 'XL320'; % [WARNING] Operating Voltage : 7.4V |
| 68 | +% My_DXL = 'MX_SERIES'; % MX series with 2.0 firmware update. |
| 69 | + |
| 70 | +% Control table address and data to Read/Write for my DYNAMIXEL, My_DXL, in use. |
| 71 | +switch (My_DXL) |
| 72 | + |
| 73 | + case {'X_SERIES','MX_SERIES'} |
| 74 | + ADDR_TORQUE_ENABLE = 64; |
| 75 | + ADDR_GOAL_POSITION = 116; |
| 76 | + ADDR_PRESENT_POSITION = 132; |
| 77 | + DXL_MINIMUM_POSITION_VALUE = 0; % Dynamixel will rotate between this value |
| 78 | + DXL_MAXIMUM_POSITION_VALUE = 4095; % and this value (note that the Dynamixel would not move when the position value is out of movable range. Check e-manual about the range of the Dynamixel you use.) |
| 79 | + BAUDRATE = 57600; |
| 80 | + |
| 81 | + case ('PRO_SERIES') |
| 82 | + ADDR_TORQUE_ENABLE = 562; % Control table address is different in DYNAMIXEL model |
| 83 | + ADDR_GOAL_POSITION = 596; |
| 84 | + ADDR_PRESENT_POSITION = 611; |
| 85 | + DXL_MINIMUM_POSITION_VALUE = -150000; % Refer to the Minimum Position Limit of product eManual |
| 86 | + DXL_MAXIMUM_POSITION_VALUE = 150000; % Refer to the Maximum Position Limit of product eManual |
| 87 | + BAUDRATE = 57600; |
| 88 | + |
| 89 | + case {'P_SERIES','PRO_A_SERIES'} |
| 90 | + ADDR_TORQUE_ENABLE = 512; % Control table address is different in DYNAMIXEL model |
| 91 | + ADDR_GOAL_POSITION = 564; |
| 92 | + ADDR_PRESENT_POSITION = 580; |
| 93 | + DXL_MINIMUM_POSITION_VALUE = -150000; % Refer to the Minimum Position Limit of product eManual |
| 94 | + DXL_MAXIMUM_POSITION_VALUE = 150000; % Refer to the Maximum Position Limit of product eManual |
| 95 | + BAUDRATE = 57600; |
| 96 | + case ('XL320') |
| 97 | + ADDR_TORQUE_ENABLE = 24; |
| 98 | + ADDR_GOAL_POSITION = 30; |
| 99 | + ADDR_PRESENT_POSITION = 37; |
| 100 | + DXL_MINIMUM_POSITION_VALUE = 0; % Refer to the CW Angle Limit of product eManual |
| 101 | + DXL_MAXIMUM_POSITION_VALUE = 1023; % Refer to the CCW Angle Limit of product eManual |
| 102 | + BAUDRATE = 1000000; % Default Baudrate of XL-320 is 1Mbps |
| 103 | +end |
| 104 | + |
| 105 | + |
| 106 | +% DYNAMIXEL Protocol Version (1.0 / 2.0) |
| 107 | +% https://emanual.robotis.com/docs/en/dxl/protocol2/ |
| 108 | +PROTOCOL_VERSION = 2.0; |
55 | 109 |
|
56 | | -% Protocol version |
57 | | -PROTOCOL_VERSION = 2.0; % See which protocol version is used in the Dynamixel |
| 110 | +% Factory default ID of all DYNAMIXEL is 1 |
| 111 | +DXL_ID = 1; |
58 | 112 |
|
59 | | -% Default setting |
60 | | -DXL_ID = 1; % Dynamixel ID: 1 |
61 | | -BAUDRATE = 57600; |
62 | | -DEVICENAME = 'COM1'; % Check which port is being used on your controller |
63 | | - % ex) Windows: 'COM1' Linux: '/dev/ttyUSB0' Mac: '/dev/tty.usbserial-*' |
| 113 | +% Use the actual port assigned to the U2D2. |
| 114 | +% ex) Windows: 'COM*', Linux: '/dev/ttyUSB*', Mac: '/dev/tty.usbserial-*' |
| 115 | +DEVICENAME = '/dev/ttyUSB0'; |
64 | 116 |
|
| 117 | +% Common Control Table Address and Data |
| 118 | +ADDR_OPERATING_MODE = 11; |
| 119 | +OPERATING_MODE = 3; % value for operating mode for position control |
65 | 120 | TORQUE_ENABLE = 1; % Value for enabling the torque |
66 | 121 | TORQUE_DISABLE = 0; % Value for disabling the torque |
67 | | -DXL_MINIMUM_POSITION_VALUE = -150000; % Dynamixel will rotate between this value |
68 | | -DXL_MAXIMUM_POSITION_VALUE = 150000; % and this value (note that the Dynamixel would not move when the position value is out of movable range. Check e-manual about the range of the Dynamixel you use.) |
69 | 122 | DXL_MOVING_STATUS_THRESHOLD = 20; % Dynamixel moving status threshold |
70 | 123 |
|
71 | 124 | ESC_CHARACTER = 'e'; % Key for escaping loop |
|
112 | 165 |
|
113 | 166 |
|
114 | 167 | % Enable Dynamixel Torque |
115 | | -write1ByteTxRx(port_num, PROTOCOL_VERSION, DXL_ID, ADDR_PRO_TORQUE_ENABLE, TORQUE_ENABLE); |
| 168 | +write1ByteTxRx(port_num, PROTOCOL_VERSION, DXL_ID, ADDR_TORQUE_ENABLE, TORQUE_ENABLE); |
116 | 169 | dxl_comm_result = getLastTxRxResult(port_num, PROTOCOL_VERSION); |
117 | 170 | dxl_error = getLastRxPacketError(port_num, PROTOCOL_VERSION); |
118 | 171 | if dxl_comm_result ~= COMM_SUCCESS |
|
130 | 183 | end |
131 | 184 |
|
132 | 185 | % Write goal position |
133 | | - write4ByteTxRx(port_num, PROTOCOL_VERSION, DXL_ID, ADDR_PRO_GOAL_POSITION, typecast(int32(dxl_goal_position(index)), 'uint32')); |
| 186 | + write4ByteTxRx(port_num, PROTOCOL_VERSION, DXL_ID, ADDR_GOAL_POSITION, typecast(int32(dxl_goal_position(index)), 'uint32')); |
134 | 187 | dxl_comm_result = getLastTxRxResult(port_num, PROTOCOL_VERSION); |
135 | 188 | dxl_error = getLastRxPacketError(port_num, PROTOCOL_VERSION); |
136 | 189 | if dxl_comm_result ~= COMM_SUCCESS |
|
141 | 194 |
|
142 | 195 | while 1 |
143 | 196 | % Read present position |
144 | | - dxl_present_position = read4ByteTxRx(port_num, PROTOCOL_VERSION, DXL_ID, ADDR_PRO_PRESENT_POSITION); |
| 197 | + dxl_present_position = read4ByteTxRx(port_num, PROTOCOL_VERSION, DXL_ID, ADDR_PRESENT_POSITION); |
145 | 198 | dxl_comm_result = getLastTxRxResult(port_num, PROTOCOL_VERSION); |
146 | 199 | dxl_error = getLastRxPacketError(port_num, PROTOCOL_VERSION); |
147 | 200 | if dxl_comm_result ~= COMM_SUCCESS |
|
167 | 220 |
|
168 | 221 |
|
169 | 222 | % Disable Dynamixel Torque |
170 | | -write1ByteTxRx(port_num, PROTOCOL_VERSION, DXL_ID, ADDR_PRO_TORQUE_ENABLE, TORQUE_DISABLE); |
| 223 | +write1ByteTxRx(port_num, PROTOCOL_VERSION, DXL_ID, ADDR_TORQUE_ENABLE, TORQUE_DISABLE); |
171 | 224 | dxl_comm_result = getLastTxRxResult(port_num, PROTOCOL_VERSION); |
172 | 225 | dxl_error = getLastRxPacketError(port_num, PROTOCOL_VERSION); |
173 | 226 | if dxl_comm_result ~= COMM_SUCCESS |
|
0 commit comments