【DRV8320HでBLDCを回したい】第4回+α:NUCLEO-F302R8でセンサレス120度通電制御+α
はじめに
第4回ではNUCLEO-F302R8でセンサレス120度通電制御する方法について書きました。
しかし、ドローンのESCとして使用するには前回の制御では回転速度が足りないという問題も抱えていました。 あれから色々試行錯誤した結果、なんとかそれなりにモータを回せるようになってきたのでやったことをメモ書きで残しておきます。
変更点
下記に変更点を書いていきます。色々と変更したのですが、最終的に何が効いてモータが回るようになったのかは自分でもいまいち理解できていない部分もあります。なので、とりあえず変更点を列挙します。
ゼロクロス検出方法の変更
前回は下図のようにPWM周期のHIGHのタイミングでゼロクロスを判定するようにしていました。
今回は下図のように常にゼロクロス判定をするように変更しています。
変更した理由としては6000KVや7000KVのような高速回転するモータではPWM周波数にもよりますがサンプリングが足りずにゼロクロス間隔が飽和しているような気がしたためです。正直、変更後の検出方法はなんでPWMの出力Lowタイミングでもゼロクロス検出できるのか自分でも分かっていません。よくわかんないけど動くからヨシ!の状態...。
転流処理の高速化
下記のような相補PWMによる駆動を行うために転流のタイミングでLow Side出力ピンのモードを相補PWMモードとGPIOモードにHAL_GPIO_Init()関数を読んで切り替えていました。
しかし、この部分の処理が異常に重く下記のように転流処理に28.6usの時間がかかっていました。
そこで、必要最低限の処理だけを実行するようにした所、転流にかかる処理を4usまで高速化できました。
ピンモードの切替としてはMODERレジスタを操作するだけで良い感じでした。
PWM周波数・供給電圧の変更
Dutyを上げて行くとある程度のDutyからDRV8320Hの何らかの保護機能に引っかかては復帰しを繰り返す現象が見られました。過電流などが流れている場合、CLR_FLT動作をしないと復帰できないようなので、自動で復帰してくることから「VCPチャージ・ポンプの低電圧誤動作防止」が働いているような気がしました。また、PWM周波数を上げると回せるDuty上限が上昇していく現象を確認しました。さらに、電源電圧を上げることでも回せるDuty上限が上昇しました。このことがわかったので最終的にPWM周波数は40kHzから72kHzに変更、電源電圧は7.4Vから11.1Vで駆動させるようにした所、Duty100%でも保護機能に引っかからないようになりました。
チャージポンプに関しては下記のデータシートにあるようにPWM周波数と電源電圧に依存するっぽいので、やはりこの辺りが影響していたのかなあという感じです。
残課題
モータは回るようになりましたがが処理負荷的に通信機能が実装できるか微妙です。ESCとして機能させるには上位ECUと通信が必要なのでその処理が入るかはこれから検討が必要です。
おわりに
今回は完全に個人的な備忘録として書いています。読んでいる人にはナンノコッチャだと思うので適当に流し読みしてください。 これで【DRV8320HでBLDCを回したい】に関しては一区切りにしたいと思います。
【DRV8320HでBLDCを回したい】第4回:NUCLEO-F302R8でセンサレス120度通電制御
はじめに
第3回ではBEMFをADCで読み取る方法について書きました。
第3回では上手く読み取れているように書きましたが、実際にADCの結果を使用してセンサレス制御をやってみても上手くいきませんでした。 かなり行き詰まっていた中で、たまたま下記記事を見つけて参考にした所、センサレスでBLDCを回すことができました。この記事を見つけてなかったら未だに回せていないと思います、本当に助かりました!
また、今回はゼロクロスをADCではなくF302R8内蔵のコンパレータを使用して行いました(コンパレータはF411REには搭載されていなかったのでF302R8を使いました)。 理由としては、①ADC→②仮想中点と各相電圧を比較→③ゼロクロス判定といった処理の①②をコンパレータを使えばハード側でやってくれるのでソフトの負荷軽減になるかなと思ったからです。
NUCLEO-F302R8の設定
Clockの設定
Clockはとりあえず最大動作周波数に設定
TIM1設定
TIM1はモータへのPWM出力を行うために使用します。 Channelの1~4を「PWM Generation CHx」に設定。
- CH1:U相制御用出力
- CH2:V相制御用出力
- CH3:W相制御用出力
- CH4:ゼロクロス判定割り込み用出力
「Counter Mode」は「Center Aligned mode 1」に設定。Center Aligned modeにすることでカウンタがノコギリ波ではなく三角波になります。modeは1~3までありますがキャプチャコンペア割り込み発生タイミングが変わるようです。
「Counter Period」はPWM周波数が40kHzになるように設定しています。一応PWM周波数はソフトの方で可変できるように実装しました。
また「TIM1 capture compare interrupt」を有効にしておきます。これはCH4のコンペアマッチタイミングでゼロクロス判定を行うためです。
TIM2設定
TIM2はゼロクロスの間隔を計測するために使用します。 Clock Sourceを「Internal Clock」に変更
PrescalerはTIM2のカウンタが1usで1カウントするように設定しています。
あくまでもゼロクロス間隔を計測するだけなので割り込みはありません。
TIM6設定
TIM6はゼロクロスを検出したタイミングから次の転流(ゼロクロス間隔/2、電気角でいうと30deg後?)タイミングで実際に転流を行うための割り込みを発生させる為に使用します。 Clock Sourceを「Internal Clock」に変更
PrescalerはTIM2と同じ1usで1カウントするように設定しています。
割り込みも忘れずに有効にします。
COMP2, 4, 6設定
COMPはゼロクロス検出のために使用します。
今回はCOMPタイミングで割り込み等は発生させないので、機能を有効化させるだけです。COMP4, 6も同じように設定すればOK。
GPIO設定
あとはデバッグとDRV8320Hを制御するのに必要なGPIOの設定を行いました。赤枠の部分を「GPIO_Output」で設定しています。
これでCube MXの設定は終了なのでGenerate codeします。
1つ注意点なのが、CubeMXのバグかわかりませんがCOMP4, 6のInvertingInputに代入する値が間違って生成されるので直す必要があります。「COMP_INVERTINGINPUT_IO2」が正しい設定です。
プログラム
BLDCのセンサレス駆動で追加したコードに付いて下記に示します。
main.h
プロトタイプ宣言が一つあります。main.cに本体がいてstm32f3xx_it.cで使用したいため.hに宣言しています。
/* USER CODE BEGIN EFP */ void BLDC_CC_interrupt(); // TIM1CH4CC割り込みコールバック /* USER CODE END EFP */
main.c
シリアル関連で使用するのでインクルードしました。
/* Private includes ----------------------------------------------------------*/ /* USER CODE BEGIN Includes */ #include <stdio.h> /* USER CODE END Includes */
BLDC_PWM_FREQ は初期のPWM周波数、BLDC_PWM_ON は初期のDutyです。
/* Private define ------------------------------------------------------------*/ /* USER CODE BEGIN PD */ #define BLDC_PWM_FREQ 900 // PWM周波数 900 = 40kHz #define BLDC_PWM_ON 150 // ON duty 150 / 900 * 100[%] #define BLDC_PWM_OFF 0 // OFF duty #define BLDC_PWM_ZEROCROSS_CHECK_TIMING 10 // ゼロクロス判定タイミングduty // UVWのコンパレータ状態 #define COMPARATOR_STATE_0 0b101 // U:1 V:0 W:1 #define COMPARATOR_STATE_1 0b100 // U:1 V:0 W:0 #define COMPARATOR_STATE_2 0b110 // U:1 V:1 W:0 #define COMPARATOR_STATE_3 0b010 // U:0 V:1 W:0 #define COMPARATOR_STATE_4 0b011 // U:0 V:1 W:1 #define COMPARATOR_STATE_5 0b001 // U:0 V:0 W:1 // 転流状態 typedef enum { COMMUTATION_STATE_0 = 0, COMMUTATION_STATE_1, COMMUTATION_STATE_2, COMMUTATION_STATE_3, COMMUTATION_STATE_4, COMMUTATION_STATE_5, COMMUTATION_STATE_ERROR, }BLDC_CommutationState_enum; /* USER CODE END PD */
BLDCを回す上で必要な情報は構造体でまとめています。
/* USER CODE BEGIN PV */ typedef struct { int duty; int comm_state; // 現在の転流状態 int comm_flag; // 転流したフラグ int zero_cross_interval_us; // ゼロクロス間隔[us] int comp_UVW; // 現在のコンパレータの状態(UVWまとめたやつ) int comp_UVW_old; // 1つ前のコンパレータの状態 }BLDC_Data_struct; BLDC_Data_struct BLDC; /* USER CODE END PV */
センサレス駆動用に追加した関数のプロトタイプ宣言。
/* USER CODE BEGIN PFP */ void BLDC_Initialization(); // 初期化 void BLDC_Update_CommutationState(int state); // 実際に転流させる void BLDC_Set_Duty(int duty); // Duty設定用 int BLDC_Get_Comparator(); // コンパレータの状態を取得 int BLDC_Get_NextCommutationState(int comp_uvw); // コンパレータの状態を渡して次の転流状態を取得 int BLDC_Get_ZeroCrossInterval(); // ゼロクロス間隔を取得 void BLDC_Set_NextCommutationTiming(int zero_cross_interval_us); // 次の転流タイミングを設定 void BLDC_Check_ZeroCross(); // ゼロクロス判定 void BLDC_TIM6_interrupt(); // TIM6割り込みコールバック /* USER CODE END PFP */
BLDCセンサレス駆動用に追加した関数
/* Private user code ---------------------------------------------------------*/ /* USER CODE BEGIN 0 */ void BLDC_Initialization() { // PWM duty BLDC_Set_Duty(BLDC_PWM_ON); // DRV8320H enable HAL_GPIO_WritePin(ENABLE_GPIO_Port, ENABLE_Pin, GPIO_PIN_SET); // Initialize duty value __HAL_TIM_SET_AUTORELOAD(&htim1, BLDC_PWM_FREQ-1); __HAL_TIM_SET_COMPARE(&htim1, TIM_CHANNEL_1, BLDC_PWM_OFF); __HAL_TIM_SET_COMPARE(&htim1, TIM_CHANNEL_2, BLDC_PWM_OFF); __HAL_TIM_SET_COMPARE(&htim1, TIM_CHANNEL_3, BLDC_PWM_OFF); __HAL_TIM_SET_COMPARE(&htim1, TIM_CHANNEL_4, BLDC_PWM_ZEROCROSS_CHECK_TIMING); // PWM start HAL_TIM_PWM_Start(&htim1, TIM_CHANNEL_1); HAL_TIM_PWM_Start(&htim1, TIM_CHANNEL_2); HAL_TIM_PWM_Start(&htim1, TIM_CHANNEL_3); HAL_TIM_PWM_Start_IT(&htim1, TIM_CHANNEL_4); // Comparator start HAL_COMP_Start(&hcomp2); HAL_COMP_Start(&hcomp4); HAL_COMP_Start(&hcomp6); //Zero cross interval counter start HAL_TIM_Base_Start(&htim2); } void BLDC_Update_CommutationState(int state) { switch(state) { case COMMUTATION_STATE_0: // U -> V __HAL_TIM_SET_COMPARE(&htim1, TIM_CHANNEL_1, BLDC.duty); __HAL_TIM_SET_COMPARE(&htim1, TIM_CHANNEL_2, BLDC_PWM_OFF); __HAL_TIM_SET_COMPARE(&htim1, TIM_CHANNEL_3, BLDC_PWM_OFF); HAL_GPIO_WritePin(INL_U_GPIO_Port, INL_U_Pin, GPIO_PIN_RESET); HAL_GPIO_WritePin(INL_V_GPIO_Port, INL_V_Pin, GPIO_PIN_SET); HAL_GPIO_WritePin(INL_W_GPIO_Port, INL_W_Pin, GPIO_PIN_RESET); break; case COMMUTATION_STATE_1: // U -> W __HAL_TIM_SET_COMPARE(&htim1, TIM_CHANNEL_1, BLDC.duty); __HAL_TIM_SET_COMPARE(&htim1, TIM_CHANNEL_2, BLDC_PWM_OFF); __HAL_TIM_SET_COMPARE(&htim1, TIM_CHANNEL_3, BLDC_PWM_OFF); HAL_GPIO_WritePin(INL_U_GPIO_Port, INL_U_Pin, GPIO_PIN_RESET); HAL_GPIO_WritePin(INL_V_GPIO_Port, INL_V_Pin, GPIO_PIN_RESET); HAL_GPIO_WritePin(INL_W_GPIO_Port, INL_W_Pin, GPIO_PIN_SET); break; case COMMUTATION_STATE_2: // V -> W __HAL_TIM_SET_COMPARE(&htim1, TIM_CHANNEL_1, BLDC_PWM_OFF); __HAL_TIM_SET_COMPARE(&htim1, TIM_CHANNEL_2, BLDC.duty); __HAL_TIM_SET_COMPARE(&htim1, TIM_CHANNEL_3, BLDC_PWM_OFF); HAL_GPIO_WritePin(INL_U_GPIO_Port, INL_U_Pin, GPIO_PIN_RESET); HAL_GPIO_WritePin(INL_V_GPIO_Port, INL_V_Pin, GPIO_PIN_RESET); HAL_GPIO_WritePin(INL_W_GPIO_Port, INL_W_Pin, GPIO_PIN_SET); break; case COMMUTATION_STATE_3: // V -> U __HAL_TIM_SET_COMPARE(&htim1, TIM_CHANNEL_1, BLDC_PWM_OFF); __HAL_TIM_SET_COMPARE(&htim1, TIM_CHANNEL_2, BLDC.duty); __HAL_TIM_SET_COMPARE(&htim1, TIM_CHANNEL_3, BLDC_PWM_OFF); HAL_GPIO_WritePin(INL_U_GPIO_Port, INL_U_Pin, GPIO_PIN_SET); HAL_GPIO_WritePin(INL_V_GPIO_Port, INL_V_Pin, GPIO_PIN_RESET); HAL_GPIO_WritePin(INL_W_GPIO_Port, INL_W_Pin, GPIO_PIN_RESET); break; case COMMUTATION_STATE_4: // W -> U __HAL_TIM_SET_COMPARE(&htim1, TIM_CHANNEL_1, BLDC_PWM_OFF); __HAL_TIM_SET_COMPARE(&htim1, TIM_CHANNEL_2, BLDC_PWM_OFF); __HAL_TIM_SET_COMPARE(&htim1, TIM_CHANNEL_3, BLDC.duty); HAL_GPIO_WritePin(INL_U_GPIO_Port, INL_U_Pin, GPIO_PIN_SET); HAL_GPIO_WritePin(INL_V_GPIO_Port, INL_V_Pin, GPIO_PIN_RESET); HAL_GPIO_WritePin(INL_W_GPIO_Port, INL_W_Pin, GPIO_PIN_RESET); break; case COMMUTATION_STATE_5: // W -> V __HAL_TIM_SET_COMPARE(&htim1, TIM_CHANNEL_1, BLDC_PWM_OFF); __HAL_TIM_SET_COMPARE(&htim1, TIM_CHANNEL_2, BLDC_PWM_OFF); __HAL_TIM_SET_COMPARE(&htim1, TIM_CHANNEL_3, BLDC.duty); HAL_GPIO_WritePin(INL_U_GPIO_Port, INL_U_Pin, GPIO_PIN_RESET); HAL_GPIO_WritePin(INL_V_GPIO_Port, INL_V_Pin, GPIO_PIN_SET); HAL_GPIO_WritePin(INL_W_GPIO_Port, INL_W_Pin, GPIO_PIN_RESET); break; default: break; } } void BLDC_Set_Duty(int duty) { BLDC.duty = duty; } int BLDC_Get_Comparator() { int comp_u; int comp_v; int comp_w; int comp_uvw; comp_u = (READ_BIT(hcomp2.Instance->CSR, COMP_CSR_COMPxOUT)) >> COMP_CSR_COMPxOUT_Pos; comp_v = (READ_BIT(hcomp4.Instance->CSR, COMP_CSR_COMPxOUT)) >> COMP_CSR_COMPxOUT_Pos; comp_w = (READ_BIT(hcomp6.Instance->CSR, COMP_CSR_COMPxOUT)) >> COMP_CSR_COMPxOUT_Pos; comp_uvw = (comp_u << 2) | (comp_v << 1) | comp_w; return comp_uvw; } int BLDC_Get_NextCommutationState(int comp_uvw) { int comm_next_state; switch(comp_uvw) { case COMPARATOR_STATE_0: comm_next_state = COMMUTATION_STATE_0; break; case COMPARATOR_STATE_1: comm_next_state = COMMUTATION_STATE_1; break; case COMPARATOR_STATE_2: comm_next_state = COMMUTATION_STATE_2; break; case COMPARATOR_STATE_3: comm_next_state = COMMUTATION_STATE_3; break; case COMPARATOR_STATE_4: comm_next_state = COMMUTATION_STATE_4; break; case COMPARATOR_STATE_5: comm_next_state = COMMUTATION_STATE_5; break; default: comm_next_state = COMMUTATION_STATE_ERROR; break; } return comm_next_state; } int BLDC_Get_ZeroCrossInterval() { int zero_cross_interval_us; zero_cross_interval_us = __HAL_TIM_GET_COUNTER(&htim2); __HAL_TIM_SET_COUNTER(&htim2, 0); return zero_cross_interval_us; } void BLDC_Set_NextCommutationTiming(int zero_cross_interval_us) { __HAL_TIM_SET_AUTORELOAD(&htim6, (int)(zero_cross_interval_us / 2)); __HAL_TIM_SET_COUNTER(&htim6, 0); HAL_TIM_Base_Start_IT(&htim6); } void BLDC_Check_ZeroCross() { if(BLDC.comp_UVW != BLDC.comp_UVW_old) { BLDC.zero_cross_interval_us = BLDC_Get_ZeroCrossInterval(); BLDC_Set_NextCommutationTiming(BLDC.zero_cross_interval_us); BLDC.comp_UVW_old = BLDC.comp_UVW; HAL_GPIO_TogglePin(LD2_GPIO_Port, LD2_Pin); } } void BLDC_CC_interrupt() { if(BLDC.comm_flag == 0) { BLDC.comp_UVW = BLDC_Get_Comparator(); BLDC_Check_ZeroCross(); } else { BLDC.comm_flag = 0; } } void BLDC_TIM6_interrupt() { BLDC.comm_state = BLDC_Get_NextCommutationState(BLDC.comp_UVW); BLDC_Update_CommutationState(BLDC.comm_state); BLDC.comm_flag = 1; HAL_TIM_Base_Stop_IT(&htim6); HAL_GPIO_TogglePin(DEBUG_A_GPIO_Port, DEBUG_A_Pin); } void HAL_TIM_PeriodElapsedCallback(TIM_HandleTypeDef *htim) { if (htim == &htim6){ BLDC_TIM6_interrupt(); } } /* USER CODE END 0 */
main関数の中身
int main(void) { /* USER CODE BEGIN 1 */ int bldc_step = 0; int i = 0; int duty = BLDC_PWM_ON; int freq = BLDC_PWM_FREQ; uint8_t buff[1]; HAL_StatusTypeDef ret; /* USER CODE END 1 */ /* MCU Configuration--------------------------------------------------------*/ /* Reset of all peripherals, Initializes the Flash interface and the Systick. */ HAL_Init(); /* USER CODE BEGIN Init */ /* USER CODE END Init */ /* Configure the system clock */ SystemClock_Config(); /* USER CODE BEGIN SysInit */ /* USER CODE END SysInit */ /* Initialize all configured peripherals */ MX_GPIO_Init(); MX_USART2_UART_Init(); MX_TIM1_Init(); MX_COMP2_Init(); MX_COMP4_Init(); MX_COMP6_Init(); MX_TIM2_Init(); MX_TIM6_Init(); /* USER CODE BEGIN 2 */ BLDC_Initialization(); // Forced commutation for(i = 0; i < 5; i ++) { BLDC_Update_CommutationState(bldc_step); bldc_step++; bldc_step %= 6; HAL_Delay(5); } /* USER CODE END 2 */ /* Infinite loop */ /* USER CODE BEGIN WHILE */ while (1) { ret = HAL_UART_Receive(&huart2, buff, 1, 1000); // B1スイッチを押しながらシリアルで「1」「2」を送信すると周波数が変化 // B1スイッチを押さずにシリアルで「1」「2」を送信するとDutyが変化 if(HAL_GPIO_ReadPin(B1_GPIO_Port, B1_Pin) == 1) { if (ret == HAL_OK) { if(buff[0] == '1') { duty += 10; } else if(buff[0] == '2') { duty -= 10; } } BLDC_Set_Duty(duty); } else { if (ret == HAL_OK) { if(buff[0] == '1') { freq += 10; } else if(buff[0] == '2') { freq -= 10; } } __HAL_TIM_SET_AUTORELOAD(&htim1, freq-1); } if (ret == HAL_OK) { char str[100] = {0}; sprintf(str,"%d\t%d\r\n",duty,freq); HAL_UART_Transmit(&huart2, (uint8_t*)str, sizeof(str), 1000); } /* USER CODE END WHILE */ /* USER CODE BEGIN 3 */ } /* USER CODE END 3 */ }
stm32f4xx_it.c
コールバック関数追加
void TIM1_CC_IRQHandler(void) { /* USER CODE BEGIN TIM1_CC_IRQn 0 */ BLDC_CC_interrupt(); /* USER CODE END TIM1_CC_IRQn 0 */ HAL_TIM_IRQHandler(&htim1); /* USER CODE BEGIN TIM1_CC_IRQn 1 */ /* USER CODE END TIM1_CC_IRQn 1 */ }
BEMF検出回路
今回は下記のような回路でBEMF検出を行っています。フィルターはなく単純に分圧しているだけです。電源電圧7.4Vのときに3.3Vを超えないように手持ちの抵抗で設計しました。
フィルター無しで検出できるのはソフトの方でPWMがONのタイミングでのみBEMF検出を行っているのでPWMパルスのノイズを無視できています。 この方法の欠点としてはPWMのDutyが小さいとPWM ONの区間が短すぎてBEMF検出処理が間に合わなくなって正常に回らなくなったりしました。
動作確認
プログラムを動作させたときの波形を示します。ちゃんとゼロクロスを検出して転流することができています。
- BEMF検出回路を通った後のU相電圧(黃色)
- BEMF検出回路を通った後のV相電圧(水色)
- BEMF検出回路を通った後の仮想中性点(紫色)
- ゼロクロス検出トグル出力(青色)
ちなみに今回のプログラムは下記のような駆動方法なのですが、
試しに下記のような相補PWMのような駆動方法を試すと
下記のような波形になりました。自分は雰囲気でモータ回してるので駆動方法による特性とかは全く分かってませんが、上の波形と比べると同じDutyで回しているのにこちらのほうが回転数が遅くなりました。
- BEMF検出回路を通った後のU相電圧(黃色)
- BEMF検出回路を通った後のV相電圧(水色)
- BEMF検出回路を通った後の仮想中性点(紫色)
- ゼロクロス検出トグル出力(青色)
おわりに
今回でなんとかBLDCをセンサレス駆動させることができました。これで自作ESCが作れるぞと思ったのも束の間、色々調べてみると課題が出てきました。
今回の手法だと1000KVモータはDuy100%まで回せたのですが、6000KVモータはどうやらゼロクロス判定が40kHz周期では粗すぎるようでDutyを上げていくと回転数が飽和してしまいました。 ゼロクロス判定周期を増やそうとしているのですが中々上手く行ってないです。
今回のプログラムだと100k eRPMで回るかどうかという感じですが、市販のESCは500k eRPMとかで回ると仕様に書いてあるのでこれくらい回せないと6000KVとかは回らないのかなあとか思っています。
このあたりを解決しないとドローン飛ばせないと思うので、自作ESCはまだまだ先になりそうです。
【STM32備忘録】Nucleo基板のST-LINKで別のNucleo基板に書き込む
はじめに
ST-LINKが分離されたF446RE基板を手に入れたので、これに書き込みを行う手順を覚え書きとして残しておく
参考文献
「nucleo stlink」で調べると色々と出て来た。
配線
書き込みは余っていたNucleo-F302R8のST-LINKを使用する。前準備としてNucleo-F302R8のCN2のジャンパは2つとも外す。
配線は下記のように行った。
F302R8 | F446RE | ケーブルの色 |
---|---|---|
CN4-1 : VDD_TARGET | CN6-04 : +3.3V | Red |
CN4-2 : SWCLK | CN7-15 : PA14 | Green |
CN4-3 : GND | CN6-06 : GND | Black |
CN4-4 : SWDIO | CN7-13 : PA13 | Yellow |
CN4-5 : NRST | CN6-03 : NRST | Blue |
CN6-5 : +5V | CN6-08 : VIN | Orange |
CN4のピン番号は下記のよう感じ、CN4-6は使用していない。
配線の全体感としては下記のような感じ。F446REへの電源供給はF302R8の+5Vから行っている。
プロジェクトの作成
いつもは「Board Selector」の方からプロジェクトを作成していたが、今回は「MCU/MPU Selector」の方から作成してみる。違いとしては「Board Selector」の方から作成するとNucleoとして動かすための最低限の機能が自動設定されるが「MCU/MPU Selector」では何も設定されていないプロジェクトが作成される。
Step1. 今回はSTM32F446REを使用する
Step2. 「Project Name」はお好み、「Target Language」もお好み。自分はC++で書くことがあるのでC++を選んでいる。
Step3. 下記のようにプロジェクトは何も設定されていない状態で作成される
Step4. とりあえずデバッグ用にLEDを光らせるためのポート出力を設定
Step5. Labelも設定しておく
Step6. ST-LINKからデバッグできるように「Serial Wire」を選択
Step7. クロックの設定は初期状態だと下記のようになっていた。ここはお好みで変更し、設定を保存してGenerate Codeする。
書き込み
Step0. プログラムが書き込めているか分かるように簡単なLチカプログラムを作成
Step1. 三角マークをクリック。
Step2. 下記画面が出ると思うので「デバッガ」タブを選択し、下記画面にあるように設定を行って「OK」を押すと書き込み開始。
Step3. 下記画面が出たら書き込み成功
おわりに
今回はNucleo基板のST-LINKで別のNucleo基板に書き込む方法について書きました。この方法を使えばたぶんチップ単体に対しても書き込めるんだと思っている。
【DRV8320HでBLDCを回したい】第3回:NUCLEO-F411REでBEMFを読み取る
はじめに
第2回はTeensy4.0を使用してBLDCを120度通電で強制転流させました。
第3回ではセンサレス120度通電を実現するのに必要な要素であるBEMFの読み取りについて書こうと思います。
BEMFの読み取り方法
BLDCを駆動させている時は基本PWMを使用しているので、波形がパルス状になっています。
拡大すると以下のような感じ、パルス状になっています。
今回は下記画像のようにPWMパルスのHIGHのタイミングでAD変換することでBEMFを読み取ってみようと思います。
NUCLEO-F411REの設定
Teensy4.0でPWMと同期してADCを行う設定が分からなかったので、今回はNUCLEO-F411REを使用します。
参考にしたのは以下のサイトです。以下のサイトではPWMパルスがすべてLOWのタイミングでADCしていますが、自分の場合は設定をアレンジしてPWMパルスがすべてHIGHのタイミングでADCします。
Cube MXの設定
Clock設定
Clock設定でタイマー関係を100MHzにしました。これは特に必要というわけではないんですがなるべく早いほうが良いかなと思ったので設定を変えました。
TIM設定
Channelの1~4を「PWM Generaton CHx」に設定。
- CH1:U相制御用出力
- CH2:V相制御用出力
- CH3:W相制御用出力
- CH4:ADCトリガ用
「Counter Mode」は「Center Aligned mode 1」に設定。Center Aligned modeにすることでカウンタがノコギリ波ではなく三角波になります。modeは1~3までありますがキャプチャコンペア割り込み発生タイミングが変わるようです。
「Counter Period」はPWM周期が20kHzになるように設定しています。ここはお好みで設定してください。
「Trigger Event Selection」は「Output Compare (OC4REF)」に設定。これでCH4のキャプチャコンペア割り込みが発生したタイミングでトリガーを発生できるようになるんだと思ってます。
また「TIM1 capture compare interrupt」を有効にしておきます。これは主にデバッグ用です。
ADC設定
使用するADCのCHにチェックを付けます。これは自分の使用するピンに合わせて設定してください。また、「ADC1 global interrupt」にチェックを付けます。これでADC完了時に割り込みが入るようになります。
ADC_Injected_ConversionModeの「Number Of Conversions」を「3」に設定します。これはUVWの三相をADCするためです。「External Trigger Source」を「Timer 1 Trigger Out event」に設定します。これによってTIMで設定した「Trigger Event Selection」をADCの開始トリガーに出来ます。あとは各「Injected Rank」の「Channel」を使用するADCのCHに変更します。
GPIO設定
あとはDRV8320Hを制御するのに必要なGPIOの設定を行いました。赤枠の部分を「GPIO_Output」で設定しています。
これでCube MXの設定は終了なのでGenerate codeします。
プログラム
追加したプログラムをファイル名ごとに説明します。
main.h
プログラムで新たに追加した定義です。PWM_DUTY_HIGHはBLDCを駆動する時のDuty比です。低めに設定しています。PWM_AD_TIMINGはAD変換するタイミングです。このあたりは波形を見ながら調整しました。DEBUG_BUFFER_SIZEはRAMの容量が許す限りは大きくしても問題ないと思います。
/* USER CODE BEGIN Private defines */ #define PWM_DUTY_HIGH 300 #define PWM_DUTY_LOW 0 #define PWM_AD_TIMING 100 #define DELAY_MS 1 #define DEBUG_BUFFER_SIZE 3200 /* USER CODE END Private defines */
main.c
主にデバッグ用に使用する変数です。実体はstm32f4xx_it.cに定義します。
/* USER CODE BEGIN PV */ extern int debug_ad_flag; extern int debug_buff[4][DEBUG_BUFFER_SIZE]; extern int debug_send_flag; /* USER CODE END PV */
BLDCの120度通電の各STEPの通電状態を切り替える用の関数です。
/* Private user code ---------------------------------------------------------*/ /* USER CODE BEGIN 0 */ void update_CommutationState (int state) { switch(state) { case 0: // U -> V __HAL_TIM_SET_COMPARE(&htim1, TIM_CHANNEL_1, PWM_DUTY_HIGH); __HAL_TIM_SET_COMPARE(&htim1, TIM_CHANNEL_2, PWM_DUTY_LOW); __HAL_TIM_SET_COMPARE(&htim1, TIM_CHANNEL_3, PWM_DUTY_LOW); HAL_GPIO_WritePin(INL_U_GPIO_Port, INL_U_Pin, GPIO_PIN_RESET); HAL_GPIO_WritePin(INL_V_GPIO_Port, INL_V_Pin, GPIO_PIN_SET); HAL_GPIO_WritePin(INL_W_GPIO_Port, INL_W_Pin, GPIO_PIN_RESET); break; case 1: // U -> W __HAL_TIM_SET_COMPARE(&htim1, TIM_CHANNEL_1, PWM_DUTY_HIGH); __HAL_TIM_SET_COMPARE(&htim1, TIM_CHANNEL_2, PWM_DUTY_LOW); __HAL_TIM_SET_COMPARE(&htim1, TIM_CHANNEL_3, PWM_DUTY_LOW); HAL_GPIO_WritePin(INL_U_GPIO_Port, INL_U_Pin, GPIO_PIN_RESET); HAL_GPIO_WritePin(INL_V_GPIO_Port, INL_V_Pin, GPIO_PIN_RESET); HAL_GPIO_WritePin(INL_W_GPIO_Port, INL_W_Pin, GPIO_PIN_SET); break; case 2: // V -> W __HAL_TIM_SET_COMPARE(&htim1, TIM_CHANNEL_1, PWM_DUTY_LOW); __HAL_TIM_SET_COMPARE(&htim1, TIM_CHANNEL_2, PWM_DUTY_HIGH); __HAL_TIM_SET_COMPARE(&htim1, TIM_CHANNEL_3, PWM_DUTY_LOW); HAL_GPIO_WritePin(INL_U_GPIO_Port, INL_U_Pin, GPIO_PIN_RESET); HAL_GPIO_WritePin(INL_V_GPIO_Port, INL_V_Pin, GPIO_PIN_RESET); HAL_GPIO_WritePin(INL_W_GPIO_Port, INL_W_Pin, GPIO_PIN_SET); break; case 3: // V -> U __HAL_TIM_SET_COMPARE(&htim1, TIM_CHANNEL_1, PWM_DUTY_LOW); __HAL_TIM_SET_COMPARE(&htim1, TIM_CHANNEL_2, PWM_DUTY_HIGH); __HAL_TIM_SET_COMPARE(&htim1, TIM_CHANNEL_3, PWM_DUTY_LOW); HAL_GPIO_WritePin(INL_U_GPIO_Port, INL_U_Pin, GPIO_PIN_SET); HAL_GPIO_WritePin(INL_V_GPIO_Port, INL_V_Pin, GPIO_PIN_RESET); HAL_GPIO_WritePin(INL_W_GPIO_Port, INL_W_Pin, GPIO_PIN_RESET); break; case 4: // W -> U __HAL_TIM_SET_COMPARE(&htim1, TIM_CHANNEL_1, PWM_DUTY_LOW); __HAL_TIM_SET_COMPARE(&htim1, TIM_CHANNEL_2, PWM_DUTY_LOW); __HAL_TIM_SET_COMPARE(&htim1, TIM_CHANNEL_3, PWM_DUTY_HIGH); HAL_GPIO_WritePin(INL_U_GPIO_Port, INL_U_Pin, GPIO_PIN_SET); HAL_GPIO_WritePin(INL_V_GPIO_Port, INL_V_Pin, GPIO_PIN_RESET); HAL_GPIO_WritePin(INL_W_GPIO_Port, INL_W_Pin, GPIO_PIN_RESET); break; case 5: // W -> V __HAL_TIM_SET_COMPARE(&htim1, TIM_CHANNEL_1, PWM_DUTY_LOW); __HAL_TIM_SET_COMPARE(&htim1, TIM_CHANNEL_2, PWM_DUTY_LOW); __HAL_TIM_SET_COMPARE(&htim1, TIM_CHANNEL_3, PWM_DUTY_HIGH); HAL_GPIO_WritePin(INL_U_GPIO_Port, INL_U_Pin, GPIO_PIN_RESET); HAL_GPIO_WritePin(INL_V_GPIO_Port, INL_V_Pin, GPIO_PIN_SET); HAL_GPIO_WritePin(INL_W_GPIO_Port, INL_W_Pin, GPIO_PIN_RESET); break; default: break; } } /* USER CODE END 0 */
ADCの開始とPWMの開始処理です。CH4のみ「Start_IT」関数になっているのはデバッグ用の割り込みを発生させるためです。CH4はADCトリガ用のPWMなのでピンから出力を出したくない場合はHAL_TIM_PWM_Start_IT関数をコメントアウトします。__HAL_TIM_SET_COMPAREによってコンペアマッチの値が設定された時点で内部的にはADC用のトリガが発生しているようです。HAL_TIM_PWM_Start関数はピン出力を開始するかどうかの設定っぽいです(少し自信ない)。
/* USER CODE BEGIN 2 */ // DRV8320H enable HAL_GPIO_WritePin(ENABLE_GPIO_Port, ENABLE_Pin, GPIO_PIN_SET); // ADC start HAL_ADCEx_InjectedStart_IT(&hadc1); // Initialize duty value __HAL_TIM_SET_COMPARE(&htim1, TIM_CHANNEL_1, PWM_DUTY_LOW); __HAL_TIM_SET_COMPARE(&htim1, TIM_CHANNEL_2, PWM_DUTY_LOW); __HAL_TIM_SET_COMPARE(&htim1, TIM_CHANNEL_3, PWM_DUTY_LOW); __HAL_TIM_SET_COMPARE(&htim1, TIM_CHANNEL_4, PWM_AD_TIMING); // PWM start HAL_TIM_PWM_Start(&htim1, TIM_CHANNEL_1); HAL_TIM_PWM_Start(&htim1, TIM_CHANNEL_2); HAL_TIM_PWM_Start(&htim1, TIM_CHANNEL_3); // For debug HAL_TIM_PWM_Start_IT(&htim1, TIM_CHANNEL_4); /* USER CODE END 2 */
update_CommutationState関数を一定間隔で呼ぶことで強制転流をしています。その下の処理はデバッグ処理です。今回は20kHzでADCを行っているため、周期が早すぎてリアルタイムでシリアル通信などで外部にログが出力できませんでした。そこでNUCLEOに搭載されている青いタクトスイッチを押すとそこからADC結果をバッファー配列に溜め込んでバッファーが一杯になったらBLDCの駆動を停止してシリアルで出力するようなデバッグ処理を追加しています。
/* Infinite loop */ /* USER CODE BEGIN WHILE */ while (1) { update_CommutationState(0); HAL_Delay(DELAY_MS); update_CommutationState(1); HAL_Delay(DELAY_MS); update_CommutationState(2); HAL_Delay(DELAY_MS); update_CommutationState(3); HAL_Delay(DELAY_MS); update_CommutationState(4); HAL_Delay(DELAY_MS); update_CommutationState(5); HAL_Delay(DELAY_MS); // For debug if(HAL_GPIO_ReadPin(B1_GPIO_Port, B1_Pin) == 0) { debug_ad_flag = 1; } // For debug if(debug_send_flag == 1) { HAL_GPIO_WritePin(LD2_GPIO_Port, LD2_Pin, GPIO_PIN_RESET); HAL_ADCEx_InjectedStop_IT(&hadc1); __HAL_TIM_SET_COMPARE(&htim1, TIM_CHANNEL_1, PWM_DUTY_LOW); __HAL_TIM_SET_COMPARE(&htim1, TIM_CHANNEL_2, PWM_DUTY_LOW); __HAL_TIM_SET_COMPARE(&htim1, TIM_CHANNEL_3, PWM_DUTY_LOW); HAL_GPIO_WritePin(INL_U_GPIO_Port, INL_U_Pin, GPIO_PIN_RESET); HAL_GPIO_WritePin(INL_V_GPIO_Port, INL_V_Pin, GPIO_PIN_RESET); HAL_GPIO_WritePin(INL_W_GPIO_Port, INL_W_Pin, GPIO_PIN_RESET); char buf[] = "U,V,W\r\n"; HAL_UART_Transmit(&huart2, (uint8_t*)buf, sizeof(buf), 1000); for(int i = 0; i < DEBUG_BUFFER_SIZE; i++) { char str[100] = {0}; sprintf(str,"%d, %d, %d, %d\r\n",debug_buff[0][i],debug_buff[1][i],debug_buff[2][i],debug_buff[3][i]); HAL_UART_Transmit(&huart2, (uint8_t*)str, sizeof(str), 1000); } while(1); } /* USER CODE END WHILE */ /* USER CODE BEGIN 3 */ } /* USER CODE END 3 */
stm32f4xx_it.c
デバッグ用に使用する変数の宣言
/* Private variables ---------------------------------------------------------*/ /* USER CODE BEGIN PV */ int debug_ad_flag = 0; int debug_buff[4][DEBUG_BUFFER_SIZE]; int debug_send_flag = 0; int i = 0; /* USER CODE END PV */
ADC完了時に呼ばれる関数です。ADCした値の取得とデバッグ用の処理が書いてあります。仮想中性点は各相のADC値を足して3で割って算出しています。
void ADC_IRQHandler(void) { /* USER CODE BEGIN ADC_IRQn 0 */ int u_phase_voltage = 0; int v_phase_voltage = 0; int w_phase_voltage = 0; int virtual_neutral_voltage = 0; // For debug HAL_GPIO_WritePin(LD2_GPIO_Port, LD2_Pin, GPIO_PIN_RESET); // Get ADC result u_phase_voltage = HAL_ADCEx_InjectedGetValue(&hadc1, ADC_INJECTED_RANK_2);// U v_phase_voltage = HAL_ADCEx_InjectedGetValue(&hadc1, ADC_INJECTED_RANK_3);// V w_phase_voltage = HAL_ADCEx_InjectedGetValue(&hadc1, ADC_INJECTED_RANK_1);// W virtual_neutral_voltage = (u_phase_voltage + v_phase_voltage + w_phase_voltage) / 3;// N // For debug if(debug_ad_flag == 1 && i < DEBUG_BUFFER_SIZE) { debug_buff[0][i] = u_phase_voltage;// U debug_buff[1][i] = v_phase_voltage;// V debug_buff[2][i] = w_phase_voltage;// W debug_buff[3][i] = virtual_neutral_voltage;//N i++; } // For debug if(i == DEBUG_BUFFER_SIZE) { debug_send_flag = 1; } /* USER CODE END ADC_IRQn 0 */ HAL_ADC_IRQHandler(&hadc1); /* USER CODE BEGIN ADC_IRQn 1 */ /* USER CODE END ADC_IRQn 1 */ }
デバッグ用にポート出力の処理を追加しています。TIM1のCH4のコンペアマッチタイミングで呼ばれるのでADC開始のタイミングでポート出力がHIGHになります。逆にポート出力をLOWにする設定は上に示したADC_IRQHandlerに記述しています。
void TIM1_CC_IRQHandler(void) { /* USER CODE BEGIN TIM1_CC_IRQn 0 */ // For debug HAL_GPIO_WritePin(LD2_GPIO_Port, LD2_Pin, GPIO_PIN_SET); /* USER CODE END TIM1_CC_IRQn 0 */ HAL_TIM_IRQHandler(&htim1); /* USER CODE BEGIN TIM1_CC_IRQn 1 */ /* USER CODE END TIM1_CC_IRQn 1 */ }
動作確認
プログラムを動作させたときの波形を示します。NUCLEOでも強制転流で回すことが出来ました。相変わらず誘起電圧の位相が変な気がしますが...。
拡大すると以下のような感じです。ADトリガは立ち上がりがADC開始、立ち下がりがADC完了を示しています。PWMのHIGHのタイミングでADC出来ていることが分かります。ADC開始から完了まで3usで今回は3CHをADCしているので1CHにつき1usって感じでしょうか。駆動時のDuty比を下げすぎるとADCが間に合わない可能性もありそうです。
タクトスイッチを押すとシリアルで下記のようにログが出力されます。
このデータをエクセルでグラフ化すると下記のような感じ、それっぽい値が取れています。
おわりに
今回ははセンサレス120度通電を実現するのに必要なBEMFの読み取りについて書きました。
次は各相の誘起電圧と仮想中点電圧を比較してゼロクロス検出の方法について書ければなあと思います。
センサレスで回せました↓↓↓
【DRV8320HでBLDCを回したい】第2回:Teensy4.0を使用した強制転流(120度矩形波駆動)
はじめに
第1回は使用するBLDCドライバであるDRV8320Hのデータシートを読んで、簡単に動作確認を行いました。
第2回ではDRV8320HとTeensy4.0を使用して強制転流でモータを回すことができたのでそれについて書きます。
強制転流(120度矩形波駆動)
今回はフィードバックなどを行わず、とりあえず120度通電することでモータを回してみます。使用したモータは下記になります。
以下のサイトが強制転流を行うにあたって参考になった文献です。
強制転流(120度矩形波駆動)でモータを回場合、とりあえず下記の順番でインバータ回路を駆動させれば良さそうでした。
120度通電の際は下記のようにインバータのどこをPWM制御するかで種類があるようですが、自分は赤枠の手法で行いました。
プログラム
Teensy4.0で動かしたプログラムを下記に示します。電源電圧は7.4Vで動作させました。今回使用したモータだとPWMのDuty比をかなり小さくしないと過電流でモータドライバがFaultに落ちます。コメントアウトの形跡を見てもらうと分かりますが、最初は常にDuty100%で動かそうとしていましたが、過電流で動かなかったです。ここでしばらく嵌ってました。
Teensy4.0とDRV8320HでBLDCの強制転流を行うプログラム
強制転流(120度矩形波駆動)の様子
下記に強制転流の様子を示します。ゼロクロス検出とかやらずに転流しているので低速回転でもうるさいです。
強制転流時の波形を下記に示します。
今回はハイサイド側のFETをPWM駆動で、ローサイド側は普通にHIGH、LOW駆動となっています。
気になる点
TOSHIBAの資料と自分の強制転流波形の誘起電圧の上りと下りが逆になっているのが気になります。この波形でゼロクロス検出してよいのか?強制転流すると位相が反転するということ?この辺はまだ良くわからないです。
おわりに
今回はBLDCモータを強制転流(120度矩形波駆動)で回しました。今までもここまでは出来てたので問題はここからです。
次はBEMFを検出してゼロクロス検出したタイミングで転流させることに挑戦したいですが、PWM駆動で相電圧がパルス状になっているのでどうすればよいのやら...。もしアイデアが浮かばなかったらこの連載はここで終わると思う...。
BEMF検出一応できた?↓↓↓
【DRV8320HでBLDCを回したい】第1回:データシートの解析と動作確認
はじめに
自作ドローンを作っているとESCやBLDCモータなどのパーツの供給寿命が気になります。体感ですが1年経てば殆どの部品がもう売っていない...。 また、BLDCモータとESCは経験上、相性があるようで、ESCを変えることで同じモータでも今まで出せていた回転数が出なかったりとかがありました。
そういった不安定な供給と相性問題を解決すべく、自作ESCの開発を今まで何度か試みていたのですが、上手く行っていないのが現状です(なんだかんだで市販品ってすごいんだなあと思いました)。 ただ、上手く行かない割にはモチベーションは定期的に上がってくるので、今回はやることをブログにまとめながら進めていこうと思いこの記事を書いています。 最終的にはセンサレスでBLDCを回すのが目標ですが、現時点で目処は全くついていません!
第1回は使用するBLDCドライバのデータシートの解析と動作確認としていくつか波形を取ったのでそれについてです。
DRV8320Hについて
BLDCドライバとしてTI社のDRV8320Hを使用します。選定理由としては市販されているESCでこの素子が使用されているものがあったからです。あとは日本語資料が豊富です。
検証用の評価ボードはDigikeyで購入しました。
公式のページも載せておきます。ユーザーガイドや回路図もあるので結構見ます
データシートの解析
まずはデータシートの重要な部分を抜粋し、備忘録として残します。
ブロック構成としては下記のようになっています。青枠で示した部分がFETを駆動するのに使用する入力ピン。赤枠で示した部分がIC自体の設定を行うのに使用するピンです。
ENABLEピンについては下記のような記述があります。
MODE、IDRIVE、VDSについては下記のような記述がありました。
MODEピンによって下記4つの制御モードが有るようです。
- 6x PWMモード
- 3x PWMモード
- 1x PWMモード
- 独立PWMモード
自分は6x PWMモードを使用するのでMODEピンはGNDに接続すれば良さそうです。
注意点としてMODEピンの設定を行うときはFETの駆動を止めておく必要があるそうです。
IDRIVEピンはゲート駆動電流、VDSピンは過電流検出の閾値を設定できます。これに関してはよく分かっていないのでとりあえずHi-Z(端子に何も繋いでない状態)に設定しています。一応、Hi-Zにしておけば設定できる値の中央値の設定になるっぽいのでそうしてます。
6x PWMモードにおける波形の確認
簡単に実験条件を示します。
- 電源電圧:7.4V
- 負荷なし(モータ等は接続していない状態)
- 制御用マイコン:Teensy4.0
オシロスコープで下記赤枠部分を監視しています。評価ボードにはTP(テストポート)が出ているので簡単に監視できます。
駆動時の波形を下記に示します。
波形を拡大すると下記のような感じです。DRV8320Hの6x PWMモードではデッドタイムが勝手に挿入されるようです。
1つ気になった点としてはGHA(A相のHigh側)は立ち下がりが2段階になっています。これはチャージポンプの影響?
補足するとDRV8320Hにはハイサイド側のNch FETを駆動するためのチャージポンプ回路があって、どれくらい昇圧されるかの計算式がデータシートに載っています。
今回の電源電圧は7.4Vなので実測値と計測値を比較すると1Vくらい違いましたが、これは誤差範囲?まぁハイサイド側のFETを駆動できるだけの電圧さえ発生できれば問題ないとは思ってます。
- 計算値:2 * 7.4 - 1.5 = 13.3V
- 実測値:14.2V
おわりに
今回は使用するBLDCドライバのデータシートの解析と簡単な動作確認を行いました。
一応なんとなく使い方は分かったので次回は120度の強制転流で回せればいいなと思っています。
回りました↓↓↓
【自作ドローンの製作Ⅱ】第4回:機体のスペック変更とホバリング飛行
はじめに
第3回では機体のハードウェア構成についてまとめました。
しかし、前回紹介したモータではトルクが足りなかったようでプロペラを満足に回すことができず、推力が得られませんでした。また、ナイロン素材のフレームが柔らかいためか、機体の振動もひどかったので、モータの変更、フレームの補強などを行いました。
改良の結果なんとかホバリング飛行はできるようになったので、今回は機体の改良部分とホバリング飛行について書こうと思います。
ハードウェアの改良
モータの変更
モータは今まで下記の「RCX NK1108 6000KV FPV Racing Motor for Mini/Micro Drone」を使用していました。
しかし、上記モータでは3025プロペラ(長さ:3.0インチ、ピッチ:2.5インチ)を回すことができなかったので、下記の「RCINPOWER GTS 1207 7500KV Brushless Motor for 2-3S RC Drone FPV Racing」に変更しました。
https://www.helimonster.jp/?pid=146593747www.helimonster.jp
現在は問題なく推力が出ています。最初に選定したモータは昔使ったことあるモータとKV値が同じだったので買ったのですが、KV値が同じだからといって同じプロペラを回せるわけではないということを今回学びました。個人的には販売ページに推力試験の結果を載せているモータを買うのが良い気がします。
フレームの変更
機体の振動を抑えるために、アルミ板で補強することを考えました。下記のようなアルミ板を1-off.jpで発注しました。大きいパーツが12,000円、小さいパーツが4000円ほどで製作して頂きました。
これらのパーツを機体に取り付けることで、フレームを固くすることができ振動を抑えられるようになりました。
ホバリング飛行
上記の改造を行った結果、ホバリング飛行はできるようになりました。以下がホバリング飛行の動画です。
現状、高さだけはToFセンサの値を使用した自動制御が可能になっています。プロポのスイッチを切り替えるとその時の高さを維持するような制御がかかります。
並進の自動制御に関してはオプティカルフローセンサのノイズが酷く、それを解決する方法がまだ浮かんでいないので実装できていないです。加速度センサなどのデータも活用してカルマンフィルタなどを組んだほうが良いのかもとは思っていますが、フィルタ設計やったことがないので時間がかかりそうだと思っています。
手っ取り早い解決方法は、横にToFセンサを取り付ける方法だと思いますが、センサの数が増えるのが課題ですね。
ホバリング飛行時の位置・姿勢データ
ホバリング飛行動画のログデータを載せておきます。位置・姿勢どちらもPD制御をしています。
姿勢:Roll
横軸:時間[s]、縦軸:姿勢[deg]です。Rollは目標値に対して追従できています。
姿勢:Pitch
横軸:時間[s]、縦軸:姿勢[deg]です。Pitchは目標値に対して少しオフセットがあるけど追従できています。オフセットなくすにはPゲインを上げる?
姿勢:Yaw
横軸:時間[s]、縦軸:姿勢[deg]です。Yawはもう少しPゲインを上げたほうが良さそう。
位置:Z
横軸:時間[s]、縦軸:位置[m]です。Z軸は全体的にPもDもゲインが足りてないので調整が必要ですね。
速度:XY(オプティカルフローセンサ生値)
横軸:時間[s]、縦軸:速度[単位不明]です。センサの生値なので単位は不明です。この値をどうやって綺麗にしようか悩み中です。
おわりに
今回は機体の改良部分とホバリング飛行について書きました。
XY並進の自動制御は一旦保留にします。次回は傾いた姿勢でホバリングしている動画が見せられればと思います。
追記(2022/10/15):諸々の事情(主にモチベ低下)で【自作ドローンの製作Ⅱ】については一旦ここで終了にします。次は傾いた姿勢でホバリングできるドローン作れればいいな...。