Dynamixel Protocol LibraryはDYNAMIXEL Communiation Protocol 1.0に対応した製品をWindows等のOSから操作するためのライブラリ集です。
シリアル通信に関するAPI、タイミングやエラー処理、プロトコルの整合性チェック等を本ライブラリ内で行っているため、シリアル通信である事をほとんど意識すること無くアプリケーションの作りこみに専念することができます。
なお、PCとBTE061D・BTE061E・BTE068・BTE068B・BTE068C・BTE082・BTE083・BTE074・BTE079・BTE080・BTE079B・BTE080B・BTE079C・BTE080C・BTE096・BTE101・BTX229のいずれかがUSBポートに接続され、PCのOSに仮想COMポートが増設された状態で使用するものとします。BTE100の場合はRaspberry Piに依存します。
以下のリンクよりライブラリ及びサンプルプログラムをアーカイブしたファイルがダウンロードできます。
最新版のアーカイブファイルには以下のファイルが同梱されます。必要に応じて解凍してください。
| DXLIB | dxlib_x32.dll | ライブラリ本体 | |
| dxlib_x64.dll | |||
| libdxlib_x32.a | GCC用ライブラリ(定義のみ) | ||
| libdxlib_x64.a | |||
| dxlib_x32.llb | MSVC用ライブラリ(定義のみ) | ||
| dxlib_x64.lib | |||
| dxlib.cpp | ライブラリソース | ||
| dxlib.h | ライブラリヘッダ | ||
| dxlib_matlab.h | matlab用ヘッダ | ||
| dxlib.py | python用API定義 | ||
| dxmemmap.h | DX/AX/RX/EX/MXシリーズ用コントロールテーブル定義ヘッダ | ||
| makelib.cmd | ライブラリ再構築用バッチ | ||
| build_dxlib.sh | Linux向けライブラリ再構築用スクリプト | ||
| SampleCode | C | smpl??.c | サンプル |
| dxmisc.h | サンプル共通設定 | ||
| kbhit.h | kbhitエミュレーション | ||
| makefile | サンプルコンパイル用makefile | ||
| makeexe.cmd | Windows向け再構築用バッチ | ||
| dxlib.h | DXLIBフォルダに収録されるものと同一 | ||
| dxmemmap.h | |||
| dxlib_x32.dll | |||
| dxlib_x64.dll | |||
| DELPHI | Project1.dpr | サンプル | |
| Unit1.dfm | |||
| Unit1.pas | |||
| DXLIB.pas | |||
| dxlib_x32.dll | DXLIBフォルダに収録されるものと同一 | ||
| dxlib_x64.dll | |||
| Python | smpl??.py | サンプル | |
| kbhit.py | kbhitエミュレーション | ||
| dxlib.py | DXLIBフォルダに収録されるものと同一 | ||
| dxlib_x32.dll | |||
| dxlib_x64.dll | |||
| LabVIEW2011 | sample??.vi | サンプル | |
| DXLIB.llb | dllの呼び出しをvi化 | ||
| DXLIB_DXL.llb | dllの呼び出しをvi化 | ||
| DXLIB_Wrapper.llb | アクチュエータに特化したvi | ||
| dxlib_x32.dll | DXLIBフォルダに収録されるものと同一 | ||
| EXCEL | text.xls | サンプルシート | |
| dxlib_x32.dll | DXLIBフォルダに収録されるものと同一 | ||
| dxlib_x64.dll | |||
| Ruby | smpl??.rb | サンプル | |
| dxlib_x32.dll | DXLIBフォルダに収録されるものと同一 | ||
| dxlib_x64.dll | |||
GCC Developer Liteの詳細についてはこちら。
「基本パック」と「WINパック」をダウンロードしてインストールしてください。
'SampleCode\C'フォルダにはAPIの基本的な使い方を紹介したサンプルが同梱されます。ポート・ボーレート・ID等は使用する環境に合わせて適宜修正して使用します。
静的にDLLを使用する場合は以下の手順でDLLをリンクする指定を行った上でコンパイルします。なお32bit環境を前提とします。
ダウンロードファイルを解凍後、コンパイルするソースファイルと同一フォルダに以下のファイルをコピー
| ファイル | ファイル名 | 備考 |
| ヘッダ | dxlib.h | 必要な宣言を集約 |
| DLL | dxlib_x32.dll | DLL本体(実行時およびリンク時に必要) |
ツールメニュー→コンパイラオプションをクリックし、表示されるダイアログボックスの設定リストから'x86 (Console)'を選択

etc...タブ内の追加ボタンを押し、新規に行を追加

新規に追加された空の行をクリックし'dxlib_x32.dll'と入力

OKを押して設定を反映
動的にDLLを使用する場合はDLL自体をコンパイラオプションへ追記する必要はありません。その代わりにソース中でdxlib.hをインクルードする前に_DYNAMICLOADマクロを定義しておきます。
#define _DYNAMICLOAD #include "dxlib.h"
これによりヘッダファイル内の諸定義が切り替わり、DLLのロード及びアンロードを行うLoadDLLとUnloadDLLが利用できるようになります。
TDeviceID dev;
// DLLを読み込み
if (LoadDLL ()) {
if ((dev = DX_OpenPort (COMPORT, BAUDRATE))) {
...
DX_ClosePort (dev);
}
// DLLを破棄
UnloadDLL ();
}
LoadDLLが成功していない状態で各APIを呼び出してはいけません。またDLL自体は実行プログラムと同じフォルダかOSがDLLを検索できる場所に配置しておく必要があります。
サンプルをコンパイルするだけならばGCC Developer Liteを起動する必要は無く、サンプルフォルダ内に同梱される「makeexe.cmd」を実行すればmakefileを読み込んでGCC Developer Liteに同梱されるmakeを使用してコンパイルします。
引数にソース名をしていするとそのソースだけコンパイル、何も付けなければフォルダ内の拡張子がCのソースファイル全てがコンパイル対象となります。
makeexe smpl4_byte_rw (特定のソースのみコンパイル) makeexe (カレントの全ソースをコンパイル)
なおI/Fのポート名やボーレート等はサンプル共通として「dxmisc.h」に記述してありますので、環境に応じて修正した上でコンパイルして下さい。また64bit環境を優先します。
Visual C++ 2010 ExpressでDLLの静的なリンク方法のみ紹介します。
ダウンロードファイルを解凍後、コンパイルするソースファイルと同一フォルダに以下のファイルをコピー
| ファイル | ファイル名 | 備考 |
| ヘッダ | dxlib.h | 必要な宣言を集約 |
| DLL | dxlib_x32.dll | 実行時に必要 |
| ライブラリ | dxlib_x32.lib | リンク時に必要 |
構成プロパティ→C/C++→全般→追加のインクルードディレクトリの項目にヘッダファイルの格納フォルダを指定

構成プロパティ→リンカー→全般→追加のライブラリディレクトリの項目にLIBファイルの格納フォルダを指定

構成プロパティ→リンカー→入力→追加の依存ファイルの項目にLIBファイル名を指定

構成プロパティ→C/C++→プリコンパイル済ヘッダーの項目にプリコンパイル済ヘッダーを使用しないを指定

'SampleCode\LabVIEW2011'フォルダにサンプルが同梱されます。ポート・ボーレート・ID等は使用する環境に合わせて適宜修正して使用します。
LabVIEWには外部のDLLへアクセスする手段が提供されています。しかしながらDXLIBそのままの定義ではLabVIEWからは使いづらいため、サンプルプログラムではサブviでラッピングしてDXLIB.llbにまとめて提供しています。


DXLIB.llbから各viを開き、開いたviの右上にあるアイコンを自分のブロックダイアグラムにドラッグドロップするという操作でviを使用しても良いのですが、頻繁に操作するとなると少々煩雑です。
関数パレットに登録すればスムーズに操作できますので、その手順を紹介します。





'SampleCode\DELPHI'フォルダにサンプルが同梱されます。ポート・ボーレート・ID等は使用する環境に合わせて適宜修正して使用します。
DELPHIはPASCAL言語によるPC向け開発ツールであり、外部のDLLへ容易にアクセスする事が出来ます。サンプルに含まれるDXLIB.pas内にdxlib_x32.dllないしdxlib_x64.dllを動的にロードする関数を用意しましたので、ユーザソースのuses節にdxlibを追記すればDynamixel Libraryの各APIへ簡便にアクセスできます。
'SampleCode\EXCEL'フォルダにサンプルが同梱されます。
ここではVBと似たMicrosoft OfficeのVBAを使用し、マクロの標準モジュールにDXLIB_HEADという名称でDLLに含まれるいくつかのAPIが定義してあります。
Module1にPingTestとMotorTestというマクロが記述されていますので、ワークシートから適宜マクロを呼び出して実行してください。結果がシート上に反映されます。
なお、Officeにも32bit版と64bit版があるため、Declare宣言の方法が異なります。その部分はDXLIB_HEADにて判定していますので、参考にしてください。
'SampleCode\Ruby'フォルダにサンプルが同梱されます。ライブラリ名・ポート・ボーレート・ID等は使用する環境に合わせて適宜修正して使用します。
Rubyはオープンソースの動的なプログラミング言語で、外部のライブラリはfiddleを使用してアクセスします。
require "fiddle/import" module DXLIB extend Fiddle::Importer dlload './dxlib_x32.dll' extern 'void * DX_OpenPort( const char *, long )' extern 'char DX_Active( void * )' extern 'char DX_Ping( void *, unsigned char, unsigned short * )' extern 'char DX_ClosePort( void * )' end devid = dxlib.DX_OpenPort( 'ポート名', ボーレート )
LinuxやmacOSの場合は予めライブラリを再構築しておいて下さい。
'SampleCode\Python'フォルダにサンプルが同梱されます。ポート・ボーレート・ID等は使用する環境に合わせて適宜修正して使用します。
Pythonはオープンソースの動的なプログラミング言語で、外部のDLLへ簡易にアクセスできます。
各APIのPython用の宣言を定義したdxlib.pyをimportするだけで済みます。
from dxlib import * # dxlibをインポート
なおdxlib.pyはctypesによるDLLの単純なラッパーに過ぎませんので、Pythonならではの抽象的な定義は何一つ受け付けてくれません。Pythonからプログラミングを始めた方は微妙に扱いづらいかと思いますので、詳細はサンプルコードを参考にしてください。
LinuxやmacOSの場合は予めライブラリを再構築しておいて下さい。
MATLABからの使用例を紹介します。ポート・ボーレート・ID等は使用する環境に合わせて適宜修正して下さい。また、mex-setupにてCコンパイラを選択しておく必要があります。
まずはMATLAB起動後、「ファイル(F)」→「パス設定(H)」でdxlib_x32.dll(MATALBが64bitの場合はdxlib_x64.dll)とdxlib_matlab.hの格納されたパスを指定します。dxlib.hはMATLABでは解釈できない記述が多いため使用しないでください。
loadlibrary('dxlib_x32.dll','dxlib_matlab.h','alias','dxlib')ロードされたdxlibのDX_OpenPortを呼出します。関数名の後はポートとボーレートです。
devid = calllib('dxlib','DX_OpenPort','\\.\COM3',1000000)TErrorCodeはポインタで引き渡しているため、事前に型宣言をしておきます。値はErr.Valueで取得可能です。必要なければ0を指定しても構いません。
Err = libpointer('uint16Ptr', 0);
Ret = calllib('dxlib', 'DX_Ping', devid, 1, Err);
fprintf('%x', Err.Value);DX_OpenPortを行ったので、DX_ClosePortを使用してポートを閉じます。
calllib('dxlib','DX_ClosePort',devid)unloadlibrary('dxlib')LinuxないしmacOS上でのdx2libのコンパイル方法を紹介します。
wget https://www.besttechnology.co.jp/download/DXLIB_V4.6.zip unzip DXLIB_V4.6.zip
cd DXLIB_v4.6/DXLIB bash ./build_dxlib.shコンパイルが成功するとライブラリファイルがサンプルディレクトリにコピーされる
gcc sample.c -L. -ldxlib -o sample
'SampleCode\C'のサンプルプログラムはmakeを使ってコンパイルできます。
make smpl14_DXL_velocity (特定のソースのみコンパイル) make (カレントの全ソースをコンパイル)
コンパイルや実行にあたってI/Fやカーネル・ディストリビューションに依存しますので、そのまま使用できない場合は適宜ソースを修正下さい。またWindowsを前提とした_DYNAMICLOADマクロが宣言されているとコンパイルできません。
なおI/Fのポート名やボーレート等はサンプル共通として「dxmisc.h」に記述してありますので、環境に応じて修正した上でコンパイルして下さい。
Dynamixel Libraryではシリアル通信を直接意識するコードを記述せずに、対象IDのデバイスのコントロールテーブルへの読み書き行うAPIを用意しています。
C言語のソースにdxlib.hをインクルードすれば、APIを使用するのに必要なプロトタイプとマクロの定義がなされます。
注意事項:
DynamixelのStatus Return Levelを必ず2に設定した上で使用する事。それ以外の値が設定されていた場合はAPIが想定した応答が得られず、タイムアウトするまでAPIから返らない。
ライブラリの内部情報を初期化すると同時に指定されたCOMポートをオープンし、DX_SetBaudrateを使用して通信速度を設定した後、ユニークなTDeviceIDを返す。以後はこのTDeviceIDを使用して各APIを使用する。
複数のCOMポートを使用する場合は、使用するポート毎にDX_OpenPortを行いTDeviceIDを取得しなくてはならない。
なお、Linuxにおけるボーレートの指定に関しては、DX_SetBaudrateの解説に注意の事。
TDeviceID DX_OpenPort (char *name, uint32_t baud);
DX_OpenPortで開いたCOMポートを閉じる。
DX_ClosePortが実行された以後は指定されたTDeviceIDでの通信が行えなくなる。
bool DX_ClosePort (TDeviceID dvid);
既にオープンされているTDeviceIDの通信速度の変更を行う。
実行すると強制的に受信バッファがクリアされる。
bool DX_SetBaudrate (TDeviceID dvid, long baud);
指定されたTDeviceIDのポートが開かれており、使用可能であるかを確認する。
USB接続等によりインターフェース自体が取り外し可能な場合に、実際に使用可能であるかを判断するために使用するが、状況によっては正確に判断できない場合もある。
bool DX_Active (TDeviceID dvid);
I/FやOSの都合で生じるであろうタイムラグを予め設定する。
内部で算出している受信タイムアウト時間とタイムアウトオフセット時間を加算した時間を超えた場合に、タイムアウトエラーとして処理する。
デフォルトは30[ms]。
void DX_SetTimeOutOffset (TDeviceID dvid, uint32_t offsettime);
PINGインストラクションを使用して対象IDからの応答を確認する。
bool DX_Ping (TDeviceID dvid, uint8_t id, TErrorCode *err);
DX_OpenPortで開いた際のTDeviceID。
対象とするID (0~254)。
エラーコード。
正常な応答が得られた場合はtrue、それ以外はfalseを返す。
TDeviceID dev;
TErrorCode err;
// オープン
dev = DX_OpenPort ("\\\\.\\COM10", 57143);
if (dev) {
// ID=1にPINGを発行
if (DX_Ping (dev, 1, &err))
printf ("Found [%08X]\n", err);
else
printf ("Not found [%08X]\n", err);
// クローズ
DX_ClosePort (dev);
}
PINGインストラクションでBROADCASTING IDを指定して不特定の対象の応答を確認する。
BROADCASTING IDを指定した場合の応答時間はデバイスによって差があるため、異なるデバイスが混在している環境では正確な情報を取得できない場合がある。
bool DX_Ping2 (TDeviceID dvid, uint32_t *num, TDxAlarmStatus *AlarmStatus, TErrorCode *err);
DX_OpenPortで開いた際のTDeviceID。
検索する最大数及び検索で見つかったデバイス数の保存先。
検索で見つかったデバイス情報の保存先。
少なくともnumで指定したサイズ分の領域を確保しておく必要がある。
エラーコード。
1台以上のデバイスからの応答が得られた場合はtrue、それ以外はfalseを返す。
TDeviceID dev;
TErrorCode err;
uint8_t id;
TDxAlarmStatus stat[254];
int i;
uint32_t num = 252;
// オープン
dev = DX_OpenPort ("\\\\.\\COM10", 57143);
if (dev) {
// 不明な対象に対してPINGを発行
if (DX_Ping2 (dev, &num, stat, &err)) {
for (i = 0; i < num; i++)
printf ("Found ID=%d %02X\n", stat[i].id, stat[i].Status);
}
// クローズ
DX_ClosePort (dev);
}
対象IDのコントロールテーブルから1バイトのデータを読み出す。
bool DX_ReadByteData(TDeviceID dvid, uint8_t id, uint16_t adr, uint8_t *rdata, TErrorCode *err);
DX_OpenPortで開いた際のTDeviceID。
対象とするID (0~253)。
コントロールテーブルのアドレス。
読み出した値の保存先。
エラーコード。
正常な応答が得られた場合はtrue、それ以外はfalseを返す。
TDeviceID dev;
TErrorCode err;
uint8_t dat;
// オープン
dev = DX_OpenPort ("\\\\.\\COM10", 1000000);
if (dev) {
// ID=1のAX-12からLEDの状態を取得
if (DX_ReadByteData (dev, 1, 25, &dat, &err)) {
printf ("LED STAT=%d\n", dat);
}
DX_ClosePort (dev);
}
対象IDのコントロールテーブルへ1バイトのデータを書き込む。
bool DX_WriteByteData(TDeviceID dvid, uint8_t id, uint16_t adr, uint8_t dat, TErrorCode *err);
DX_OpenPortで開いた際のTDeviceID。
対象とするID (0~253, 254)。
コントロールテーブルのアドレス。
書き込む値。
エラーコード。
正常な応答が得られた場合はtrue、それ以外はfalseを返す。
BROADCASTING IDを指定した場合は応答待ちを行わない。
TDeviceID dev;
TErrorCode err;
uint8_t dat;
// オープン
dev = DX_OpenPort ("\\\\.\\COM10", 1000000);
if (dev) {
// ID=1のAX-12からLEDの状態を取得
if (DX_ReadByteData (dev, 1, 25, &dat, &err)) {
dat ^= 1; // ビット反転
// ID=1のAX-12へLEDの状態を設定
DX_WriteByteData (dev, 1, 25, dat, &err);
}
DX_ClosePort (dev);
}
対象IDのコントロールテーブルから1ワード(2バイト)のデータを読み出す。
bool DX_ReadWordData(TDeviceID dvid, uint8_t id, uint16_t adr, uint16_t *rdata, TErrorCode *err);
DX_OpenPortで開いた際のTDeviceID。
対象とするID (0~253)。
コントロールテーブルのアドレス。
読み出した値の保存先。
エラーコード。
正常な応答が得られた場合はtrue、それ以外はfalseを返す。
TDeviceID dev;
TErrorCode err;
uint16_t dat;
// オープン
dev = DX_OpenPort ("\\\\.\\COM10", 1000000);
if (dev) {
// ID=1のAX-12から現在位置を取得
if (DX_ReadWordData (dev, 1, 36, &dat, &err)) {
printf ("PRESENT POS=%d\n", dat);
}
DX_ClosePort (dev);
}
対象IDのコントロールテーブルへ1ワード(2バイト)のデータを書き込む。
bool DX_WriteWordData(TDeviceID dvid, uint8_t id, uint16_t adr, uint16_t dat, TErrorCode *err);
DX_OpenPortで開いた際のTDeviceID。
対象とするID (0~253, 254)。
コントロールテーブルのアドレス。
書き込む値。
エラーコード。
正常な応答が得られた場合はtrue、それ以外はfalseを返す。
BROADCASTING IDを指定した場合は応答待ちを行わない。
TDeviceID dev;
TErrorCode err;
// オープン
dev = DX_OpenPort ("\\\\.\\COM10", 1000000);
if (dev) {
// ID=1のAX-12へ位置(511)を指令
DX_WriteWordData (dev, 1, 30, 511, &err);
DX_ClosePort (dev);
}
対象IDのコントロールテーブルから2ワード(4バイト)のデータを読み出す。
bool DX_ReadLongData(TDeviceID dvid, uint8_t id, uint16_t adr, uint32_t *rdata, TErrorCode *err);
DX_OpenPortで開いた際のTDeviceID。
対象とするID (0~253)。
コントロールテーブルのアドレス。
読み出した値の保存先。
エラーコード。
正常な応答が得られた場合はtrue、それ以外はfalseを返す。
TDeviceID dev;
TErrorCode err;
uint32_t dat;
// オープン
dev = DX_OpenPort ("\\\\.\\COM10", 1000000);
if (dev) {
// ID=1のXM430から現在位置を取得
if (DX_ReadLongData (dev, 1, 132, &dat, &err)) {
printf ("PRESENT POS=%d\n", dat);
}
DX_ClosePort (dev);
}
対象IDのコントロールテーブルへ2ワード(4バイト)のデータを書き込む。
bool DX_WriteLongData(TDeviceID dvid, uint8_t id, uint16_t adr, uint32_t dat, TErrorCode *err);
DX_OpenPortで開いた際のTDeviceID。
対象とするID (0~253, 254)。
コントロールテーブルのアドレス。
書き込む値。
エラーコード。
正常な応答が得られた場合はtrue、それ以外はfalseを返す。
BROADCASTING IDを指定した場合は応答待ちを行わない。
TDeviceID dev;
TErrorCode err;
// オープン
dev = DX_OpenPort ("\\\\.\\COM10", 1000000);
if (dev) {
// ID=1のXM430へ位置(1024)を指令
DX_WriteLongData (dev, 1, 30, 1024, &err);
DX_ClosePort (dev);
}
対象IDのコントロールテーブルから指定サイズのデータを読み出す。
bool DX_ReadBlockData (TDeviceID dvid, uint8_t id, uint16_t adr, uint8_t *rdata, uint32_t len, TErrorCode *err);
DX_OpenPortで開いた際のTDeviceID。
対象とするID (0~253)。
コントロールテーブルのアドレス。
読み出したデータの保存先。
読み出すデータのサイズ。
エラーコード。
正常な応答が得られた場合はtrue、それ以外はfalseを返す。
TDeviceID dev;
TErrorCode err;
uint8_t comp[4];
dev = DX_OpenPort ("\\\\.\\COM10", 1000000);
if (dev) {
// ID=1のAX-12+からコンプライアンスのデータを取得
if (DX_ReadBlockData (dev, 1, 26, comp, 4, &err) {
printf (
"CWM=%d CCWM=%d CWS=%d CCWS=%d\n",
comp[0], comp[1], comp[2], comp[3]
);
}
DX_ClosePort (dev);
}
対象IDのコントロールテーブルへ指定サイズのデータを書き込む。
bool DX_WriteBlockData(TDeviceID dvid, uint8_t id, uint16_t adr, uint8_t *dat, uint32_t len, TErrorCode *err);
DX_OpenPortで開いた際のTDeviceID。
対象とするID (0~253, 254)。
コントロールテーブルのアドレス。
書き込むデータの保存先。
書き込むデータのサイズ。
エラーコード。
正常な応答が得られた場合はtrue、それ以外はfalseを返す。
BROADCASTING IDを指定した場合は応答待ちを行わない。
TDeviceID dev;
TErrorCode err;
uint8_t comp[4] = { 0, 1, 200, 200 };
dev = DX_OpenPort ("\\\\.\\COM10", 1000000);
if (dev) {
// ID=1のAX-12+のコンプライアンスを変更
DX_WriteBlockData (dev, 1, 26, comp, 4, &err);
DX_ClosePort (dev);
}
SYNCインストラクションには読み出し機能が無いが、DX_ReadBlockDataを使用して指定された複数IDからブロック読み出しを行う。正確には「同期」していない。
bool DX_ReadSyncData (TDeviceID dvid, uint8_t *dat, uint32_t size, uint8_t *retdat, TErrorCode *err);
DX_OpenPortで開いた際のTDeviceID。
読み出す情報の保存先
[addr][length][ID1][ID2]...[IDn]
addr:先頭アドレス (1バイト)
length:先頭アドレスからのバイト数 (1バイト)
IDn:読み出す対象IDを列挙 (nバイト)。
datのサイズ。
エラーコード。
指定された全てのIDに対する読み出しが正常に完了したらtrue、それ以外はfalseを返す。
SYNCインストラクションを使用して複数IDへブロック書き込みを行う。
書き込まれるデータの構成はユーザに委ねられる。
bool DX_WriteSyncData (TDeviceID dvid, uint8_t *dat, uint32_t size, TErrorCode *err);
DX_OpenPortで開いた際のTDeviceID。
書き込むパラメータの保存先。
パラメータのサイズ。
エラーコード。
インターフェースより送信が行われた場合はtrue、それ以外はfalseを返す。
#define _POS1 (400)
#define _POS2 (511)
TDeviceID dev;
TErrorCode err;
uint8_t param[8] = {
30, // アドレス (Goal Position)
2, // データ長 (2 byte)
// ID=1用データ
1,
_POS1 & 0xff,
_POS1 >> 8,
// ID=2用データ
2,
_POS2 & 0xff,
_POS2 >> 8
};
dev = DX_OpenPort ("\\\\.\\COM10", 1000000);
if (dev) {
// 2つのAX-12へ同時に位置を指令
DX_WriteSyncData (dev, param, 8, &err);
DX_ClosePort (dev);
}
任意のインストラクションパケットを送信する。
bool DX_TxPacket (TDeviceID dvid, uint8_t id, TInstruction inst, uint8_t *param, uint32_t len, TErrorCode *err);
DX_OpenPortで開いた際のTDeviceID。
対象とするID (0~254)。
使用するインストラクション。
送信するパラメータの保存先。
送信するパラメータのサイズ。
エラーコード。
インターフェースより送信が行われた場合はtrue、それ以外はfalseを返す。
TDeviceID dev;
TErrorCode err;
uint8_t param[2] = {
25, // アドレス (LED)
0, // データ
};
dev = DX_OpenPort ("\\\\.\\COM10", 1000000);
if (dev) {
// ID=1のAX-12+のLEDを消灯
DX_TxPacket (dev, 1, INST_WRITE, param, 2, &err);
DX_ClosePort (dev);
}
ステータスパケットを受信する。
基本的にDX_TxPacketとペアで使用する。ステータスパケットが得られない状況で使用するとタイムアウトするまで返らない。
なお、本APIはDX_SetTimeOutOffsetで設定されたオフセット値は使用せず、引数で指定された受信タイムアウトのみが適用される。
bool DX_RxPacket (TDeviceID dvid, uint8_t *rdata, uint32_t rdatasize, uint32_t *rlen, uint32_t timeout, TErrorCode *err);
DX_OpenPortで開いた際のTDeviceID。
受信バッファ。
ステータスパケットを受信するのに十分なサイズを確保しておく必要がある。
rdataのサイズ。
実際に受信されたステータスパケットのサイズ。
受信タイムアウト[ms]。
エラーコード。
受信成功時はtrue、それ以外はfalseを返す。
int i;
uint32_t len;
TDeviceID dev;
TErrorCode err;
uint8_t param[2] = {
25, // アドレス (LED)
1, // サイズ
};
dev = DX_OpenPort ("\\\\.\\COM10", 1000000);
if (dev) {
// ID=1のAX-12+からLEDの状態を読み出す要求
if (DX_TxPacket (dev, 1, INST_READ, param, 2, &err)) {
// ステータスパケットを受信
DX_RxPacket (dev, dat, sizeof (dat), &len, 100, &err);
for (i = 0; i < len; i++) {
printf ("[%02X]", dat[i]);
}
}
DX_ClosePort (dev);
}
INST_PING
INST_READ
INST_WRITE
INST_REG_WRITE
INST_ACTION
INST_RESET
INST_SYNC_WRITE
INST_SYNG_REG_WRITE
| bit | macro name | |
| 15 | ERR_INVALID_DEVID | 使用できないTDeviceID |
| 14 | ERR_INVALID_ID | 指定できないID |
| 13 | ERR_DIFF_ID | 異なるIDからの応答 |
| 12 | ERR_ILLEGAL_SIZE | 異常なデータサイズ |
| 11 | ERR_INVALID_PARAM | 異常なパラメータ |
| 10 | ERR_COMM | シリアルポートエラー |
| 9 | ERR_CHECKSUM | 異常なチェックサム |
| 8 | ERR_TIMEOUT | 受信タイムアウト |
| 7 | ||
| 6 | ERR_DX_INST | 未定義のインストラクションが指定された、もしくはreg_writeなしでactionが指定された |
| 5 | ERR_DX_OVERLOAD | 指定された最大トルクで現在の負荷を制御できない |
| 4 | ERR_DX_CHECKSUM | インストラクションパケットのチェックサムが正しく無い |
| 3 | ERR_DX_RANGE | パラメータの設定範囲を超えた |
| 2 | ERR_DX_OVERHEAT | 内部温度が設定温度を超えた |
| 1 | ERR_DX_ANGLE | Angle Limitの範囲外にGoal Positionが指定された |
| 0 | ERR_DX_OVERVOLTAGE | 電源電圧が指定動作電圧の範囲を超えた |
使用するDynamixelの情報を予めライブラリ内に保持させておき、位置や角速度等の指令およびフィードバック値は物理値を扱い、各々の区別はIDのみで行うAPIです。
これAPIによりDynamixelのモデルごとに異なるコントロールテーブルや煩雑な運転方法の違いを意識する事なく、少ないコードで目的の挙動を実現できます。
なお、従来通りコントロールテーブルへの直接アクセスを制限するものではありませんが、その場合は本機能が想定する状況と一致しなくなる事があります。
※以下の使用例はDX2LIBを前提としています。
Dynamixelが持つ固有の情報を予め記憶させておくことで、それ以後の操作はIDのみを指定し、どのモデルであっても使用頻度が高いアイテムはコントロールテーブルを意識する事無く同じAPIで同様の動作ができます。
ID0~252のデバイスを順次検索し、サポートするDynamixelであればライブラリ内のリストに登録する。
リストに登録されていないデバイスのIDに対しては存在しないものとして通信を行わないため、DXL_ScanDevicesかDXL_GetModelInfoを用いて予めリストに登録しておく必要がある。
int DXL_ScanDevices (TDeviceID dvid, uint8_t *ids);
見つかったデバイスの数。
#include <stdio.h>
#include <dx2lib.h>
void main (void) {
// COM10を57600bpsでオープン
TDeviceID dev = DX2_OpenPort ("\\\\.\\COM10", 57600);
if (dev != 0) {
// ID=0~252の情報を取得し成功したもののみライブラリ内のリストに追加
printf("detect num=%d\n", DXL_ScanDevices (dev, NULL));
DX2_Close (dev);
}
}
指定IDのモデル情報の取得し、サポートするDynamixelであればライブラリ内のリストに登録する。
リストに登録されていないデバイスのIDに対しては存在しないものとして通信を行わないため、DXL_ScanDevicesかDXL_GetModelInfoを用いて予めリストに登録しておく必要がある。
PDXL_ModelInfo DXL_GetModelInfo (TDeviceID dvid, uint8_t id);
登録されたIDと一致するTDXL_ModelInfoのアドレス。
#include <stdio.h>
#include <dx2lib.h>
void main (void) {
TDeviceID dev = DX2_OpenPort ("/dev/ttyUSB0", 57600);
for (uint8_t id = 0; id <= 252; id++) {
// idの情報を取得し成功したらライブラリ内のリストに追加
PDXL_ModelInfo p = DXL_GetModelInfo (dev, id);
if (p->modelno != 0)
printf ("[%3d] %s ($%04X) %d\n", id, p->name, p->modelno, p->devtype);
}
}
DX2_ClosePort (dev);
}
ライブラリ内のリストに登録された全てのデバイスの情報をコンソールに出力する。
ID・モデル名・モデル番号の順に出力される。
bool DXL_PrintDevicesList (int (*pf) (const char *, ...));
printf等の書式化文字列出力ルーチンのポインタ。
処理が正常終了したらtrue、それ以外はfalseを返す。
#include <stdio.h>
#include <dx2lib.h>
void main (void) {
TDeviceID dev = DX2_OpenPort ("/dev/ttyUSB0", 57600);
DXL_ScanDevices (dev, NULL);
DXL_PrintDevicesList ((void *)&printf);
DX2_ClosePort (dev);
}
追加APIの処理の中で最後に取得したエラーを返す。本API自体は通信を行わない。
TErrorCode DXL_GetErrorCode (TDeviceID dvid, uint8_t id);
エラーコード。
対象IDのコントロールテーブルにハードウェアエラーが備わっている場合にのみ取得する。
bool DXL_GetHWErrorCode (TDeviceID dvid, uint8_t id, uint8_t *hwerr);
運転モードはDynamixelのDrive Mode、動作モードはOperating Modeを意味します。
運転モードはデフォルトの回転方向やプロファイルの選択、マスタースレーブの設定を行います。
動作モードについてはDynamixel X・Pシリーズの動作モードを基準とし、他のモデルにおいてもこの動作モードの番号を踏襲することとします。
対象IDの運転モードを変更する。
指定されたモードと現在のモードが異なる場合にのみトルクをOFFにし運転モードを更新する。
対称IDがライブラリ内のリストに登録されている必要がある。
bool DXL_SetDriveMode (TDeviceID dvid, uint8_t id, uint8_t mode);
処理が正常終了したらtrue、それ以外はfalseを返す。
#include <dx2lib.h>
void main (void) {
TDeviceID dev = DX2_OpenPort ("\\\\.\\COM10", 57600);
// ID:1を検索し見つかれば登録
DXL_GetModelInfo (dev, 1);
// ID:1のXシリーズをTime-Base Profileに設定
DXL_SetDriveMode (dev, 1, 4);
DX2_ClosePort (dev);
}
複数IDの運転モードを一括変更する。
指定されたモードと現在のモードが異なる場合にのみトルクをOFFにし運転モードを更新する。
ライブラリ内のリストに登録されていないIDは無視される。
bool DXL_SetDriveModesEquival (TDeviceID dvid, const uint8_t *ids, int num, uint8_t mode);
処理が正常終了したらtrue、それ以外はfalseを返す。
#include <dx2lib.h>
void main (void) {
TDeviceID dev = DX2_OpenPort ("\\\\.\\COM10", 57600);
uint8_t ids[3] = {1, 2, 3};
// ID:1~3を検索し見つかれば登録
for (int i = 0; i < sizeof (ids); i++) DXL_GetModelInfo (dev, ids[i]);
// ID:1~3のDrive Modeを出荷時デフォルト値に設定
DXL_SetDriveModesEquival (dev, ids, sizeof (ids), 0);
DX2_ClosePort (dev);
}
対象IDの動作モードを変更する。
指定されたモードと現在のモードが異なる場合にのみトルクをOFFにし動作モードを更新する。
対称IDがライブラリ内のリストに登録されている必要がある。
bool DXL_SetOperatingMode (TDeviceID dvid, uint8_t id, uint8_t mode);
DX?_OpenPortで開いた際のTDeviceID。
対象とするID (0~252)。
Dynamixel Xシリーズの動作モードを想定し、それに完全対応しないデバイスに対しては近似値もしくは失敗を返す。
0: Current Control (電流制御)
1: Velocity Control (速度制御)
3: Position Control (位置制御)
4: Expand Position Control (多回転位置制御)
5: Current-Base Position Control
16: PWM Control
処理が正常終了したらtrue、それ以外はfalseを返す。
#include <dx2lib.h>
void main (void) {
TDeviceID dev = DX2_OpenPort ("\\\\.\\COM10", 57600);
// ID:1を検索し見つかれば登録
DXL_GetModelInfo (dev, 1);
// ID:1をCurrent-Base Position Controlに設定
DXL_SetOperatingMode (dev, 1, 5);
DX2_ClosePort (dev);
}
複数IDの動作モードを一括変更する。
指定されたモードと現在のモードが異なる場合にのみトルクをOFFにし動作モードを更新する。
ライブラリ内のリストに登録されていないIDは無視される。
bool DXL_SetOperatingModesEquival (TDeviceID dvid, const uint8_t *ids, int num, uint8_t mode);
DX?_OpenPortで開いた際のTDeviceID。
対象とするID一覧を保持する配列の保存先。
対象とするID数
Dynamixel Xシリーズの動作モードを想定し、それに完全対応しないデバイスに対しては近似値もしくは失敗を返す。
0: Current Control
1: Velocity Control
3: Position Control
4: Expand Position Control
5: Current-Base Position Control
16: PWM Control
処理が正常終了したらtrue、それ以外はfalseを返す。
#include <dx2lib.h>
void main (void) {
TDeviceID dev = DX2_OpenPort ("\\\\.\\COM10", 57600);
uint8_t ids[3] = {1, 2, 3};
// ID:1~3を検索し見つかれば登録
for (int i = 0; i < sizeof (ids); i++) DXL_GetModelInfo (dev, ids[i]);
// ID:1~3をVelocity Controlに設定
DXL_SetOperatingModesEquival (dev, ids, sizeof (ids), 1);
DX2_ClosePort (dev);
}
対象IDの動作モードを取得する。なお内部ではDrive Modeも一緒に取得し保持している。
bool DXL_GetOperatingMode (TDeviceID dvid, uint8_t id, uint8_t *mode);
対象IDの制御を開始ないし停止させる。
なお、プロトコルV2のDynamixelは明示的に制御を開始しない限りモータの制御を行わない。
bool DXL_SetTorqueEnable (TDeviceID dvid, uint8_t id, bool en);
処理が正常終了したらtrue、それ以外はfalseを返す。
#include <dx2lib.h>
void main (void) {
TDeviceID dev = DX2_OpenPort ("\\\\.\\COM10", 57600);
DXL_GetModelInfo (dev, 1);
DXL_SetOperatingMode (dev, 1, 3);
// ID:1の制御をON
DXL_SetTorqueEnable (dev, 1, true);
// ID:1へ角度指令 180deg
DXL_SetGoalAngle (dev, 1, 180.0);
// 1000ms待機
Sleep (1000);
// ID:1の制御をOFF
DXL_SetTorqueEnable (dev, 1, false);
DX2_ClosePort (dev);
}
複数IDの制御を個別に開始ないし停止させる。
ライブラリ内のリストに登録されていないIDは無視される。
なお、プロトコルV2のDynamixelは明示的に制御を開始しない限りモータの制御を行わない。
bool DXL_SetTorqueEnables (TDeviceID dvid, const uint8_t *ids, const bool *ens, int num);
複数IDの制御を一括で開始ないし停止させる。
ライブラリ内のリストに登録されていないIDは無視される。
なお、プロトコルV2のDynamixelは明示的に制御を開始しない限りモータの制御を行わない。
bool DXL_SetTorqueEnablesEquival (TDeviceID dvid, const uint8_t *ids, int num, bool en);
処理が正常終了したらtrue、それ以外はfalseを返す。
#include <dx2lib.h>
void main (void) {
TDeviceID dev = DX2_OpenPort ("\\\\.\\COM10", 57600);
DXL_GetModelInfo (dev, 1);
DXL_GetModelInfo (dev, 2);
DXL_GetModelInfo (dev, 3);
uint8_t ids[3] = {1, 2, 3};
// ID:1~3の制御をON
DXL_SetTorqueEnablesEquival (dev, ids, sizeof (ids), true);
DX2_ClosePort (dev);
}
対象IDのトルクイネーブル状態を取得する。
bool DXL_GetTorqueEnable (TDeviceID dvid, uint8_t id, bool *en);
複数IDのトルクイネーブル状態を取得する。
ライブラリ内のリストに登録されていないIDは無視される。
bool DXL_GetTorqueEnables (TDeviceID dvid, const uint8_t *ids, bool *en, int num);
DynamixelのコントロールテーブルではPositionと称しているユニークな単位系を持つアイテムは、モデルによって動作角度や分解能が大きく異なります。異なるモデルを混在して運用する場合は非常に不便なため、物理値の角度[deg]を用いてアクセスします。
指定IDへ目標角度を指令する。
動作モードがPosition Controlである事と、プロトコルV2のDynamixelは明示的に制御を開始しない限りモータの制御を行わない。
bool DXL_SetGoalAngle (TDeviceID dvid, uint8_t id, double angle);
処理が正常終了したらtrue、それ以外はfalseを返す。
#include <dx2lib.h>
void main (void) {
TDeviceID dev = DX2_OpenPort ("\\\\.\\COM10", 57600);
DXL_GetModelInfo (dev, 1);
DXL_SetOperatingMode (dev, 1, 3);
DXL_SetTorqueEnable (dev, 1, true);
// ID:1へ角度指令 180deg
DXL_SetGoalAngle (dev, 1, 180.0);
Sleep (1000);
// ID:1へ角度指令 -180deg
DXL_SetGoalAngle (dev, 1, -180.0);
Sleep (1000);
// ID:1へ角度指令 0deg
DXL_SetGoalAngle (dev, 1, 0.0);
Sleep (1000);
DXL_SetTorqueEnable (dev, 1, false);
DX2_ClosePort (dev);
}
複数IDへ個別の目標角度を指令する。
ライブラリ内のリストに登録されていないIDは無視される。
動作モードがPosition Controlである事と、プロトコルV2のDynamixelは明示的に制御を開始しない限りモータの制御を行わない。
bool DXL_SetGoalAngles (TDeviceID dvid, const uint8_t *ids, const double *angles, int num);
処理が正常終了したらtrue、それ以外はfalseを返す。
#include <dx2lib.h>
void main (void) {
TDeviceID dev = DX2_OpenPort ("\\\\.\\COM10", 57600);
DXL_GetModelInfo (dev, 1);
DXL_GetModelInfo (dev, 2);
DXL_GetModelInfo (dev, 3);
uint8_t ids[3] = {1, 2, 3};
DXL_SetOperatingModesEquival (dev, ids, sizeof (ids), 3);
DXL_SetTorqueEnablesEquival (dev, ids, sizeof (ids), true);
// 3軸分の角度を保存したの配列
double angles[3] = { 0.0, 150.0, 300.0 };
// 3軸分の角度指令
DXL_SetGoalAngles (dev, ids, angles, sizeof (ids));
Sleep (2000);
DXL_SetTorqueEnablesEquival (dev, ids, sizeof (ids), false);
DX2_ClosePort (dev);
}
対象IDの現在角度を取得する。
bool DXL_GetPresentAngle (TDeviceID dvid, uint8_t id, double *angle);
処理が正常終了したらtrue、それ以外はfalseを返す。
#include <stdio.h>
#include <dx2lib.h>
void main (void) {
TDeviceID dev = DX2_OpenPort ("\\\\.\\COM10", 57600);
uint8_t id = 1;
DXL_GetModelInfo (dev, id);
DXL_SetOperatingMode (dev, id, 3);
DXL_SetTorqueEnable (dev, id, true);
DXL_SetGoalAngle (dev, id, -180.0);
Sleep (1000);
DXL_SetGoalAngle (dev, id, 180.0);
for (int i = 0; i < 1000; i++) {
double pang;
// 現在角度取得
if (DXL_GetPresentAngle (dev, id, &pang))
printf ("%5.1\r", pang);
Sleep (10);
}
DXL_SetTorqueEnable (dev, id, false);
DX2_ClosePort (dev);
}
複数IDの現在角度を取得する。
ライブラリ内のリストに登録されていないIDは無視される。
bool DXL_GetPresentAngles (TDeviceID dvid, const uint8_t *ids, double *angles, int num);
制御をOFFにする事で制御が停止するのと合わせて脱力状態になります。それでは現在の角度を保持しつつ止めることができないため、指令されたタイミングの角度を取得してその値をそのまま角度指令し直す機能を設けています。
指定IDを現在角度で停止させる。
動作モードがPosition Controlである事。
bool DXL_StandStillAngle (TDeviceID dvid, uint8_t id);
複数IDを現在角度で停止させる。
ライブラリ内のリストに登録されていないIDは無視される。
動作モードがPosition Controlである事。
bool DXL_StandStillAngles (TDeviceID dvid, const uint8_t *ids, int num);
DynamixelのコントロールテーブルではVelocityと称しているユニークな単位系を持つアイテムは、モデルによってレンジや分解能が異なります。異なるモデルを混在して運用する場合は非常に不便なため、物理値の角速度[deg/sec]を用いてアクセスします。
指定IDへ目標角速度を指令する。
動作モードがVelocity Controlである事と、プロトコルV2のDynamixelは明示的に制御を開始しない限りモータの制御を行わない。
bool DXL_SetGoalVelocity (TDeviceID dvid, uint8_t id, double velocity);
処理が正常終了したらtrue、それ以外はfalseを返す。
#include <dx2lib.h>
void main (void) {
TDeviceID dev = DX2_OpenPort ("\\\\.\\COM10", 57600);
DXL_GetModelInfo (dev, 1);
DXL_SetOperatingMode (dev, 1, 1);
DXL_SetTorqueEnable (dev, 1, true);
// 角速度指令 30deg/s
DXL_SetGoalVelocity (dev, 1, 30.0);
Sleep (1000);
// 角速度指令 40deg/s
DXL_SetGoalVelocity (dev, 1, 40.0);
Sleep (1000);
DXL_SetTorqueEnable (dev, 1, false);
DX2_ClosePort (dev);
}
複数IDへ個別の目標角速度を指令する。
ライブラリ内のリストに登録されていないIDは無視される。
動作モードがVelocity Controlである事と、プロトコルV2のDynamixelは明示的に制御を開始しない限りモータの制御を行わない。
bool DXL_SetGoalVelocities (TDeviceID dvid, const uint8_t *ids, const double *velocities, int num);
対象IDの現在角速度を取得する。
bool DXL_GetPresentVelocity (TDeviceID dvid, uint8_t id, double *velocity);
複数IDの現在角速度を取得する。
ライブラリ内のリストに登録されていないIDは無視される。
bool DXL_GetPresentVelocities (TDeviceID dvid, const uint8_t *ids, double *velocities, int num);
角度と合わせて角速度を同時に指令することで、指定角度へゆっくり動かすと行った動作を行わせる事ができます。
なお、Dynamixelの角速度制御の分解能はさほど大きくないため、角速度が低い場合は誤差が大きくなります。
指定IDへ目標角度と目標角速度を指令する。
動作モードがPosition Controlである事と、プロトコルV2のDynamixelは明示的に制御を開始しない限りモータの制御を行わない。
bool DXL_SetGoalAngleAndVelocity (TDeviceID dvid, uint8_t id, double angle, double velocity);
処理が正常終了したらtrue、それ以外はfalseを返す。
#include <dx2lib.h>
void main (void) {
TDeviceID dev = DX2_OpenPort ("\\\\.\\COM10", 57600);
uint8_t id = 3;
DXL_GetModelInfo (dev, id);
DXL_SetOperatingMode (dev, id, 3);
DXL_SetTorqueEnable (dev, id, true);
// 現在角度から-170degの角度へ30deg/sの角速度で
DXL_SetGoalAngleAndVelocity (dev, id, -170.0, 30.0);
Sleep (10000);
// 現在角度から160degの角度へ40deg/sの角速度で
DXL_SetGoalAngleAndVelocity (dev, id, 160.0, 40.0);
Sleep (10000);
DXL_SetTorqueEnable (dev, id, false);
DX2_ClosePort (dev);
}
複数IDへ個別の目標角度と目標角速度を指令する。
ライブラリ内のリストに登録されていないIDは無視される。
動作モードがPosition Controlである事と、プロトコルV2のDynamixelは明示的に制御を開始しない限りモータの制御を行わない。
bool DXL_SetGoalAnglesAndVelocities (TDeviceID dvid, const uint8_t *ids, const PAngleVelocity anglevelocity, int num);
DX?_OpenPortで開いた際のTDeviceID。
対象とするID一覧を保持する配列の保存先。
idsで指定されたID順に目標角度[deg]と目標角速度[deg/s]を保持する構造体の配列の保存先。
対象とするID数
処理が正常終了したらtrue、それ以外はfalseを返す。
角度と合わせて時間を同時に指令します。ライブラリ内では時間を角速度(=(目標角度-現在角度)/移動時間)に変換して指令します。
なお、Dynamixelの角速度制御の分解能はさほど大きくないため、移動速度が長い場合は誤差が大きくなります。
また事前にDXL_SetDriveModeもしくはDXL_SetDriveModesEquivalでVelocity-Base Profile(出荷時デフォルト)を指定しておく必要があります。
最新のファームウェアを備えたDynamixelの場合は角度と時間2のAPIを利用することを推奨します。
指定IDへ目標角度と現在角度から目標角度までの移動時間を指令する。
動作モードがPosition Controlである事と、プロトコルV2のDynamixelは明示的に制御を開始しない限りモータの制御を行わない。
bool DXL_SetGoalAngleAndTime (TDeviceID dvid, uint8_t id, double angle, double sec);
処理が正常終了したらtrue、それ以外はfalseを返す。
#include <dx2lib.h>
void main (void) {
TDeviceID dev = DX2_OpenPort ("\\\\.\\COM10", 57600);
uint8_t id = 3;
DXL_GetModelInfo (dev, id);
DXL_SetOperatingMode (dev, id, 3);
DXL_SetTorqueEnable (dev, id, true);
// 現在角度から-150degの角度へ3秒で移動
DXL_SetGoalAngleAndTime (dev, id, -150.0, 3.0);
Sleep (4000);
// 現在角度から180degの角度へ5秒で移動
DXL_SetGoalAngleAndTime (dev, id, 180.0, 5.0);
Sleep (6000);
DXL_SetTorqueEnable (dev, id, false);
DX2_ClosePort (dev);
}
複数IDへ個別の目標角度と現在角度から目標角度までの移動時間を指令する。
ライブラリ内のリストに登録されていないIDは無視される。
動作モードがPosition Controlである事と、プロトコルV2のDynamixelは明示的に制御を開始しない限りモータの制御を行わない。
bool DXL_SetGoalAnglesAndTime (TDeviceID dvid, const uint8_t *ids, const double *angles, int num, double sec);
角度と合わせて時間を同時に指令します。目的は先のAPIと同様ですが、Dynamixelの新しいファームウェアに備わっているTime-Base Profileを用いて指令するため、指定時間通りに目標角度に到達します。
事前にDXL_SetDriveModeもしくはDXL_SetDriveModesEquivalでTime-Base Profileを設定しておく必要があります。
指定IDへ目標角度と現在角度から目標角度までの移動時間を指令する。
動作モードがPosition Controlである事と、プロトコルV2のDynamixelは明示的に制御を開始しない限りモータの制御を行わない。
bool DXL_SetGoalAngleAndTime2 (TDeviceID dvid, uint8_t id, double angle, double sec);
処理が正常終了したらtrue、それ以外はfalseを返す。
#include <dx2lib.h>
void main (void) {
TDeviceID dev = DX2_OpenPort ("\\\\.\\COM10", 57600);
uint8_t id = 3;
DXL_GetModelInfo (dev, id);
// Time-Base profileを設定
DXL_SetDriveMode (dev, id, 0x04);
DXL_SetOperatingMode (dev, id, 3);
DXL_SetTorqueEnable (dev, id, true);
// 現在角度から-150degの角度へ3秒で移動
DXL_SetGoalAngleAndTime2 (dev, id, -150.0, 3.0);
Sleep (4000);
// 現在角度から180degの角度へ5秒で移動
DXL_SetGoalAngleAndTime2 (dev, id, 180.0, 5.0);
Sleep (6000);
DXL_SetTorqueEnable (dev, id, false);
DX2_ClosePort (dev);
}
複数IDへ個別の目標角度と現在角度から目標角度までの移動時間を指令する。
ライブラリ内のリストに登録されていないIDは無視される。
動作モードがPosition Controlである事と、プロトコルV2のDynamixelは明示的に制御を開始しない限りモータの制御を行わない。
bool DXL_SetGoalAnglesAndTime2 (TDeviceID dvid, const uint8_t *ids, const double *angles, int num, double sec);
指定IDへ目標電流を指令する。
プロトコルV2のDynamixelは明示的に制御を開始しない限りモータの制御を行わない。
bool DXL_SetGoalCurrent (TDeviceID dvid, uint8_t id, double current);
処理が正常終了したらtrue、それ以外はfalseを返す。
#include <dx2lib.h>
void main (void) {
TDeviceID dev = DX2_OpenPort ("\\\\.\\COM10", 57600);
DXL_GetModelInfo (dev, 1);
DXL_SetOperatingMode (dev, 1, 0);
DXL_SetTorqueEnable (dev, 1, true);
// 電流指令 200mA
DXL_SetGoalCurrent (dev, 1, 200.0);
Sleep (1000);
// 電流指令 -200mA
DXL_SetGoalAngle (dev, 1, -200.0);
Sleep (1000);
DXL_SetTorqueEnable (dev, 1, false);
DX2_ClosePort (dev);
}
複数IDへ個別の目標電流を指令する。
ライブラリ内のリストに登録されていないIDは無視される。
プロトコルV2のDynamixelは明示的に制御を開始しない限りモータの制御を行わない。
bool DXL_SetGoalCurrents (TDeviceID dvid, const uint8_t *ids, const double *currents, int num);
指定IDの現在電流を取得する。
bool DXL_GetPresentCurrent (TDeviceID dvid, uint8_t id, double *current);
複数IDの現在電流を取得する。
ライブラリ内のリストに登録されていないIDは無視される。
bool DXL_GetPresentCurrents (TDeviceID dvid, const uint8_t *ids, double *currents, int num);
指定IDへ目標PWMを指令する。
動作モードがPWM Controlである事と、プロトコルV2のDynamixelは明示的に制御を開始しない限りモータの制御を行わない。
bool DXL_SetGoalPWM (TDeviceID dvid, uint8_t id, double pwm);
処理が正常終了したらtrue、それ以外はfalseを返す。
#include <dx2lib.h>
void main (void) {
TDeviceID dev = DX2_OpenPort ("\\\\.\\COM10", 57600);
DXL_GetModelInfo (dev, 1);
DXL_SetOperatingMode (dev, 1, 16);
DXL_SetTorqueEnable (dev, 1, true);
// PWM指令 50%
DXL_SetGoalPWM (dev, 1, 50.0);
Sleep (1000);
// PWM指令 -40%
DXL_SetGoalPWM (dev, 1, -40.0);
Sleep (1000);
DXL_SetTorqueEnable (dev, 1, false);
DX2_ClosePort (dev);
}
複数IDへ個別の目標PWMを指令する。
ライブラリ内のリストに登録されていないIDは無視される。
動作モードがPWM Controlである事と、プロトコルV2のDynamixelは明示的に制御を開始しない限りモータの制御を行わない。
bool DXL_SetGoalPWMs (TDeviceID dvid, const uint8_t *ids, const double *pwms, int num);
指定IDの現在PWMを取得する。
bool DXL_GetPresentPWM (TDeviceID dvid, uint8_t id, double *pwm);
複数IDの現在PWMを取得する。
ライブラリ内のリストに登録されていないIDは無視される。
bool DXL_GetPresentPWMs (TDeviceID dvid, const uint8_t *ids, double *pwms, int num);