今回はトイラジコンの制御に使用するプログラムについて、メインとなる処理の仕様をまとめていきます。
ラジコンのプロポ(リモコン)からのPWM信号(出力指令)の処理方法
制御ブロック図
まずはラジコンのPWM入力受付処理周りの実装から。
前回までに紹介したブロック図でいうところの、下記の赤点線で囲まれた部分です。

今回はラジコン用のプロポから、全部で5chの入力を受け付ける仕様としていました。
しかし、今回選定したPICマイコンでは、すべてのチャネルのPWM入力を受ける(パルス幅測定を行う)程、マイコン機能に余力がありません。
このため、当初はPWM入力を適当なCRローパスフィルタにかけ、なまらせたうえでAD値として認識しようと思っていました。
(PICマイコンはAD変換はほぼ全部のchについており、多チャンネルでも対応できるため。)
しかし、今回使用するラジコンのリモコンのPWM仕様は下記のようになっていました。
-
-
【ラジコン】RC用リモコン RadioLink T8FB & R8FB のPWM仕様を調査してみる
今回はラジコン用に販売されている汎用の送信機、受信機セットを購入したので、仕様を調査してみます。 基本的にラジコンの送信機、受信機の信号はすべてECUが吸収してくれるのであえて調べようと思ったことはな ...
続きを見る
もともとパルス入力をCRローパスフィルタで適当になまらせ、平均値をAD変換して取得する、、、という予定だったのですが、キャリア周期が50Hz程度と低く、更新周期を考慮するとあまり現実的な方法ではありませんでした。
このため、下記のように変更しています。(詳細は後述。)

変更箇所は、「ADC」➡「IOC」です。
PWM仕様の詳細確認
今回使用するT8FBの受信機から出力されるパルス仕様は下記の画像の通りです。(全部で8chあります。)
多チャンネルをロジックプローブで同時測定した波形になります。


ラジコン用のPWMについて、多チャンネルの波形出力がどんな感じになっているのか知らなかったのですが、どうやら1chごとに順番にON時間を作っていっているようです。
今回は8chあるので、8段の階段上の波形になりました。
1chのPWMの立ち上がりタイミングは、最終段のch-D7を除き、前回のchのON区間が終了すると同時に設定されているようです。
今回は受信機からのPWMのうち、D1,D4,D5,D6,D7の5chを使用します。
(ブロック図のchは1始まりになっちゃってました・・・)
飛ばすチャンネルがある点も注意が必要です。
実装方法の検討
続いて、実装方法の検討です。
今回チャネル数の制約により、残念ながらマイコンのキャプチャ機能に頼ってduty比を判別していくことはできません。
このため、下記のような作戦で行きます。

実装詳細:PWMのパルス幅取得処理
今回の実装の詳細なタイミングチャートを下記に示します。

設計についてざっくりまとめます。
基本的にPICマイコンの全ピンに搭載されているIOC(Interrupt On Change)割り込みを使用し、あとはソフトウェアによるパワー実装で解決しています。結構、、、強引だと思いますが、きれいに動いてしまったのでヨシ・・・・
★動作概要★
・最初のチャネルのPWM入力の立ち下がりを検知した場合、フリーランタイマを起動させる
(回路構成上、立ち上がりと立ち下がりを反転させているので、「立下り検知」)
・最初のチャネルのPWMの立ち上がりを検知した場合、タイムスタンプとしてその時点でのタイマのカウントを保存していく。
・以降、他のチャネルでも立ち上がりと立下りのタイミングでタイマカウント値の現在値を保存していく。
・最後のチャネルのパルスの終了を検知した場合、タイマカウンタをリセットしてカウントストップする。
ここでは触れないですが、タイムアウト等の細かい分岐もいくつか実装し、数回パルス幅測定がトチっても変なdutyにならないようにしてみました。たぶん、、、動いてるはず。。。多分。
上記の処理はすべて割り込み処理内で実施します。
値の代入と簡単なシーケンス繊維のみのため、処理時間的には結構短めです。
ただし隣り合ったPWM入力の立ち上がりと立ち下がりがほぼ同一のタイミングで来てしまうので、切り替え付近は処理が間に合わなそうでした。この辺はソフトウェアでうまくごまかしてdutyが適切な値になるように調整しています。
実装詳細:PWMのパルス幅再計算処理
パルス幅の取得処理は割り込みで実施しますが、duty比への再計算はメインループの中で時間をかけて実施します。
今回はハードウェアのキャプチャ機能を使用していない(できない)ため、取得したデータはパルスのON時間と直接紐づいていません。
ストップウォッチのように、単なるタイムスタンプとして取得しているだけです。
このため、duty比に直すには、いくつかの計算を行う必要があります。
「今回はパルス幅1500usがラジコン用の汎用PWM仕様としてduty0%に相当する」という特徴を利用して、下記のような式で再計算を行ってみました。

1500usを基準とすると若干変換が面倒になりますが、0%の時に1500us - 500us = 0us であることを使うと、単なる引き算と割合計算のみで成立します。
最終的に完成版のソフトにたどり着くまでに結構時間かかりました・・・
この処理の問題点と対策について
この処理ですが、実は1つ問題点があります。
「タイムスタンプ取得タイミングが他の処理時間に影響を受けた場合、duty比が本来と値からずれてくる」という問題です。
(結構致命的。)
実際デバッグ中にプロポを操作していないのにduty比がチラチラ変化する現象が何度かありました。
他にも割り込み処理を実行しているため、それらの実行中にタイムスタンプを取得することができず、処理遅延の分だけduty比が増える、という状態が起きていました。
ただし、この問題は簡単に解決できました。
今回使用したPIC18F25Q10には割り込み優先度の設定があり、highとlowの2種類を選べます。

また下記の記載の通り、低優先度割り込みの動作中に、多重割り込みが可能です。

このため、処理時間のずれが許されないパルス幅測定(タイムスタンプ取得)のみ、高優先度としています。
設計制約として、他の割り込みを高優先度に設定できない問題が出てきますが、PICの場合は割り込みごとに2つのベクタにジャンプし、それ以降は要求フラグを確認して順次処理を行っていくような割り込みの作りなので、実装次第であまり問題にはならないと思われます。
(割り込みごとにベクタアドレスが用意されているわけではないので、いったん高優先度割り込み入ったあとでも、処理順序を入れ替える猶予があります。)
今回の場合は下記のようにduty比(タイムスタンプ取得)処理を最も上に移動し、それ以降の高優先度割り込み処理は下に書く、という実装にしました。
これなら、たとえ同時に割り込みが発生したとしても影響は軽微です。
いったんduty比取得以外の割り込み処理を実行し、そのあとにduty比取得の割り込みが来た・・・というケース考慮すると、実際はあまり長い処理は入れられないという制約はどうしても残ってしまいますが、今回はそういう処理は作ってないということで、問題ナス。
/**************************************************************/
/* Function: */
/* 高優先度 割り込み処理 */
/* */
/* 割り込みベクタはHigh/Lowで2コ */
/**************************************************************/
void __interrupt (high_priority) high_isr(void)
{
#if 1
if( INT_FLAG_IOC == SET )
{
IOCIE = CLEAR; /* IOCAF読み取り中に再度割り込み入ると読み取り失敗するので、処理開始前に禁止する */
/* duty検出処理 */
func_rc_g_duty_detection(); /* ラジコンプロポ duty取得処理 */
/*INT_FLAG_IOC = CLEAR;*/ /* IOCFはIOC割り込みのステータスビット IOCの割り込みフラグは、上記関数内で個別にクリア */
/* 回転数検出用 割り込み発生フラグ */
/* 処理時間少ないのでduty検出処理には影響ないはず。 */
if( IOCCF0 == SET )
{
func_speedsens_g_edge_detect_mtr();
IOCCF0 = CLEAR;
}
if( IOCCF1 == SET )
{
func_speedsens_g_edge_detect_1stgear();
IOCCF1 = CLEAR;
}
IOCIE = SET;
}
#endif
}デバッグ作業についてコメント
連続で割り込みが入る処理のデバッグはめんどい。
マジでこの一言に尽きる。
デバッグ作業がほんとに面倒でした・・・
何が面倒かというと、PICKIT3を使用してMPLABでブレークポイントをかけるまではよいのですが、ラジコンのPWM入力は止まってくれないのでどんどん割り込みフラグがたまっていくんですよね。。。
ちょうどいいところまで来ても、再び割り込みが入って「isr」に飛ばされ場所がわからなくなります。
この辺の動的動作のデバッグはちょっとやりずらかったです。
実装
実装についても載せておきます。
ちょっと汚いのでのちのちもう少し整理します。。。
/*
* File: radio_control.c
* Author: ICE_MEGANE
* ラジコン用リモコン処理全般
* Created on 2026/04/20, 22:26
*/
#include <xc.h>
#include "./mcufunc/pic18f25q10.h"
#include "userdefine.h"
#include "./mcufunc/gpio.h"
#include "./mcufunc/mcu_setup.h"
#include "./mcufunc/timer_driver.h"
#include "./radio_control.h"
/* ポート設定 */
#define RC_IOC_BITPOS_CH_THROTTLE ((u8)0) /* 0:RC_DUTY_CH_THROTTLE */
#define RC_IOC_BITPOS_CH_SHIFT_MODE ((u8)3) /* 1:RC_DUTY_CH_SHIFT_MODE */
#define RC_IOC_BITPOS_CH_RESPONSE ((u8)2) /* 2:RC_DUTY_CH_RESPONSE */
#define RC_IOC_BITPOS_CH_PADDLE_SHIFT_INPUT ((u8)1) /* 3:RC_DUTY_CH_PADDLE_SHIFT_INPUT */
#define RC_IOC_BITPOS_CH_REV_LIMIT ((u8)4) /* 4:RC_DUTY_CH_REV_LIMIT */
/* 設定関連 */
#define RC_DUTY_PULSE_ON_LOGIC LOW /* 入力パルスのアクティブロジック */ /* ※IOCAF、IOCANの設定と合わせること */
#define RC_DUTY_JUDGE_TIMEOUT_CNT ((u8)5)
#define RC_DUTY_CONVERSION_ROUND ((u16)100) /* dutyの端点丸め数値 */
#define RC_DUTY_0P_CNT ((u16)2000) /* duty0%相当のカウント現在値 */
#define RC_DUTY_100P_CNT ((u16)4000) /* duty100%相当のカウント現在値 */
#define RC_DUTY_100P_CNT_DIFF ( RC_DUTY_100P_CNT - RC_DUTY_0P_CNT ) /* duty100%相当のタイマカウント差分 */
/* duty増減方向の設定(リモコンの操作反転したい場合に使う) */
#define RC_DUTY_PROP ((u8)0) /* 比例 */
#define RC_DUTY_REVERSE_PROP ((u8)1) /* 反比例 */
u8 u8_rc_s_debug_flag;
u8 u8_rc_g_duty_judge_sequence; /* パルス幅測定シーケンス */
u16 u16_rc_g_duty_speed; /* 前進/後進 速度入力 */
u16 u16_rc_g_duty_shift_mode; /* シフトチェンジモード入力 (セミオートマ/オート) */
u16 u16_rc_g_duty_speed_gain; /* 加速度合い(エンジン応答)入力 */
u16 u16_rc_g_duty_shift_updown; /* シフトアップダウン入力 */
u16 u16_rc_g_duty_rev_limit; /* レブリミット閾値入力 */
static u8 u8_rc_s_duty_judge_timeout_flag; /* パルス幅取得 タイムアウト */
static u8 u8_rc_s_duty_judge_timeout_cnt; /* パルス幅取得 失敗カウント */
static u8 u8_rc_s_duty_get_complete; /* 1msタスクでのduty取得完了フラグ */ /* タイミング的にループと割り込みで同時書き込みすることはないはず。 */
static u8 u8_rc_s_duty_cnt_debug;
/* 割り込みで取得する値保存用の構造体 */
typedef struct rc_duty_sample_str
{
u8 u8_start_capture_complete_flag; /* 指定のチャネルのタイマカウント取得完了フラグ(ON開始時) */
u8 u8_end_capture_complete_flag; /* 指定のチャネルのタイマカウント取得完了フラグ(ON終了時) */
u16 u16_ch_duty_cnt_start; /* duty ON開始時のタイマカウント ( タイマレジスタからの取得値 ) */
u16 u16_ch_duty_cnt_end; /* duty OFF開始時のタイマカウント ( タイマレジスタからの取得値 ) */
}rc_duty_sample_data;
static rc_duty_sample_data rc_duty_get_by_int_tbl[ RC_DUTY_CH_IDX_MAX ] =
{
{ CLEAR, CLEAR, (u16)0, (u16)0 },
{ CLEAR, CLEAR, (u16)0, (u16)0 },
{ CLEAR, CLEAR, (u16)0, (u16)0 },
{ CLEAR, CLEAR, (u16)0, (u16)0 },
{ CLEAR, CLEAR, (u16)0, (u16)0 },
};
/* ループタスクで使用するduty比保存テーブル (0~100) ※外部の処理でも使う */
u8 u8_rc_g_ch_duty_tbl[ RC_DUTY_CH_IDX_MAX ] =
{
(u8)0,
(u8)0,
(u8)0,
(u8)0,
(u8)0
};
/*===================================================================================================================================*/
/*===================================================================================================================================*/
/* レジスタ設定 */
/* SFRからの読み止しだけは、メモリからの毎回呼び出しを指定する */
typedef struct rc_duty_sample_register_setting
{ /* レジスタ設定 */
volatile u8 *port_addr; /* IOCポートレジスタへのポインタ ※指している先をvolatileとして扱う */
u8 port_bitmask; /* IOCポートレジスタのビット指定 */
volatile u8 *flag_addr; /* IOCフラグレジスタへのポインタ(アドレス指定しておく) */
u8 flag_bitmask; /* IOCフラグレジスタのビット指定 */
u8 duty_direction; /* プロポのレバーに対するduty増減方向 */
}rc_duty_sample_setting;
/* ここで全チャネルまとめて指定できるようにしておきたい */
static const rc_duty_sample_setting rc_duty_get_register_combi_tbl[ RC_DUTY_CH_IDX_MAX ] =
{ /* IOCポート, IOCポート-ビット位置, IOCフラグ, IOCフラグ-ビット位置, dutyの増減方向 */
{ &PORTA, (u8)(1U << RC_IOC_BITPOS_CH_THROTTLE), &IOCAF, (u8)(1U << RC_IOC_BITPOS_CH_THROTTLE), RC_DUTY_REVERSE_PROP }, /* RC_DUTY_CH_THROTTLE */
{ &PORTA, (u8)(1U << RC_IOC_BITPOS_CH_SHIFT_MODE), &IOCAF, (u8)(1U << RC_IOC_BITPOS_CH_SHIFT_MODE), RC_DUTY_PROP }, /* RC_DUTY_CH_SHIFT_MODE */
{ &PORTA, (u8)(1U << RC_IOC_BITPOS_CH_RESPONSE), &IOCAF, (u8)(1U << RC_IOC_BITPOS_CH_RESPONSE), RC_DUTY_PROP }, /* RC_DUTY_CH_RESPONSE */
{ &PORTA, (u8)(1U << RC_IOC_BITPOS_CH_PADDLE_SHIFT_INPUT), &IOCAF, (u8)(1U << RC_IOC_BITPOS_CH_PADDLE_SHIFT_INPUT), RC_DUTY_PROP }, /* RC_DUTY_CH_PADDLE_SHIFT_INPUT */
{ &PORTA, (u8)(1U << RC_IOC_BITPOS_CH_REV_LIMIT), &IOCAF, (u8)(1U << RC_IOC_BITPOS_CH_REV_LIMIT), RC_DUTY_PROP }, /* RC_DUTY_CH_REV_LIMIT */
};
/*===================================================================================================================================*/
/*===================================================================================================================================*/
/* 関数プロトタイプ宣言 */
static void func_rc_s_convert_tmrcount_to_duty( void );
static void func_rc_s_debug_pulseout( void );
static void func_rc_s_ioc_flag_erase( u8 u8_ioc_ch );
static void func_rc_s_ioc_state_read_back( u8 *u8_flag_buff, u8 *u8_port_buff ,u8 u8_ioc_ch );
/* グローバル変数 */
/**************************************************************/
/* Function: */
/* 変数初期設定 */
/* */
/**************************************************************/
void func_rc_g_init( void )
{
u8 u8_loopcnt;
u8_rc_s_duty_judge_timeout_flag = CLEAR;
u8_rc_s_duty_judge_timeout_cnt = (u8)0;
u8_rc_g_duty_judge_sequence = RC_SEQ_DUTY_SAMPLING_WAIT;
u16_rc_g_duty_speed = (u16)0;
u16_rc_g_duty_shift_mode = (u16)0;
u16_rc_g_duty_speed_gain = (u16)0;
u16_rc_g_duty_shift_updown = (u16)0;
u16_rc_g_duty_rev_limit = (u16)0;
u8_rc_s_debug_flag = CLEAR;
u8_rc_s_duty_get_complete = CLEAR;
u8_rc_s_duty_cnt_debug = (u8)0;
}
/**************************************************************/
/* Function: */
/* main関数 */
/* */
/* */
/**************************************************************/
void func_rc_g_main( void )
{
/* @@割り込み関数で更新される変数を、この処理内で再更新しないこと */
func_rc_s_convert_tmrcount_to_duty(); /* タイマカウントからdutyへの変換 */
func_rc_s_debug_pulseout(); /* パルス幅取得の動作確認処理 */
}
/**************************************************************/
/* Function: */
/* 入力パルスのduty識別・決定関数 */
/* */
/* ほんとはMCUハードウェア機能だけで完結させたいが、タイマ数が足りないのでパワー実装 */
/* @@多少判定処理のクロック誤差が生まれると思うが、実測で誤差として流せるか確認して判断したい */
/* ポート指定を容易に行えるように&同一タイミングのパルスはなるべく同じタイマ値を取得したいので、この処理内で判別する */
/**************************************************************/
void func_rc_g_duty_detection( void )
{
u8 u8_loopcnt;
u16 u16_timer_register_buff;
u8 u8_ch_sample_not_complete_flag;
u8 u8_ioc_flag_buff;
u8 u8_ioc_port_buff;
/* ローカル変数初期化 */
u8_ioc_flag_buff = (u8)0;
u8_ioc_port_buff = (u8)0;
u8_loopcnt = (u8)0;
u16_timer_register_buff = (u16)0;
u8_ch_sample_not_complete_flag = CLEAR;
switch ( u8_rc_g_duty_judge_sequence )
{
case RC_SEQ_DUTY_SAMPLING_WAIT:
/* 初回のトリガ操作を待機中・・・ */
/* いずれかのチャネルでIOC割り込みが発生した場合にタイマスタート */
/* 最初のチャネルだけdutyが小さくならないよう、タイミング優先でまずはタイマスタート */
func_mset_g_timer5_couter_set( (u16)1 ); /* タイマ レジスタクリア ※オーバーフロー割り込み仕様するので、リセット時に割り込みはいらないよう1をセットする */
func_mset_g_timer5_onoff( ON ); /* タイマ カウントスタート */
#if 0
for( u8_loopcnt = (u8)0; u8_loopcnt < RC_DUTY_CH_IDX_MAX ; u8_loopcnt++ )
{
func_rc_s_ioc_state_read_back( &u8_ioc_flag_buff, &u8_ioc_port_buff ,u8_loopcnt );
if( ( u8_ioc_flag_buff == SET ) &&
( u8_ioc_port_buff == RC_DUTY_PULSE_ON_LOGIC ) )
{ /* いずれかのチャネルで、ON区間開始を検知:連続測定開始 */
u8_rc_g_duty_judge_sequence = RC_SEQ_DUTY_SAMPLING;
u8_rc_s_duty_get_complete = CLEAR; /* メインループ側でのタイマ値取得完了フラグ クリア */
}
else
{ /* ON区間終了を検知 */
/* 初回がON区間終了から始めるのはおかしいので、タイマ停止。シーケンスそのまま */
func_mset_g_timer5_couter_set( (u16)1 ); /* タイマ レジスタクリア ※オーバーフロー割り込み仕様するので、リセット時に割り込みはいらないよう1をセットする */
func_mset_g_timer5_onoff( OFF ); /* タイマ カウント停止 */
rc_duty_get_by_int_tbl[u8_loopcnt].u16_ch_duty_cnt_start = (u16)0;
rc_duty_get_by_int_tbl[u8_loopcnt].u16_ch_duty_cnt_end = (u16)0;
rc_duty_get_by_int_tbl[u8_loopcnt].u8_start_capture_complete_flag = CLEAR;
rc_duty_get_by_int_tbl[u8_loopcnt].u8_end_capture_complete_flag = CLEAR;
}
func_rc_s_ioc_flag_erase( u8_loopcnt ); /* IOCフラグクリア */
}
#else
/* 最後のチャネルのサンプル終了後、次にCH0のIOC割り込みが入るまで若干猶予がある。 */
/* このタイミングでループタスクで値回収したいので、開始はCH0に固定する */
u8_loopcnt = RC_DUTY_CH_THROTTLE;
func_rc_s_ioc_state_read_back( &u8_ioc_flag_buff, &u8_ioc_port_buff ,u8_loopcnt );
if( ( u8_ioc_flag_buff == SET ) &&
( u8_ioc_port_buff == RC_DUTY_PULSE_ON_LOGIC ) )
{ /* いずれかのチャネルで、ON区間開始を検知:連続測定開始 */
u8_rc_g_duty_judge_sequence = RC_SEQ_DUTY_SAMPLING;
u8_rc_s_duty_get_complete = CLEAR; /* メインループ側でのタイマ値取得完了フラグ クリア */
}
else
{ /* ON区間終了を検知 */
/* 初回がON区間終了から始めるのはおかしいので、タイマ停止。シーケンスそのまま */
func_mset_g_timer5_onoff( OFF ); /* タイマ カウント停止 */
func_mset_g_timer5_couter_set( (u16)1 ); /* タイマ レジスタクリア ※オーバーフロー割り込み仕様するので、リセット時に割り込みはいらないよう1をセットする */
rc_duty_get_by_int_tbl[u8_loopcnt].u16_ch_duty_cnt_start = (u16)0;
rc_duty_get_by_int_tbl[u8_loopcnt].u16_ch_duty_cnt_end = (u16)0;
rc_duty_get_by_int_tbl[u8_loopcnt].u8_start_capture_complete_flag = CLEAR;
rc_duty_get_by_int_tbl[u8_loopcnt].u8_end_capture_complete_flag = CLEAR;
}
for( u8_loopcnt = (u8)0; u8_loopcnt < RC_DUTY_CH_IDX_MAX ; u8_loopcnt++ )
{ /* フラグは全部クリアする */
func_rc_s_ioc_flag_erase( u8_loopcnt ); /* IOCフラグクリア */
}
#endif
break;
case RC_SEQ_DUTY_SAMPLING:
u16_timer_register_buff = func_mset_g_timer5_read(); /* 割り込みが来た時点でいったんタイマレジスタの値を保持しておく */
/* 順番にチャネル判定 */
#if 0
/* 1チャンネルでの動作確認用 */
func_rc_s_ioc_state_read_back( &u8_ioc_flag_buff, &u8_ioc_port_buff ,RC_DUTY_CH_REV_LIMIT );
if( u8_ioc_flag_buff == SET )
{
if( u8_rc_s_debug_flag == SET )
{
u8_rc_s_debug_flag = CLEAR;
}
else
{
u8_rc_s_debug_flag = SET;
}
GPIO_OUT_DEBUG = u8_rc_s_debug_flag;
}
for( u8_loopcnt = (u8)0; u8_loopcnt < RC_DUTY_CH_IDX_MAX ; u8_loopcnt++ )
{ /* フラグは全部クリアする */
func_rc_s_ioc_flag_erase( u8_loopcnt ); /* IOCフラグクリア */
}
#else
/* IOC割り込みフラグが立ってるポートを確認 */
for( u8_loopcnt = (u8)0; u8_loopcnt < RC_DUTY_CH_IDX_MAX ; u8_loopcnt++ )
{
func_rc_s_ioc_state_read_back( &u8_ioc_flag_buff, &u8_ioc_port_buff ,u8_loopcnt );
if( u8_ioc_flag_buff == SET )
{ /* IOC割り込み発生あり */
if( u8_ioc_port_buff != RC_DUTY_PULSE_ON_LOGIC )
{ /* ON区間終わりの時 */
rc_duty_get_by_int_tbl[u8_loopcnt].u16_ch_duty_cnt_end = u16_timer_register_buff; /* IOC割り込み発生時点でのタイマ値を取得 ※PWM仕様上、複数チャネルが同時に切り替わることはないはず。 */
rc_duty_get_by_int_tbl[u8_loopcnt].u8_end_capture_complete_flag = SET; /* 対象のチャネルのパルス幅測定 完了 */
}
else
{ /* ON区間始まりの時:開始キャプチャとして保存する ※基本連続しているので、1つ後のチャネルでここに来る */
rc_duty_get_by_int_tbl[u8_loopcnt].u16_ch_duty_cnt_start = u16_timer_register_buff; /* IOC割り込み発生時点でのタイマ値を取得 ※PWM仕様上、複数チャネルが同時に切り替わることはないはず。 */
rc_duty_get_by_int_tbl[u8_loopcnt].u8_start_capture_complete_flag = SET; /* 対象のチャネルのパルス幅測定 完了 */
}
func_rc_s_ioc_flag_erase( u8_loopcnt ); /* IOCフラグクリア */
}
if( rc_duty_get_by_int_tbl[u8_loopcnt].u8_end_capture_complete_flag == CLEAR )
{ /* まだON区間測定が終了してないチャネルがある */
u8_ch_sample_not_complete_flag = SET;
}
}
/* 全チャネル パルス幅測定 完了判定 */
if( u8_ch_sample_not_complete_flag != SET )
{ /* 全チャネルサンプリング完了 */
u8_rc_g_duty_judge_sequence = RC_SEQ_DUTY_SAMPLING_WAIT; /* 待機状態へ戻す ※待機状態中にループタスクで値回収 */
func_mset_g_timer5_onoff( OFF );
func_mset_g_timer5_couter_set( (u16)1 );
for( u8_loopcnt = (u8)0; u8_loopcnt < RC_DUTY_CH_IDX_MAX ; u8_loopcnt++ )
{ /* ループが2回連続で走るが、すでに全CHサンプル完了後なのでOK */
rc_duty_get_by_int_tbl[u8_loopcnt].u8_start_capture_complete_flag = CLEAR;
rc_duty_get_by_int_tbl[u8_loopcnt].u8_end_capture_complete_flag = CLEAR;
}
}
#endif
break;
case RC_SEQ_DUTY_SAMPLING_TIMEOUT:
/* タイムアウト発生 */
/* CH0のIOC割り込み発生後、8CHすべて取得できる時間以上経過したのにパルスが来なかった後、IOC割り込み発生するとここに来る */
/* パルス幅の取得タイミングがずれたときにCH0開始に戻すために設けた */
/* 完全にパルスが止まった場合はIOC割り込みがなく、ここに来ることができないので、ループタスク側でもタイムアウト処理を作ったほうが良いかも */
if( u8_rc_s_duty_judge_timeout_cnt < U8_MAX )
{
u8_rc_s_duty_judge_timeout_cnt++;
}
if( u8_rc_s_duty_judge_timeout_cnt > RC_DUTY_JUDGE_TIMEOUT_CNT )
{ /* 何度もタイムアウトが発生している */
u8_rc_g_duty_judge_sequence = RC_SEQ_DUTY_SAMPLING_FAILE;
}
else
{
u8_rc_g_duty_judge_sequence = RC_SEQ_DUTY_SAMPLING_WAIT;
}
func_mset_g_timer5_onoff( OFF ); /* タイマ カウント停止 */
func_mset_g_timer5_couter_set( (u16)1 ); /* タイマ レジスタクリア ※オーバーフロー割り込み仕様するので、リセット時に割り込みはいらないよう1をセットする */
for( u8_loopcnt = (u8)0; u8_loopcnt < RC_DUTY_CH_IDX_MAX ; u8_loopcnt++ )
{ /* フラグは全部クリアする */
func_rc_s_ioc_flag_erase( u8_loopcnt ); /* IOCフラグクリア */
}
break;
case RC_SEQ_DUTY_SAMPLING_FAILE:
/* パルス幅測定失敗 */
/* ここに来た時点で設計ミスなので、デバッグ時点ではあえて抜けるないようにしておく。 */
for( u8_loopcnt = (u8)0; u8_loopcnt < RC_DUTY_CH_IDX_MAX ; u8_loopcnt++ )
{
// *(rc_duty_get_register_combi_tbl[u8_loopcnt].port_addr) != (u8)0; /* 読み取り専用なので特に意味なし */
func_rc_s_ioc_flag_erase( u8_loopcnt ); /* IOCフラグクリア */
rc_duty_get_by_int_tbl[u8_loopcnt].u16_ch_duty_cnt_start = (u16)0;
rc_duty_get_by_int_tbl[u8_loopcnt].u16_ch_duty_cnt_end = (u16)0;
rc_duty_get_by_int_tbl[u8_loopcnt].u8_start_capture_complete_flag = CLEAR;
rc_duty_get_by_int_tbl[u8_loopcnt].u8_end_capture_complete_flag = CLEAR;
}
u8_rc_s_duty_judge_timeout_cnt = (u8)0;
/* @@何度もここに来るので、ここに関数記述するのは微妙かもしれない。実害ないのでいったん保留。 */
func_mset_g_timer5_onoff( OFF ); /* タイマ カウント停止 */
func_mset_g_timer5_couter_set( (u16)1 ); /* タイマ レジスタクリア ※オーバーフロー割り込み仕様するので、リセット時に割り込みはいらないよう1をセットする */
break;
default:
break;
}
}
/**************************************************************/
/* Function: */
/* 入力パルスのduty識別・決定関数 */
/* IOC割り込みがあったのにパルス幅取得を完了できなかった場合の処理 */
/**************************************************************/
void func_rc_g_duty_detect_timeout( void )
{
//u8_rc_s_duty_judge_timeout_flag = SET;
}
/**************************************************************/
/* Function: */
/* *u8_flagbuff:引数/変数 IOCフラグ状態 */
/* *u8_portbuff:引数/変数 IOC割り当てのポート状態 */
/* u8_ioc_ch:引数 IOCのチャネル指定 */
/**************************************************************/
static void func_rc_s_ioc_state_read_back( u8 *u8_flag_buff, u8 *u8_port_buff ,u8 u8_ioc_ch )
{
u8 u8_iocxf_flag;
u8 u8_iocxf_port_state;
u8_iocxf_flag = *(rc_duty_get_register_combi_tbl[ u8_ioc_ch ].flag_addr); /* IOCフラグレジスタの値を取得 */
u8_iocxf_flag = u8_iocxf_flag & (rc_duty_get_register_combi_tbl[ u8_ioc_ch ].flag_bitmask); /* ビットマスク */
if( u8_iocxf_flag != (u8)0 )
{ /* IOCフラグレジスタの該当ビットが0ではない */
*u8_flag_buff = SET; /* のちの処理でビット位置気にしないよう、この時点で上書きする */
}
else
{
*u8_flag_buff = CLEAR;
}
/* IOCポートの確認 */
u8_iocxf_port_state = *(rc_duty_get_register_combi_tbl[ u8_ioc_ch ].port_addr); /* IOCに該当のポート状態を取得 */
u8_iocxf_port_state = u8_iocxf_port_state & (rc_duty_get_register_combi_tbl[ u8_ioc_ch ].port_bitmask); /* ビットマスク */
if( u8_iocxf_port_state != (u8)0 )
{
*u8_port_buff = SET;
}
else
{
*u8_port_buff = CLEAR;
}
}
/**************************************************************/
/* Function: */
/* IOC割り込みの特定のビットをクリアする */
/**************************************************************/
static void func_rc_s_ioc_flag_erase( u8 u8_ioc_ch )
{
u8 u8_ioc_flag_buff;
u8_ioc_flag_buff = rc_duty_get_register_combi_tbl[ u8_ioc_ch ].flag_bitmask;
u8_ioc_flag_buff = (u8)~u8_ioc_flag_buff; /* ビット反転 */
*( rc_duty_get_register_combi_tbl[ u8_ioc_ch ].flag_addr ) &= u8_ioc_flag_buff;
}
/**************************************************************/
/* Function: */
/* 入力パルス幅の一時保存値を回収 */
/* タイマの計算値を0~100の1byte内のdutyへ変換する */
/* インバータ電圧、角度ともに100段程度分解能があれば困らないはず */
/* @@除算が激重でこの処理が一番処理負荷高いので、処理時間問題ないかチェックする */
/**************************************************************/
static void func_rc_s_convert_tmrcount_to_duty( void )
{
u8 u8_loopcnt;
u8 u8_duty_calc_disable_flag;
u16 u16_pulse_on_time_cnt_buff;
u16 u16_calc_buff;
u16 u16_calc_buff2;
u32 u32_calc_buff;
u16 u16_tmr_cnt_base;
u16 u16_tmr_cnt_gap;
/* ローカル変数初期化 */
u8_loopcnt = (u8)0;
u16_pulse_on_time_cnt_buff = (u16)0;
u16_calc_buff = (u16)0;
u16_calc_buff2 = (u16)0;
u8_duty_calc_disable_flag = CLEAR;
/* グローバル変数へ移植 */
/* 割り込み更新がないタイミングでデータを取り出す */
if( ( u8_rc_s_duty_get_complete == CLEAR ) &&
( u8_rc_g_duty_judge_sequence == RC_SEQ_DUTY_SAMPLING_WAIT ) )
{ /* 次のパルス開始タイミングまで待機中 (duty更新なし中) */
/* 基準カウント数の算出 */
u16_tmr_cnt_base = RC_DUTY_100P_CNT - RC_DUTY_0P_CNT;
for( u8_loopcnt = (u8)0; u8_loopcnt < RC_DUTY_CH_IDX_MAX; u8_loopcnt++ )
{
u16_calc_buff = rc_duty_get_by_int_tbl[ u8_loopcnt ].u16_ch_duty_cnt_start; /* パルスON開始時のタイマ・カウント */
u16_calc_buff2 = rc_duty_get_by_int_tbl[ u8_loopcnt ].u16_ch_duty_cnt_end; /* パルスON終了時のタイマ・カウント */
if( u16_calc_buff < u16_calc_buff2 )
{ /* 正常:後ろのタイミングのタイマカウントのほうが大きい */
u16_calc_buff = u16_calc_buff2 - u16_calc_buff;
if( u16_calc_buff >= RC_DUTY_0P_CNT )
{ /* 下限のパルス幅以上の値がある */
u16_tmr_cnt_gap = u16_calc_buff - RC_DUTY_0P_CNT; /* 下限のパルス分を減算 */
if( u16_tmr_cnt_gap < RC_DUTY_CONVERSION_ROUND)
{ /* ほぼ0%よりのパルス幅 */
u16_tmr_cnt_gap = (u16)0; /* 0%に丸め込む */
}
if( u16_tmr_cnt_gap > u16_tmr_cnt_base )
{ /* 100%より大きい */
u16_tmr_cnt_gap = u16_tmr_cnt_base; /* 100%に丸め込む */
}
else
{
u16_calc_buff = u16_tmr_cnt_base - u16_tmr_cnt_gap;
if( u16_calc_buff < RC_DUTY_CONVERSION_ROUND )
{ /* ほぼ100%のパルス幅になっている */
u16_tmr_cnt_gap = u16_tmr_cnt_base; /* 100%に丸め込む */
}
}
}
else
{ /* 0%より小さいパルス幅 */
u16_tmr_cnt_gap = (u16)0;
}
}
else
{ /* ラジコンのPWMの性質上、パルス幅がゼロになることはない */
u8_duty_calc_disable_flag = SET; /* 異常時:計算しない*/
}
if( u8_duty_calc_disable_flag == CLEAR )
{ /* duty計算許可がある */
if( rc_duty_get_register_combi_tbl[ u8_loopcnt ].duty_direction == RC_DUTY_REVERSE_PROP )
{ /* duty増減方向を反転させる場合 */
u16_tmr_cnt_gap = u16_tmr_cnt_base - u16_tmr_cnt_gap;
}
#if 1
/* タイマ値 -> %変換 */
u32_calc_buff = func_ud_g_calcmul_2x2_byte( u16_tmr_cnt_gap, (u16)RC_CH_DUTY_100P );
u32_calc_buff = func_ud_g_calcdiv_4x4_byte( u32_calc_buff, (u32)u16_tmr_cnt_base );
u8_rc_g_ch_duty_tbl[ u8_loopcnt ] = (u8)u32_calc_buff;
#else
/* タイマ値 -> %変換 */
/* こっちのほうが重い */
u32_calc_buff = func_ud_g_calcdiv_4x4_byte( RC_DUTY_100P_CNT, RC_CH_DUTY_100P );
u32_calc_buff = func_ud_g_calcdiv_4x4_byte( (u32)u16_pulse_on_time_cnt_buff, u32_calc_buff );
u8_rc_g_ch_duty_tbl[ u8_loopcnt ] = (u8)u32_calc_buff;
#endif
}
}
u8_rc_s_duty_get_complete = SET;
}
}モータ/1次ギヤ回転数 計算方法
概要
つづいて今回使用するPIC18F25Q10で回転数検出を行う方法について。
今回は変速処理をスムーズに行うために、モータと1次ギヤ側の回転数をうまく合わせるような制御を入れます。
(詳細は動画の方で述べたいと思います。)
このため、回転数を検出する必要があります。
ギヤにつけたマグネットとホールセンサを使用し、1回転で1周期のパルスが発生するようにして、このパルスをもとに回転数計算を行います。
実装概要決め
回転数の検出方法ですが、今回もマイコンハードウェア的な制約により、キャプチャは使えません。
このため、キャプチャに似たことが実現できそうな「ゲートトグルモード」を使用します。
PIC18F25Q10のタイマ構成は、Timer1、3、5の場合下記のようになっています。
タイマクロックのカウント許可信号が、TMRxONだけでなく、TMRxGEが1の場合はTxGPPSで指定した入力ピンの状態によって切り替えられる・・・という構成になっています。
(詳細はタイマ1,3,5のゲート機能を確認)

ざっくりまとめると、「あるポートの電圧レベルがH、またはLの時に限り、タイマのカウントを進める」といった仕様です。
ゲート機能については4パターンほど動作モードが用意されているのですが、今回はそのうちの1つの下記の仕様を使います。

このモードでは、下記のようなタイマカウント動作が実現できます。
・タイマのゲートに割り当てたパルス状の入力信号について、1周期おきにタイマのカウントアップを許可する。
(パルスの発生回数/2だけ、タイマのカウントアップを行うことができる)
・タイマのゲートに入力された信号が1周期完了した場合、タイマゲート割り込みを発生、カウントアップを停止する。
このモードでは、1周期おきという制約が付くものの、カウントアップ動作を1周期分だけ許可するという、キャプチャに近い動作をします。
キャプチャと異なり、ゲート割り込み発生時に現在のカウント値が特定のレジスタに保存されたりカウントリセットされたりはしませんが、この辺は割り込みを使ってうまくゴチャゴチャさせると何とかなります。
実装詳細:回転数検出
ゲートトグルモードを使用して回転数検出を行う場合のタイミングチャートを下記に示します。
今回は1周期おきにタイマゲートが閉じる都合上、回転数相当のカウント値を取得するフェーズとカウント値をリセットするフェーズの2つを設け、処理することにしました。
回転数の反応速度は落ちますが、この辺はマイコンの制約なので致し方ないかな~と思います。

モードの中には下記のようにONパルスの間だけ回転数検出を行うような、「タイマゲート有効モード」なるものも存在します。
一応、こちらのモードのほうが毎周期タイマのカウントを更新できるので、応答性は良くなります。
ただしこの場合、パルスのON幅とOFF幅が50:50の比率でない場合に、回転数に逆算するためのロジックが面倒になるので、今回は採用しませんでした。
おそらくON幅と回転数の紐づきをまとめたデータをあらかじめ取得しておかないと、うまく成り立たないかな~と思います。
測定はめんどいのでやめました。

この処理の問題点と対策
この処理ですが、タイマのゲート機能の特性上、下記のような不都合があります。
・ゲート機能では、ゲートが閉じている間はカウント動作そのものが停止する
➡ゲート入力に割り当てたパルスが立ち上がり or 足り下がりのどちらで停止したかにより、オーバーフローの発生有無が変わってくる。
実際の実装においては、モータが停止した時に停止判定できないことが問題になります。
(最後に保存したタイマのカウント値以降ゲート割り込み、タイマオーバーフロー割り込みが発生しないので、回転数更新ができなくなります。)
これを解決するため、今回は下記のような実装としてみました。

タイマのカウント現在地を使用して回転数計算をすること自体は変わりありません。
変化点は、タイマのゲート入力のポートについてIOC割り込みを有効化し、ソフト内で別のタイマのカウント値をベースに低速側の回転数計算を行う処理を追加したことです。
2つめの「キャプチャ保存配列2」では、タイマゲート割り込みにより取得する回転数帯よりずっと低い領域での回転数のみを検知します。
(周期としては100~1000ms程度の周期。0~500rpm程度が狙い。)
これにより、停止付近や低速での回転数計算自体は、継続して行われます。
ソフト内では2つの回転数を計算し、有効な回転数を持つ方を「現在の回転数」として扱うような設定を行いました。

インバータ制御部分
作成中。
おいおい追記していきます。