Skip to content

Commit

Permalink
Merge pull request #29 from ROBOTIS-GIT/develop
Browse files Browse the repository at this point in the history
Develop
  • Loading branch information
Kei authored Feb 6, 2020
2 parents a688da3 + 70ce86a commit 6b048cf
Show file tree
Hide file tree
Showing 45 changed files with 4,889 additions and 2,229 deletions.
1 change: 1 addition & 0 deletions .travis.yml
Original file line number Diff line number Diff line change
Expand Up @@ -25,3 +25,4 @@ notifications:
branches:
only:
- master
- develop
14 changes: 14 additions & 0 deletions README.md
Original file line number Diff line number Diff line change
@@ -1,9 +1,23 @@
# 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.
- 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||
|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))|


## How to add new DYNAMIXEL model.
- For the convenience of the user, Dynamixel2Arduino API hardcodes some information in the control table and stores it in flash.
- 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)

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

## TODO
- Separation of protocol codes (protocol, packet handler)
Original file line number Diff line number Diff line change
@@ -0,0 +1,174 @@
/*******************************************************************************
* Copyright 2016 ROBOTIS CO., LTD.
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*******************************************************************************/

/*
This is an example deprecated. (Not recommended, just an example for legacy)
*/

#include <Dynamixel2Arduino.h>

// Please modify it to suit your hardware.
#if defined(ARDUINO_AVR_UNO) || defined(ARDUINO_AVR_MEGA2560) // When using DynamixelShield
#include <SoftwareSerial.h>
SoftwareSerial soft_serial(7, 8); // DYNAMIXELShield UART RX/TX
#define DXL_SERIAL Serial
#define DEBUG_SERIAL soft_serial
const uint8_t DXL_DIR_PIN = 2; // DYNAMIXEL Shield DIR PIN
#elif defined(ARDUINO_SAM_DUE) // When using DynamixelShield
#define DXL_SERIAL Serial
#define DEBUG_SERIAL SerialUSB
const uint8_t DXL_DIR_PIN = 2; // DYNAMIXEL Shield DIR PIN
#elif defined(ARDUINO_SAM_ZERO) // When using DynamixelShield
#define DXL_SERIAL Serial1
#define DEBUG_SERIAL SerialUSB
const uint8_t DXL_DIR_PIN = 2; // DYNAMIXEL Shield DIR PIN
#elif defined(ARDUINO_OpenCM904) // When using official ROBOTIS board with DXL circuit.
#define DXL_SERIAL Serial3 //OpenCM9.04 EXP Board's DXL port Serial. (Serial1 for the DXL port on the OpenCM 9.04 board)
#define DEBUG_SERIAL Serial
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)
#elif defined(ARDUINO_OpenCR) // When using official ROBOTIS board with DXL circuit.
// 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
#define DXL_SERIAL Serial3
#define DEBUG_SERIAL Serial
const uint8_t DXL_DIR_PIN = 84; // OpenCR Board's DIR PIN.
#else // Other boards when using DynamixelShield
#define DXL_SERIAL Serial1
#define DEBUG_SERIAL Serial
const uint8_t DXL_DIR_PIN = 2; // DYNAMIXEL Shield DIR PIN
#endif

/* XelInfoForBulkReadParam_t
A structure that contains the information needed for the parameters of the 'bulkRead packet'.
typedef struct ParamForBulkReadInst{
uint8_t id_count;
XelInfoForBulkReadParam_t xel[DXL_MAX_NODE]; //refer to below.
} ParamForBulkReadInst_t;
typedef struct XelInfoForBulkReadParam{
uint8_t id;
uint16_t addr;
uint16_t length;
} XelInfoForBulkReadParam_t;
*/

/* XelInfoForBulkWriteParam_t
A structure that contains the information needed for the parameters of the 'bulkWrite packet'.
typedef struct ParamForBulkWriteInst{
uint8_t id_count;
XelInfoForBulkWriteParam_t xel[DXL_MAX_NODE]; //refer to below.
} ParamForBulkWriteInst_t;
typedef struct XelInfoForBulkWriteParam{
uint8_t id;
uint16_t addr;
uint16_t length;
uint8_t data[DXL_MAX_NODE_BUFFER_SIZE];
} XelInfoForBulkWriteParam_t;
*/

/* RecvInfoFromStatusInst_t
A structure used to receive data from multiple XELs.
typedef struct RecvInfoFromStatusInst{
uint8_t id_count;
XelInfoForStatusInst_t xel[DXL_MAX_NODE]; //refer to below.
} RecvInfoFromStatusInst_t;
typedef struct XelInfoForStatusInst{
uint8_t id;
uint16_t length;
uint8_t error;
uint8_t data[DXL_MAX_NODE_BUFFER_SIZE];
} XelInfoForStatusInst_t;
*/

ParamForBulkReadInst_t bulk_read_param;
ParamForBulkWriteInst_t bulk_write_param;
RecvInfoFromStatusInst_t read_result;

Dynamixel2Arduino dxl(DXL_SERIAL, DXL_DIR_PIN);

void setup() {
// put your setup code here, to run once:
DEBUG_SERIAL.begin(115200);
dxl.begin(57600);
dxl.scan();

// fill the members of structure for bulkWrite
bulk_write_param.xel[0].id = 1;
bulk_write_param.xel[1].id = 2;
bulk_write_param.xel[0].addr = 116; //Goal Position on X serise
bulk_write_param.xel[1].addr = 104; //Goal Velocity on X serise
bulk_write_param.xel[0].length = 4;
bulk_write_param.xel[1].length = 4;
bulk_write_param.id_count = 2;

// fill the members of structure for bulkRead
bulk_read_param.xel[0].id = 1;
bulk_read_param.xel[1].id = 2;
bulk_read_param.xel[0].addr = 132; //Present Position on X serise
bulk_read_param.xel[1].addr = 128; //Present Velocity on X serise
bulk_read_param.xel[0].length = 4;
bulk_read_param.xel[1].length = 4;
bulk_read_param.id_count = 2;

dxl.torqueOff(1);
dxl.setOperatingMode(1, OP_POSITION);
dxl.torqueOn(1);

dxl.torqueOff(3);
dxl.setOperatingMode(3, OP_VELOCITY);
dxl.torqueOn(3);
}

void loop() {
// put your main code here, to run repeatedly:
static int32_t position = 0, velocity = 0;
int32_t recv_position = 0, recv_velocity = 0;

// set value to data buffer for bulkWrite
position = position >= 4095 ? 0 : position+409;
memcpy(bulk_write_param.xel[0].data, &position, sizeof(position));
velocity = velocity >= 200 ? -200 : velocity+10;
memcpy(bulk_write_param.xel[1].data, &velocity, sizeof(velocity));

// send command using bulkWrite
dxl.bulkWrite(bulk_write_param);
delay(100);

// Print the read data using bulkRead
dxl.bulkRead(bulk_read_param, read_result);
DEBUG_SERIAL.println(F("======= Bulk Read ========"));
memcpy(&recv_position, read_result.xel[0].data, read_result.xel[0].length);
memcpy(&recv_velocity, read_result.xel[1].data, read_result.xel[1].length);
DEBUG_SERIAL.print(F("ID: "));DEBUG_SERIAL.print(read_result.xel[0].id);DEBUG_SERIAL.print(" ");
DEBUG_SERIAL.print(F(", Present Position: "));DEBUG_SERIAL.print(recv_position);DEBUG_SERIAL.print(" ");
DEBUG_SERIAL.print(F(", Packet Error: "));DEBUG_SERIAL.print(read_result.xel[0].error);DEBUG_SERIAL.print(" ");
DEBUG_SERIAL.print(F(", Param Length: "));DEBUG_SERIAL.print(read_result.xel[0].length);DEBUG_SERIAL.print(" ");
DEBUG_SERIAL.println();
DEBUG_SERIAL.print(F("ID: "));DEBUG_SERIAL.print(read_result.xel[1].id);DEBUG_SERIAL.print(" ");
DEBUG_SERIAL.print(F(", Present Velocity: "));DEBUG_SERIAL.print(recv_velocity);DEBUG_SERIAL.print(" ");
DEBUG_SERIAL.print(F(", Packet Error: "));DEBUG_SERIAL.print(read_result.xel[1].error);DEBUG_SERIAL.print(" ");
DEBUG_SERIAL.print(F(", Param Length: "));DEBUG_SERIAL.print(read_result.xel[1].length);DEBUG_SERIAL.print(" ");
DEBUG_SERIAL.println();
DEBUG_SERIAL.println();
delay(100);
}


Original file line number Diff line number Diff line change
Expand Up @@ -14,15 +14,38 @@
* limitations under the License.
*******************************************************************************/

/*
This is an example deprecated. (Not recommended, just an example for legacy)
*/

#include <Dynamixel2Arduino.h>

#if defined(ARDUINO_AVR_UNO) || defined(ARDUINO_AVR_MEGA2560)
// Please modify it to suit your hardware.
#if defined(ARDUINO_AVR_UNO) || defined(ARDUINO_AVR_MEGA2560) // When using DynamixelShield
#include <SoftwareSerial.h>
SoftwareSerial soft_serial(7, 8); // DYNAMIXELShield UART RX/TX
#define DXL_SERIAL Serial
#define DEBUG_SERIAL soft_serial
const uint8_t DXL_DIR_PIN = 2; // DYNAMIXEL Shield DIR PIN
#else
#elif defined(ARDUINO_SAM_DUE) // When using DynamixelShield
#define DXL_SERIAL Serial
#define DEBUG_SERIAL SerialUSB
const uint8_t DXL_DIR_PIN = 2; // DYNAMIXEL Shield DIR PIN
#elif defined(ARDUINO_SAM_ZERO) // When using DynamixelShield
#define DXL_SERIAL Serial1
#define DEBUG_SERIAL SerialUSB
const uint8_t DXL_DIR_PIN = 2; // DYNAMIXEL Shield DIR PIN
#elif defined(ARDUINO_OpenCM904) // When using official ROBOTIS board with DXL circuit.
#define DXL_SERIAL Serial3 //OpenCM9.04 EXP Board's DXL port Serial. (Serial1 for the DXL port on the OpenCM 9.04 board)
#define DEBUG_SERIAL Serial
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)
#elif defined(ARDUINO_OpenCR) // When using official ROBOTIS board with DXL circuit.
// 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
#define DXL_SERIAL Serial3
#define DEBUG_SERIAL Serial
const uint8_t DXL_DIR_PIN = 84; // OpenCR Board's DIR PIN.
#else // Other boards when using DynamixelShield
#define DXL_SERIAL Serial1
#define DEBUG_SERIAL Serial
const uint8_t DXL_DIR_PIN = 2; // DYNAMIXEL Shield DIR PIN
Expand Down Expand Up @@ -124,7 +147,7 @@ void setup() {
sync_write_param.addr = 64; //Torque Enable on X serise
sync_write_param.length = 1;
sync_write_param.xel[0].id = 1;
sync_write_param.xel[1].id = 3;
sync_write_param.xel[1].id = 2;
sync_write_param.xel[0].data[0] = 0;
sync_write_param.xel[1].data[0] = 0;
sync_write_param.id_count = 2;
Expand All @@ -133,12 +156,12 @@ void setup() {
sync_read_param.addr = 126; //Present Current on X serise
sync_read_param.length = 2;
sync_read_param.xel[0].id = 1;
sync_read_param.xel[1].id = 3;
sync_read_param.xel[1].id = 2;
sync_read_param.id_count = 2;

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

// fill the members of structure for bulkRead
bulk_read_param.xel[0].id = 1;
bulk_read_param.xel[1].id = 3;
bulk_read_param.xel[1].id = 2;
bulk_read_param.xel[0].addr = 132; //Present Position on X serise
bulk_read_param.xel[1].addr = 128; //Present Velocity on X serise
bulk_read_param.xel[0].length = 4;
Expand Down
Loading

0 comments on commit 6b048cf

Please sign in to comment.