前回2804 220KVモータにMT6701を取り付けて角度を検出できるようになったので、次はDRV8313を使用して回してみた。FETとゲートドライバ内蔵の3相モータドライバICでこのクラスのモータなら簡単に回すことが可能とか。同志から借りてきた。
これでArduinoからSimpleFOCライブラリを使って簡単にベクトル制御が試せるっぽい。
マイコンには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とか値を入力すると角度制御で無事動かすことができた。
パラメータとかいじってないのに普通に動くのでこれは楽…
昇圧回路だと電源が足りないのか、角度固定中に手で無理やり動かすと唸りを上げているのでちゃんとした電源にして試さないと…
とりあえずこれでモータの動作確認もできたので次は電流センサを追加してベクトル制御に対応させたい。
0 件のコメント:
コメントを投稿