Raspberry PiからZeusCarを制御する方法(Arduino編)

  • URLをコピーしました!

※本ページはアフィリエイト広告を利用しています

今回はSunFounder製のメカナムホイールロボットZeusCarRaspberry Piから制御する方法について解説します。

ZeusCarのコントローラーはArduinoですが、処理能力の高いRaspberry Piを新たに搭載することで、画像処理や機械学習を使った推論処理などを実行することが可能になります。

今回はZeusCar側のArduinoのスケッチを紹介しますので、ぜひ参考にして組みてください。

目次

ZeusCarとは

当サイトでも過去に何度か紹介しているSunFounderのZeusCarについて以下の記事で解説しています。

Arduinoをコントローラとして使用しているメカナムホイールのロボットです。

Raspberry PiとArduinoの通信方法

Raspberry PiとArduinoの基本的な通信方法を以下の記事で解説していますので、事前にライブラリのインストールなどを済ませておいてください。

作成したArduinoスケッチ

今回のRaspberry PiからZeusCarを制御するアプリケーションで使用するArduino側のプログラムを解説します。

Raspberry Pi側のコードについては別の記事で紹介します。

Arduino側プログラムはSunFounder公式が公開している1_basic_move.inoを改良する形で作成しました。

ベースとなるソースコードは以下のページからダウンロードできます。

こちらのソースコードに、シリアル通信でRaspberry Piから指令を受け取ってモーターを駆動する仕様に変更を加えていきます。

コード解説

  1. 必要なライブラリ(Arduino.hSoftPWM.h)のインクルード。
  2. モーター制御のための動作指示に対応する定数(FORWARD, BACKWARDなど)の定義。
  3. モーター駆動に使用するピンの設定と、モーターの正逆方向の設定。
  4. 最小モーターパワーの設定。
  5. ソフトウェアPWMを使用するための初期化関数carBegin()のプロトタイプ宣言。
  6. セットアップ関数setup()でシリアル通信を開始し、PWMとモーターの初期化を行う。
  7. loop()関数内でRaspberry Piからのシリアル通信を監視し、受信データに基づいてモーターの動作を制御する。
    • 受信した文字列を整数に変換し、その値に応じて前進、後退、左右の旋回、停止などの動作を実行。
  8. モーターのPWM制御を行うcarSetMotors()関数で、各モーターへの出力を調整。
    • モーターの正逆の方向を考慮し、PWM信号の強度を調整して出力。
  9. 各動作(前進、後退、左右の移動、旋回、停止)を実現するための関数群(carForward(), carBackward(), carLeft(), carRight(), carTurnLeft(), carTurnRight(), carStop())。
    • これらの関数はcarSetMotors()を呼び出して、適切なモーターに対してPWM信号を出力し、指定された動作を実現します。

作成した全体のソースコード

作成した全体のコードは以下の通りです。

/*******************************************************************
 * basic_move
 
  Control the direction and speed of motors rotation by pwm,
  to make the car go forward, backward, left turn, right turn and stop.

******************************************************************/
#include <Arduino.h>
#include <SoftPWM.h>

// 各動作に対応する定数の定義
#define FORWARD        0
#define BACKWARD       1
#define LEFT           2
#define RIGHT          3
#define LEFTFORWARD    4
#define RIGHTFORWARD   5
#define LEFTBACKWARD   6
#define RIGHTBACKWARD  7
#define TURNLEFT       8
#define TURNRIGHT      9
#define STOP           10

/*
 *  [0]--|||--[1]
 *   |         |
 *   |         |
 *   |         |
 *   |         |
 *  [3]-------[2]
 */
/** Set the pins for the motors */
//モーターピンの設定
#define MOTOR_PINS \
  (uint8_t[8]) { \
    3, 4, 5, 6, A3, A2, A1, A0 \
  }
/** Set the positive and negative directions for the motors */
//モーターの正逆の方向を設定
#define MOTOR_DIRECTIONS \
  (uint8_t[4]) { \
    1, 0, 0, 1 \
  }

#define MOTOR_POWER_MIN 28  // 最小モーターパワー28/255

//PWM初期化処理のプロトタイプ宣言
void carBegin();

int8_t power = 80;
int flg; // フラグ変数

void setup() {
  Serial.begin(9600);  // シリアル通信の開始
  Serial.println("Zeus Car basic move");
  SoftPWMBegin();  //init softpwm, before the motors initialization ソフトウェアPWMの初期化
  carBegin();      // init motors モーターの初期化
  flg = STOP; //動作フラグ初期化
}

void loop() {
  if (Serial.available() > 0) {
    //Raspberry Piから指令値を受信
    // シリアルからデータを読み取り、Stringとして格納
    String receivedStr = Serial.readString();

    // Stringをintに変換
    flg = receivedStr.toInt();

    // フラグの値に基づいて処理を分岐
    switch (flg) {
      case FORWARD: //前進
        carForward(power);
        break;
      case BACKWARD: //後退
        carBackward(power);
        break;
      case LEFT: //左方向
        carLeft(power);
        break;
      case RIGHT: //右方向
        carRight(power);
        break;
      case LEFTFORWARD: //左前方
        carLeftForward(power);
        break;
      case RIGHTFORWARD: //右前方
        carRightForward(power);
        break;
      case LEFTBACKWARD: //左後方
        carLeftBackward(power);
        break;
      case RIGHTBACKWARD: //右後方
        carRightBackward(power);
        break;
      case TURNLEFT: //左回転
        carTurnLeft(power);
        break;
      case TURNRIGHT: //右回転
        carTurnRight(power);
        break;
      case STOP: //停止
        carStop();
        break;
    }
    //現在実行されているコマンドを送信
    Serial.println(flg);  // 整数値を送信
    delay(1000); // 処理実行後に1秒間待機}
  }
}

//PWM初期化処理
void carBegin() {
  for (uint8_t i = 0; i < 8; i++) {
    SoftPWMSet(MOTOR_PINS[i], 0);
    SoftPWMSetFadeTime(MOTOR_PINS[i], 100, 100);
  }
}

//PWM出力処理
/*
引数:各モータの出力値 power0,  power1, power2, power3
   +値:正転
   -値:逆転
*/
void carSetMotors(int8_t power0, int8_t power1, int8_t power2, int8_t power3) {
  bool dir[4];
  int8_t power[4] = { power0, power1, power2, power3 };
  int8_t newPower[4];

  for (uint8_t i = 0; i < 4; i++) {
    dir[i] = power[i] > 0;

    if (MOTOR_DIRECTIONS[i]) dir[i] = !dir[i];

    if (power[i] == 0) {
      newPower[i] = 0;
    } else {
      newPower[i] = map(abs(power[i]), 0, 100, MOTOR_POWER_MIN, 255);
    }
    SoftPWMSet(MOTOR_PINS[i * 2], dir[i] * newPower[i]);
    SoftPWMSet(MOTOR_PINS[i * 2 + 1], !dir[i] * newPower[i]);
  }
}

void carForward(int8_t power) {
  carSetMotors(power, power, power, power);
}

void carBackward(int8_t power) {
  carSetMotors(-power, -power, -power, -power);
}

void carLeft(int8_t power) {
  carSetMotors(-power, power, -power, power);
}

void carRight(int8_t power) {
  carSetMotors(power, -power, power, -power);
}

void carLeftForward(int8_t power) {
  carSetMotors(0, power, 0, power);
}

void carLeftBackward(int8_t power) {
  carSetMotors(-power, 0, -power, 0);
}

void carRightForward(int8_t power) {
  carSetMotors(power, 0, power, 0);
}

void carRightBackward(int8_t power) {
  carSetMotors(0, -power, 0, -power);
}

void carTurnLeft(int8_t power) {
  carSetMotors(-power, power, power, -power);
}

void carTurnRight(int8_t power) {
  carSetMotors(power, -power, -power, power);
}

void carStop() {
  carSetMotors(0, 0, 0, 0);
}

まとめ

今回はSunFounder製のメカナムホイールロボットZeusCarをRaspberry Piから制御する方法について解説しました。

次回はRaspberry Pi側のPythonコードを紹介する予定です。

それでは、また次の記事でお会いしましょう。

よかったらシェアしてね!
  • URLをコピーしました!

コメント

コメントする

CAPTCHA


目次