| 総重量 34.84g |
ESP8266から9軸センサBMX055を読込、Madgwickフィルタ・PID制御し、RemoteXYアプリ( WiFi)操作による浮上テストを行いましたが部屋が狭くスマホ操作は難しいです。
動画
回路図

ESP-WROOM-02D+ピッチ変換基板
●Wi-Fiモジュール ESP-WROOM-02D 技適製品 【https://akizukidenshi.com/catalog/g/g113289/】
秋月電子通商から引用
●仕様
・シリーズ:ESP8266
・電源電圧min.:2.7V
・電源電圧max.:3.6V
・コア:Xtensa LX6
・コアサイズ:32bit
・クロック:160MHz
・ROM:2MB
・プログラムメモリ[B]:2MB
・GPIO:11
・UART/USART:1
・I2C:0
・SPI:1
ドローンフレーム・モータ
●コアレス モーター 0716
●フレーム BETAFPV 65S 65mm Micro Whoop Frame for 7x16mm Motors Version 4【https://item.rakuten.co.jp/airstage/10015759/】
バッテリー
基板
フレームに合わせて切断
丸ピンヘッダ ・ソケット2.54mmピッチ
コンパクトなのでESP8266と基板接続に使用しました。
接触不良が発生したので、丸ピンヘッダの表面にハンダを流してからソケットに挿入しました。
9軸センサBMX055
●9軸(加速度3軸+ジャイロ3軸+磁気コンパス3軸)センサ BMX055にレベル変換回路
●I2Cアドレス
加速度0x19 ジャイロ0x69 磁気0x13
JP1オープン JP2オープン JP3オープン ●プルアップ接続
JP4ショート JP5ショート
●電源3.3V 信号3.3V
JP6オープン JP7ショート JP8オープン
接触不良対策、丸ピンヘッダにハンダを流す。
SI2302A
●MOSFETドライバー SI2302A
ADP3338
表面実装低損失レギュレーターADP3338AKCZ-3.3基板(表)
MOSFETドライバー SI2302A
レギュレーターADP3338AKCZ-3.3
基板(裏)
チップ抵抗・チップコンデンサーESP8266コントローラ
ドライバー基板にESP8266・BMX055をコネクタ接続
ESP8266コントローラ取付
モータケーブルを基板にハンダ付けし、フレームにESP8266コントローラを取付けて固定する。(輪ゴム→ポリウレタン Puバンドに変更)
アマゾン【プロペラ CW CCW 10 6 E010 T36 NIHUI NH010 用】
プログラム書込み
パソコンUSBポートのFT232RL USBシリアル変換とESP8266のTXD・RXD・VCC・GND接続して、プログラム書込みを行います。
●FT232RLショートピン➨3.3V側
●ESP8266 IO0にGNDピン挿入(書込み)
電池残量チェッカー
電池の残量チェックに便利な電圧計を製作しました(電圧計にコネクタをハンダ固定)バッテリー保管(約3.8Vで保管)
RemoteXYアプリ
●同ブログ関連記事:【RemoteXY使い方】
【Properties】【Configuration】設定変更
[Connection]WiFi access point
[Board]ESP8266 based board
[Module]WiFi on chip
【Apply】実行
【Slider】をスマホ画面に貼付け、大きさ・色等を変更
(コントロール配置は5個以内)
【Get source code】実行
コードをArduino IDE エディタ画面に貼付てスケッチを行う。
両手で旋回と上昇を操作する配置
ジョイスティック 1(右) ↕上昇/下降 ↔左移動/右移動
ジョイスティック 2(左) ↕前進/後進 ↔左旋回/右旋回
ON:モータ起動
C: キャリブレーション
プログラム Arduino IDE【ボード:Generic ESP8266 Module】
//////////////////////////////////////////////
// RemoteXY include library //
//////////////////////////////////////////////
// you can enable debug logging to Serial at 115200
//#define REMOTEXY__DEBUGLOG
// RemoteXY select connection mode and include library
#define REMOTEXY_MODE__WIFI_POINT
#include <ESP8266WiFi.h>
// RemoteXY connection settings
#define REMOTEXY_WIFI_SSID "RemoteXY"
#define REMOTEXY_WIFI_PASSWORD "12345678"
#define REMOTEXY_SERVER_PORT 6377
#include <RemoteXY.h>
// RemoteXY GUI configuration
#pragma pack(push, 1)
uint8_t RemoteXY_CONF[] = // 64 bytes
{ 255,6,0,0,0,57,0,17,0,0,0,83,1,200,84,1,1,4,0,5,
120,4,79,79,0,2,26,31,5,1,4,79,79,0,2,26,31,10,84,52,
33,30,49,4,26,31,79,78,0,31,79,70,70,0,1,84,4,33,30,1,
2,31,67,0 };
// this structure defines all the variables and events of your control interface
struct {
// input variables
int8_t joystick_01_x; // from -100 to 100
int8_t joystick_01_y; // from -100 to 100
int8_t joystick_02_x; // from -100 to 100
int8_t joystick_02_y; // from -100 to 100
uint8_t pushSwitch_01; // =1 if state is ON, else =0
uint8_t button_01; // =1 if button pressed, else =0
// other variable
uint8_t connect_flag; // =1 if wire connected, else =0
} RemoteXY;
#pragma pack(pop)
/////////////////////////////////////////////
// END RemoteXY include //
/////////////////////////////////////////////
#include<Wire.h>
#include <MadgwickAHRS.h>
Madgwick MadgwickFilter;
float ROLL_P, ROLL_I, ROLL_D, ROLL_M;
float PITCH_P, PITCH_I, PITCH_D, PITCH_M;
float YAW_P, YAW_I, YAW_D, YAW_M;
float R, P, Y;
float Kp, Kd, Ki;
int throttle, Jx1, Jy1, Jx2, Jy2, Auto;
#define M1 12
#define M2 13
#define M3 14
#define M4 15
#define PWN_FREQ 1000 // PWM frequency: 1000Hz(1kHz)
#define PWN_RANGE 100 // PWN range: 100
// BMX055
#define Addr_Accl 0x19 // 加速度センサのI2Cアドレス(JP1,JP2,JP3 = Openの時)
#define Addr_Gyro 0x69 // ジャイロセンサのI2Cアドレス(JP1,JP2,JP3 = Openの時)
#define Addr_Mag 0x13 // 磁気センサのI2Cアドレス(JP1,JP2,JP3 = Openの時)
// センサーの値を保存するグローバル変数
float ax = 0.00;//加速度
float ay = 0.00;
float az = 0.00;
float gx = 0.00;//角速度
float gy = 0.00;
float gz = 0.00;
int mx = 0.00;
int my = 0.00;
int mz = 0.00;
float ROLL = 0.00;
float PITCH = 0.00;
float YAW = 0.00;
void BMX055_Init() //BMX055の初期化
{
Wire.beginTransmission(Addr_Accl);
Wire.write(0x0F); // Select PMU_Range register
Wire.write(0x03); // Range = +/- 2g
Wire.endTransmission();
delay(100);
//------------------------------------------------------------//
Wire.beginTransmission(Addr_Accl);
Wire.write(0x10); // Select PMU_BW register
Wire.write(0x08); // Bandwidth = 7.81 Hz
Wire.endTransmission();
delay(100);
//------------------------------------------------------------//
Wire.beginTransmission(Addr_Accl);
Wire.write(0x11); // Select PMU_LPW register
Wire.write(0x00); // Normal mode, Sleep duration = 0.5ms
Wire.endTransmission();
delay(100);
//------------------------------------------------------------//
Wire.beginTransmission(Addr_Gyro);
Wire.write(0x0F); // Select Range register
Wire.write(0x04); // Full scale = +/- 125 degree/s
Wire.endTransmission();
delay(100);
//------------------------------------------------------------//
Wire.beginTransmission(Addr_Gyro);
Wire.write(0x10); // Select Bandwidth register
Wire.write(0x07); // ODR = 100 Hz
Wire.endTransmission();
delay(100);
//------------------------------------------------------------//
Wire.beginTransmission(Addr_Gyro);
Wire.write(0x11); // Select LPM1 register
Wire.write(0x00); // Normal mode, Sleep duration = 2ms
Wire.endTransmission();
delay(100);
//------------------------------------------------------------//
Wire.beginTransmission(Addr_Mag);
Wire.write(0x4B); // Select Mag register
Wire.write(0x83); // Soft reset
Wire.endTransmission();
delay(100);
//------------------------------------------------------------//
Wire.beginTransmission(Addr_Mag);
Wire.write(0x4B); // Select Mag register
Wire.write(0x01); // Soft reset
Wire.endTransmission();
delay(100);
//------------------------------------------------------------//
Wire.beginTransmission(Addr_Mag);
Wire.write(0x4C); // Select Mag register
Wire.write(0x00); // Normal Mode, ODR = 10 Hz 0x00 //100Hz 0x07
Wire.endTransmission();
//------------------------------------------------------------//
Wire.beginTransmission(Addr_Mag);
Wire.write(0x4E); // Select Mag register
Wire.write(0x84); // X, Y, Z-is enabled
Wire.endTransmission();
//------------------------------------------------------------//
Wire.beginTransmission(Addr_Mag);
Wire.write(0x51); // Select Mag register
Wire.write(0x04); // No. of Repetitions for X-Y is = 9
Wire.endTransmission();
//------------------------------------------------------------//
Wire.beginTransmission(Addr_Mag);
Wire.write(0x52); // Select Mag register
Wire.write(0x16); // No. of Repetitions for Z-Axis = 15
Wire.endTransmission();
}
void BMX055_All() //BMX055から全データとMadgwickフィルタの結果を取得する
{
unsigned int data[8];
//加速度データを取得する
for (int i = 0; i < 6; i++)
{
Wire.beginTransmission(Addr_Accl);
Wire.write((2 + i));// Select data register
Wire.endTransmission();
Wire.requestFrom(Addr_Accl, 1);// Request 1 byte of data
// Read 6 bytes of data
// ax lsb, ax msb, ay lsb, ay msb, az lsb, az msb
if (Wire.available() == 1)
data[i] = Wire.read();
}
// Convert the data to 12-bits
ax = ((data[1] * 256) + (data[0] & 0xF0)) / 16;
if (ax > 2047) ax -= 4096;
ay = ((data[3] * 256) + (data[2] & 0xF0)) / 16;
if (ay > 2047) ay -= 4096;
az = ((data[5] * 256) + (data[4] & 0xF0)) / 16;
if (az > 2047) az -= 4096;
ax = ax * 0.0098; // range = +/-2g
ay = ay * 0.0098; // range = +/-2g
az = az * 0.0098; // range = +/-2g
// 上記の乗数は秋月のマニュアル通りですが、誤値とのことです。
// 正しくは、mg換算で0.98、G換算で0.00098
// とのことです。
//ジャイロデータを取得する
for (int i = 0; i < 6; i++)
{
Wire.beginTransmission(Addr_Gyro);
Wire.write((2 + i)); // Select data register
Wire.endTransmission();
Wire.requestFrom(Addr_Gyro, 1); // Request 1 byte of data
if (Wire.available() == 1)
data[i] = Wire.read();
}
// Convert the data
gx = (data[1] * 256) + data[0];
if (gx > 32767) gx -= 65536;
gy = (data[3] * 256) + data[2];
if (gy > 32767) gy -= 65536;
gz = (data[5] * 256) + data[4];
if (gz > 32767) gz -= 65536;
gx = gx * 0.0038; // Full scale = +/- 125 degree/s
gy = gy * 0.0038; // Full scale = +/- 125 degree/s
gz = gz * 0.0038; // Full scale = +/- 125 degree/s
//コンパスデータを取得する
for (int i = 0; i < 8; i++)
{
Wire.beginTransmission(Addr_Mag);
Wire.write((0x42 + i)); // Select data register
Wire.endTransmission();
Wire.requestFrom(Addr_Mag, 1); // Request 1 byte of data
// Read 6 bytes of data
// mx lsb, mx msb, my lsb, my msb, mz lsb, mz msb
if (Wire.available() == 1)
data[i] = Wire.read();
}
// Convert the data
mx = ((data[1] << 5) | (data[0] >> 3));
if (mx > 4095) mx -= 8192;
my = ((data[3] << 5) | (data[2] >> 3));
if (my > 4095) my -= 8192;
mz = ((data[5] << 7) | (data[4] >> 1));
if (mz > 16383) mz -= 32768;
}
void setup()
{
RemoteXY_Init ();
pinMode(M1, OUTPUT);
pinMode(M2, OUTPUT);
pinMode(M3, OUTPUT);
pinMode(M4, OUTPUT);
Wire.begin();
Serial.begin(115200);
BMX055_Init(); //BMX055の初期化
delay(300);
MadgwickFilter.begin(100);//フィルタのサンプリングを100Hzで
analogWriteFreq(PWN_FREQ);
analogWriteRange(PWN_RANGE);
R = 0;
P = 0;
Y = 0;
Kp = 0;
Ki = 0;
Kd = 0;
}
void loop()
{
RemoteXY_Handler ();
Jx1 = RemoteXY.joystick_01_x; //左右移動
Jy1 = RemoteXY.joystick_01_y; //上下浮上
Jx2 = RemoteXY.joystick_02_x; //上下移動
Jy2 = RemoteXY.joystick_02_y; //左右回転
Auto = RemoteXY.pushSwitch_01; //自動浮上
BMX055_All();//BMX055から全データ
MadgwickFilter.update(gx, gy, gz, ax, ay, az, mx, my, mz);
ROLL = MadgwickFilter.getRoll();
PITCH = MadgwickFilter.getPitch();
YAW = MadgwickFilter.getYaw();
YAW = YAW - 90;
if (RemoteXY.button_01 == 1) { //"CALボタン"
R = ROLL;
P = PITCH;
Y = YAW;
ROLL_M = 0;
PITCH_M = 0;
YAW_M = 0;
}
ROLL = ROLL - R; //キャリブレーション
PITCH = PITCH - P;
YAW = YAW - Y;
// PID制御
ROLL_P = ROLL / 90; // P成分:傾き-90~90度 → -1~1
ROLL_I += ROLL_P; // I成分:傾きの積算。
if (10 < abs(ROLL_I)) ROLL_I = 0; //上限設定
ROLL_D = gx / 125; // D成分:角速度-125~125dps → -1~1
ROLL_M = ROLL_P * Kp +
ROLL_I * Ki +
ROLL_D * Kd;
PITCH_P = PITCH / 90; // P成分:傾き-90~90度 → -1~1
PITCH_I += PITCH_P; // I成分:傾きの積算。
if (10 < abs(PITCH_I)) PITCH_I = 0; //上限設定
PITCH_D = gy / 125; // D成分:角速度-125~125dps → -1~1
PITCH_M = PITCH_P * Kp +
PITCH_I * Ki +
PITCH_D * Kd;
YAW_P = YAW / 90; // P成分:傾き-90~90度 → -1~1
YAW_I += YAW_P; // I成分:傾きの積算。
if (10 < abs(YAW_I)) YAW_I = 0; //上限設定
YAW_D = gz / 125; // D成分:角速度-125~125dps → -1~1
YAW_M = YAW_P * Kp +
YAW_I * Ki +
YAW_D * Kd;
YAW_M = YAW_M + Jx2/20;
ROLL_M = ROLL_M + Jy2/20;
PITCH_M = PITCH_M - Jx1/20;
//自動浮上
if(Auto == 1 ){
//定数
Kp = 40;
Ki = 0.1;
Kd = 10;
throttle = (Jy1 + 100)/2 * 0.7;
}else{
throttle = 0;
ROLL_M = 0;
PITCH_M = 0;
YAW_M = 0;
}
analogWrite(M1, (throttle + ROLL_M + PITCH_M - YAW_M));
analogWrite(M2, (throttle + ROLL_M - PITCH_M + YAW_M));
analogWrite(M3, (throttle - ROLL_M - PITCH_M - YAW_M));
analogWrite(M4, (throttle - ROLL_M + PITCH_M + YAW_M));
delay(5);
}





.png)
0 件のコメント:
コメントを投稿