Skip to content

Commit 2634a23

Browse files
authored
Merge pull request #57 from ROBOTIS-GIT/develop
prepare to release
2 parents ee03828 + 60e9b86 commit 2634a23

File tree

6 files changed

+32
-16
lines changed

6 files changed

+32
-16
lines changed

README.md

Lines changed: 3 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -1,13 +1,14 @@
11
# Dynamixel2Arduino [![Build Status](https://travis-ci.org/ROBOTIS-GIT/Dynamixel2Arduino.svg?branch=master)](https://travis-ci.org/ROBOTIS-GIT/Dynamixel2Arduino/branches)
22

33
## 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.
4+
- The examples defines GPIO pins based on the use with DYNAMIXEL Shields.
5+
- When running DYNAMIXEL without DYNAMIXEL Shields on OpenCM9.04, OpenCR or custom boards, you might need to change the Serial and DYNAMIXEL Direction Pin.
56
- We provide the information below to make it easier to define Serial and Direction pins for specific hardware.
67

78
|Board Name|Serial|Direction Pin|Note|
89
|:-:|:-:|:-:|:-:|
910
|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+
|OpenCM485EXP|Serial3|22||
1112
|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))|
1213

1314

examples/basic/position_mode/position_mode.ino

Lines changed: 25 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -61,6 +61,7 @@ void setup() {
6161

6262
// Use UART port of DYNAMIXEL Shield to debug.
6363
DEBUG_SERIAL.begin(115200);
64+
while(!DEBUG_SERIAL);
6465

6566
// Set Port baudrate to 57600bps. This has to match with DYNAMIXEL baudrate.
6667
dxl.begin(57600);
@@ -73,6 +74,9 @@ void setup() {
7374
dxl.torqueOff(DXL_ID);
7475
dxl.setOperatingMode(DXL_ID, OP_POSITION);
7576
dxl.torqueOn(DXL_ID);
77+
78+
// Limit the maximum velocity in Position Control Mode. Use 0 for Max speed
79+
dxl.writeControlTableItem(PROFILE_VELOCITY, DXL_ID, 30);
7680
}
7781

7882
void loop() {
@@ -81,17 +85,28 @@ void loop() {
8185
// Please refer to e-Manual(http://emanual.robotis.com/docs/en/parts/interface/dynamixel_shield/) for available range of value.
8286
// Set Goal Position in RAW value
8387
dxl.setGoalPosition(DXL_ID, 512);
84-
delay(1000);
85-
// Print present position in raw value
86-
DEBUG_SERIAL.print("Present Position(raw) : ");
87-
DEBUG_SERIAL.println(dxl.getPresentPosition(DXL_ID));
88-
delay(1000);
88+
89+
int i_present_position = 0;
90+
float f_present_position = 0.0;
91+
92+
while (abs(512 - i_present_position) > 10)
93+
{
94+
f_present_position = dxl.getPresentPosition(DXL_ID, UNIT_DEGREE);
95+
i_present_position = dxl.getPresentPosition(DXL_ID);
96+
DEBUG_SERIAL.print("Present_Position(raw) : ");
97+
DEBUG_SERIAL.println(i_present_position);
98+
}
99+
delay(500);
89100

90101
// Set Goal Position in DEGREE value
91102
dxl.setGoalPosition(DXL_ID, 5.7, UNIT_DEGREE);
92-
delay(1000);
93-
// Print present position in degree value
94-
DEBUG_SERIAL.print("Present Position(degree) : ");
95-
DEBUG_SERIAL.println(dxl.getPresentPosition(DXL_ID, UNIT_DEGREE));
96-
delay(1000);
103+
104+
while (abs(5.7 - f_present_position) > 2.0)
105+
{
106+
f_present_position = dxl.getPresentPosition(DXL_ID, UNIT_DEGREE);
107+
i_present_position = dxl.getPresentPosition(DXL_ID);
108+
DEBUG_SERIAL.print("Present_Position(raw) : ");
109+
DEBUG_SERIAL.println(i_present_position);
110+
}
111+
delay(500);
97112
}

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.4.5
2+
version=0.4.6
33
author=ROBOTIS
44
license=Apache-2.0
55
maintainer=Will Son([email protected])

src/dxl_c/protocol.c

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -2,7 +2,7 @@
22

33
#if defined(ARDUINO)
44
#include <Arduino.h>
5-
#if !defined(ESP_PLATFORM) && !defined(ARDUINO_ARCH_MBED)
5+
#if !defined(ESP_PLATFORM) && !defined(ARDUINO_ARCH_MBED) && !defined(ARDUINO_ARCH_SAMD)
66
#include <avr/pgmspace.h>
77
#endif
88
#endif

src/utility/config.h

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -83,7 +83,7 @@
8383

8484
#if defined(ARDUINO)
8585
#include <Arduino.h>
86-
#if !defined(ESP_PLATFORM) && !defined(ARDUINO_ARCH_MBED)
86+
#if !defined(ESP_PLATFORM) && !defined(ARDUINO_ARCH_MBED) && !defined(ARDUINO_ARCH_SAMD)
8787
#include <avr/pgmspace.h>
8888
#endif
8989
#endif

src/utility/port_handler.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -40,7 +40,7 @@ void SerialPortHandler::begin(unsigned long baud)
4040
pinMode(BDPIN_DXL_PWR_EN, OUTPUT);
4141
digitalWrite(BDPIN_DXL_PWR_EN, HIGH);
4242
}
43-
delay(200); // Wait for the DYNAMIXEL to power up normally.
43+
delay(300); // Wait for the DYNAMIXEL to power up normally.
4444
#endif
4545

4646
baud_ = baud;

0 commit comments

Comments
 (0)