Skip to content

Commit 3d2f468

Browse files
Merge pull request #88 from ROBOTIS-GIT/Sync_Pos
Sync pos
2 parents 14ca4d4 + 321c7cf commit 3d2f468

File tree

3 files changed

+245
-5
lines changed

3 files changed

+245
-5
lines changed
Lines changed: 240 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,240 @@
1+
// Copyright 2021 ROBOTIS CO., LTD.
2+
//
3+
// Licensed under the Apache License, Version 2.0 (the "License");
4+
// you may not use this file except in compliance with the License.
5+
// You may obtain a copy of the License at
6+
//
7+
// http://www.apache.org/licenses/LICENSE-2.0
8+
//
9+
// Unless required by applicable law or agreed to in writing, software
10+
// distributed under the License is distributed on an "AS IS" BASIS,
11+
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
// See the License for the specific language governing permissions and
13+
// limitations under the License.
14+
15+
// Example Environment
16+
//
17+
// - DYNAMIXEL: X series
18+
// ID = 1 & 2, Baudrate = 57600bps, DYNAMIXEL Protocol 2.0
19+
// - Controller: Arduino MKR ZERO
20+
// DYNAMIXEL Shield for Arduino MKR
21+
// - https://emanual.robotis.com/docs/en/parts/interface/mkr_shield/
22+
//
23+
// Author: David Park
24+
25+
#include <Dynamixel2Arduino.h>
26+
27+
// Please modify it to suit your hardware.
28+
#if defined(ARDUINO_AVR_UNO) || defined(ARDUINO_AVR_MEGA2560) // When using DynamixelShield
29+
#include <SoftwareSerial.h>
30+
SoftwareSerial soft_serial(7, 8); // DYNAMIXELShield UART RX/TX
31+
#define DXL_SERIAL Serial
32+
#define DEBUG_SERIAL soft_serial
33+
const uint8_t DXL_DIR_PIN = 2; // DYNAMIXEL Shield DIR PIN
34+
#elif defined(ARDUINO_SAM_DUE) // When using DynamixelShield
35+
#define DXL_SERIAL Serial
36+
#define DEBUG_SERIAL SerialUSB
37+
const uint8_t DXL_DIR_PIN = 2; // DYNAMIXEL Shield DIR PIN
38+
#elif defined(ARDUINO_SAM_ZERO) // When using DynamixelShield
39+
#define DXL_SERIAL Serial1
40+
#define DEBUG_SERIAL SerialUSB
41+
const uint8_t DXL_DIR_PIN = 2; // DYNAMIXEL Shield DIR PIN
42+
#elif defined(ARDUINO_OpenCM904) // When using official ROBOTIS board with DXL circuit.
43+
#define DXL_SERIAL Serial3 //OpenCM9.04 EXP Board's DXL port Serial. (Serial1 for the DXL port on the OpenCM 9.04 board)
44+
#define DEBUG_SERIAL Serial
45+
const uint8_t DXL_DIR_PIN = 22; //OpenCM9.04 EXP Board's DIR PIN. (28 for the DXL port on the OpenCM 9.04 board)
46+
#elif defined(ARDUINO_OpenCR) // When using official ROBOTIS board with DXL circuit.
47+
// For OpenCR, there is a DXL Power Enable pin, so you must initialize and control it.
48+
// Reference link : https://github.com/ROBOTIS-GIT/OpenCR/blob/master/arduino/opencr_arduino/opencr/libraries/DynamixelSDK/src/dynamixel_sdk/port_handler_arduino.cpp#L78
49+
#define DXL_SERIAL Serial3
50+
#define DEBUG_SERIAL Serial
51+
const uint8_t DXL_DIR_PIN = 84; // OpenCR Board's DIR PIN.
52+
#else // Other boards when using DynamixelShield
53+
#define DXL_SERIAL Serial1
54+
#define DEBUG_SERIAL Serial
55+
const uint8_t DXL_DIR_PIN = 2; // DYNAMIXEL Shield DIR PIN
56+
#endif
57+
58+
59+
/* syncRead
60+
Structures containing the necessary information to process the 'syncRead' packet.
61+
62+
typedef struct XELInfoSyncRead{
63+
uint8_t *p_recv_buf;
64+
uint8_t id;
65+
uint8_t error;
66+
} __attribute__((packed)) XELInfoSyncRead_t;
67+
68+
typedef struct InfoSyncReadInst{
69+
uint16_t addr;
70+
uint16_t addr_length;
71+
XELInfoSyncRead_t* p_xels;
72+
uint8_t xel_count;
73+
bool is_info_changed;
74+
InfoSyncBulkBuffer_t packet;
75+
} __attribute__((packed)) InfoSyncReadInst_t;
76+
*/
77+
78+
/* syncWrite
79+
Structures containing the necessary information to process the 'syncWrite' packet.
80+
81+
typedef struct XELInfoSyncWrite{
82+
uint8_t* p_data;
83+
uint8_t id;
84+
} __attribute__((packed)) XELInfoSyncWrite_t;
85+
86+
typedef struct InfoSyncWriteInst{
87+
uint16_t addr;
88+
uint16_t addr_length;
89+
XELInfoSyncWrite_t* p_xels;
90+
uint8_t xel_count;
91+
bool is_info_changed;
92+
InfoSyncBulkBuffer_t packet;
93+
} __attribute__((packed)) InfoSyncWriteInst_t;
94+
*/
95+
96+
const uint8_t BROADCAST_ID = 254;
97+
const float DYNAMIXEL_PROTOCOL_VERSION = 2.0;
98+
const uint8_t DXL_ID_CNT = 2;
99+
const uint8_t DXL_ID_LIST[DXL_ID_CNT] = {1, 2};
100+
const uint16_t user_pkt_buf_cap = 128;
101+
uint8_t user_pkt_buf[user_pkt_buf_cap];
102+
103+
// Starting address of the Data to read; Present Position = 132
104+
const uint16_t SR_START_ADDR = 132;
105+
// Length of the Data to read; Length of Position data of X series is 4 byte
106+
const uint16_t SR_ADDR_LEN = 4;
107+
// Starting address of the Data to write; Goal Position = 116
108+
const uint16_t SW_START_ADDR = 116;
109+
// Length of the Data to write; Length of Position data of X series is 4 byte
110+
const uint16_t SW_ADDR_LEN = 4;
111+
typedef struct sr_data{
112+
int32_t present_position;
113+
} __attribute__((packed)) sr_data_t;
114+
typedef struct sw_data{
115+
int32_t goal_position;
116+
} __attribute__((packed)) sw_data_t;
117+
118+
119+
sr_data_t sr_data[DXL_ID_CNT];
120+
DYNAMIXEL::InfoSyncReadInst_t sr_infos;
121+
DYNAMIXEL::XELInfoSyncRead_t info_xels_sr[DXL_ID_CNT];
122+
123+
sw_data_t sw_data[DXL_ID_CNT];
124+
DYNAMIXEL::InfoSyncWriteInst_t sw_infos;
125+
DYNAMIXEL::XELInfoSyncWrite_t info_xels_sw[DXL_ID_CNT];
126+
127+
Dynamixel2Arduino dxl(DXL_SERIAL, DXL_DIR_PIN);
128+
129+
//This namespace is required to use DYNAMIXEL Control table item name definitions
130+
using namespace ControlTableItem;
131+
132+
int32_t goal_position[2] = {1024, 2048};
133+
uint8_t goal_position_index = 0;
134+
135+
void setup() {
136+
// put your setup code here, to run once:
137+
uint8_t i;
138+
pinMode(LED_BUILTIN, OUTPUT);
139+
DEBUG_SERIAL.begin(115200);
140+
dxl.begin(57600);
141+
dxl.setPortProtocolVersion(DYNAMIXEL_PROTOCOL_VERSION);
142+
143+
// Prepare the SyncRead structure
144+
for(i = 0; i < DXL_ID_CNT; i++){
145+
dxl.torqueOff(DXL_ID_LIST[i]);
146+
dxl.setOperatingMode(DXL_ID_LIST[i], OP_POSITION);
147+
}
148+
dxl.torqueOn(BROADCAST_ID);
149+
150+
// Fill the members of structure to syncRead using external user packet buffer
151+
sr_infos.packet.p_buf = user_pkt_buf;
152+
sr_infos.packet.buf_capacity = user_pkt_buf_cap;
153+
sr_infos.packet.is_completed = false;
154+
sr_infos.addr = SR_START_ADDR;
155+
sr_infos.addr_length = SR_ADDR_LEN;
156+
sr_infos.p_xels = info_xels_sr;
157+
sr_infos.xel_count = 0;
158+
159+
for(i = 0; i < DXL_ID_CNT; i++){
160+
info_xels_sr[i].id = DXL_ID_LIST[i];
161+
info_xels_sr[i].p_recv_buf = (uint8_t*)&sr_data[i];
162+
sr_infos.xel_count++;
163+
}
164+
sr_infos.is_info_changed = true;
165+
166+
// Fill the members of structure to syncWrite using internal packet buffer
167+
sw_infos.packet.p_buf = nullptr;
168+
sw_infos.packet.is_completed = false;
169+
sw_infos.addr = SW_START_ADDR;
170+
sw_infos.addr_length = SW_ADDR_LEN;
171+
sw_infos.p_xels = info_xels_sw;
172+
sw_infos.xel_count = 0;
173+
174+
for(i = 0; i < DXL_ID_CNT; i++){
175+
info_xels_sw[i].id = DXL_ID_LIST[i];
176+
info_xels_sw[i].p_data = (uint8_t*)&sw_data[i].goal_position;
177+
sw_infos.xel_count++;
178+
}
179+
sw_infos.is_info_changed = true;
180+
}
181+
182+
void loop() {
183+
// put your main code here, to run repeatedly:
184+
static uint32_t try_count = 0;
185+
uint8_t i, recv_cnt;
186+
187+
// Insert a new Goal Position to the SyncWrite Packet
188+
for(i = 0; i < DXL_ID_CNT; i++){
189+
sw_data[i].goal_position = goal_position[goal_position_index];
190+
}
191+
192+
// Update the SyncWrite packet status
193+
sw_infos.is_info_changed = true;
194+
195+
DEBUG_SERIAL.print("\n>>>>>> Sync Instruction Test : ");
196+
DEBUG_SERIAL.println(try_count++);
197+
198+
// Build a SyncWrite Packet and transmit to DYNAMIXEL
199+
if(dxl.syncWrite(&sw_infos) == true){
200+
DEBUG_SERIAL.println("[SyncWrite] Success");
201+
for(i = 0; i<sw_infos.xel_count; i++){
202+
DEBUG_SERIAL.print(" ID: ");DEBUG_SERIAL.println(sw_infos.p_xels[i].id);
203+
DEBUG_SERIAL.print("\t Goal Position: ");DEBUG_SERIAL.println(sw_data[i].goal_position);
204+
}
205+
if(goal_position_index == 0)
206+
goal_position_index = 1;
207+
else
208+
goal_position_index = 0;
209+
} else {
210+
DEBUG_SERIAL.print("[SyncWrite] Fail, Lib error code: ");
211+
DEBUG_SERIAL.print(dxl.getLastLibErrCode());
212+
}
213+
DEBUG_SERIAL.println();
214+
215+
delay(250);
216+
217+
218+
// Transmit predefined SyncRead instruction packet
219+
// and receive a status packet from each DYNAMIXEL
220+
recv_cnt = dxl.syncRead(&sr_infos);
221+
if(recv_cnt > 0) {
222+
DEBUG_SERIAL.print("[SyncRead] Success, Received ID Count: ");
223+
DEBUG_SERIAL.println(recv_cnt);
224+
for(i = 0; i<recv_cnt; i++){
225+
DEBUG_SERIAL.print(" ID: ");
226+
DEBUG_SERIAL.print(sr_infos.p_xels[i].id);
227+
DEBUG_SERIAL.print(", Error: ");
228+
DEBUG_SERIAL.println(sr_infos.p_xels[i].error);
229+
DEBUG_SERIAL.print("\t Present Position: ");
230+
DEBUG_SERIAL.println(sr_data[i].present_position);
231+
}
232+
}else{
233+
DEBUG_SERIAL.print("[SyncRead] Fail, Lib error code: ");
234+
DEBUG_SERIAL.println(dxl.getLastLibErrCode());
235+
}
236+
DEBUG_SERIAL.println("=======================================================");
237+
238+
digitalWrite(LED_BUILTIN, !digitalRead(LED_BUILTIN));
239+
delay(750);
240+
}

examples/advanced/sync_read_write_raw/sync_read_write_raw.ino renamed to examples/advanced/sync_read_write_velocity/sync_read_write_velocity.ino

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -94,9 +94,9 @@ const uint8_t DXL_ID_LIST[DXL_ID_CNT] = {1, 2};
9494
const uint16_t user_pkt_buf_cap = 128;
9595
uint8_t user_pkt_buf[user_pkt_buf_cap];
9696

97-
const uint16_t SR_START_ADDR = 126;
98-
const uint16_t SR_ADDR_LEN = 10; //2+4+4
99-
const uint16_t SW_START_ADDR = 104; //Goal velocity
97+
const uint16_t SR_START_ADDR = 126; // Starting Data Addr, Can differ Depending on what address to access
98+
const uint16_t SR_ADDR_LEN = 10; // Data Length (2+4+4), Can differ depending on how many address to access.
99+
const uint16_t SW_START_ADDR = 104;
100100
const uint16_t SW_ADDR_LEN = 4;
101101
typedef struct sr_data{
102102
int16_t present_current;
@@ -151,7 +151,6 @@ void setup() {
151151
}
152152
sr_infos.is_info_changed = true;
153153

154-
155154
// Fill the members of structure to syncWrite using internal packet buffer
156155
sw_infos.packet.p_buf = nullptr;
157156
sw_infos.packet.is_completed = false;
@@ -162,6 +161,7 @@ void setup() {
162161

163162
sw_data[0].goal_velocity = 0;
164163
sw_data[1].goal_velocity = 100;
164+
165165
for(i=0; i<DXL_ID_CNT; i++){
166166
info_xels_sw[i].id = DXL_ID_LIST[i];
167167
info_xels_sw[i].p_data = (uint8_t*)&sw_data[i].goal_velocity;

library.properties

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,5 @@
11
name=Dynamixel2Arduino
2-
version=0.5.1
2+
version=0.5.2
33
author=ROBOTIS
44
license=Apache-2.0
55
maintainer=Will Son([email protected])

0 commit comments

Comments
 (0)