2025年6月28日土曜日

タミヤのスリムタイヤキットを自作してみる

 BLDCモータをベクトル制御できるようになったところで、やっぱり車体に搭載して動かしてみたいのでタイヤを作ってみることに。
タミヤのスリムタイヤキットはモータへの負担が小さく駆動率が高いということで、こういったダイレクトドライブモータとの相性が良いと思うんだけど、今回使用したモータに取り付けるのに加工しないといけないので、ホイールごとプリントしてもらえばいいかなと。

ホイールだけプリントしてスリムタイヤのゴムの部分だけ使っても良さそうだけど、実は大きなOリングをそのまま使えないかと言うことでOリングでやってみることに。(大学の時研究室でもOリングをタイヤにしていたし)
Oリングみたいなタイヤはモデル化のときとかに接地面が安定するので…

ということでOリングを使えるようなホイールの3Dモデルを作ってみた。スリムタイヤは横幅3.5mmっぽいのでOリングでも良い所ありそう。P-48だと外経も55mmっぽいしタミヤのスリムタイヤと同じ感じにできそう?
小さいほうがトルクが出そう?ということでP-46のOリングでホイールを設計してみた。

見た目がめっちゃプーリー。

モータとOリングを取り付けるとこんな見た目に。外経が52mmぐらいの予定。Oリングとぴったりサイズで作るとゆるゆるになったりするんじゃないかということで少し大きめに作ってOリングを引っ張るように調整しないといけないかも?

アリエクで線経が4mmで外径が52mmという少し太めのOリングを見つけてしまったのでとりあえず取り寄せてタイヤを作ってみようかな。250円で10本入りっぽいし。

ちなみにこのタイヤをユニバーサルプレートに装着して何かを作ろうとしてもキャスターのサイズが合わないのでキャスターとかも高さを調整する必要がありそう。まぁタミヤのギアボックス用にできてるもんな…

2025年6月24日火曜日

BLDCモータドライバをCAN対応にしてみた。

 先日作ったFOC対応のBLDCモータドライバはCANトランシーバも積んでいるのでCANに対応させてみた。

こんな感じで電源とCANだけ接続してやればOK。I2Cみたいに束ねられるので配線が楽かも。マスター側のポートも1ポートで良いし。
基板設計時にもRS485かCANか迷ったけどとりあえずCANのほうがハードウェア側で色々やってくれるから楽なんじゃないかなということで。

とりあえずCANのプロトコルはOdrive風にしてみた。しかしOdriveとSimpleFOCだと単位が違うのが少し面倒。rpsとrad/sの変換を入れようとしてるけども、まずはSTM32F103でCAN通信をやりながらSimpleFOCでベクトル制御を動かせるかを試したいので値は変換しない状態でやってみようかと思う。

#include "SPI.h"
#include "SimpleFOC.h"
#include "SimpleFOCDrivers.h"
#include "encoders/MT6701/MagneticSensorMT6701SSI.h"
#include <EEPROM.h>
#include "stm32f103-can.h"

#define Protocol_Version 0x01
#define Hw_Version_Major 0x00
#define Hw_Version_Minor 0x00
#define Hw_Version_Variant 0x00
#define Fw_Version_Major 0x00
#define Fw_Version_Minor 0x00
#define Fw_Version_Revision 0x00
#define Fw_Version_Unreleased 0x00

#define NODE_ID_DEFAULT 0x000
#define NODE_BC 0x3F

uint16_t nodeID = 0x005;

#define MOTOR_POLE 7

#define CS1 PA15
#define SCK1 PB3
#define MISO1 PB4
#define MOSI1 PB5
#define DRV_EN PB12
#define TX3_SCL2 PB10
#define RX3_SDA2 PB11
#define CAN_RX PB8
#define CAN_TX PB9
#define V_CURR PA0
#define W_CURR PA1
#define U_CURR PA2
#define TEMP PA3
#define VOLTAGE PA4
#define LED_BUILTIN PC13

HardwareSerial Serial3(TX3_SCL2, RX3_SDA2);
SPIClass SPI_1(MOSI1, MISO1, SCK1);
MagneticSensorMT6701SSI sensor(CS1);
InlineCurrentSense current_sense = InlineCurrentSense(0.01, -50 * 4, W_CURR, V_CURR, U_CURR);
BLDCMotor motor = BLDCMotor(MOTOR_POLE);
BLDCDriver6PWM driver = BLDCDriver6PWM(PA8, PB13, PA9, PB14, PA10, PB15, DRV_EN);  //W V U EN

typedef union {  //IEEE 754 Float
  uint8_t uint[8];
  float value[2];
} FLOAT_BYTE_UNION;

uint8_t eepromRead(uint8_t reqID) {
  uint8_t lastData = 0xFF;
  for (uint16_t i = 0; i < EEPROM.length(); i += 2) {
    uint8_t dataID = EEPROM.read(i);
    uint8_t data = EEPROM.read(i + 1);
    //Serial1.println(dataID);
    if (dataID == reqID) {
      lastData = data;
      //Serial1.print("EEPROM Read:");
      //Serial1.println(i);
    }
    if (dataID == 0xFF | dataID == 0x00) {
      break;
    }
  }
  //Serial1.print("EEPROM Data:");
  //Serial1.println(lastData);
  return lastData;
}

void eepromWrite(uint8_t reqID, uint8_t data) {
  uint16_t lastID = 0xFFFF;
  for (uint16_t i = 0; i < EEPROM.length(); i += 2) {
    uint8_t eepromId = EEPROM.read(i);
    if (eepromId == 0xFF | eepromId == 0x00) {
      lastID = i;
      //Serial1.print("EEPROM Write:");
      //Serial1.println(i);
      break;
    }
  }
  if (lastID == EEPROM.length()) {
    lastID = 0;
  }
  EEPROM.write(lastID, reqID);
  EEPROM.write(lastID + 1, data);
}
void CANread() {
  if (CANMsgAvail()) {
    CAN_msg_t CAN_RX_msg;
    CANReceive(&CAN_RX_msg);
    uint16_t cmdID = uint16_t(CAN_RX_msg.id & 0x1F);
    uint16_t nodeIDrcv = CAN_RX_msg.id >> 5;
    CAN_msg_t CAN_TX_msg;
    memset(&CAN_TX_msg, 0, sizeof(CAN_msg_t));
    CAN_TX_msg.type = DATA_FRAME;
    CAN_TX_msg.format = STANDARD_FORMAT;
    CAN_TX_msg.id = ((nodeID << 5) | cmdID);
    if (nodeIDrcv == nodeID) {
      switch (cmdID) {
        // case 0x003:  //Get Motor Error
        //   break;
        // case 0x004:  //Get Encoder Error
        //   break;
        // case 0x005:  //Get Sensorless Error
        //   break;
        case 0x006:  //Set Axis Node ID
          if (CAN_RX_msg.type == DATA_FRAME) {
            uint32_t reqNodeID = CAN_RX_msg.data[0] | CAN_RX_msg.data[1] << 8 | CAN_RX_msg.data[2] << 16 | CAN_RX_msg.data[3] << 24;
            //Serial1.println(reqNodeID,HEX);
            if ((reqNodeID < 0x3F) && (reqNodeID != eepromRead(1))) {
              eepromWrite(1, reqNodeID);
              //Serial1.println("nodeID update");
            }
          }
          break;
        case 0x009:  //Get Encoder Estimates
          if (CAN_RX_msg.type == REMOTE_FRAME) {
            FLOAT_BYTE_UNION output;
            output.value[0] = motor.shaft_angle;
            output.value[1] = motor.shaft_velocity;
            memcpy(CAN_TX_msg.data, output.uint, 8);
            CAN_TX_msg.len = 8;
            CANSend(&CAN_TX_msg);
          }
          break;
        case 0x00C:  //Set Input Pos
          if (CAN_RX_msg.type == DATA_FRAME) {
            FLOAT_BYTE_UNION input;
            memcpy(input.uint, CAN_RX_msg.data, 8);
            motor.controller = MotionControlType::angle;
            target_angle = input.value[0];
          }
          break;
        case 0x00D:  //Set Input Vel
          if (CAN_RX_msg.type == DATA_FRAME) {
            FLOAT_BYTE_UNION input;
            memcpy(input.uint, CAN_RX_msg.data, 8);
            motor.controller = MotionControlType::velocity;
            target_angle = input.value[0];
          }
          break;
        case 0x00E:  //Set Input Torque
          if (CAN_RX_msg.type == DATA_FRAME) {
            FLOAT_BYTE_UNION input;
            memcpy(input.uint, CAN_RX_msg.data, 8);
            motor.controller = MotionControlType::torque;
            target_angle = input.value[0];
          }
          break;
        // case 0x014:  //Get IQ
        //   break;
        case 0x015:  //Get Temperature(FET IEEE 754 Float, Motor IEEE 754 Float)
          if (CAN_RX_msg.type == REMOTE_FRAME) {
            FLOAT_BYTE_UNION output;
            output.value[0] = (1.43 - analogRead(ATEMP) * 3.3 / 4095) / 0.0043 + 25;
            output.value[1] = analogRead(AVREF);
            memcpy(CAN_TX_msg.data, output.uint, 8);
            CAN_TX_msg.len = 8;
            CANSend(&CAN_TX_msg);
          }
          break;
        case 0x017:  //Get Bus Voltage and Current
          if (CAN_RX_msg.type == REMOTE_FRAME) {
            FLOAT_BYTE_UNION output;
            output.value[0] = analogRead(VOLTAGE) * 3.3 / 4095.0 * 4.0;
            output.value[1] = motor.current.q;
            memcpy(CAN_TX_msg.data, output.uint, 8);
            CAN_TX_msg.len = 8;
            CANSend(&CAN_TX_msg);
          }
          break;
        // case 0x01c:  //Get ADC Voltage
        //   break;
        default:
          break;
      }
    }
    if (CAN_RX_msg.type == REMOTE_FRAME) {
      switch (cmdID) {
        case 0x000:  //Get Version
          CAN_TX_msg.data[0] = Protocol_Version;
          CAN_TX_msg.data[1] = Hw_Version_Major;
          CAN_TX_msg.data[2] = Hw_Version_Minor;
          CAN_TX_msg.data[3] = Hw_Version_Variant;
          CAN_TX_msg.data[4] = Fw_Version_Major;
          CAN_TX_msg.data[5] = Fw_Version_Minor;
          CAN_TX_msg.data[6] = Fw_Version_Revision;
          CAN_TX_msg.data[7] = Fw_Version_Unreleased;
          CAN_TX_msg.len = 8;
          CANSend(&CAN_TX_msg);
          break;
        case 0x001:  //Heartbeat Message
          CAN_TX_msg.data[1] = nodeID >> 8;
          CAN_TX_msg.data[0] = nodeID;
          CAN_TX_msg.len = 8;
          CANSend(&CAN_TX_msg);
          break;
        default:
          break;
      }
    }
  }
}
float target_angle = 0;
Commander command = Commander(Serial3);
void doTarget(char* cmd) {
  command.scalar(&target_angle, cmd);
}

void doMotor(char* cmd) {
  command.motor(&motor, cmd);
}

void doAnalog(char* cmd) {
  if (cmd[0] == 'T') Serial3.println(analogRead(TEMP));
  else if (cmd[0] == 'V') {
    Serial3.print("Voltage: ");
    Serial3.println(analogRead(VOLTAGE) * 0.0032);
  }
};

void setup() {
  analogReadResolution(12);
  pinMode(LED_BUILTIN, OUTPUT);
  digitalWrite(LED_BUILTIN, HIGH);
  Serial3.setTx(TX3_SCL2);
  Serial3.setRx(RX3_SDA2);
  Serial3.begin(115200);
  SimpleFOCDebug::enable(&Serial3);

  sensor.init(&SPI_1);
  motor.linkSensor(&sensor);
  driver.voltage_power_supply = 8;
  driver.init();
  motor.linkDriver(&driver);
  current_sense.linkDriver(&driver);
  // control loop type and torque mode
  motor.torque_controller = TorqueControlType::foc_current;
  motor.controller = MotionControlType::velocity;
  motor.motion_downsample = 0.0;

  // velocity loop PID
  motor.PID_velocity.P = 0.2;
  motor.PID_velocity.I = 20.0;
  motor.PID_velocity.D = 0.0;
  motor.PID_velocity.output_ramp = 1000.0;
  motor.PID_velocity.limit = 8.0;
  // Low pass filtering time constant
  motor.LPF_velocity.Tf = 0.01;
  // angle loop PID
  motor.P_angle.P = 20.0;
  motor.P_angle.I = 0.0;
  motor.P_angle.D = 0.0;
  motor.P_angle.output_ramp = 0.0;
  motor.P_angle.limit = 40.0;
  // Low pass filtering time constant
  motor.LPF_angle.Tf = 0.0;
  // current q loop PID
  motor.PID_current_q.P = 1.5;
  motor.PID_current_q.I = 15.0;
  motor.PID_current_q.D = 0.0;
  motor.PID_current_q.output_ramp = 1000.0;
  motor.PID_current_q.limit = 5.0;
  // Low pass filtering time constant
  motor.LPF_current_q.Tf = 0.005;
  // current d loop PID
  motor.PID_current_d.P = 1.5;
  motor.PID_current_d.I = 15.0;
  motor.PID_current_d.D = 0.0;
  motor.PID_current_d.output_ramp = 1000.0;
  motor.PID_current_d.limit = 5.0;
  // Low pass filtering time constant
  motor.LPF_current_d.Tf = 0.02;
  // Limits
  motor.velocity_limit = 200.0;
  motor.voltage_limit = 5.0;
  motor.current_limit = 2.0;
  // sensor zero offset - home position
  motor.sensor_offset = 0.0;
  // general settings
  // pwm modulation settings
  motor.foc_modulation = FOCModulationType::SpaceVectorPWM;
  motor.modulation_centered = 1.0;

  motor.useMonitoring(Serial3);

  motor.linkCurrentSense(&current_sense);
  current_sense.init();

  motor.init();
  motor.sensor_direction = Direction::CW;
  motor.initFOC();

  command.add('T', doTarget, "target angle");
  command.add('M', doMotor, "motor");
  command.add('A', doAnalog, "analog read");
  motor.monitor_downsample = 0;
  //motor.monitor_variables = 0;

  Serial3.println(F("Motor ready."));
  Serial3.println(F("Set the target angle using serial terminal:"));

  bool ret = CANInit(CAN_250KBPS, 2);//PB8,PB9
  nodeID = eepromRead(1);
  if (nodeID >= 0x3F) {
    eepromWrite(1, NODE_ID_DEFAULT);
    nodeID = NODE_ID_DEFAULT;
  }
  CAN1->FMR |= 0x1UL;
  CAN1->FMR &= 0xFFFFC0FF;
  CAN1->FMR |= 0x1C << 8;
  CANSetFilter(0, 1, 0, 0, ((nodeID << 5) << 21), 0xFC000004);
  CANSetFilter(1, 1, 0, 0, ((NODE_BC << 5) << 21), 0xFC000004);
  CAN1->FMR &= ~(0x1UL);

  _delay(1000);
}

void loop() {
  motor.loopFOC();
  motor.move(target_angle);
  motor.monitor();
  command.run();
  CANread();
}

Odriveのほうもバージョンによってコマンドが変わっていたりするけどとりあえず使いそうなところだけ有効にしてみた。ノードIDはEEPROMに記録するようにした。同じファームを書いてあとからCANでノードIDを書き換えられる。ODriveではモードを切り替えないと現在のモード以外でのコマンドは受け付けないけど、モード切替なしにデータを受け取ったモードに自動で変更するようにしてみた。

CANのライブラリは以前フィルタを試したときに使わせてもらったスケッチと同じように元ネタのstm32f103.inoのsetupとloopを削除して"stm32f103-can.h"として別ファイルにして使用してみた。

いちいちCANでコマンドを入力するのが面倒なので簡易的なPythonツールを作成しようかなと思う。もしくはESP32で直接やってしまったほうが早いかなぁ?

あと通信が切れたときのためにモータの動作を止められるように通信Watchdogをつけておいたほうがいいかもしれないかなぁ。モータが回りっぱなしになってしまうし。

2025年6月22日日曜日

FOCモータドライバをチューニングしてみた。

 前回ようやく自作のFOCモータドライバでモータを回転させることができたけども、前回の設定だとSimpleFOCのVoltageモードの角度制御だったので、今回はモータのトルクを最大限使用できるようにベクトル制御で動かしてみる。インライン電流センサ3個積んでるのはこのため。(2個でもいけるけど念の為)

VoltageモードでもセンサレスESCに接続して動作確認したときはだいぶトルクが有る感じがした。ちなみにそのままFOC Currentに切り替えたらハンチングですごい振動していた。

スケッチの中でPIDの値をいじるのはちょっと面倒なので、SimpleFOCのチューニングをGUIでできるというSimpleFOCStudioを使ってみた。このツールはPythonで作られているっぽい。PythonはThonnyで実行していたのでThonnyの環境でも実行できるかどうか確認してみた。(Condaとかの環境インストール面倒だったし…

まずはGithubのSimpleFOCStudioから最新のソースコードをZIPでダウンロードしてくる。

解凍したらThonnyでsimpleFOCStudio.pyを開く。Thonnyからシステムシェルを開いて

pip install PyQt5 numpy pyqtgraph

のような感じで必要なライブラリをインストール。あとは実行するだけ。Thonny 4.1.7で普通に動いてしまった。

Windowが開いたら左上のアイコンからTreeViewで新しい窓を作って、Commandのところにスケッチ側で入れたコマンド(前回のコードだとM)を入れてConfigureでCOMポートの設定をすれば良い。

とりあえずモータドライバに5Vを接続してFOC Currentのチューニングをしてみることに。

とりあえずはPを少しずつ上げていって、ハンチングしないギリギリでIを上げてみたいな感じで少しずつ調整してみた。電流を流せるようにSpace Vector PWMにして、とりあえずAngleモードのFOC Current制御で手でモータを動かしたときに戻ってくるときにハンチングしないかどうかである程度決めたあとに角度を小さく降ったり大きく降ったり動かしてみながらハンチングしない所を探っていった。
このやり方が正しいかどうかはよくわからないけど…

チューニングができたらArduinoの設定値として生成してくれるのでこれをスケッチの中のモータ関連の設定値のあたりと置き換えればチューニングした値をデフォルト設定にできる。

ラジコン用ESCでこのモータの動作確認したときはトルクが少し弱かったので大丈夫かなぁと思っていたけどこれならベクトル制御で結構トルク出せそうですごい。

まだ電圧上げられそうなので電圧との関係も見ながらチューニングしてみようかな。





2025年6月21日土曜日

自作モータドライバでSimpleFOC動かしてみた

 モータドライバ用の3Dプリント部品を作ってもらったので、前回組み立てたSimpleFOC モータドライバ基板をモータに組み付けて動かしてみた。

モータとモータドライバ間に挟むアダプタはこんな感じ。9.2mmにしてみた。

モータドライバの裏側にはモータと接続するためのピンヘッダとMT6701を取り付け。MT6701は結局単品で購入するより基板ごと購入したほうが安かったので、144円のI2Cタイプのモジュールを購入して剥がして移植した。

M2x12だとモータへのネジのかかりが少なすぎる気がする…モータ側のネジは3.8mmぐらいは行けそうなのでM2x14にしたほうがいいかなぁ。それ以上行くとコイルに傷をつけたらいやだし。
書き込みはBluepillをBMP化したやつを使用。デバッグはUSBシリアルアダプタを使用した。Arduino環境でSTLink V2を使うときでもCubeProgrammerをインストールしないといけないので、そのまま使えるBMPは便利かもしれない?シリアルポートも付いてるのでこれ1台で全部行けるんだけどswlinkファームだとどのピンかわからなかったので別途USBシリアルを使用している。
電源コネクタはリポバッテリとかでもよく使われてるPHコネクタ、シリアルポートはQwiicとピン配置を合わせてあるので今回はUARTとして使ったけど、I2Cとしても使用できる。CANはSWDと同じコネクタを使いまわし。書き込み用のSWDはRaspberry Pi Pico Hと同じ。JSTのSHコネクタの互換品(フットプリントそのままで装着できた)。

早速ファームウェアを書き込んでみる。

#include "SPI.h"
#include "SimpleFOC.h"
#include "SimpleFOCDrivers.h"
#include "encoders/MT6701/MagneticSensorMT6701SSI.h"

#define MOTOR_POLE 7

#define CS1 PA15
#define SCK1 PB3
#define MISO1 PB4
#define MOSI1 PB5
#define DRV_EN PB12
#define TX3_SCL2 PB10
#define RX3_SDA2 PB11
#define CAN_RX PB8
#define CAN_TX PB9
#define V_CURR PA0
#define W_CURR PA1
#define U_CURR PA2
#define TEMP PA3
#define VOLTAGE PA4
#define LED_BUILTIN PC13

HardwareSerial Serial3(TX3_SCL2, RX3_SDA2);
SPIClass SPI_1(MOSI1, MISO1, SCK1);
MagneticSensorMT6701SSI sensor(CS1);
InlineCurrentSense current_sense = InlineCurrentSense(0.01, -50*4, W_CURR, V_CURR, U_CURR);
BLDCMotor motor = BLDCMotor(MOTOR_POLE);
BLDCDriver6PWM driver = BLDCDriver6PWM(PA8, PB13, PA9, PB14, PA10, PB15, DRV_EN);  //W V U EN

float target_angle = 0;
Commander command = Commander(Serial3);
void doTarget(char* cmd) { command.scalar(&target_angle, cmd); }

void doMotor(char* cmd) { command.motor(&motor, cmd); }

void setup() {
  analogReadResolution(12);
  pinMode(LED_BUILTIN,OUTPUT);
  digitalWrite(LED_BUILTIN,HIGH);
  Serial3.setTx(TX3_SCL2);
  Serial3.setRx(RX3_SDA2);
  Serial3.begin(115200);
  SimpleFOCDebug::enable(&Serial3);

  sensor.init(&SPI_1);
  motor.linkSensor(&sensor);
  driver.voltage_power_supply = 8;
  driver.init();
  motor.linkDriver(&driver);
  current_sense.linkDriver(&driver);
  motor.foc_modulation = FOCModulationType::SpaceVectorPWM;
  motor.controller = MotionControlType::angle;
  motor.PID_velocity.P = 0.2f;
  motor.PID_velocity.I = 20;
  motor.voltage_limit = 8;
  motor.LPF_velocity.Tf = 0.01f;
  motor.P_angle.P = 20;
  motor.velocity_limit = 40;
  motor.useMonitoring(Serial3);

  motor.linkCurrentSense(&current_sense);
  current_sense.init();
  Serial3.print("current_sense.gain:\t");
  Serial3.print(current_sense.gain_a);
  Serial3.print(", ");
  Serial3.print(current_sense.gain_b);
  Serial3.print(", ");
  Serial3.println(current_sense.gain_c);
  Serial3.print("current_sense.offset_i:\t");
  Serial3.print(current_sense.offset_ia);
  Serial3.print(", ");
  Serial3.print(current_sense.offset_ib);
  Serial3.print(", ");
  Serial3.println(current_sense.offset_ic);

  motor.init();
  motor.initFOC();

  command.add('T', doTarget, "target angle");
  command.add('M', doMotor, "motor");
  //motor.monitor_downsample = 0;
  //motor.monitor_variables = 0;

  Serial3.println(F("Motor ready."));
  Serial3.println(F("Set the target angle using serial terminal:"));
  _delay(1000);
}

void loop() {
  motor.loopFOC();
  motor.move(target_angle);
  motor.monitor();
  command.run();
}

前回モータをテストしたときのスケッチを今回自作したモータドライバ基板用に少し編集した。電源電圧測定回路とか大丈夫かテストするときに気がついたんだけど、デフォルトでADCが10bitで動いてるっぽかったのでanalogReadResolution(12);をしておいた。そうするとInlineCurrentSenseで電流値が4倍に見えてしまうようになったのでInlineCurrentSenseのところでオペアンプのゲインのところを4倍に設定したら電流がうまく表示されるようになった。

とりあえず角度モードでモータが回ったので次はそれぞれの設定値をチューニングしないと。

2025年6月16日月曜日

SimpleFOC用モータドライバを実装してみた

 というわけで先日届いた基板用の部品がある程度届いたので実装してみた。けっこう大変だった。

部品はほぼアリエクで手配した。一部前に秋月で購入していた部品を使用してる。
MT6701は基板に実装されたやつに磁石まで付属してるほうが安かったので剥がして使う予定。(144円だった)

とりあえず表面はこんな感じ。TMC6300周りにちょっと詰め込みすぎて順番を考えないとコテが入らないという問題が。斜めカットC2を使用したけど結構きれいにハンダできた気がする。
STM32とINA240は足があるので足の間がショートするとちょっと面倒。新しいハンダをはんだごてに付けながら少しずつ拭っていくといい感じにハンダできた。ハンダ吸い取り線を使うとレジストに傷がついたりするので今回はハンダゴテだけで頑張った。

デバッグコネクタ(SHコネクタの3Pin)がまだ届いてないので書き込みができないんだけども、とりあえず電源を入れて3.3Vが生成されていることを確認できた。INA240A2からも1.68Vぐらい出ているのでとりあえず0Aで真ん中ぐらいで出力ができていることを確認できた。

ちなみにTPS63070は2.8Vぐらい入れないと3.3Vが生成されなかった。一旦起動したら下げても大丈夫なんだけどやはりアリエクから購入したICは怪しい気がする。(STM32F103もなんかハンダコーティングされてたから使用済み品?)

まぁとりあえず色々と安く手に入っているので動けばいいのだけれども…

モータドライバとモータの間にいれるアダプタも設計中。スペーサ兼マウント的なやつ。回転方向に力がかかったりするとアレなので穴径をギリギリにしなと滑りそう。

はやくデバッグコネクタ届かないかなぁ

2025年6月15日日曜日

SimpleFOC用にモータドライバ基板を起こしてみた

 この前BluepillとSimpleFOC miniでジンバル用モータを動かすことができたんだけど、電流センサをつけないとFOC制御とは呼べないと思うので電流センサも内蔵させた基板を起こしてみることに。

SimpleFOC miniも8V以上ってことでもうちょっと低い電圧から動かしたいし。

よくある、モータの後ろにそのまま取り付けできるような、角度センサも内蔵したモータドライバ基板を作ってみたかったし。

とりあえずKiCadの最新版を入れて、足りないフットプリントはRSのライブラリを使用してみた。

部品構成としてはマイコンはBluepillと同じSTM32F103CBT6、モータドライバはより低電圧から動作できるようにTMC6300、角度センサはこの前試したMT6701、電流センサはINA240にしてみた。
電流センサは最初ACS712がSimpleFOCフォーラムでも3.3Vでも見れる範囲は小さくなるけど一応動くということで手軽でいいなと思っていたんだけど、ホールエフェクト電流センサの近くに磁気エンコーダはまずいかな?と思ってシャント抵抗にした。
インライン電流センスにしたのでINA180でも良かったかもしれないけどINA240のTSSOP-8なら下にパターン通せるし。

電源回路はTMC6300の動作範囲にできるだけ合わせたかったのでTPS63070にしてみた。ESP32でブラシ付きモータ動かしてたときみたいに昇降圧にしておけば電圧下がってもリセットしにくいかなと。モータのトルクがどのぐらい出せるかわからないけど乾電池動作も可能かも。

ついでにこのモータドライバを複数枚使いたいときにCAN使えたらいいなと思ってCANトランシーバも乗っけてみてたり。最初はSimpleFOCのモニタとかをそのまま通せるようにRS-485にしようと思って設計していたんだけど、STM32F103にはRS-485 ModeがなかったのでGPIOでやるのも送信完了の処理が面倒そうだったのでやめた。CANトランシーバも思ったよりやすかったし。

モータよりほんの少しだけ小さい直径34mmに詰め込んでみた。
基板設計よくわからない。
丸田先生のCompact SimpleFOC Controller Boardのインスパイア的な感じかな…
CAD画面のスクショだと見づらいので3Dモードでのスクショはこんな感じ。シャント抵抗の3Dモデルはテキトー。本当は12mΩぐらい。2層基板に詰め込んでみた。はたして動くのだろうか

電子部品は結構アリエクでポチった。アリエクで大丈夫なのかな…
コネクタはJSTのフットプリントなんだけど互換の端子で行けるかな?互換の端子のほうが厚みはある気がする。
6PWMでコンプリメンタリタイマを使用するとシリアルブートローダのピンが使えなくなるのでBOOT0はGNDに直結。ライタはとりあえずBlackMagicProbeを使う予定。SWDのコネクタはRaspberry Pi Picoのパクリ。(小さいし)

ということでJLCPCBで発注してみた。
KiCADのFabrication Toolkitっていうプラグインを入れてZIPファイルを生成したらJLCPCBのサイトaにドラッグアンドドロップするだけだった。
ガーバビューワーも見やすい。とりあえず5枚で2ドル、送料がOCS NESで1ドルキャンペーンにPayPal手数料0.5ドルで合計530円ぐらいだった。
6/8に発注したら6/11には発送されていて、13日には関空に到着していたっぽい。そして今日ヤマトでネコポスとして到着。トラッキングは最初はOCSのサイトで確認できて、国内につくと同じトラッキングがヤマトで確認できるようになっていた。
あとは実装するだけ。TMC6300の真ん中のパッドが手ハンダできるようにスルーホールにしておけばよかったかな。ちょっと気合でハンダしないといけないかも。ホットプレートも安いの出てるし購入検討しようかな…
電子部品のほうがまだ全部揃ってないのでこんな感じで実装の表を作って待機かな。

2025年6月14日土曜日

アナログパネルメータをRaspberry Pi Picoで動かしてみた。

 アナログメータってかっこいいよね。ということでアリエクでアナログメータが安く売っていたので試しに買ってみた。マイコン直結で動かせたたら面白いので今回は電圧用の3V品にしてみた。

91C4
91C4っていうメータ。
やすい送料を選んでみたので送料込みで227円だった。3週間ぐらいかかった。UM~DOのトラッキングは最後まで追跡できないっぽいので追跡できなくなってから1週間後ぐらいに届いた感じ。
ネジも付属していた。
91C4
裏面は固定用と思われるネジが下に出ていて、端子が真ん中あたりから出てる感じ。この向きだと右側がGNDで左側が入力っぽい。
全部M3だった。

91C4
自立するぐらい奥行きは長い。

3V仕様なので3.3VのマイコンのPWMで動かせるんじゃないかということでRaspberry Pi Picoに接続して試してみた。
#define pwmPin 15  // PWM 出力に使う GPIO ピン

void setup() {
  Serial.begin(115200);
  while (!Serial);
  pinMode(pwmPin, OUTPUT);
  analogWriteFreq(20000);       // PWM周波数を20kHzに設定
  analogWriteResolution(8);     // 8bit分解能(0〜255)

  Serial.println("Set PWM");
}

void loop() {
  if (Serial.available()) {
    int duty = Serial.parseInt();

    if (duty < 0) duty = 0;
    if (duty > 255) duty = 255;

    analogWrite(pwmPin, duty);

    Serial.print("PWM:");
    Serial.println(duty);
  }
}
メータのプラスをGPIO15に繋いで、GNDはGNDに接続してシリアルコンソールから数字を送ると針が動くやつ。earlephilhower版のArduino環境。
マイコンは3.3Vなのでいきなり255は振り切ってしまうので振り切らないギリギリをちょっとずつ試したところ、3Vメーターだと245ぐらいが最大だった。
次に自動でスイープしてみた。
#define pwmPin 15

void setup() {
  analogWriteFreq(20000);          // 20kHzに設定
  analogWriteResolution(8);        // 8bit分解能 (0~255)
  pinMode(pwmPin, OUTPUT);
}

void loop() {
  for (int duty = 0; duty <= 245; duty++) {
    analogWrite(pwmPin, duty);
    delay(20);
  }

  for (int duty = 245; duty >= 0; duty--) {
    analogWrite(pwmPin, duty);
    delay(20);
  }
}

最大と最小付近で少し針が触れる感じが良い。

やっぱりアナログメータ味があるね。自動車用のメータとかだとステッピングモータ系になっていたりするので針がキビキビ動いたりするけど、こちらはかなり振れる。

昔テストしてみたArduinoでOBD2のデータ取るやつとか使うとレスポンスが悪いアナログメータが作れそう。
音声をADCで入力してメーターに出力するという無駄な自作VUメータとかも作れるかも。

2025年6月7日土曜日

ジンバル用ブラシレスモータをSimpleFOCで動かしてみた

 前回2804 220KVモータMT6701を取り付けて角度を検出できるようになったので、次はDRV8313を使用して回してみた。FETとゲートドライバ内蔵の3相モータドライバICでこのクラスのモータなら簡単に回すことが可能とか。同志から借りてきた。
これでArduinoからSimpleFOCライブラリを使って簡単にベクトル制御が試せるっぽい。

DRV8313は電源とPWM3つとENさえ繋げばモータが回せる構成。今回借りてきたのはSimpleFOCMiniという評価ボード。

マイコンにはBluepillを使用してみた。STM32F103はモータを回すためのタイマとかも充実しているような感じっぽいけど、今回は3PWMなのであんまり関係ないかも。6PWMでコンプリメンタリタイマを使ったり、同期でローサイドの電流測ったりするなら良いかもしれない。

DRV8313が最低8Vっぽいので昇圧回路を使用した。あとBluepillのUSB CDCだとリセット直後のログが見づらいのでSerial Bootloader経由で書き込むようにしておいた。これなら書き込んだあとにそのままシリアルのログが見れる。

とりあえず電流センサは搭載していないのでMT6701と3PWMでの角度制御を試してみた。
#include "Arduino.h"
#include "SPI.h"
#include "SimpleFOC.h"
#include "SimpleFOCDrivers.h"
#include "encoders/MT6701/MagneticSensorMT6701SSI.h"

#define CSN1 PA15
#define CLK1 PB3
#define MISO1 PB4
#define MOSI1 PB5

SPIClass SPI_1(MOSI1, MISO1, CLK1);
MagneticSensorMT6701SSI sensor(CSN1);
BLDCMotor motor = BLDCMotor(7);
BLDCDriver3PWM driver = BLDCDriver3PWM(PB6, PB7, PB8, PB5);

float target_angle = 0;
Commander command = Commander(Serial);
void doTarget(char* cmd) { command.scalar(&target_angle, cmd); }

void setup() {

  Serial.begin(115200);
  SimpleFOCDebug::enable(&Serial);

  sensor.init(&SPI_1);
  motor.linkSensor(&sensor);
  driver.voltage_power_supply = 8;
  driver.init();
  motor.linkDriver(&driver);
  motor.foc_modulation = FOCModulationType::SpaceVectorPWM;
  motor.controller = MotionControlType::angle;
  motor.PID_velocity.P = 0.2f;
  motor.PID_velocity.I = 20;
  motor.voltage_limit = 8;
  motor.LPF_velocity.Tf = 0.01f;
  motor.P_angle.P = 20;
  motor.velocity_limit = 40;
  motor.useMonitoring(Serial);
  motor.init();
  motor.initFOC();

  command.add('T', doTarget, "target angle");

  Serial.println(F("Motor ready."));
  Serial.println(F("Set the target angle using serial terminal:"));
  _delay(1000);
}

void loop() {
  motor.loopFOC();
  motor.move(target_angle);
  command.run();
}
SimpleFOC付属のサンプルスケッチにSimpleFOCDriverのMT6701の設定を追加しただけ。
これを書き込むとモータがゆっくり正転逆転してセンサのキャリブレーションを行って、シリアルコンソールからT10とか値を入力すると角度制御で無事動かすことができた。

パラメータとかいじってないのに普通に動くのでこれは楽…
昇圧回路だと電源が足りないのか、角度固定中に手で無理やり動かすと唸りを上げているのでちゃんとした電源にして試さないと…

とりあえずこれでモータの動作確認もできたので次は電流センサを追加してベクトル制御に対応させたい。

2025年6月2日月曜日

ジンバル用モータに磁気エンコーダ基板を取り付けてみた。

 この前購入した2804 220KV用にSSI接続化したMT6701センサ基板を取り付けられるような3Dプリント部品が出来上がってきたので早速組み立ててみた。

今回はM2x6で全部組み立てられる設計。センサ側は穴を少し小さめにしておいたので無理やりM2ネジをねじ込んでねじ切っておいた。バリが出たのでカッターで少し面取り。

モータを取り付けてみると固定穴はいい感じの寸法かも。使わないコネクタを避けた部分が少しズレてた。あたっていないのでまぁOK。
最後にSSI化したMT6701のセンサ基板を装着。PWM/Anarogの部分にはCSが来ている。

モータとMT6701が合体できたのでセンサの動作確認。センサと磁石のギャップは1.3mmぐらいに設定してある。
前にBluepillで試したときのスケッチでもいいんだけど、SimpleFOCで動かしたかったのでSimpleFOCのDriverライブラリを使用してMT6701の動作確認。(結局磁石の距離がいい感じなのかを調べるために使ったんだけどね…)
#include <SimpleFOC.h>
#include <SimpleFOCDrivers.h>
#include <encoders/mt6701/MagneticSensorMT6701SSI.h>

SPIClass SPI_1(PB5, PB4, PB3);  // MOSI, MISO, SCK
#define MT6701_CS PA15 //CS

MagneticSensorMT6701SSI sensor = MagneticSensorMT6701SSI(MT6701_CS);

void setup() {
  Serial.begin(115200);
  sensor.init(&SPI_1);
}

void loop() {
  sensor.update();
  float angle = sensor.getSensorAngle();
  float degrees = angle * (360.0 / (2 * PI));
  Serial.print("Angle (rad): ");
  Serial.print(angle, 4);
  Serial.print(", (deg): ");
  Serial.println(degrees, 2);
  delay(200);
}

このライブラリはSimpleFOCをMT6701のようないろんな磁気エンコーダに対応できるようなライブラリで、MT6701にも対応している。このライブラリを使用して角度を表示できるようなスケッチでまずはセンサの動作確認をしてみた。MOSIは未使用なので、基板のシルクでいうとSDAにMISOを、SCLにSCKを、PWM/AnalogピンはパターンカットしてCSに接続しているのでCSに接続、VCCは3.3Vを使用。

SimpleFOCでは角度はラジアンで扱っているのでわかりやすいように度になおして表示してみた。ちゃんと一周で360度になるので大丈夫そう。

とりあえずセンサの動作確認ができたので次回はモータドライバを接続してSimpleFOCで回せるようにしてみたい。