概要

シリアルサーボを3個使った近藤科学製のロボアーム「KXR-A3S」をGR-ROSEで動かしてみます。

準備

  • GR-ROSE、USBケーブル(マイクロBタイプ)、完成済みの「KXR-A3」を準備します。
  • なお、3つのサーボのID設定は図に示す通り、下から順に1, 2, 3としてください。ID1のサーボがGR-ROSEの
  • Serial1の部分につながっていることを確認してください。
画像

キットの起動

それでは早速動かしてみます。まずはプログラムを実行する前に、以下の手順を実行してください。

シリアルサーボに電源が供給され、GR-ROSEがUSBメモリとして認識されます。

  1. GR-ROSEにUSBを接続する。
  2. 電源スイッチをONにする。
  3. GR-ROSEのリセットボタンを押す。
画像

モータ動作確認(1軸)

以下のプログラムを実行してください。1番下にあるID1のモーターが動作します。

サーボモーターの仕様として、原点の0°では7500という数値を指定します。稼働範囲の最大値135°で11500、最小値-135°で3500を指定します。これらの数値は汎用性がないため、プログラムではラジアン指定でモータを動かせるように「krs_setposition」という関数を用意しています。また、モータの位置を取得できる「krs_getposition」という関数を用意して、シリアルモニターにラジアンを出力しています。

画像
以下の図のようにモーターの位置をラジアンで表示しています。
#include <Arduino.h>
#include <ICS.h>

#define KRS_MIN 3500
#define KRS_MAX 11500
#define KRS_ORG 7500
#define KRS_FREE 0
#define SERVO_MIN -135
#define SERVO_MAX 135

IcsController ICS(Serial1);
IcsServo servo1;

void krs_setposition(IcsServo* servo, float radian){
  int angle = radian * 180 / PI;
  int pos = map(angle, SERVO_MIN, SERVO_MAX, KRS_MIN, KRS_MAX);
  if(pos > KRS_MIN && pos < KRS_MAX){
    servo->setPosition(pos);
    delay(1);
  }
}

float krs_getposition(IcsServo* servo){
  int pos = servo->getPosition();
  delay(1);
  int angle = map(pos, KRS_MIN, KRS_MAX, SERVO_MIN, SERVO_MAX);
  return angle * PI / 180; // angle to radian
}

void setup() {
  Serial.begin(9600);
  ICS.begin();
  servo1.attach(ICS, 0x01);
  
  krs_setposition(&servo1, 0);
}

void loop() {
  static bool id1, id2, id3;
  krs_setposition(&servo1, (PI/2));
  delay(1000);
  Serial.println(krs_getposition(&servo1));
  krs_setposition(&servo1, -(PI/2));
  delay(1000);
  Serial.println(krs_getposition(&servo1));
}

モータ動作確認(3軸)

それでは次に3つのサーボを動かしてみます。以下のプログラムを実行してください。

IcsServoクラスのオブジェクトを配列で生成し、プログラムを簡素にしています。

-45°~45°の範囲でモーターをランダムに動かしています。

#include <Arduino.h>
#include <ICS.h>

#define KRS_MIN 3500
#define KRS_MAX 11500
#define KRS_ORG 7500
#define KRS_FREE 0
#define SERVO_MIN -135
#define SERVO_MAX 135

IcsController ICS(Serial1);
IcsServo servo[3];

void krs_setposition(IcsServo* servo, float radian){
  int angle = radian * 180 / PI;
  int pos = map(angle, SERVO_MIN, SERVO_MAX, KRS_MIN, KRS_MAX);
  if(pos > KRS_MIN && pos < KRS_MAX){
    servo->setPosition(pos);
    delay(1);
  }
}

void setup() {
  Serial.begin(9600);
  ICS.begin();
  for(int i = 0; i < 3; i++){
    servo[i].attach(ICS, i+1); // id1 to id3
    servo[i].setStretch(30);
    delay(1);
    servo[i].setSpeed(30);
    delay(1);
    krs_setposition(&servo[i], 0);
    delay(1);
  }
}

void loop() {
  for(int i = 0; i < 3; i++){
    int angle = random(-45, 45);
    float radian = angle * PI / 180;
    krs_setposition(&servo[i], radian);
    delay(200);
  }
}

ICS Managerで接続する方法

ICS Managerは近藤科学から提供されているPC用のソフトウェアです。

シリアルサーボのID値や初期設定を行うことができます。

以下のプログラムを実行することで、GR-ROSEがUSBシリアルブリッジとして動作し、ICS Mangerで

シリアルサーボの制御を行うことができます。

画像
ICS Manager
// For using ICS manager
#include <Arduino.h>

void setup() {
  pinMode(PIN_LED1, OUTPUT);

  Serial.begin(115200); // to USB
  Serial1.begin(115200, SERIAL_8E1); // to Motor
  Serial1.direction(HALFDUPLEX);
}

void loop() {
  if(Serial.available())
  {
    char c = Serial.read();
    Serial1.write(c);
  }

  if(Serial1.available())
  {
    char c = Serial1.read();
    Serial.write(c);
  }
}