ロボット開発(第一回): DYNAMIXELモータをarduino互換ボードで動かす
はじめに
今更ながらこちらの動画を拝見しましたところ、強化学習やSim2Realの技術ってこんなに進んでるのかーと触発されまして、自分も何かやってみたいなと思い立ち活動することにしました!
とはいえ、ロボット犬を個人で購入するにはハードルが高いので、ロボットを自作しつつAIと掛け合わせて何か面白いものを産み出せればと思ってます。
ロボットといえばまずはモータだろということで、早速DYNAMIXELのXL330-M288-TとXL330-M077-Tを購入し、arduino互換ボードで動かしてみました。
DYNAMIXELモータを動かす記事は色々あるのですが、今回試したDYNAMIXEL Shieldを使った記事はあまり多くなく書き記しておこうと思った次第です。手軽に動かすにはOpenRB-150などのマイコンを使うのが一般的なようで以下の記事が参考になります。色々書きましたが、DYNAMIXEL Shieldは自分の用途にマッチしなかった(後述)ので今後は別のやり方を検討します。
ハードウェア
今回は以下のハードウェアを使います。
PC
一般的なWindowsが入っているPCにUbuntu22.04を入れて使っています。
モータ
ベストテクノロジー様で購入しました。M288はトルク型、M077はスピード型です。
- DYNAMIXEL XL330-M288-T
- DYNAMIXEL XL330-M077-T
基板、その他
- arduino互換ボードであるSeeeduino v4.2
- 在庫切れですが、後継のv4.3があります
-
DYNAMIXEL Shield
- 公式マニュアルがあり、読んでおかないと色々とハマります
-
シリアル-USBコンバータ
- arduinoのハードウェアシリアルは1つしかなく、そのシリアルはモーターへの司令に使われるため、デバッグ出力のためのprintln()などが正常に動作しません。したがってソフトウェアシリアルを使ってデバッグ出力を行う必要があり、それをPCに取り込むために使います。
- 安定化電源 HM305
セットアップ
arduino IDE
公式の手順に従い、ライブラリをインストールします。
ハードウェア
以下のように配線を行いました。

- SeeeduinoとDYNAMIXEL Shieldを接続
- M288とM077をDYNAMIXEL Shieldに接続
- DYNAMIXELモータはデイジーチェーン接続が可能なので直列に接続
- DYNAMIXEL Shieldに安定化電源を接続
- 5V/1.5A制限
- シリアル-USBコンバータのRXを8番ピン、TXを7番ピンに接続
- DYNAMIXEL ShieldのパワースイッチをON
- DYNAMIXEL Shieldのジャンパーピンを外す
- 今回は安定化電源からShieldに電源を供給します
- 今回は安定化電源からShieldに電源を供給します
動かす
プログラムの書き込み方法
最初に注意したいのがプログラムの書き込みです。公式マニュアルに記載がありますが、arduino IDEからプログラムを書き込む際はディップスイッチをUpload側にセットしないと書き込みに失敗します。そして書き込みが終わったらディップスイッチをDYNAMIXEL側にセットしモータを動かします。

デバッグシリアルの表示
デバッグ出力を確認するため、PC側でシリアルモニタを立ち上げます。今回はminicomを使いましたが、他にも色々あるので好きなソフトウェアで問題ありません。minicomの解説は多数あるので、検索して使ってみてください。うまく出力が見えない場合は通信レートやポート設定が間違っている可能性が高いです。以下は実行例です。
$ minicom -D /dev/ttyUSB0
idの設定
DYNAMIXELモータはデイジーチェーン接続が可能であるため、モータを識別するためにIDが割り振られています。購入直後は1になっているので、複数個動かす場合はユニークなIDをつける必要があります。本来これはDYNAMIXEL Wizard 2.0というソフトウェアで行うことができるのですが、残念ながら今回のハードウェア構成では使うことができません、、、
DYNAMIXEL WizardはPC上で動くソフトウェアであり、PC -[USB-シリアル通信]-> 何かしらのマイコン -[シリアル通信]-> モータ と繋がっている状態で、PCからコマンドを出してモータのID変更等を行うのですが、ここで何かしらのマイコンはPCからのコマンドをスルーしてモータに伝える必要があります。しかし今回使ったSeeeduinoはハードウェアシリアルが1系統しかなくスルーすることができません。冒頭で紹介したOpenRB-150ではこれが可能であるため、DYNAMIXEL Wizardを使うことができるはずです。
今回は以下のソフトウェアを使わせて頂きました。IDや通信レートの変更、モータのスキャンなどができとても便利です!
IDの変更はこちらのプログラムで行うことができ、以下の箇所を編集してIDEから書き込み実行します。
const uint8_t OLD_ID = 1;
const uint8_t NEW_ID = 4;
また、この作業を行う場合は、モータを1個だけ接続するようにしてください。
モータを回す
ここまでやってついにモータを回せます。今回はライブラリに付属するExampleを流用して4つのモータを動かしました。
#include <DynamixelShield.h>
#if defined(ARDUINO_AVR_UNO) || defined(ARDUINO_AVR_MEGA2560)
#include <SoftwareSerial.h>
SoftwareSerial soft_serial(7, 8); // DYNAMIXELShield UART RX/TX
#define DEBUG_SERIAL soft_serial
#elif defined(ARDUINO_SAM_DUE) || defined(ARDUINO_SAM_ZERO)
#define DEBUG_SERIAL SerialUSB
#else
#define DEBUG_SERIAL Serial
#endif
const uint8_t DXL_ID1 = 1;
const uint8_t DXL_ID2 = 2;
const uint8_t DXL_ID3 = 3;
const uint8_t DXL_ID4 = 4;
const float DXL_PROTOCOL_VERSION = 2.0;
DynamixelShield dxl;
//This namespace is required to use Control table item names
using namespace ControlTableItem;
void setup() {
// put your setup code here, to run once:
// For Uno, Nano, Mini, and Mega, use UART port of DYNAMIXEL Shield to debug.
DEBUG_SERIAL.begin(115200);
// Set Port baudrate to 57600bps. This has to match with DYNAMIXEL baudrate.
dxl.begin(57600);
// Set Port Protocol Version. This has to match with DYNAMIXEL protocol version.
dxl.setPortProtocolVersion(DXL_PROTOCOL_VERSION);
// Get DYNAMIXEL information
dxl.ping(DXL_ID1);
dxl.ping(DXL_ID2);
dxl.ping(DXL_ID3);
dxl.ping(DXL_ID4);
// Turn off torque when configuring items in EEPROM area
dxl.torqueOff(DXL_ID1);
dxl.torqueOff(DXL_ID2);
dxl.torqueOff(DXL_ID3);
dxl.torqueOff(DXL_ID4);
dxl.setOperatingMode(DXL_ID1, OP_POSITION);
dxl.setOperatingMode(DXL_ID2, OP_POSITION);
dxl.setOperatingMode(DXL_ID3, OP_POSITION);
dxl.setOperatingMode(DXL_ID4, OP_POSITION);
dxl.torqueOn(DXL_ID1);
dxl.torqueOn(DXL_ID2);
dxl.torqueOn(DXL_ID3);
dxl.torqueOn(DXL_ID4);
}
void loop() {
// put your main code here, to run repeatedly:
// 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_ID1, 210, UNIT_DEGREE);
dxl.setGoalPosition(DXL_ID2, 210, UNIT_DEGREE);
dxl.setGoalPosition(DXL_ID3, 210, UNIT_DEGREE);
dxl.setGoalPosition(DXL_ID4, 210, UNIT_DEGREE);
delay(1000);
// Print present position in raw value
DEBUG_SERIAL.println("Present Position(degree) : ");
DEBUG_SERIAL.println(dxl.getPresentPosition(DXL_ID1, UNIT_DEGREE));
DEBUG_SERIAL.println(dxl.getPresentPosition(DXL_ID2, UNIT_DEGREE));
DEBUG_SERIAL.println(dxl.getPresentPosition(DXL_ID3, UNIT_DEGREE));
DEBUG_SERIAL.println(dxl.getPresentPosition(DXL_ID4, UNIT_DEGREE));
delay(1000);
// Set Goal Position in DEGREE value
dxl.setGoalPosition(DXL_ID1, 330, UNIT_DEGREE);
dxl.setGoalPosition(DXL_ID2, 330, UNIT_DEGREE);
dxl.setGoalPosition(DXL_ID3, 330, UNIT_DEGREE);
dxl.setGoalPosition(DXL_ID4, 330, UNIT_DEGREE);
delay(1000);
// Print present position in degree value
DEBUG_SERIAL.println("Present Position(degree) : ");
DEBUG_SERIAL.println(dxl.getPresentPosition(DXL_ID1, UNIT_DEGREE));
DEBUG_SERIAL.println(dxl.getPresentPosition(DXL_ID2, UNIT_DEGREE));
DEBUG_SERIAL.println(dxl.getPresentPosition(DXL_ID3, UNIT_DEGREE));
DEBUG_SERIAL.println(dxl.getPresentPosition(DXL_ID4, UNIT_DEGREE));
delay(1000);
}
動きましたね!

PCで立ち上げているminicomにも出力が出ています。
Present Position(degree) :
209.97
209.97
209.97
210.06
Present Position(degree) :
330.00
330.09
329.82
330.00
まとめ&教訓
今回はarduino互換ボードとDYNAMIXEL Shieldを使ってモータを動かしました。しかしこの構成だと以下のデメリットがあります。
- DYNAMIXEL Wizardが使えない、、、
- ソフトウェアシリアルを使って頑張ればできるのかもしれないが、安定しなさそう
-
PC -> マイコン -> モータと繋いでPCからコマンドを送れない
最終的には PC -> マイコン(コマンドスルー) -> モータ の構成を考えているので、そのような方は素直にOpenRBなどを使いましょうw
ただ、OpenRBは結構高いので、次はM5Stackでコマンドスルーできないか検討してみます!
Discussion