Skip to content

Commit

Permalink
Merge pull request #57 from ROBOTIS-GIT/develop
Browse files Browse the repository at this point in the history
prepare to release
  • Loading branch information
ROBOTIS-Will authored Dec 22, 2020
2 parents ee03828 + 60e9b86 commit 2634a23
Show file tree
Hide file tree
Showing 6 changed files with 32 additions and 16 deletions.
5 changes: 3 additions & 2 deletions README.md
Original file line number Diff line number Diff line change
@@ -1,13 +1,14 @@
# Dynamixel2Arduino [![Build Status](https://travis-ci.org/ROBOTIS-GIT/Dynamixel2Arduino.svg?branch=master)](https://travis-ci.org/ROBOTIS-GIT/Dynamixel2Arduino/branches)

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

|Board Name|Serial|Direction Pin|Note|
|:-:|:-:|:-:|:-:|
|OpenCM9.04|Serial1|28|because of the OpenCM 9.04 driver code, you must call Serial1.setDxlMode(true); before dxl.begin();.|
|OpenCM9.04 EXP|Serial3|22||
|OpenCM485EXP|Serial3|22||
|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))|


Expand Down
35 changes: 25 additions & 10 deletions examples/basic/position_mode/position_mode.ino
Original file line number Diff line number Diff line change
Expand Up @@ -61,6 +61,7 @@ void setup() {

// Use UART port of DYNAMIXEL Shield to debug.
DEBUG_SERIAL.begin(115200);
while(!DEBUG_SERIAL);

// Set Port baudrate to 57600bps. This has to match with DYNAMIXEL baudrate.
dxl.begin(57600);
Expand All @@ -73,6 +74,9 @@ void setup() {
dxl.torqueOff(DXL_ID);
dxl.setOperatingMode(DXL_ID, OP_POSITION);
dxl.torqueOn(DXL_ID);

// Limit the maximum velocity in Position Control Mode. Use 0 for Max speed
dxl.writeControlTableItem(PROFILE_VELOCITY, DXL_ID, 30);
}

void loop() {
Expand All @@ -81,17 +85,28 @@ void loop() {
// Please refer to e-Manual(http://emanual.robotis.com/docs/en/parts/interface/dynamixel_shield/) for available range of value.
// Set Goal Position in RAW value
dxl.setGoalPosition(DXL_ID, 512);
delay(1000);
// Print present position in raw value
DEBUG_SERIAL.print("Present Position(raw) : ");
DEBUG_SERIAL.println(dxl.getPresentPosition(DXL_ID));
delay(1000);

int i_present_position = 0;
float f_present_position = 0.0;

while (abs(512 - i_present_position) > 10)
{
f_present_position = dxl.getPresentPosition(DXL_ID, UNIT_DEGREE);
i_present_position = dxl.getPresentPosition(DXL_ID);
DEBUG_SERIAL.print("Present_Position(raw) : ");
DEBUG_SERIAL.println(i_present_position);
}
delay(500);

// Set Goal Position in DEGREE value
dxl.setGoalPosition(DXL_ID, 5.7, UNIT_DEGREE);
delay(1000);
// Print present position in degree value
DEBUG_SERIAL.print("Present Position(degree) : ");
DEBUG_SERIAL.println(dxl.getPresentPosition(DXL_ID, UNIT_DEGREE));
delay(1000);

while (abs(5.7 - f_present_position) > 2.0)
{
f_present_position = dxl.getPresentPosition(DXL_ID, UNIT_DEGREE);
i_present_position = dxl.getPresentPosition(DXL_ID);
DEBUG_SERIAL.print("Present_Position(raw) : ");
DEBUG_SERIAL.println(i_present_position);
}
delay(500);
}
2 changes: 1 addition & 1 deletion library.properties
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
name=Dynamixel2Arduino
version=0.4.5
version=0.4.6
author=ROBOTIS
license=Apache-2.0
maintainer=Will Son([email protected])
Expand Down
2 changes: 1 addition & 1 deletion src/dxl_c/protocol.c
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@

#if defined(ARDUINO)
#include <Arduino.h>
#if !defined(ESP_PLATFORM) && !defined(ARDUINO_ARCH_MBED)
#if !defined(ESP_PLATFORM) && !defined(ARDUINO_ARCH_MBED) && !defined(ARDUINO_ARCH_SAMD)
#include <avr/pgmspace.h>
#endif
#endif
Expand Down
2 changes: 1 addition & 1 deletion src/utility/config.h
Original file line number Diff line number Diff line change
Expand Up @@ -83,7 +83,7 @@

#if defined(ARDUINO)
#include <Arduino.h>
#if !defined(ESP_PLATFORM) && !defined(ARDUINO_ARCH_MBED)
#if !defined(ESP_PLATFORM) && !defined(ARDUINO_ARCH_MBED) && !defined(ARDUINO_ARCH_SAMD)
#include <avr/pgmspace.h>
#endif
#endif
Expand Down
2 changes: 1 addition & 1 deletion src/utility/port_handler.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,7 @@ void SerialPortHandler::begin(unsigned long baud)
pinMode(BDPIN_DXL_PWR_EN, OUTPUT);
digitalWrite(BDPIN_DXL_PWR_EN, HIGH);
}
delay(200); // Wait for the DYNAMIXEL to power up normally.
delay(300); // Wait for the DYNAMIXEL to power up normally.
#endif

baud_ = baud;
Expand Down

0 comments on commit 2634a23

Please sign in to comment.