Skip to content

Commit 6b048cf

Browse files
author
Kei
authored
Merge pull request #29 from ROBOTIS-GIT/develop
Develop
2 parents a688da3 + 70ce86a commit 6b048cf

Some content is hidden

Large Commits have some content hidden by default. Use the searchbox below for content that may be hidden.

45 files changed

+4889
-2229
lines changed

.travis.yml

+1
Original file line numberDiff line numberDiff line change
@@ -25,3 +25,4 @@ notifications:
2525
branches:
2626
only:
2727
- master
28+
- develop

README.md

+14
Original file line numberDiff line numberDiff line change
@@ -1,9 +1,23 @@
11
# Dynamixel2Arduino [![Build Status](https://travis-ci.org/ROBOTIS-GIT/Dynamixel2Arduino.svg?branch=master)](https://travis-ci.org/ROBOTIS-GIT/Dynamixel2Arduino/branches)
22

3+
## Serial and Direction Pin definitions by board
4+
- The examples default to pins based on DynamixelShield. Therefore, when using hardware other than DynamixelShield (eg OpenCM9.04, OpenCR, Custom DXL boards), you need to change the Serial and Direction Pin.
5+
- We provide the information below to make it easier to define Serial and Direction pins for specific hardware.
6+
7+
|Board Name|Serial|Direction Pin|Note|
8+
|:-:|:-:|:-:|:-:|
9+
|OpenCM9.04|Serial1|28|because of the OpenCM 9.04 driver code, you must call Serial1.setDxlMode(true); before dxl.begin();.|
10+
|OpenCM9.04 EXP|Serial3|22||
11+
|OpenCR|Serial3|84|For OpenCR, there is a DXL Power Enable pin, so you must initialize and control it. ([Reference link](https://github.com/ROBOTIS-GIT/OpenCR/blob/master/arduino/opencr_arduino/opencr/libraries/DynamixelSDK/src/dynamixel_sdk/port_handler_arduino.cpp#L78))|
12+
13+
314
## How to add new DYNAMIXEL model.
415
- For the convenience of the user, Dynamixel2Arduino API hardcodes some information in the control table and stores it in flash.
516
- To do this, you need to add code to some files. In this regard, please refer to [PR#3](https://github.com/ROBOTIS-GIT/Dynamixel2Arduino/pull/3) and [PR#7](https://github.com/ROBOTIS-GIT/Dynamixel2Arduino/pull/7)
617

18+
## How to create custom PortHandler Class
19+
- Please refer to [port_handler.h](https://github.com/ROBOTIS-GIT/Dynamixel2Arduino/blob/master/src/utility/port_handler.h)
20+
- Create a new class by inheriting PortHandler as public. (Like SerialPortHandler and USBSerialPortHandler)
721

822
## TODO
923
- Separation of protocol codes (protocol, packet handler)
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,174 @@
1+
/*******************************************************************************
2+
* Copyright 2016 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+
17+
/*
18+
This is an example deprecated. (Not recommended, just an example for legacy)
19+
*/
20+
21+
#include <Dynamixel2Arduino.h>
22+
23+
// Please modify it to suit your hardware.
24+
#if defined(ARDUINO_AVR_UNO) || defined(ARDUINO_AVR_MEGA2560) // When using DynamixelShield
25+
#include <SoftwareSerial.h>
26+
SoftwareSerial soft_serial(7, 8); // DYNAMIXELShield UART RX/TX
27+
#define DXL_SERIAL Serial
28+
#define DEBUG_SERIAL soft_serial
29+
const uint8_t DXL_DIR_PIN = 2; // DYNAMIXEL Shield DIR PIN
30+
#elif defined(ARDUINO_SAM_DUE) // When using DynamixelShield
31+
#define DXL_SERIAL Serial
32+
#define DEBUG_SERIAL SerialUSB
33+
const uint8_t DXL_DIR_PIN = 2; // DYNAMIXEL Shield DIR PIN
34+
#elif defined(ARDUINO_SAM_ZERO) // When using DynamixelShield
35+
#define DXL_SERIAL Serial1
36+
#define DEBUG_SERIAL SerialUSB
37+
const uint8_t DXL_DIR_PIN = 2; // DYNAMIXEL Shield DIR PIN
38+
#elif defined(ARDUINO_OpenCM904) // When using official ROBOTIS board with DXL circuit.
39+
#define DXL_SERIAL Serial3 //OpenCM9.04 EXP Board's DXL port Serial. (Serial1 for the DXL port on the OpenCM 9.04 board)
40+
#define DEBUG_SERIAL Serial
41+
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)
42+
#elif defined(ARDUINO_OpenCR) // When using official ROBOTIS board with DXL circuit.
43+
// For OpenCR, there is a DXL Power Enable pin, so you must initialize and control it.
44+
// Reference link : https://github.com/ROBOTIS-GIT/OpenCR/blob/master/arduino/opencr_arduino/opencr/libraries/DynamixelSDK/src/dynamixel_sdk/port_handler_arduino.cpp#L78
45+
#define DXL_SERIAL Serial3
46+
#define DEBUG_SERIAL Serial
47+
const uint8_t DXL_DIR_PIN = 84; // OpenCR Board's DIR PIN.
48+
#else // Other boards when using DynamixelShield
49+
#define DXL_SERIAL Serial1
50+
#define DEBUG_SERIAL Serial
51+
const uint8_t DXL_DIR_PIN = 2; // DYNAMIXEL Shield DIR PIN
52+
#endif
53+
54+
/* XelInfoForBulkReadParam_t
55+
A structure that contains the information needed for the parameters of the 'bulkRead packet'.
56+
57+
typedef struct ParamForBulkReadInst{
58+
uint8_t id_count;
59+
XelInfoForBulkReadParam_t xel[DXL_MAX_NODE]; //refer to below.
60+
} ParamForBulkReadInst_t;
61+
62+
typedef struct XelInfoForBulkReadParam{
63+
uint8_t id;
64+
uint16_t addr;
65+
uint16_t length;
66+
} XelInfoForBulkReadParam_t;
67+
*/
68+
69+
/* XelInfoForBulkWriteParam_t
70+
A structure that contains the information needed for the parameters of the 'bulkWrite packet'.
71+
72+
typedef struct ParamForBulkWriteInst{
73+
uint8_t id_count;
74+
XelInfoForBulkWriteParam_t xel[DXL_MAX_NODE]; //refer to below.
75+
} ParamForBulkWriteInst_t;
76+
77+
typedef struct XelInfoForBulkWriteParam{
78+
uint8_t id;
79+
uint16_t addr;
80+
uint16_t length;
81+
uint8_t data[DXL_MAX_NODE_BUFFER_SIZE];
82+
} XelInfoForBulkWriteParam_t;
83+
*/
84+
85+
/* RecvInfoFromStatusInst_t
86+
A structure used to receive data from multiple XELs.
87+
88+
typedef struct RecvInfoFromStatusInst{
89+
uint8_t id_count;
90+
XelInfoForStatusInst_t xel[DXL_MAX_NODE]; //refer to below.
91+
} RecvInfoFromStatusInst_t;
92+
93+
typedef struct XelInfoForStatusInst{
94+
uint8_t id;
95+
uint16_t length;
96+
uint8_t error;
97+
uint8_t data[DXL_MAX_NODE_BUFFER_SIZE];
98+
} XelInfoForStatusInst_t;
99+
*/
100+
101+
ParamForBulkReadInst_t bulk_read_param;
102+
ParamForBulkWriteInst_t bulk_write_param;
103+
RecvInfoFromStatusInst_t read_result;
104+
105+
Dynamixel2Arduino dxl(DXL_SERIAL, DXL_DIR_PIN);
106+
107+
void setup() {
108+
// put your setup code here, to run once:
109+
DEBUG_SERIAL.begin(115200);
110+
dxl.begin(57600);
111+
dxl.scan();
112+
113+
// fill the members of structure for bulkWrite
114+
bulk_write_param.xel[0].id = 1;
115+
bulk_write_param.xel[1].id = 2;
116+
bulk_write_param.xel[0].addr = 116; //Goal Position on X serise
117+
bulk_write_param.xel[1].addr = 104; //Goal Velocity on X serise
118+
bulk_write_param.xel[0].length = 4;
119+
bulk_write_param.xel[1].length = 4;
120+
bulk_write_param.id_count = 2;
121+
122+
// fill the members of structure for bulkRead
123+
bulk_read_param.xel[0].id = 1;
124+
bulk_read_param.xel[1].id = 2;
125+
bulk_read_param.xel[0].addr = 132; //Present Position on X serise
126+
bulk_read_param.xel[1].addr = 128; //Present Velocity on X serise
127+
bulk_read_param.xel[0].length = 4;
128+
bulk_read_param.xel[1].length = 4;
129+
bulk_read_param.id_count = 2;
130+
131+
dxl.torqueOff(1);
132+
dxl.setOperatingMode(1, OP_POSITION);
133+
dxl.torqueOn(1);
134+
135+
dxl.torqueOff(3);
136+
dxl.setOperatingMode(3, OP_VELOCITY);
137+
dxl.torqueOn(3);
138+
}
139+
140+
void loop() {
141+
// put your main code here, to run repeatedly:
142+
static int32_t position = 0, velocity = 0;
143+
int32_t recv_position = 0, recv_velocity = 0;
144+
145+
// set value to data buffer for bulkWrite
146+
position = position >= 4095 ? 0 : position+409;
147+
memcpy(bulk_write_param.xel[0].data, &position, sizeof(position));
148+
velocity = velocity >= 200 ? -200 : velocity+10;
149+
memcpy(bulk_write_param.xel[1].data, &velocity, sizeof(velocity));
150+
151+
// send command using bulkWrite
152+
dxl.bulkWrite(bulk_write_param);
153+
delay(100);
154+
155+
// Print the read data using bulkRead
156+
dxl.bulkRead(bulk_read_param, read_result);
157+
DEBUG_SERIAL.println(F("======= Bulk Read ========"));
158+
memcpy(&recv_position, read_result.xel[0].data, read_result.xel[0].length);
159+
memcpy(&recv_velocity, read_result.xel[1].data, read_result.xel[1].length);
160+
DEBUG_SERIAL.print(F("ID: "));DEBUG_SERIAL.print(read_result.xel[0].id);DEBUG_SERIAL.print(" ");
161+
DEBUG_SERIAL.print(F(", Present Position: "));DEBUG_SERIAL.print(recv_position);DEBUG_SERIAL.print(" ");
162+
DEBUG_SERIAL.print(F(", Packet Error: "));DEBUG_SERIAL.print(read_result.xel[0].error);DEBUG_SERIAL.print(" ");
163+
DEBUG_SERIAL.print(F(", Param Length: "));DEBUG_SERIAL.print(read_result.xel[0].length);DEBUG_SERIAL.print(" ");
164+
DEBUG_SERIAL.println();
165+
DEBUG_SERIAL.print(F("ID: "));DEBUG_SERIAL.print(read_result.xel[1].id);DEBUG_SERIAL.print(" ");
166+
DEBUG_SERIAL.print(F(", Present Velocity: "));DEBUG_SERIAL.print(recv_velocity);DEBUG_SERIAL.print(" ");
167+
DEBUG_SERIAL.print(F(", Packet Error: "));DEBUG_SERIAL.print(read_result.xel[1].error);DEBUG_SERIAL.print(" ");
168+
DEBUG_SERIAL.print(F(", Param Length: "));DEBUG_SERIAL.print(read_result.xel[1].length);DEBUG_SERIAL.print(" ");
169+
DEBUG_SERIAL.println();
170+
DEBUG_SERIAL.println();
171+
delay(100);
172+
}
173+
174+

examples/advanced/sync_bulk_raw/sync_bulk_raw.ino renamed to examples/advanced/DEPRECATED_sync_bulk_raw/DEPRECATED_sync_bulk_raw.ino

+29-6
Original file line numberDiff line numberDiff line change
@@ -14,15 +14,38 @@
1414
* limitations under the License.
1515
*******************************************************************************/
1616

17+
/*
18+
This is an example deprecated. (Not recommended, just an example for legacy)
19+
*/
20+
1721
#include <Dynamixel2Arduino.h>
1822

19-
#if defined(ARDUINO_AVR_UNO) || defined(ARDUINO_AVR_MEGA2560)
23+
// Please modify it to suit your hardware.
24+
#if defined(ARDUINO_AVR_UNO) || defined(ARDUINO_AVR_MEGA2560) // When using DynamixelShield
2025
#include <SoftwareSerial.h>
2126
SoftwareSerial soft_serial(7, 8); // DYNAMIXELShield UART RX/TX
2227
#define DXL_SERIAL Serial
2328
#define DEBUG_SERIAL soft_serial
2429
const uint8_t DXL_DIR_PIN = 2; // DYNAMIXEL Shield DIR PIN
25-
#else
30+
#elif defined(ARDUINO_SAM_DUE) // When using DynamixelShield
31+
#define DXL_SERIAL Serial
32+
#define DEBUG_SERIAL SerialUSB
33+
const uint8_t DXL_DIR_PIN = 2; // DYNAMIXEL Shield DIR PIN
34+
#elif defined(ARDUINO_SAM_ZERO) // When using DynamixelShield
35+
#define DXL_SERIAL Serial1
36+
#define DEBUG_SERIAL SerialUSB
37+
const uint8_t DXL_DIR_PIN = 2; // DYNAMIXEL Shield DIR PIN
38+
#elif defined(ARDUINO_OpenCM904) // When using official ROBOTIS board with DXL circuit.
39+
#define DXL_SERIAL Serial3 //OpenCM9.04 EXP Board's DXL port Serial. (Serial1 for the DXL port on the OpenCM 9.04 board)
40+
#define DEBUG_SERIAL Serial
41+
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)
42+
#elif defined(ARDUINO_OpenCR) // When using official ROBOTIS board with DXL circuit.
43+
// For OpenCR, there is a DXL Power Enable pin, so you must initialize and control it.
44+
// Reference link : https://github.com/ROBOTIS-GIT/OpenCR/blob/master/arduino/opencr_arduino/opencr/libraries/DynamixelSDK/src/dynamixel_sdk/port_handler_arduino.cpp#L78
45+
#define DXL_SERIAL Serial3
46+
#define DEBUG_SERIAL Serial
47+
const uint8_t DXL_DIR_PIN = 84; // OpenCR Board's DIR PIN.
48+
#else // Other boards when using DynamixelShield
2649
#define DXL_SERIAL Serial1
2750
#define DEBUG_SERIAL Serial
2851
const uint8_t DXL_DIR_PIN = 2; // DYNAMIXEL Shield DIR PIN
@@ -124,7 +147,7 @@ void setup() {
124147
sync_write_param.addr = 64; //Torque Enable on X serise
125148
sync_write_param.length = 1;
126149
sync_write_param.xel[0].id = 1;
127-
sync_write_param.xel[1].id = 3;
150+
sync_write_param.xel[1].id = 2;
128151
sync_write_param.xel[0].data[0] = 0;
129152
sync_write_param.xel[1].data[0] = 0;
130153
sync_write_param.id_count = 2;
@@ -133,12 +156,12 @@ void setup() {
133156
sync_read_param.addr = 126; //Present Current on X serise
134157
sync_read_param.length = 2;
135158
sync_read_param.xel[0].id = 1;
136-
sync_read_param.xel[1].id = 3;
159+
sync_read_param.xel[1].id = 2;
137160
sync_read_param.id_count = 2;
138161

139162
// fill the members of structure for bulkWrite
140163
bulk_write_param.xel[0].id = 1;
141-
bulk_write_param.xel[1].id = 3;
164+
bulk_write_param.xel[1].id = 2;
142165
bulk_write_param.xel[0].addr = 116; //Goal Position on X serise
143166
bulk_write_param.xel[1].addr = 104; //Goal Velocity on X serise
144167
bulk_write_param.xel[0].length = 4;
@@ -147,7 +170,7 @@ void setup() {
147170

148171
// fill the members of structure for bulkRead
149172
bulk_read_param.xel[0].id = 1;
150-
bulk_read_param.xel[1].id = 3;
173+
bulk_read_param.xel[1].id = 2;
151174
bulk_read_param.xel[0].addr = 132; //Present Position on X serise
152175
bulk_read_param.xel[1].addr = 128; //Present Velocity on X serise
153176
bulk_read_param.xel[0].length = 4;

0 commit comments

Comments
 (0)