エンコーダ付きDCモータPID制御の実験-haya_imu応用例

はじめに

DCモータに対する、PID制御とは、制御量(本文では減速機出力シャフトの回転速度、角速度といい)と、目標値(本文ではターゲット回転速度、目標角速度といい)の差分(本文ではエラーといい)を無くすための操作量(PWMパルス出力)に関わる、P(比例)制御、I(積分)制御、D(微分)制御をかけるとのこと。ロータリエンコーダは回転速度を安易に計算可能な要素(A相/B相パルス)を提供する、常用デバイスとして利用される。本実験の趣旨としては、回転速度の計算ベースとなる、エンコーダのA/B相パルスは正しく計測されたかどうか、またPID制御の精度、確度を評価するに当たって、他のデバイス、本実験ではhaya_imu(ICM-42688、MMC5983MA内蔵)を活用して評価すること。

実験環境

●12V入力DCブラシモータ
●12V出力DC電源(Motor Shieldへ給電)
●磁気式エンコーダ
●Arduino Leonardo正規品基板
●Adafruit Motor Shield v1.2互換基板(ライブラリ修正あり、Timer3A/D5-pin/PWM周波数を4KHzへ変更済み)
●9軸センサhaya_imu v3.2
●Raspberry Pi 3 Model-B(ROS Slave、Unbuntu20.04/Noetic、haya_imuへ接続)
●5V出力DC電源(Raspberry Piへ給電)
●Lenovo L560(ROS Master、Unbuntu18.04/Melodic、Arduino Leonardoへ接続)

haya_imu用いてDCモータPID制御評価環境
haya_imu用いてDCモータPID制御評価環境

開発要素

ROSパッケージ

以下ROSパッケージ、ROSカスタムメッセージまたはライブラリをインストールして、catkin_makeしておく。

rosserial
haya_motor_ros
haya_imu_ros
ros_lib by rosserail_arduino with Arduino IDE
Adafruit-Motor-Shield-library-leonardo
arduino_node(ino) on Leonardo with Arduino IDE 

ROSノード

/arduino_haya_motor
/haya_imu_node
/haya_motor_node
/rosout
/rqt_plot

ROSトピック

/arduino_msg
/diagnostics
/haya_angular_velocity_z
/imu_data
/pid_params
/rosout
/rosout_agg

ROSカスタムメッセージ

haya_imu_ros/ImuData
haya_motor_ros/ArduinoMsgs
haya_motor_ros/PidMsgs

ROSノードの相互作用状況

エンコーダ付きDCモータPID制御の実験-ROS node & ROS topic
エンコーダ付きDCモータPID制御の実験-ROS node & ROS topic

Arduinoノード

エンコーダA相パルス割込みハンドラ

  if (digitalRead(ENCODER_A) != digitalRead(ENCODER_B)) {
    current_counter++;
  }
  else {
    current_counter--;
  }

エンコーダB相パルス割込みハンドラ

  if (digitalRead(ENCODER_A) == digitalRead(ENCODER_B)) {
    current_counter++;
  }
  else {
    current_counter--;
  }

エンコーダカウンタによる回転速度

// Run the PID loop at 100 times per second
#define PID_RATE_HZ 10 // 10Hz
// Convert the rate into an interval
#define PID_INTERVAL_MS (1000 / PID_RATE_HZ) // 10ms
#define PID_INTERVAL_S (float)(1.0 / PID_RATE_HZ) // 0.1s
#define PPR 12 // Encoder pulse / round
#define COUNTER_FACTOR 4 // 1*encoder-pulse = 4*counter
#define REDUCTION_RATIO 100 // Gear reduction ratio
#define CPR (PPR * COUNTER_FACTOR * REDUCTION_RATIO) // Counters of encoder / round
current_velocity = (current_counter - previous_counter) * 360.0 / (CPR * PID_INTERVAL_S);

PID係数

本実験環境で何回も実験を繰り返して、納得いくPID係数Kp、Ki、Kdを決めておく。

PID操作量

●Position法

  error = target_velocity - current_velocity;
  integral += error * PID_INTERVAL_S;
  differential = (error - previous_error) / PID_INTERVAL_S;
  previous_error = error;
  pwm = (int32_t)(Kp * error + Ki * integral + Kd * differential);

●Increment法

  error = target_velocity - current_velocity;
  proportion = Kp * (error - previous_error);
  integral = Ki * error * PID_INTERVAL_S;
  differential = Kd * (error - 2 * previous_error + previous_error2) / PID_INTERVAL_S;
  pwm += (int32_t)(proportion + integral + differential);
  previous_error2 = previous_error;
  previous_error = error;

実験手順

Run roscore

Run roscore@ROS Master

roscore

Launch haya_imu_node

Launch haya_imu_node@ROS Slave

roslaunch haya_imu_ros haya_imu.launch

Launch haya_motor_node

Launch haya_motor_node@ROS Master

roslaunch haya_motor_ros haya_motor.launch

結果確認

PID制御の目標値、制御量

以下のデータを表示させて、エンコーダ、IMUからのカウンタによる回転速度を確かめて、PID係数Kp、Ki、Kdを決めてまた、エンコーダまたは、PID制御を評価する。PWM周波数をデフォルトの490Hzから4KHzに変更することで回転速度の分散は小さくなっている。これは490Hzより4KHz周波数のほうはモータにブレーキをかけずにPWM波形は滑らかになって果たしてモータ出力シャフトの回転速度も滑らかになったわけである。

/haya_angular_velocity_z 
/pid_params/target_velocity
/arduino_msg/current_velocity
PID制御の目標値、エンコーダによる回転速度、haya_imu測った回転速度曲線
PID制御の目標値、エンコーダによる回転速度、haya_imu測った回転速度曲線

haya_imuで測った回転速度が、エンコーダによる回転速度より分散が大きくなって、これは測定法および測定ポジションは違って、またモータシャフトによる振動や、慣性力に由来するものと考えられる。

PID制御の目標値、制御量、操作量

PID制御の目標値、PWM操作量、エンコーダによる回転速度

PID制御の目標値、PWM操作量、エンコーダによる回転速度
PID制御の目標値、PWM操作量、エンコーダによる回転速度

PID制御の操作量PWM波形

オシロスコープは測った操作量PWMの波形、モータコイルに起因する逆起電力による、コイルサージは約-14Vあったと、モータシールド実装モータドライバL293Dにコイルサージ(逆起電流)を流すダイオードが効いていると考えられる。ないと一瞬-12Vの数十倍~-1千万V(無限大)に達する可能性ある。これで回路で繋がっているデジタルICを一発でぶち壊すことになる。

PID制御の操作量PWM波形
PID制御の操作量PWM波形

エンコーダ出力パルス波形

約1/10の確率でノイズに起因するスパイクが起きるらしいので、MCUにノイズフィルタ実装の入力PINは望ましい。

エンコーダパルス波形ノイズスパイクあり
エンコーダパルス波形ノイズスパイクあり

リポジトリ

haya_motor_ros、arduino_node、修正ありMotor Shieldライブラリ含むリポジトリは、https://github.com/soarbear/haya_motor_ros に公開済み(BSD 3-Clause License)

最後に

IMUはモータシャフトでなくロボット本体に装着した場合、エンコーダのみならずLidar、カメラ、GPS他のセンサーとフュージョンする場合多い。

参考記事

ロータリエンコーダによる速度計算
9軸センサーICM-42688+MMC5983 6軸&9軸回転ベクトル&3軸オイラー角 MAX1000Hz同時出力 ROS/ROS2対応 USB接続

0

ロボット・ドローン部品お探しなら
ROBOT翔・電子部品ストア

エンコーダ付きDCモータPID制御の実験-hayate_imu応用例

はじめに

DCモータに対する、PID制御とは、制御量(本文では出力減速機シャフトの回転速度、角速度といい)と、目標値(本文ではターゲット回転速度、目標角速度といい)の差分(本文ではエラーといい)を無くすための操作量(PWMパルス出力)に関わる、P(比例)制御、I(積分)制御、D(微分)制御をかけるとのこと。ロータリエンコーダは回転速度を安易に計算可能な要素(A相/B相パルス)を提供する、常用デバイスとして利用される。本実験の趣旨としては、回転速度の計算ベースとなる、エンコーダのA/B相パルスは正しく計測されたかどうか、またPID制御の精度、確度を評価するに当たって、他のデバイス、本実験ではhayate_imu(ICM-20948内蔵)を活用して評価すること。

実験環境

●12V入力DCブラシモータ
●12V出力DC電源(Motor Shieldへ給電)
●磁気式エンコーダ
●Arduino Leonardo正規品基板
●Adafruit Motor Shield v1.2互換基板(ライブラリ修正あり、Timer3A/D5-pin/PWM周波数を4KHzへ変更済み)
●9軸センサhayate_imu v2.4
●Raspberry Pi 3 Model-B(ROS Slave、Unbuntu20.04/Noetic、hayate_imuへ接続)
●5V出力DC電源(Raspberry Piへ給電)
●Lenovo L560(ROS Master、Unbuntu18.04/Melodic、Arduino Leonardoへ接続)

hayate_imu用いてDCモータPID制御評価環境
hayate_imu用いてDCモータPID制御評価環境

開発要素

ROSパッケージ

以下ROSパッケージ、ROSカスタムメッセージまたはライブラリをインストールして、catkin_makeしておく。

rosserial
hayate_motor_ros
hayate_imu_ros
ros_lib by rosserail_arduino with Arduino IDE
Adafruit-Motor-Shield-library-leonardo
arduino_node(ino) on Leonardo with Arduino IDE 

ROSノード

/arduino_node
/hayate_imu_ros
/hayate_motor_node
/rosout
/rqt_plot

ROSトピック

/arduino_msg
/diagnostics
/hayate_angular_velocity_z
/imu_cali
/imu_data
/imu_demo
/pid_params
/rosout
/rosout_agg

ROSカスタムメッセージ

hayate_imu_ros/ImuCali
hayate_imu_ros/ImuData
hayate_motor_ros/ArduinoMsgs
hayate_motor_ros/PidMsgs

ROSノードの相互作用状況

エンコーダ付きDCモータPID制御の実験-ROS node & ROS topic
エンコーダ付きDCモータPID制御の実験-ROS node & ROS topic

Arduinoノード

エンコーダA相パルス割込みハンドラ

  if (digitalRead(ENCODER_A) != digitalRead(ENCODER_B)) {
    current_counter++;
  }
  else {
    current_counter--;
  }

エンコーダB相パルス割込みハンドラ

  if (digitalRead(ENCODER_A) == digitalRead(ENCODER_B)) {
    current_counter++;
  }
  else {
    current_counter--;
  }

エンコーダカウンタによる回転速度

// Run the PID loop at 100 times per second
#define PID_RATE_HZ 10 // 10Hz
// Convert the rate into an interval
#define PID_INTERVAL_MS (1000 / PID_RATE_HZ) // 10ms
#define PID_INTERVAL_S (float)(1.0 / PID_RATE_HZ) // 0.1s
#define PPR 12 // Encoder pulse / round
#define COUNTER_FACTOR 4 // 1*encoder-pulse = 4*counter
#define REDUCTION_RATIO 100 // Gear reduction ratio
#define CPR (PPR * COUNTER_FACTOR * REDUCTION_RATIO) // Counters of encoder / round
current_velocity = (current_counter - previous_counter) * 360.0 / (CPR * PID_INTERVAL_S);

PID係数

本実験環境で何回も実験を繰り返して、納得いくPID係数Kp、Ki、Kdを決めておく。

PID操作量

●Position法

  error = target_velocity - current_velocity;
  integral += error * PID_INTERVAL_S;
  differential = (error - previous_error) / PID_INTERVAL_S;
  previous_error = error;
  pwm = (int32_t)(Kp * error + Ki * integral + Kd * differential);

●Increment法

  error = target_velocity - current_velocity;
  proportion = Kp * (error - previous_error);
  integral = Ki * error * PID_INTERVAL_S;
  differential = Kd * (error - 2 * previous_error + previous_error2) / PID_INTERVAL_S;
  pwm += (int32_t)(proportion + integral + differential);
  previous_error2 = previous_error;
  previous_error = error;

実験手順

Run roscore

Run roscore@ROS Master

roslaunch haya_imu_ros haya_imu.launch

Launch hayate_imu_node

Launch hayate_imu_node@ROS Slave

roslaunch hayate_imu_ros hayate_imu.launch

Launch hayate_motor_node

Launch hayate_motor_node@ROS Master

roslaunch hayate_motor_ros hayate_motor.launch
rqt_graph

結果確認

PID制御の目標値、制御量

以下のデータを表示させて、エンコーダ、IMUからのカウンタによる回転速度を確かめて、PID係数Kp、Ki、Kdを決めてまた、エンコーダまたは、PID制御を評価する。PWM周波数をデフォルトの490Hzから4KHzに変更することで回転速度の分散は小さくなっている。これは490Hzより4KHz周波数のほうはモータにブレーキをかけずにPWM波形は滑らかになって果たしてモータ出力シャフトの回転速度も滑らかになったわけである。

/hayate_angular_velocity_z 
/pid_params/target_velocity
/arduino_msg/current_velocity
PID制御の目標値、エンコーダによる回転速度、hayate_imu測った回転速度曲線
PID制御の目標値、エンコーダによる回転速度、hayate_imu測った回転速度曲線

hayate_imuで測った回転速度が、エンコーダによる回転速度より分散が大きくなって、これは測定法および測定ポジションは違って、またモータシャフトによる振動や、慣性力に由来するものと考えられる。

PID制御の目標値、制御量、操作量

PID制御の目標値、PWM操作量、エンコーダによる回転速度

PID制御の目標値、PWM操作量、エンコーダによる回転速度
PID制御の目標値、PWM操作量、エンコーダによる回転速度

PID制御の操作量PWM波形

オシロスコープは測った操作量PWMの波形、モータコイルに起因する逆起電力による、コイルサージは約-14Vあったと、モータシールド実装モータドライバL293Dにコイルサージ(逆起電流)を流すダイオードが効いていると考えられる。ないと一瞬-12Vの数十倍~-1千万V(無限大)に達する可能性ある。これで回路で繋がっているデジタルICを一発でぶち壊すことになる。

PID制御の操作量PWM波形
PID制御の操作量PWM波形

エンコーダ出力パルス波形

約1/10の確率でノイズに起因するスパイクが起きるらしいので、MCUにノイズフィルタ実装の入力PINは望ましい。

エンコーダパルス波形ノイズスパイクあり
エンコーダパルス波形ノイズスパイクあり

リポジトリ

hayate_motor_ros、arduino_node、修正ありMotor Shieldライブラリ含むリポジトリは、https://github.com/soarbear/hayate_motor_ros に公開済み(BSD 3-Clause License)

最後に

IMUはモータシャフトでなくロボット本体に装着した場合、エンコーダのみならずLidar、カメラ、GPS他のセンサーとフュージョンする場合多い。

参考記事

ロータリエンコーダによる速度計算
9軸IMUセンサ 6軸/9軸フュージョン 低遅延 USB出力 補正済み ROS対応

0

ロボット・ドローン部品お探しなら
ROBOT翔・電子部品ストア

9軸IMUセンサ ICM-20948をロボットに組み込もう

はじめに

TDK Invensense製9軸IMUのICM-20948は、MPU-9250の後継機種で、MPU-9250のVDDは2.4V~3.6V、VDDIOは1.71V~VDDに対して、ICM-20948のVDDは1.71V~3.6V、VDDIOは1.71V~1.95Vに低めに設定して、省電力となった。また、デジタルモーションプロセッサDMP(ICM-20948内蔵FPGA)によるデータフュージョン(FPGAによるFusion)の特長が継承して、さらにRAM容量が拡張して、6軸フュージョンのみならず9軸フュージョンまで増強して、較正機能もあると、以下参考文献を読むと詳細まで分かる。

環境

・Ubuntu 18.04
・ROS Melodic
・MCU: Cortex M0+
・IMU: ICM-20948

DMP3の出力確認

以下のように、出力レート50Hz、加速度Ax Ay Az、角速度Gx Gy Gz、磁場Mx My Mz、4元数Qw Qx Qy Qzの順に出力させる。

imu-icm20948-output
imu-icm20948-output

4時間+にわたる連続動作して出力を確かめる。確認環境は完全に静止な状態でもないので、ドリフトは納得いく範囲内にとどまっている。rvizで確かめてもドリフトが肉眼では見えないほど。ドリフトにおいては、MPU-9250から大いに改善されたと見られる。

imu-icm20948-output-4hours
imu-icm20948-output-4hours

出力確認動画は以下イメージをクリックすると、youtubeへジャンプする。

icm20948_imu_ros
icm20948_imu_ros

最後に

MPUシリーズと比べて、ユーザの事前校正いらず、長時間(実験は4時間程度まで)においても、ドリフトとくにヨウ角(Yaw、方向角)のドリフトは目立たないほどになった。また、1.71Vの低電圧でも動作可能なのでスマートデバイスや、ロボットの長時間電池駆動が可能になる。なお、出力レートはMax 225Hzと確認できた。ICM-20948 DMP3(IMU内蔵FPGA)から出力した、Accel/Gyro/Mag計9軸データ出力にFusion Quaternionの4元数データがそのまま利用可能で、遅延もソフト・カルマンフィルタなどより少なく他機種IMUより優れる(低遅延、6軸/9軸フュージョンデータ出力レート225Hz)ため、ロボットの精度向上に利用可能。1.8V VDDIO対応、DMP3の出力に手間かかった末、地磁気センサ出力は75Hzまでと少し残念だが、総じて優秀としか思わないICM-20948をロボット装置に組み込もうと決めた。

商品化モジュール

ICM-20948とCoretex M0+を組み込んだ回路を設計して、ROSに対応したロボット専用センサモジュールとして商品化して、2021年1月~、リリースと予定している。この商品は皆さんの学術研究にお役に立てるようと願う。主な仕様は以下のとおり。
・構成 CortexM0+ & TDK Invensense ICM-20948(9軸)実装
・接続 USB Type-Cコネクタ実装
・出力 6軸/9軸融合4元数はFPGA on chipから低遅延で出力、別途ソフトでフュージョン必要なし、出力レート225Hz、同時に加速度(アクセル)3軸データ225Hz、角速度(ジャイロ)3軸データ225Hz、地磁気(コンパス)3軸データ75Hzまで出力可能
・ROSパッケージ、Githubへ公開、ROS Kinetic以降対応、ROS TopicへSubscribeすることでデータが受け取り可能
・rviz実演、実演ビデオあり

【2021年3月いま現在】1回目制作分(評価版)、大学など研究機関へ無料配布中(アンケート調査あり)、WEBでの募集を含めて順次終了。

【2021年4~5月予定】2回目制作分(商用版)、販売の予定。

詳細情報

9軸IMUセンサ 6軸/9軸フュージョン 低遅延 USB出力 補正済み ROS対応

取扱店舗

9軸IMUセンサ 6軸/9軸フュージョン 低遅延 USB出力 ROS対応 | ROBOT翔

参考文献

Migrating from MPU-9250 to ICM-20948-InvenSense

関連記事

9軸IMUセンサ MPU-9250をロボットに組み込もう
6軸IMUセンサ MPU-6050をロボットに組み込もう

2+

ロボット・ドローン部品お探しなら
ROBOT翔・電子部品ストア

9軸IMUセンサ MPU-9250をロボットに組み込もう

はじめに

9軸IMUのMPU-9250はTDK InvenSense社製I2Cインターフェースの3軸ジャイロセンサ+3軸加速度センサ+3軸コンパスセンサIC、内蔵DMP(Digital Motion Processor)機能を使うことで、補正済みデータとしての4元数Quaternionまたはオイラー角、ロールRoll・ピッチPitch・ヨウYaw角の出力が選べる。また、MPUシリーズはすでに新規設計非推奨になっているため、後継機種はICMシリーズで、MPU-9250の後継機種はICM-20948となって、MPU-9250に比べて、事前校正不要で、ドリフトの低減、省電力などにおいてパフォーマンスが改善された。本文は、6軸MPU-6050に続いて、9軸MPU-9250 DMPから4元数Quaternionを読み込んで可視化するまでの手順を以下のとおりに示して、ROSドライバをGithubへ公開する。安価のため、MPU-9250サンプルの入手ルートはAliexpressにした。

mpu6050-mpu9250
mpu6050(6軸)-mpu9250(9軸)

I2Cインターフェースは、vcc、gnd、scl、sdaの4pinインターフェース

環境

・ubuntu 18.04 Tinker board(or Raspiberry Pi, PC)
・ROS melodic
・DFRobot Romeo mini v1.1(or arduino uno互換)
・MPU-9250/6500

準備①

・ros-melodic-rosserial-arduino、ros-melodic-rosserial、rviz_imu_pluginを入れる

$sudo apt-get update
$sudo apt-get install ros-melodic-rosserial-arduino
$sudo apt-get install ros-melodic-rosserial
$cd ~catkin_ws/src/
$git clone -b melodic https://github.com/ccny-ros-pkg/imu_tools
$cd ..
$catkin_make_isolated

・mpu9250_imu_rosを入れる

$cd ~/catkin_ws/src/
$git clone https://github.com/soarbear/mpu9250_imu_ros.git
$cd ~/catkin_ws/
$catkin_make_isolated

準備②

・firmware/MPU9250_DMP/MPU9250_DMP.inoをArduino IDEでArduinoに書き込む。

imu/dataの可視化

・実に使われるポートtty????を確認する。
・rvizが自動起動して、画面にあるセンサの動きを観察する。

$sudo ls -l /dev/ttyACM*
$sudo chmod 777 /dev/ttyACM0
$roslaunch mpu9250_imu_driver mpu9250_imu.launch

・以下スクリーンショットをクリックすると、youtubeへ遷移する。

mpu6050_imu_ros
mpu9250_imu_ros

センサ融合について

MPU-9250内蔵DMPおよび、センサ融合またはデータ同化Fusionに定番アルゴリズムであるKalman Filterの他、Complementary Filter、Madgwick Filterがある。振動やシステム誤差によって測定値に大きな影響あり、フィルタリングが必須とは言える。

ソースコード

mpu9250_imu_rosソースコード(Github)

後継機種

ICM-20948はMPU-9250の後継機種、その製品化情報は 9軸IMU/AHRS 6軸&9軸回転ベクトル&3軸オイラー角 MAX1000Hz同時出力 ROS/ROS2対応 USB接続9軸IMU 6軸/9軸フュージョン ICM-20948 Cortex-M0+内蔵 ROS対応

参考文献

1-Jeff Rowberg氏: I2C driver
2-ROS Repository: ROS imu_tools

関連記事

9軸IMU/AHRS 6軸&9軸回転ベクトル&3軸オイラー角 MAX1000Hz同時出力 ROS/ROS2対応 USB接続
9軸IMUセンサ 6軸/9軸フュージョン 低遅延 USB出力 補正済み ROS対応
9軸IMU ICM-20948をロボットに組み込もう
6軸IMU MPU-6050をロボットに組み込もう

3+

ロボット・ドローン部品お探しなら
ROBOT翔・電子部品ストア