みなさん,こんにちは
おかしょです.
ロボットを自律させるためには,ロボットの姿勢角を知る必要があります.
そして姿勢角を制御するためには,その姿勢角を正確に測定しなければなりません.
姿勢角を求める方法はいろいろありますが,センサーフュージョンをすることで正確な姿勢角を求めることができます.そのセンサーフュージョンについて解説します.
この記事を読むと以下のようなことがわかる・できるようになります.
- 正確な姿勢角を求める方法
- センサーフュージョンとは
- センサーフュージョンのやり方
この記事を読む前に
この記事では姿勢角を求めるために加速度センサーとジャイロセンサーをフュージョンします.
そのため,加速度センサーとジャイロセンサーで姿勢角を求める方法を知っておく必要があります.
以下の記事ではその方法を解説しています.まだ読んでいない方は読んでおくことをおすすめします.
センサーフュージョンとは
加速度センサーで姿勢角を求めることは可能です.
ただ,その正確性には条件があります.
それは,「ロボットが静止している」ということです.
加速度センサーによって重力加速度を測定することで,正確な姿勢角の算出ができます.
このときに観測する加速度にロボットの加速度が加わってしまうと,姿勢角の精度が急激に悪化してしまいます.
ジャイロセンサーはロボットの角速度を測定できるので,出力されたデータを積分することによって姿勢角の算出ができます.
(3軸の姿勢角を求めたい場合は,少し工夫が必要です.詳しくは記事を参照してください.)
しかし,このジャイロセンサーも姿勢角を求めるうえで問題があります.
姿勢角を求めるために積分をします.このときにセンサーノイズも含めて積分をしてしまうため,積分誤差がたまっていき,時間が経てばたつほど正確な姿勢角とは程遠い値となってしまいます.
このように二つのセンサーには特徴があり,姿勢角を正確に算出することは難しいです.
そんな時に使えるのが,センサーフュージョンです.
センサーフュージョンというのは,複数のセンサーを組み合わせることでそれぞれの欠点を補い合い,正確なデータを求める技術のことを言います.
つまり,今回の場合は加速度センサーが苦手とする,ロボットが加速度運動をしている時は角速度センサーが補償し,角速度センサーの積分誤差を加速度センサーが保証します.
このようにプログラムを書くことで,一つのセンサーを使っていた時よりもさらに正確な姿勢角を求めることができるようになります.
センサーフュージョンのやり方
具体的にどうすれば良いのかをここでは解説します.
結論から言うと,以下のように計算することで正確な姿勢角を求めることができます.
$$ \phi = k\cdot \phi_{A}+(1-k)\phi_{G} $$
ここで,\(\phi_{A}\)は加速度センサーから算出された姿勢角,\(\phi_{G}\)はジャイロセンサーから算出された姿勢角を表しています.
\(k\)は定数でこの値をロボットの動作する環境に合わせて調節することで,より正確な姿勢角を求めることができます.
参考までに,私は0.05としています.
3軸の姿勢角を求める場合は,各軸ごとに同じ計算をする必要があります.
ただ,z軸周りの角度\(\psi:方位角\)に関しては加速度センサーでは算出できないので,ジャイロセンサーで算出するしかありません.
ジャイロセンサーの他に地磁気センサーがある場合は,そちらを使った方が精度の良い姿勢角を求めることができます.
センサーフュージョンプログラム
最後に,Arduino Unoでセンサーフュージョンをするためのプログラムを載せておきます.
このときに使用したセンサーはLSM9DS1を使用しています.
必要なもの
姿勢角を求める際に必要となったものは,以下のものになります.
- Arduino Uno
- USBケーブル(書き込み用)
- ブレッドボード
- ジャンパー線
- XBee×2(シリアル通信用)
- XBeeピッチ変換基板(3.3V電圧レギュレータ実装)
- XBee USBインターフェースボード
- USBケーブル(通信用)
- 電池(9V)
- LSM9DS1(9軸センサー)
センサーを動かす際にコードが邪魔になるので,XBeeで無線化を行っています.XBeeがなくても動作の確認はできるので問題はありません.
回路図
今回の動作確認のために使用した回路を以下に示します.
実際に配線するとこのようになります.
プログラム
実際にArduino Unoに書き込んだプログラムは以下になります.
#include <Wire.h>
#include <math.h>
#define AG_DEVICE_ADDRESS 0x6B
#define M_DEVICE_ADDRESS 0x1E
#define AG_WHO_AM_I 0x0F
#define CTRL_REG1_G 0x10
#define CTRL_REG2_G 0x11
#define CTRL_REG3_G 0x12
#define ORIENT_CFG_G 0x13
#define OUT_T 0x15
#define STATUS_REG_T 0x17
#define OUT_G 0x18
#define CTRL_REG4 0x1E
#define CTRL_REG5_XL 0x1F
#define CTRL_REG6_XL 0x20
#define CTRL_REG7_XL 0x21
#define STATUS_REG_AG 0x27
#define OUT_A 0x28
#define M_WHO_AM_I 0x0F
#define CTRL_REG1_M 0x20
#define CTRL_REG2_M 0x21
#define CTRL_REG3_M 0x22
#define CTRL_REG4_M 0x23
#define CTRL_REG5_M 0x25
#define STATUS_REG_M 0x27
#define OUT_M 0x28
#define PRINT_RATE 40 // PRINT_RATE Hzで出力する
#define ACCELERATION_SENSITYVITY 0.000244 // scale 2g=0.061, 4g=0.122, 8g=0.244, 16g=0.732 mg/LSB
#define MAGNETIC_SENSITYVITY 0.00043 // scale 4=0.14, 8=0.29, 12=0.43, 16=0.58 mgauss/LSB
#define ANGULAR_SENSITYVITY 0.00875 // scale 245=8.75, 500=17.5, 2000=70 mdps/LSB
#define TEMPERATURE_SENSITYVITY 16 // LSB/℃
uint8_t ODR_G = 3; // Output data rate: 1=14.9, 2=59.5, 3=119, 4=238, 5=476, 6=952 Hz
uint8_t FS_G = 0; // Full scale: 0=245, 1=500, 2=no, 3=2000 dps
uint8_t BW_G = 0; // cutoff frequency: table 47
uint8_t LP_mode = 0; // low power mode: 0=disable, 1=enable
uint8_t HP_EN = 1; // high pass filter: 0=disable, 1=enable
uint8_t HPCF_G = 1; // high pass cutoff frequency: table 52
uint8_t Zen_G = 1; // enable gyro Z: 0=disable, 1=enable
uint8_t Yen_G = 1; // enable gyro Y: 0=disable, 1=enable
uint8_t Xen_G = 1; // enable gyro X: 0=disable, 1=enable
uint8_t LIR_XL1 = 1; // latch interrupt: 0=no request, 1=request
uint8_t FourD_XL1 = 0;
uint8_t SignX_G = 0; // x axis sign: 0=positive, 1=negative
uint8_t SignY_G = 0; // y axis sign: 0=positive, 1=negative
uint8_t SignZ_G = 0; // z axis sign: 0=positive, 1=negative
uint8_t Orient = 0;
uint8_t DEC_ = 0;
uint8_t Zen_XL = 1; // enable accel Z: 0=disable, 1=enable
uint8_t Yen_XL = 1; // enable accel Y: 0=disable, 1=enable
uint8_t Xen_XL = 1; // enable accel X: 0=disable, 1=enable
uint8_t ODR_XL = 3; // Output date rate: 1=10, 2=50, 3=119, 4=238, 5=476, 6=952 Hz
uint8_t FS_XL = 3; // Full scale: 0=2, 1=16, 2=4, 3=8 g
uint8_t BW_SCAL_ODR = 1; // 0=band width determined by ODR, 1=determined by BW_XL
uint8_t BW_XL = 0; // band width: 0=408, 1=211, 2=105, 3=50 Hz
uint8_t HR = 0; // high resolution mode: 0=disable, 1=enable
uint8_t DCF = 0; // low pass cutoff frequency: 0=ODR/50, 2=ODR/9, 1=ODR/100, 3=ODR/400
uint8_t FDS = 0;
uint8_t HPIS = 0;
uint8_t TEMP_COMP = 0; // temperature compensation: 0=disable, 1=enable
uint8_t OM = 0; // operation mode: 0=continuous-conversion, 1=single-conversion, 2=power-down
uint8_t DO = 7; // Output data rate: 0=0.625, 1=1.25, 2=2.5, 3=5, 4=10, 5=20, 6=40, 7=80 Hz
uint8_t FAST_ODR = 0;
uint8_t ST = 0;
uint8_t FS = 2; // full scale: 0=4, 1=8, 2=12, 3=16 gauss
uint8_t REBOOT = 0;
uint8_t SOFT_RST = 0;
uint8_t I2C_DISABLE = 0; // I2c interface: 0=enable, 1=disable
uint8_t LP = 0; // low power mode: 0=disable, 1=enable
uint8_t SIM = 0; // SPI interface
uint8_t MD = 0; // operation mode: 0=continuous-conversion, 1=single-conversion, 2=power-down
uint8_t OMZ = 3; // z axis operation mode: 0=low power, 1=medium, 2=high, 3=ultra-high performance
uint8_t BLE = 0;
uint8_t FAST_READ = 0;
uint8_t BDU = 0;
// 時間変数
unsigned long InitTime, RunTime, PrintTime, sample;
uint8_t PrintRate = 1000/PRINT_RATE;
int16_t AccX, AccY, AccZ;
float Ax, Ay, Az;
int16_t GyrX, GyrY, GyrZ;
float Gx, Gy, Gz;
int16_t MagX, MagY, MagZ;
float Mx, My, Mz;
int16_t Temp;
float Te;
double phiA, thetaA;
double phiG, thetaG, psiG;
double phi, theta, psi;
uint8_t I2Cread1byte(uint8_t DeviceAddress, uint8_t SlaveAddress)
{
Wire.beginTransmission(DeviceAddress); // 通信を開始する
Wire.write(SlaveAddress); // レジスターアドレスを送信
Wire.endTransmission(false); // リスタートメッセージをリクエストの後に送信し,接続を続ける
Wire.requestFrom(DeviceAddress, (uint8_t) 1); // 1 byte分のデータを要求する
return Wire.read(); // データを返す
}
uint8_t I2CreadMULTIbyte(uint8_t DeviceAddress, uint8_t SlaveAddress, uint8_t num, uint8_t * data)
{
Wire.beginTransmission(DeviceAddress);
Wire.write(SlaveAddress|0x80);
Wire.endTransmission(false);
Wire.requestFrom(DeviceAddress, num);
for (uint8_t i=0; i<num; i++)
{
data[i] = Wire.read();
}
return num;
}
void I2Cwrite1byte(uint8_t DeviceAddress, uint8_t SlaveAddress, uint8_t data)
{
Wire.beginTransmission(DeviceAddress); // 通信を開始する
Wire.write(SlaveAddress); // レジスターアドレスを送信
Wire.write(data); // レジスターアドレスを送信
Wire.endTransmission(); // 通信を終了する
}
bool LSM9DS1setting()
{
uint8_t who_ag, who_m;
uint8_t RegisterData = 0;
RegisterData=ODR_G<<5;
RegisterData|=FS_G<<3;
RegisterData|=BW_G;
I2Cwrite1byte(AG_DEVICE_ADDRESS, CTRL_REG1_G, RegisterData);
RegisterData=0;
I2Cwrite1byte(AG_DEVICE_ADDRESS, CTRL_REG2_G, RegisterData);
RegisterData=LP_mode<<7;
RegisterData|=HP_EN<<6;
RegisterData|=HPCF_G;
I2Cwrite1byte(AG_DEVICE_ADDRESS, CTRL_REG3_G, RegisterData);
RegisterData=0;
RegisterData=Zen_G<<5;
RegisterData|=Yen_G<<4;
RegisterData|=Xen_G<<3;
RegisterData|=LIR_XL1<<2;
RegisterData|=FourD_XL1;
I2Cwrite1byte(AG_DEVICE_ADDRESS, CTRL_REG4, RegisterData);
RegisterData=0;
RegisterData=SignX_G<<5;
RegisterData|=SignY_G<<4;
RegisterData|=SignZ_G<<3;
RegisterData|=Orient;
I2Cwrite1byte(AG_DEVICE_ADDRESS, ORIENT_CFG_G, RegisterData);
RegisterData=0;
RegisterData=DEC_<<6;
RegisterData|=Zen_XL<<5;
RegisterData|=Yen_XL<<4;
RegisterData|=Xen_XL<<3;
I2Cwrite1byte(AG_DEVICE_ADDRESS, CTRL_REG5_XL, RegisterData);
RegisterData=0;
RegisterData=ODR_XL<<5;
RegisterData|=FS_XL<<3;
RegisterData|=BW_SCAL_ODR<<2;
RegisterData|=BW_XL;
I2Cwrite1byte(AG_DEVICE_ADDRESS, CTRL_REG6_XL, RegisterData);
RegisterData=0;
RegisterData=HR<<7;
RegisterData|=DCF<<5;
RegisterData|=FDS<<2;
RegisterData|=HPIS;
I2Cwrite1byte(AG_DEVICE_ADDRESS, CTRL_REG7_XL, RegisterData);
RegisterData=0;
RegisterData=TEMP_COMP<<7;
RegisterData|=OM<<5;
RegisterData|=DO<<2;
RegisterData|=FAST_ODR<<1;
RegisterData|=ST;
I2Cwrite1byte(M_DEVICE_ADDRESS, CTRL_REG1_M, RegisterData);
RegisterData=0;
RegisterData=FS<<5;
RegisterData|=REBOOT<<3;
RegisterData|=SOFT_RST<<2;
I2Cwrite1byte(M_DEVICE_ADDRESS, CTRL_REG2_M, RegisterData);
RegisterData=0;
RegisterData=I2C_DISABLE<<7;
RegisterData|=LP<<5;
RegisterData|=SIM<<2;
RegisterData|=MD;
I2Cwrite1byte(M_DEVICE_ADDRESS, CTRL_REG3_M, RegisterData);
RegisterData=0;
RegisterData=OMZ<<2;
RegisterData|=BLE<<1;
I2Cwrite1byte(M_DEVICE_ADDRESS, CTRL_REG4_M, RegisterData);
RegisterData=0;
RegisterData=FAST_READ<<7;
RegisterData|=BLE<<6;
I2Cwrite1byte(M_DEVICE_ADDRESS, CTRL_REG5_M, RegisterData);
who_ag = I2Cread1byte(AG_DEVICE_ADDRESS, AG_WHO_AM_I);
who_m = I2Cread1byte(M_DEVICE_ADDRESS, M_WHO_AM_I);
if (who_ag==0x68&&who_m==0x3D)
{
return true;
}
else
{
return false;
}
}
void GetAccel()
{
uint8_t data[6];
if(I2Cread1byte(AG_DEVICE_ADDRESS, STATUS_REG_AG)&1) // データの更新確認
{
if(I2CreadMULTIbyte(AG_DEVICE_ADDRESS, OUT_A, 6, data)==6)
{
AccX = ((data[1]<<8)|data[0]);
AccY = ((data[3]<<8)|data[2]);
AccZ = ((data[5]<<8)|data[4]);
}
}
}
void GetGyro()
{
uint8_t data[6];
if(I2Cread1byte(AG_DEVICE_ADDRESS, STATUS_REG_AG)&2) // データの更新確認
{
if(I2CreadMULTIbyte(AG_DEVICE_ADDRESS, OUT_G, 6, data)==6)
{
GyrX = (data[1]<<8)|data[0];
GyrY = (data[3]<<8)|data[2];
GyrZ = (data[5]<<8)|data[4];
}
}
}
void GetTemp()
{
uint8_t data[6];
if(I2Cread1byte(AG_DEVICE_ADDRESS, STATUS_REG_AG)&4) // データの更新確認
{
if(I2CreadMULTIbyte(AG_DEVICE_ADDRESS, OUT_T, 2, data)==2)
{
Temp = (data[1]<<8)|data[0];
}
}
}
void GetMag()
{
uint8_t data[6];
if(I2Cread1byte(M_DEVICE_ADDRESS, STATUS_REG_M)&8) // データの更新確認
{
if(I2CreadMULTIbyte(M_DEVICE_ADDRESS, OUT_M, 6, data)==6)
{
MagX = (data[1]<<8)|data[0];
MagY = (data[3]<<8)|data[2];
MagZ = (data[5]<<8)|data[4];
}
}
}
void setup() {
Serial.begin(9600); // シリアル通信のレートを設定
Wire.begin(); // I2C通信の初期化
if(LSM9DS1setting())
{
Serial.println("LSM9DS1 setting success");
}
else
{
Serial.println("LSM9DS1 setting failure");
}
InitTime = millis();
sample = 0;
}
void loop() {
RunTime = millis()-InitTime;
GetAccel();
GetGyro();
if((millis()-PrintTime)>PrintRate)
{
Ax = AccX*ACCELERATION_SENSITYVITY;
Ay = AccY*ACCELERATION_SENSITYVITY;
Az = AccZ*ACCELERATION_SENSITYVITY;
Gx = GyrX*ANGULAR_SENSITYVITY*PI/180;
Gy = GyrY*ANGULAR_SENSITYVITY*PI/180;
Gz = GyrZ*ANGULAR_SENSITYVITY*PI/180;
phiA = atan2(-Ay,Az);
thetaA = atan2(Ax,sqrt(pow(Ay,2)+pow(Az,2)));
phiG = phi+(Gx+sin(phi)*tan(theta)*Gy+cos(phi)*tan(theta)*Gz)*(millis()-PrintTime)/1000.00;
thetaG = theta+(cos(phi)*Gy-sin(phi)*Gz)*(millis()-PrintTime)/1000.00;
psiG = psi+(sin(phi)/cos(theta)*Gy+cos(phi)/cos(theta)*Gz)*(millis()-PrintTime)/1000.00;
phi = 0.95*phiG+0.05*phiA;
theta = 0.95*thetaG+0.05*thetaA;
psi = 1.00*psiG;
Serial.print("sample:\t");
Serial.print(sample);
Serial.print("\tphi:\t,");
Serial.print((int)(phi*180/PI));
Serial.print("\ttheta:\t,");
Serial.print((int)(theta*180/PI));
Serial.print("\tpsi:\t");
Serial.println((int)(psi*180/PI));
PrintTime = millis();
sample++;
}
}
方位角の\(\psi\)だけは単純な積分しかしていないため,時間の経過とともにずれていくと思いますが,それ以外の姿勢角は正確に算出できると思うので,皆さんも試してみてください.
これの動作結果はこちらで報告しているので読んでみてください.
まとめ
この記事ではセンサーフュージョンについて解説しました.
今回のセンサーフュージョンで十分正確な姿勢角の算出ができました.
これ以上の精度を求める場合は,調節する\(k\)の値を工夫してみたり,カルマンフィルタを使ってノイズの除去を行ってみると良いかもしれません.
続けて読む
この記事で公開したプログラムを使用すれば,姿勢角の算出ができます.
しかし,数字で姿勢角が表示されても直感的には理解できません.
そこで,以下の記事ではProcessingというソフトを使用して姿勢角のビジュアル化を行っています.
これを使用することでアニメーションで表示することができます.興味がある方は是非読んでみてください.
Twitterでは記事の更新情報や活動の進捗などをつぶやいているので気が向いたらフォローしてください.
それでは最後まで読んでいただきありがとうございました.
コメント
[…] Arduinoでモータを制御する方法センサーを使って姿勢角を算出する方法 […]
[…] モーターの電子回路姿勢角算出センサーの電子回路 […]