2011/09/04(日)ArduinoでRS485通信をしてみる

2011/09/04 15:36 Arduinoimportnucho
知り合いの人から「マイコンからRS485通信がしたいぜうぎぎ」と要望があったのが発端となり、LTC485CN8とArduinoでRS405CBを動かしてみたレポートです.

LTC485CN8を使ってみる

回路図

LTC485CN8_test

説明

LTC485CN8はDE,RE端子の状態によって送信、受信のモードを切り替えて使います。
つまりマイコンは,DE,REに直結した端子をHIGHにしてから送信、LOWにしてから受信というように処理を行えばいいわけですね。
あとはまぁ別に普通のシリアル通信です。

余談となってしまうんですが,RS405CBの設定で返信ディレイ時間が用意されている理由は、送受信の切り替えに時間がかかるマイコンを使ったときに調整するためなのかなぁと思ってます。
RS405CBはFutabaのロボット用サーボの開発成果を全て盛り込んだという触れ込みだけあって、色々気が使われてる印象がありますね。

プログラムはちょっと長いので続きを読むに置いときました。

参考という名のパクリ元

RS-485の接続(爪車さん)
FT232RLでRS-485通信(爪車さん)
爪車さんはシミュレータを使いこなしつつ二足歩行ロボをやってらっしゃる凄い方です。

プログラム

あらかじめRS405CBの通信速度を38400bpsに設定しています。
unsigned char sendbuf[32];
int txden = 13;             // txdenはデジタルピン13にしてみる

void setup()
{
  Serial.begin(38400);
  digitalWrite(txden, LOW);
  torque(1, 1);//ID1のトルクON
}

void loop()
{
  move(1,1000,0);
  delay(1500);
  move(1,0,0);
  delay(1500);
  move(1,-1000,0);
  delay(1500);
  move(1,0,0);
  delay(1500);
}

void move(int sId, int sPos, int sTime) {
  unsigned char sum;

  // パケット作成
  sendbuf[0] = (unsigned char) 0xFA; // ヘッダ1
  sendbuf[1] = (unsigned char) 0xAF; // ヘッダ2
  sendbuf[2] = (unsigned char) sId; // サーボID
  sendbuf[3] = (unsigned char) 0x00; // フラグ
  sendbuf[4] = (unsigned char) 0x1E; // アドレス(0x1E=30)
  sendbuf[5] = (unsigned char) 0x04; // 長さ(4byte)
  sendbuf[6] = (unsigned char) 0x01; // 個数
  sendbuf[7] = (unsigned char) (sPos & 0x00FF); // 位置
  sendbuf[8] = (unsigned char) ((sPos & 0xFF00) >> 8); // 位置
  sendbuf[9] = (unsigned char) (sTime & 0x00FF); // 時間
  sendbuf[10] = (unsigned char) ((sTime & 0xFF00) >> 8); // 時間

  // チェックサムの計算
  sum = sendbuf[2];
  for (int i = 3; i < 11; i++) {
    sum = (unsigned char)(sum ^ sendbuf[i]);
  }
  sendbuf[11] = sum; // チェックサム

  // 送信
  digitalWrite(txden, HIGH);
  Serial.write(sendbuf, 12); 
  delay(50);//送信が終わるまで待つ
  digitalWrite(txden,LOW);
}

void torque(int sId, int sMode) {
  unsigned char sum;

  // パケット作成
  sendbuf[0] = (unsigned char) (0xFA); // ヘッダー1
  sendbuf[1] = (unsigned char) (0xAF); // ヘッダー2
  sendbuf[2] = (unsigned char) (sId); // サーボID
  sendbuf[3] = (unsigned char) (0x00); // フラグ
  sendbuf[4] = (unsigned char) (0x24); // アドレス(0x24=36)
  sendbuf[5] = (unsigned char) (0x01); // 長さ(4byte)
  sendbuf[6] = (unsigned char) (0x01); // 個数
  sendbuf[7] = (unsigned char)((sMode&0x00FF)); // ON/OFFフラグ

  // チェックサムの計算
  sum = sendbuf[2];
  for (int i = 3; i < 8; i++) {
    sum = (unsigned char) (sum ^ sendbuf[i]);
  }
  sendbuf[8] = sum; // チェックサム

  // 送信
  digitalWrite(txden, HIGH);
  Serial.write(sendbuf, 9);
  delay(50);//送信が終わるまで待つ
  digitalWrite(txden, LOW);
}

2011/12/6追記

角度情報も取得してみるプログラム

リクエスト頂きましたので角度情報を取得するプログラムを書いてみました。
Arduinoのtx,rxを使用するとPCのコンソールに表示できないため、サーボとの通信はソフトウェアシリアルを使用しています。
そのため、上記の回路図から、LTC485CN8の1ピンをarduinoの2ピンに接続、LTC485CN8の4ピンをarduinoの3ピンに接続という風に回路図を変更して、またRS405CBの通信速度を9600bpsに設定しています。ご注意ください。
#include <SoftwareSerial.h> 

int rxPin = 2;
int txPin = 3;
int txden = 13;             // txdenはデジタルピン13にしてみる

unsigned char sendbuf[32];
unsigned char readbuf[32];

SoftwareSerial mySerial =  SoftwareSerial(rxPin, txPin);

void setup()
{
  Serial.begin(9600);
  digitalWrite(txden, LOW);

  pinMode(rxPin, INPUT);
  pinMode(txPin, OUTPUT);
  mySerial.begin(9600);

  torque(1, 1);//ID1のトルクON
}

void loop()
{
  int angle;
  
  move(1,1000,0);
  delay(1500);//移動が終わるまでまつ
  angle=getAngle(1);//ID1の角度を得る
  Serial.println(angle);//角度表示
  

  move(1,0,0);
  delay(1500);//移動が終わるまでまつ
  angle=getAngle(1);//ID1の角度を得る
  Serial.println(angle);//角度表示

  move(1,-1000,0);
  delay(1500);//移動が終わるまでまつ
  angle=getAngle(1);//ID1の角度を得る
  Serial.println(angle);//角度表示

  move(1,0,0);
  delay(1500);//移動が終わるまでまつ
  angle=getAngle(1);//ID1の角度を得る
  Serial.println(angle);//角度表示
}

/**
* サーボを指定角度へ動かす
* 可動範囲は中央が0度で,サーボ上面から見て時計回りが+,反時計回りが-
* 指定角度の単位は0.1度単位
* 指定時間の単位は10ms単位(最大0.5%の誤差)
*
* @param sId サーボID
* @param sPos 指定角度
* @param sTime 指定時間
*/
void move(int sId, int sPos, int sTime) {
  unsigned char sum;

  // パケット作成
  sendbuf[0] = (unsigned char) 0xFA; // ヘッダ1
  sendbuf[1] = (unsigned char) 0xAF; // ヘッダ2
  sendbuf[2] = (unsigned char) sId; // サーボID
  sendbuf[3] = (unsigned char) 0x00; // フラグ
  sendbuf[4] = (unsigned char) 0x1E; // アドレス(0x1E=30)
  sendbuf[5] = (unsigned char) 0x04; // 長さ(4byte)
  sendbuf[6] = (unsigned char) 0x01; // 個数
  sendbuf[7] = (unsigned char) (sPos & 0x00FF); // 位置
  sendbuf[8] = (unsigned char) ((sPos & 0xFF00) >> 8); // 位置
  sendbuf[9] = (unsigned char) (sTime & 0x00FF); // 時間
  sendbuf[10] = (unsigned char) ((sTime & 0xFF00) >> 8); // 時間

  // チェックサムの計算
  sum = sendbuf[2];
  for (int i = 3; i < 11; i++) {
    sum = (unsigned char)(sum ^ sendbuf[i]);
  }
  sendbuf[11] = sum; // チェックサム

  // 送信
  digitalWrite(txden, HIGH);
  for(int i=0;i<12;i++)
  {
    mySerial.print(sendbuf[i],BYTE);
  }
  delay(50);//送信が終わるまで待つ
  digitalWrite(txden,LOW);
}

/**
* サーボのトルクをON/OFFできる
*
* @param sId サーボID
* @param sMode ON/OFFフラグ trueでトルクON
*/
void torque(int sId, int sMode) {
  unsigned char sum;

  // パケット作成
  sendbuf[0] = (unsigned char) (0xFA); // ヘッダー1
  sendbuf[1] = (unsigned char) (0xAF); // ヘッダー2
  sendbuf[2] = (unsigned char) (sId); // サーボID
  sendbuf[3] = (unsigned char) (0x00); // フラグ
  sendbuf[4] = (unsigned char) (0x24); // アドレス(0x24=36)
  sendbuf[5] = (unsigned char) (0x01); // 長さ(4byte)
  sendbuf[6] = (unsigned char) (0x01); // 個数
  sendbuf[7] = (unsigned char)((sMode&0x00FF)); // ON/OFFフラグ

  // チェックサムの計算
  sum = sendbuf[2];
  for (int i = 3; i < 8; i++) {
    sum = (unsigned char) (sum ^ sendbuf[i]);
  }
  sendbuf[8] = sum; // チェックサム

  // 送信
  digitalWrite(txden, HIGH);
  for(int i=0;i<9;i++)
  {
    mySerial.print(sendbuf[i],BYTE);
  }

  delay(50);//送信が終わるまで待つ
  digitalWrite(txden, LOW);
}

/**
* サーボの現在角度を0.1度単位で得る
* 可動範囲の中央を0として反時計方向に-150度,時計方向に150度の範囲
*
* @param sId サーボID
* @return 現在角度
*/
int getAngle(int sId) {
  getParam(sId);
  return ((readbuf[8] << 8) & 0x0000FF00) | (readbuf[7] & 0x000000FF);
}


void getParam(int sId)
{
  unsigned char sum;

  // パケット作成
  sendbuf[0] = (unsigned char) 0xFA; // ヘッダー1
  sendbuf[1] = (unsigned char) 0xAF; // ヘッダー2
  sendbuf[2] = (unsigned char) sId; // サーボID
  sendbuf[3] = (unsigned char) 0x09; // フラグ(0x01 | 0x04<<1)
  sendbuf[4] = (unsigned char) 0x00; // アドレス(0x00)
  sendbuf[5] = (unsigned char) 0x00; // 長さ(0byte)
  sendbuf[6] = (unsigned char) 0x01; // 個数

  // チェックサムの計算
  sum = sendbuf[2];
  for (int i = 3; i < 7; i++) {
    sum = (unsigned char) (sum ^ sendbuf[i]);
  }
  sendbuf[7] = sum; // チェックサム

  // 送信
  digitalWrite(txden, HIGH);
  for(int i=0;i<8;i++)
  {
    mySerial.print(sendbuf[i],BYTE);
  }
  digitalWrite(txden, LOW);
  
  // 受信
  for(int i=0;i<26;i++)
  {
    readbuf[i] = (unsigned char)mySerial.read();
  }
}

このプログラムで、Arduino上のコンソールで以下のように角度が出力されることを確認しました。

Screenshot--dev-ttyUSB0