sken_library 講習
やりたいこと | クラス名 | 関数例 |
---|---|---|
LEDを光らせる | Gpio |
init() , write() |
モーターを回す | Motor |
init() , write() , stop() |
エンコーダを読む | Encoder |
init() , read() |
サーボを動かす | RcPwm |
init() , turn() |
スイッチを読む | Gpio |
init() , read() |
シリアル通信する | Uart |
init() , read() , write() |
CAN通信する | SYSTEM |
startCanCommunicate() , canTrancemit() , addCanRceiveInterruptFunc() |
ここでは概要のみ説明するため詳しくは Skenライブラリreadme を必ず読むこと
インクルードは共通
#include "stm32f4xx.h"
#include "sken_library/include.h"
なお,ピンに関しては以下を参照 ALTAIR_MDD_V2
encoder
A0 A1 TIMER5
B3 A5 TIMER2
B6 B7 TIMER4
C6 C7 TIMER3
MD
B14(TIMER8 CH2) B15(TIMER8 CH3) もしくは B14(TIMER12 CH1) B15(TIMER12 CH2)
A8(TIMER1 CH1) A11(TIMER1 CH4)
A6(TIMER13 CH1) A7(TIMER14 CH1)
B8(TIMER10 CH1) B9(TIMER11 CH1)
Serial
tx:C10 rx:C11 SERIAL3
tx:A9 rx:A10 SERIAL1
1. Lチカのやり方(LED点滅)
Gpio led; // Gpioクラスのオブジェクトを作成
int main(void) {
sken_system.init(); // システム初期化
led.init(A5, OUTPUT); // A5ピンをデジタル出力に設定
while (1) {
led.write(HIGH); // A5ピンをHIGH(LED点灯)
sken_system.delayMillis(500); // 500ミリ秒待機
led.write(LOW); // A5ピンをLOW(LED消灯)
sken_system.delayMillis(500); // 500ミリ秒待機
}
}
ポイント
-Gpio::init()
でピンのモードを設定
-Gpio::write()
でピンの状態(HIGH/LOW)を変更
-delayMillis()
で時間待ち
2. モーターの回し方
Motor motor;
int main(void) {
sken_system.init();
motor.init(Apin, B8, TIMER10, CH1); // Aピン(回転方向1)
motor.init(Bpin, B9, TIMER11, CH1); // Bピン(回転方向2)
while (1) {
motor.write(50); // 50%のPWMで正回転
sken_system.delayMillis(2000); // 2秒回転
motor.stop(); // モータ停止
sken_system.delayMillis(2000); // 2秒停止
motor.write(-50); // 50%のPWMで逆回転
sken_system.delayMillis(2000); // 2秒回転
}
}
ポイント
- モーターはAピン・Bピン・PWMピンを指定して初期化
-write()
で回転速度(-100~100%)を指定
3. エンコーダーの読み方(カウント値・角度・速度)
基本:カウント値だけ読む
Encoder encoder;
int main(void) {
sken_system.init();
encoder.init(A0, A1, TIMER2); // A0, A1ピンをエンコーダ入力に設定
while (1) {
int count = encoder.read(); // 現在のエンコーダカウント値を取得
}
}
ポイント
-Encoder::init()
でエンコーダを使えるようにする
-Encoder::read()
で現在のカウント(回転量)を取得する
応用:角度・速度も読む(割り込みを使う)
Encoder encoder; // エンコーダオブジェクト
Encoder_data e_data; // 角度や速度を保存する構造体
// タイマー割り込み関数(毎ms呼び出される)
void encoder_interrupt() {
encoder.interrupt(&e_data); // エンコーダの値を更新
}
int main(void) {
sken_system.init();
encoder.init(A0, A1, TIMER2); // A0, A1ピンをエンコーダ入力に設定
sken_system.addTimerInterruptFunc(encoder_interrupt, 0, 1); // タイマー割り込み1ms周期で登録
while (1) {
double angle = e_data.deg; // 現在の角度 [度]
double velocity = e_data.volcity; // 現在の速度 [mm/s]
// ここでangleやvelocityを使った処理を書く
}
}
ポイント
-Encoder::interrupt()
を周期的に呼ぶことで、角度・速度を自動計算
-e_data.deg
で角度(degree)
-e_data.volcity
で速度(mm/s)が取得できる
【補足】構造体Encoder_data
の中身
struct Encoder_data {
int count; // カウンタ値
double rot; // 回転数 [回転]
double deg; // 角度 [度]
double distance; // 移動距離 [mm]
double volcity; // 速度 [mm/s]
double rps; // 回転速度 [rps]
};
必要に応じて
- 回転数 (rot
) - 移動距離 (distance
) - 回転速度 (rps
)
も使える!
4. サーボモーターの動かし方
RcPwm servo;
int main(void) {
sken_system.init();
servo.init(A5, TIMER2, CH1); // A5ピンをサーボ信号出力に設定
while (1) {
servo.turn(0); // 最小角度
sken_system.delayMillis(1000);
servo.turn(50); // 中央位置
sken_system.delayMillis(1000);
servo.turn(100); // 最大角度
sken_system.delayMillis(1000);
}
}
ポイント
-turn(%)
でサーボモータの角度を設定できる
- 0~100%で出力パルス幅(1000μs~2000μs)を調整
5. リミットスイッチの読み方
Gpio limit_switch;
int main(void) {
sken_system.init();
limit_switch.init(C13, INPUT_PULLUP); // C13ピンにプルアップ入力設定
while (1) {
if (!limit_switch.read()) { // スイッチが押されたらLOWになる
// スイッチ押されたときの処理を書く
}
}
}
ポイント
-INPUT_PULLUP
を使うとスイッチ未接続時はHIGH、押すとLOWになる
-read()
で押されたかどうかを判定
6. UARTのやり方(シリアル通信)
送信(write)
Uart serial;
uint8_t data[2] = { 'A', 'B' }; // 送るデータ
int main(void) {
sken_system.init();
serial.init(A9, A10, SERIAL1, 9600); // UART1をボーレート9600で初期化
while (1) {
serial.write(data, 2); // 2バイト送信
sken_system.delayMillis(1000); // 1秒ごとに送信
}
}
受信(read)
Uart serial;
uint8_t received_data;
int main(void) {
sken_system.init();
serial.init(A9, A10, SERIAL1, 9600);
while (1) {
received_data = serial.read(1000); // 1000ms以内に受信
if (!serial.checkTimeOut()) {
// 受信できた場合の処理
}
}
}
ポイント
-init()
でピンと速度を設定
-write()
で送信、read()
で受信
7. CAN通信のやり方(sken_system経由)
送信(canTrancemit)
uint8_t can_tx_data[8] = {1, 2, 3, 4, 5, 6, 7, 8};
int main(void) {
sken_system.init();
sken_system.startCanCommunicate(B13, B12, CAN_2); // CAN1開始
while (1) {
sken_system.canTrancemit(CAN_2, 0x123, can_tx_data, 8); // ID=0x123, 8バイト送信
sken_system.delayMillis(1000); // 1秒ごとに送信
}
}
受信(addCanReceiveInterruptFunc)
Can_data can_data; // 受信データを格納する構造体
uint8_t can_rx_data[6] = {0,0,0,0,0,0};
int main(void) {
sken_system.init();
sken_system.startCanCommunicate(B13, B12, CAN_2); // CAN1開始
sken_system.addCanRceiveInterruptFunc(CAN_2, &can_data); // 受信割り込み設定
while (1) {
if(can_data.rx_stdid == 0x123){
// 受信データはcan_data.rx_dataに格納される
can_rx_data[0] = can_data.rx_data[0];
can_rx_data[1] = can_data.rx_data[1];
can_rx_data[2] = can_data.rx_data[2];
can_rx_data[3] = can_data.rx_data[3];
can_rx_data[4] = can_data.rx_data[4];
can_rx_data[5] = can_data.rx_data[5];
}
}
}
ポイント
-startCanCommunicate()
で通信開始
-canTrancemit()
でデータ送信
-addCanRceiveInterruptFunc()
で受信設定
8. PID制御の使い方
基本:PIDゲインを設定する
Pid pid_control; // PIDコントローラーオブジェクト
int main(void) {
sken_system.init();
// P=1, I=1, D=1, 微分フィルタ時定数20msでゲイン設定
pid_control.setGain(1, 1, 1, 20);
while (1) {
// ここに制御コードを書く
}
}
ポイント
-setGain(P, I, D, 時定数)
でパラメータ設定
- 微分前ローパスフィルタ(時間定数)も指定可能!
PID制御を実行する(目標値と現在値から)
Pid pid_control;
double target = 100; // 目標値(例えば目標速度)
double now = 0; // 現在の値(現在の速度)
double out = 0; // 出力(モータへの指令など)
// 毎1msで呼び出される関数
void pid_func() {
out = pid_control.control(target, now, 1); // 目標値と現在値から制御出力を計算
}
int main(void) {
sken_system.init();
pid_control.setGain(1.0, 0.5, 0.1); // 適当なゲイン設定
sken_system.addTimerInterruptFunc(pid_func, 0, 1); // 1msごとにPID制御実行
while (1) {
// outを使ってモーターに指令を出すなど
}
}
ポイント
-control(target, now, period)
でPID出力計算
- 割り込みで周期的にPID制御するのが基本!
PID制御を実行する(偏差から直接計算)
Pid pid_control;
double e = 0; // 偏差(目標値 - 現在値)
double out = 0;
void pid_func() {
out = pid_control.control(e, 1); // 偏差から制御出力を計算
}
int main(void) {
sken_system.init();
pid_control.setGain(1.0, 0.5, 0.1); // PIDゲイン設定
sken_system.addTimerInterruptFunc(pid_func, 0, 1); // 1msごとにPID制御
while (1) {
// 目標値と現在値の差を計算
double target = 100;
double now = 50;
e = target - now; // 偏差計算
}
}
ポイント
- 偏差だけ分かっていれば、直接control(e, period)
でもOK
- 使いやすい方法を選べる!
積分・微分成分をリセットする
Pid pid_control;
double target = 100;
double now = 0;
double out = 0;
void pid_func() {
out = pid_control.control(target, now, 1);
}
int main(void) {
sken_system.init();
pid_control.setGain(1.0, 0.5, 0.1); // PIDゲイン設定
sken_system.addTimerInterruptFunc(pid_func, 0, 1); // 1msごとに制御
while (1) {
if (sken_system.millis() % 1000 == 0) { // 毎秒
pid_control.reset(); // 積分・微分成分をリセット
}
}
}
ポイント
- 長時間動かすと積分(I成分)が暴走することがある
- 必要に応じて定期的にreset()
してリフレッシュ!
Note
著者:Shion Noguchi