Table of Contents
プログラミングで扱う内容
プログラミングでは、倒立振子・自己バランスロボット(以下は自己バランスロボットと表記します)を動かすための プログラムと制御ロジック を解説します。自己バランスロボットの自立の制御方法は、ものすごく単純に書くと、[ロボットの傾斜角度を測定し]、傾斜角度の測定値と傾斜角度の目標値に差があれば、[測定値と目標値の差が減るようにモータを回転させる]です。それぞれの部品をからデータを取得し、そのデータに従って操作して、以下のようなフローでバランスを取る動作を実現します。
- GY521(MPU6050)で加速度・角速度を測定
- 加速度・角速度の測定値から傾斜角度を計算
- 傾斜角度を補正
- 傾斜角度の目標値に対してのPID 制御
- サーボモーター制御
- HC-SR04 による距離検知による衝突回避
プログラム作成の流れ
- FS90RとGY521(MPU6050)とのオフセット値の測定
- 連続サーボモータFS90Rは、ある値を設定するとモータが止まり、その値をずらすとモータが回転します。しかし、この値は部品ごとにばらつきがあります。モータの制御はこの値を中心としますから、この動作中心値を測定することが必要です。
- 加速度・角速度センサGY521(MPU6050)で計測される角速度は、センサが静止状態では、”0″の値のはずです。しかし製造のバラツキからこの値は”0″にはならずオフセット値を持っています。角速度は角度計算に使用するので、センサが静止状態でオフセット値を測定し、この値を測定値から減算して使用します。
- 自己バランス制御プログラミング
- デバッグおよびチューニング
- 障害物回避ロジックをプログラムに追加
スケッチで使用するライブラリ
- 加速度・角速度センサGY521(MPU6050) を操作するためのライブラリ
- <Wire.h> : GY521(MPU650)はI2CというプロトコルでArduinoと接続します。I2C接続のためのライブラリです。
- <MPU6050.h> : GY521(MPU650)を操作するためのライブラリです。
- 連続回転サーボモータFS90Rを操作するためのライブラリ
- <Servo.h> : 連続サーボモータFS90Rを制御するためのライブラりを使います
連続回転サーボモータの動作中心値の測定
- 連続回転サーボモータは、50HzのPWMで制御されており、writeMicroseconds()関数にパルス幅が1500usを代入した時に回転が止まり、パルス幅を1500usから上下に変化させると異なる方向に回転する仕様です。連続回転サーボモータの回転動作を[Arduinoの割込み関数を使ってサーボモーターの回転速度を測定しました。]で学習し、回転速度を測定しました。実際の連続回転サーボモータには個体差があり、パルス幅が1500us付近でモータが回転しない不感帯があり、その中心のパルス幅は1500usから少しずれていることが解ります。下図を参照ください。

- 自己バランスロボットは、連続回転サーボモータを2個使います。2個のモータを[倒立振子・自己バランスロボットの作成 – 回路設計]の記事で作成した電気回路に接続して、パルス幅を1500usから変化させ、それぞれの連続回転サーボモータの不感帯を測定し、動作の中心値を求めます。
- スケッチで連続回転サーボモータをwriteMicroseconds()関数を使って回転を制御します。サーボモータはwrite()関数で角度指定をして回転させるのでは?とも思いますが、ライブライりのコードを確認すると、write()関数は、内部では角度をusecに変換しwriteMicroseconds()関数を呼んでいます。角度設定で連続回転を制御すると、イメージ的にも変かなと感じましたのでwriteMicroseconds()関数を使っています。
- 「int speedPulse = 1500; // 回転速度を設定」の行のspeedPulseの数値を最初は10程度変化させながらモータが回転するかしないかを確認します。
////////////////////////////////////////////////////////////////////////
// 連続回転サーボモータをwriteMicroseconds()関数を使って回転させるスケッチ
////////////////////////////////////////////////////////////////////////
#include <Servo.h>
Servo servo1; // サーボ1(ピン5)
Servo servo2; // サーボ2(ピン6)
void setup() {
Serial.begin(9600); //シリアル通信を9600bpsで開始
servo1.attach(5);
servo2.attach(6);
}
void loop() {
// SG90-HVの基準値は1500µs(停止)
int speedPulse = 1500; // 回転速度を設定
servo1.writeMicroseconds(speedPulse);
servo2.writeMicroseconds(speedPulse);
// 回転速度設定値を表示
Serial.print("SpeedPulse: ");
Serial.println(speedPulse);
}- 2個の連続回転サーボモータの不感帯の測定が終わりました。以下の結果です。この値を自己バランスロボットの制御に使います。
| 連続回転サーボモータ #1 | 不感帯(us) 1390 ~ 1453 | 不感帯中心値(us) 1422 |
| 連続回転サーボモータ #2 | 不感帯(us) 1410 ~ 1468 | 不感帯中心値(us) 1439 |
加速度・角速度センサ―のオフセットの測定
- 加速度・角速度センサ―GY-521 (MPU6050)は、加速度および角速度をX,Y,Z軸の3軸で測定します。角速度はGY-521が静止した状態では0のはずですが、製造のバラツキなどからある値を持ってしまいます。自己バランスロボットをバランスの取れた静止状態にして、GY-521の角速度の値を読み出し、この値を角速度のオフセットとして、自己バランスロボットの制御に使用します。
- 自己バランスロボットが自立する位置を固定して、GY-521の出力を1000回測定し、オフセット値とします。この値は自己バランスロボットの制御用スケッチの中で使用します。
////////////////////////////////////////////////////////////////////////
//GY-521(加速度・角速度センサ)の加速度と角速度のオフセット値を計測するスケッチ
////////////////////////////////////////////////////////////////////////
#include <Wire.h>
#include <MPU6050.h>
MPU6050 mpu;
long accelX_sum = 0;
long accelY_sum = 0;
long accelZ_sum = 0;
long gyroX_sum = 0;
long gyroY_sum = 0;
long gyroZ_sum = 0;
void setup() {
Serial.begin(9600); // シリアルモニタを9600bpsで開始
Wire.begin(); // I2C開始
mpu.initialize(); // MPU6050初期化
if (!mpu.testConnection()) {
Serial.println("MPU6050接続エラー");
while (1);
}
Serial.println("MPU6050接続成功");
Serial.println("静止状態で1000回データ取得中...");
}
void loop() {
// 1000回サンプリング
for (int i = 0; i < 1000; i++) {
int16_t ax, ay, az;
int16_t gx, gy, gz;
mpu.getMotion6(&ax, &ay, &az, &gx, &gy, &gz);
accelX_sum += ax;
accelY_sum += ay;
accelZ_sum += az;
gyroX_sum += gx;
gyroY_sum += gy;
gyroZ_sum += gz;
delay(2); // サンプリング間隔(約2ms)
}
// 平均値計算
long accelX_avg = accelX_sum / 1000;
long accelY_avg = accelY_sum / 1000;
long accelZ_avg = accelZ_sum / 1000;
long gyroX_avg = gyroX_sum / 1000;
long gyroY_avg = gyroY_sum / 1000;
long gyroZ_avg = gyroZ_sum / 1000;
// 結果出力
Serial.println("=== 平均値 ===");
Serial.print("Accel X: "); Serial.println(accelX_avg);
Serial.print("Accel Y: "); Serial.println(accelY_avg);
Serial.print("Accel Z: "); Serial.println(accelZ_avg);
Serial.print("Gyro X: "); Serial.println(gyroX_avg);
Serial.print("Gyro Y: "); Serial.println(gyroY_avg);
Serial.print("Gyro Z: "); Serial.println(gyroZ_avg);
// 一度だけ計算して終了
while (1);
}
- 使用したGY-521のオフセットは、X軸: -704、Y軸 -301、Z軸 -130、でした。
自己バランスロボットの傾きの測定方法は?
- ロボットの傾きを測定するには、MPU6050のライブラリで提供されているgetMotion6()関数を使います。この関数で得られた加速度から倒立角度を計算します。得られた角速度は測定済みのオフセットを引いて使用します。[ArduinoでGY-521: MPU6050 (3軸 加速度・角速度センサ)から加速度と角速度を読み出す仕様を調べました ]で学習したようにMPU6050にはDLPF(デジタルローパスフィルター)が内蔵されています。測定誤差で加速度・角速度値が大きく変動するのを避けるため、この値を最大の6(帯域幅 約5Hz)に設定して使用します。
目標角度との差が減るようにモータを回転させる方法は?
- 測定角度と目標値の差を減らす制御には、PID制御を用いました。Webで検索すると解説と実施例が多く見つかります。積分項が積みあがると前方若しくは後方に動くので、積分項はある大きさ以上で0に戻しています。MPU6050の角速度出力はドリフトします。ドリフトの補正に相補フィルタを使用しました。連続回転サーボモータは動作の中心を不感帯の中心値に設定します。
- 作成した自己バランスロボットは倒れてしまうと、自分自身では立ち上がれません。倒れても車輪を回転させ続けるとモーター駆動ICや電源ICが壊れるかもしれません。傾斜角度が90° +/- 60°を超えるとバランスを回復することは難しいとし、その場合はモーターの回転を止めます。
- 距離センサの測定値が5cm以下になると、自己バランスロボットを意図的に動かせます。そのために目標角度を0度から5度に変更します。
////////////////////////////////////////////////////////////////////////
// 自己バランスロボット バランス制御
////////////////////////////////////////////////////////////////////////
#include <Wire.h>
#include <MPU6050.h>
#include <Servo.h>
// --- ピン設定 ---
#define TRIG_PIN 2
#define ECHO_PIN 3
#define SERVO_LEFT_PIN 5
#define SERVO_RIGHT_PIN 6
// --- サーボのニュートラルポイント ---
const int SERVO_LEFT_NEUTRAL = 1461; // マイクロ秒
const int SERVO_RIGHT_NEUTRAL = 1438; // マイクロ秒
// --- MPU6050のオフセット値 ---
const int16_t GYRO_X_OFFSET = -704;
const int16_t GYRO_Y_OFFSET = -301;
const int16_t GYRO_Z_OFFSET = -130;
// --- PIDパラメータ ---
float Kp = 20.0; // 比例ゲイン
float Ki = 0.1; // 積分ゲイン
float Kd = 0.5; // 微分ゲイン
// --- 相補フィルタ ---
const float alpha = 0.98; // ジャイロ積分の重み
float filteredAngle = 0.0;
// --- 制御の制限値 ---
const int MAX_OUTPUT = 500;
// --- 変数 ---
MPU6050 mpu;
Servo servoLeft, servoRight;
float previousError = 0.0;
float integral = 0.0;
unsigned long lastTime = 0;
// --- セットアップ ---
void setup() {
Serial.begin(115200);
Wire.begin();
// MPU6050を初期化
mpu.initialize();
if (!mpu.testConnection()) {
Serial.println("MPU6050接続失敗!");
while (1);
}
// DLPFを6に設定(帯域幅 約5Hz)
mpu.setDLPFMode(6);
// サーボを初期化
servoLeft.attach(SERVO_LEFT_PIN);
servoRight.attach(SERVO_RIGHT_PIN);
// 超音波センサを初期化
pinMode(TRIG_PIN, OUTPUT);
pinMode(ECHO_PIN, INPUT);
lastTime = millis();
}
// --- ループ処理 ---
void loop() {
// MPU6050のデータを読み取る
int16_t ax, ay, az, gx, gy, gz;
mpu.getMotion6(&ax, &ay, &az, &gx, &gy, &gz);
// ジャイロのオフセットを適用
gx -= GYRO_X_OFFSET;
gy -= GYRO_Y_OFFSET;
gz -= GYRO_Z_OFFSET;
// 加速度センサから傾斜角度を計算
float accelAngle = atan2((float)ay, (float)az) * 180.0 / PI;
// 時間差(Δt)
unsigned long currentTime = millis();
float dt = (currentTime - lastTime) / 1000.0;
lastTime = currentTime;
// ジャイロの回転速度(度/秒に変換)
float gyroRate = gx / 131.0; // MPU6050感度: 131 LSB/(deg/s)
// 相補フィルタ処理
filteredAngle = alpha * (filteredAngle + gyroRate * dt) + (1 - alpha) * accelAngle;
// 超音波距離を取得
long distance = getDistance();
// 目標角度を決定
float targetAngle = 0.0; // デフォルトは0°
if (distance < 5) {
targetAngle = 5.0; // 距離が5cm未満なら目標角度を5°に設定
}
// 傾斜が±60°を超えたらモーターを停止
if (abs(filteredAngle) > 60) {
stopMotors();
Serial.println("傾斜が60°を超えたため、モーターを停止しました。");
return;
}
// PID制御
float error = targetAngle - filteredAngle; // 目標角度を使用
integral += error * dt;
// integralが200を超えたらリセット
if (abs(integral) > 200) {
integral = 0.0;
Serial.println("Integralが200を超えたためリセットしました。");
}
float derivative = (error - previousError) / dt;
previousError = error;
float output = Kp * error + Ki * integral + Kd * derivative;
// 出力を±500に制限
if (output > MAX_OUTPUT) output = MAX_OUTPUT;
if (output < -MAX_OUTPUT) output = -MAX_OUTPUT;
// モーターを制御
controlMotors(output);
// デバッグ情報
Serial.print("Distance: "); Serial.print(distance);
Serial.print(" cm | AccelAngle: "); Serial.print(accelAngle);
Serial.print(" | FilteredAngle: "); Serial.print(filteredAngle);
Serial.print(" | TargetAngle: "); Serial.print(targetAngle);
Serial.print(" | Integral: "); Serial.print(integral);
Serial.print(" | Output: "); Serial.println(output);
}
// --- モーター制御 ---
void controlMotors(float output) {
int leftSpeed = SERVO_LEFT_NEUTRAL - (int)output;
int rightSpeed = SERVO_RIGHT_NEUTRAL + (int)output;
servoLeft.writeMicroseconds(leftSpeed);
servoRight.writeMicroseconds(rightSpeed);
}
// --- モーター停止 ---
void stopMotors() {
servoLeft.writeMicroseconds(SERVO_LEFT_NEUTRAL);
servoRight.writeMicroseconds(SERVO_RIGHT_NEUTRAL);
}
// --- 超音波距離測定 ---
long getDistance() {
digitalWrite(TRIG_PIN, LOW);
delayMicroseconds(2);
digitalWrite(TRIG_PIN, HIGH);
delayMicroseconds(10);
digitalWrite(TRIG_PIN, LOW);
long duration = pulseIn(ECHO_PIN, HIGH);
long distance = duration * 0.034 / 2;
return distance;
}
自己バランスロボットが期待通りに動かなかったら
- シリアルモニタで角度・距離を確認
- PID の値を調整
- モーターの回転方向が逆なら修正
- HC-SR04 の値が不安定なら、
- 電源ノイズ
- 配線距離
- 取り付け角度
自己バランスロボットが自立しました!
- 自立できるようになるまで、PID制御係数を調整します。根気の必要な作業です。映像はPID制御係数調整後にバランスが取れているロボットの動きです。(13秒の短い動画です)
実際は色々苦労していました
- 回路を設計し、自作シールドを作り、筐体を作って、組み立てて、後はプログラムを作れば完成と思って、プログラムを作りましたが、全く自立できませんでした。色々とWebを調べました。角度ドリフトの補正は、カルマンフィルターかMadgwickフィルターの精度が良いとの記事もあり、試しましたが効果がありません。PID制御係数を色々と変化させましたが効果がありません。PID制御をスケッチ内の計算から、PID_V1.hを使ったライブラリに変更しても効果がありません。
- 連続回転サーボモータを使って自己バランスロボットを作っている例はあまりなく、触れてはいけない構成だったのか?などと思い、また回路の作成時間と筐体の作成時間を思い出して、無駄になったのか?と悲観に暮れていました。連続回転サーボモータは[Arduinoの割込み関数を使ってサーボモーターの回転速度を測定しました。]のブログで、簡易的なタコメータを作って回転動作を調べていたので、自己バランスができるのではないかと思っていたのですが…。このブログの学習で連続回転サーボモータに回転の不感帯があることを知りました。そうか、連続回転サーボモータをwriteMicroseconds()関数で動かすときは、不感帯の中心値から制御しないといけないと思い付き、それをスケッチに加え、PIDの係数を根気よく調整するとやっと自立しました。
- 現時点では長時間自立させていると急に動いて倒れることがあり、まだPIDの係数の微調整が必要ですが、通常は安定して自立できているので、まずは一安心です。
- 連続回転サーボモータを駆動する記事は?
- [Arduinoでサーボモータ(SG90、SG90-HV)を操作しました。]
- [Arduinoの割込み関数を使ってサーボモーターの回転速度を測定しました。]
- [Arduinoを使ったタコメーターにI2C LCDを接続しサーボモーターの回転速度を表示しました]
- 加速度、角速度センサGY-521(MOU6050)を使って加速度・角速度を測定する記事は?
まとめ
倒立振子・自己バランスロボットの 回路 → 筐体 → プログラム を一通り解説しました。Arduinoを使い始めて、1回は作ってみたいと思っていました。全ての工程を終わらせるには時間はかかりましたが、自己バランスロボットが完成していい経験と勉強になりました。
今後は、異なるモータを使って倒立振子・自己バランスロボットを作成したいと考えています。
御質問、誤植の指摘、記事の改善点の気づきなどありましたら「問い合わせ 」のページからお願いします。

