UMEHOSHI ITA TOP PAGE COMPUTER SHIEN LAB
[UMEHOSHI ITA]の制御で使っているIC「PIC32MX270F256B-I/SO」のフラッシュメモリには、テスト用プログラムが書き込まれいています。
以降では、このプログラムを「テスト・ウメ・フラッシュ」と呼ぶことにして解説します。
また、「テスト・ウメ・フラッシュ」を利用したユーザー用のプログラムを
「ウメ・エディットプログラム」と呼ぶことにします。
「ウメ・エディットプログラム」の開発では「umehoshiEditツール」が必要で、
その取得や最初の操作情報は、こちらを参照してください。
(「PICKit3などの書き込みツール」をお持ちの方で、「テスト・ウメ・フラッシュ」を利用しないで、
「MPLAB X IDE」の開発環境ですべてをプログラミングする場合の情報ではありません。)
「テスト・ウメ・フラッシュ」をどのように利用して、「ウメ・エディットプログラム」を
作るかの解説で、「umehoshiEditツール」の使用例を示しています。
各サンプルは、このWebページ上でドラック&コピーして、貼り付けしてご利用ください。
各種確認プログラム | 左記に必要な部品の追加例 |
---|---|
とくに必要ありません。(D1のLEDはあるとよい) | |
PWM対応の部品追加例 | |
ADC 対応の部品追加例 | |
BEEP SWITCH 対応の部品追加例 | |
Reset SW, Type-A, CN2 部品追加例 | |
U20,D4,D5,NPN, D3 部品追加例 | |
CN11,CN-12 ,Bluetoothなどの基板 の部品追加例 |
モータやリレーなど制御対象は、CN6とCN7のコネクタで、下記はその実験のイメージです。
Type A USBの接続写真ですが、「micro B」のUSBの接続だけで可能です。どちらか一方を接続します。
(Type A USBに接続の場合は、PC側もType Aコネクタで、PC側がHOST接続にする必要があります)
それぞれこのコネクタのピンは4ピンですが、1ピンと2ピン、3ピンと4ピンが繋がっています。
それぞれはDC-JACKからの電源で+または−に加圧できるようになっています。
これは「H-Bridge Motor Drive」の回路構成になっています。
CN6の制御は、チップのRB2とRB3の端子です。
_RB2 = 1, _RB3 = 0; にすると、CN6の1-2ピンが3-4ピンよりMvの供給電圧分だけ低い電位になります。
(DC-JACKの供給電圧をMvとします。
これらを制御するチップの端子名の出力状態とコネクタの出力状態の関係を以下にまとめて示します。
なおデファオルトで、DC-JACK供給側とチップの端子側はホトカプラでGNDも含めて絶縁されています。
よって、下記の0vやMvの表現はロジック側の電位ではありません。DC-JACK供給側の電位です。
RB3 | RB2 | CN6の[1-2pin] | CN6の[1-2pin] | CN6の[3-4]をベースとした[1-2]の電位 |
---|---|---|---|---|
0 | 0 | Mv | Mv | 0v |
0 | 1 | Mv | 0v | +Mv |
1 | 0 | 0v | Mv | -Mv |
1 | 1 | 0v | 0v | 0v |
RB14 | RB13 | CN7の[1-2pin] | CN7の[3-4pin] | CN7の[1-2]をベースとした[3-4]の電位 |
---|---|---|---|---|
0 | 0 | Mv | Mv | 0v |
0 | 1 | 0v | Mv | +Mv |
1 | 0 | Mv | 0v | -Mv |
1 | 1 | 0v | 0v | 0v |
#include <xc.h> #include "common.h" __attribute__((address( 0x80005000 ))) void test (void); void test() { _RB15 = ! _RB15; // D1 LED 反転(実行できていることの確認用) // CN7[1-2]を基準として[3-4]にDC-JACKの供給電圧を与える。 _RB13 = 1; _RB14 = 0;// 動作しませんでした。 }PIC32のチップでは 「ポートに対する特定のビット操作命令が連続する場合、nop を入れる必要がある!」 ということが知られています。(RAM内のプログラムの場合?に起きるようです)
#include <xc.h> #include "common.h" __attribute__((address( 0x80005000 ))) void test (void); void test() { _RB15 = ! _RB15; // D1 LED 反転(動作確認用) // CN7[1-2]を基準として[3-4]にDC-JACKの供給電圧を与える。 _RB13 = 1; asm("nop"); _RB14 = 0;// nopがあると動作します。 }上記のように間違えやすい_RB2の表現を使わなくても、次の表現のビットANDとORを使えば問題ありません。
#include <xc.h> #include "common.h" __attribute__((address( 0x80005000 ))) void test (void); void test() { _RB15 = ! _RB15; // D1 LED 反転(動作確認用) // CN7の[1-2]に対応するRB14を0、[3-4]に対応するRB13を1にする。 // CN6の[1-2]に対応するRB2を0、[3-4]に対応するRB3を1にする。 PORTBCLR = 0b0100000000000100;// RB14,RB2を0 PORTBSET = 0b0010000000001000;// RB13,RB3を1 }これを変更して、実行するごとに、モータへの印加電圧を逆にするプログラム例を示します。
#include <xc.h> #include "common.h" __attribute__((address( 0x80005000 ))) void test (void); void test() { _RB15 = ! _RB15; // D1 LED 反転(動作確認用) if( _RB15 == 0 ){ // CN7の[1-2]に対応するRB14を0、[3-4]に対応するRB13を1にする。 // CN6の[1-2]に対応するRB2を0、[3-4]に対応するRB3を1にする。 PORTBCLR = 0b0100000000000100;// RB14,RB2を0 PORTBSET = 0b0010000000001000;// RB13,RB3を1 } else { PORTBCLR = 0b0010000000001000;// RB13,RB3を0 PORTBSET = 0b0100000000000100;// RB14,RB2を1 } }
CN6やCN7のそれぞれにモータがある場合、実行するとLEDの点灯/消灯が切り代わり、
それに応じて 2つのモータの前進回転と後進回転が切り替わります。
(前進と後進のどちらになるかは、モータの接続状態で逆になりますが・・)
なお、上記と同じコードですが使用するポートBのパターンを定義して使う方が分かりやすいでしょう。
その例を下記に示します。(3_motor/motor.c)
#include <xc.h> #include "common.h" #define CN6B02 0x0004 //CN6のPORTBbits.RB2制御用bit #define CN6B03 0x0008 //CN6のPORTBbits.RB2制御用bit #define CN7B14 0x4000 //CN7のPORTBbits.RB14制御用bit #define CN7B13 0x2000 //CN7のPORTBbits.RB13制御用bit __attribute__((address( 0x80005000 ))) void test (void); void test() { _RB15 = ! _RB15;// LEDのD1出力を反転 ★ if( _RB15 == 0 ){ PORTBCLR = CN7B14 | CN6B02;// RB14,RB2を0 PORTBSET = CN7B13 | CN6B03;// RB13,RB3を1 } else { PORTBCLR = CN7B13 | CN6B03;// RB13,RB3を0 PORTBSET = CN7B14 | CN6B02;// RB14,RB2を1 } }
コンペアモジュールを使ってPWMのデューティを設定します。
デューティの設定は、
OC5RS、OC1RS、OC3RS、
OC4RSのレジスタSFR(Special Function Registers)設定で行います。
Timer2の割り込みサイクルがPWMの周期サイクルになっており、
それぞれRB2、RB3、RB14、RB13のデューティ比の設定値になっています。
設定値の最大は、0x0ffffです。
左下の(PWM.c)はCN7コネクタに対する最大デューティ比指定で、右下の単純なモータ印加と同じ印加と言えます。
#include <xc.h> //PWM.c #include "common.h" __attribute__((address( 0x80005000 ))) void test (void); void test() { _RB15 = ! _RB15; // D1 LED 反転(動作確認用) _set_pwd_mode(1); // PWM モードへ変更 // CN7[1-2]を基準として[3-4]にDC-JACKの供給電圧を与える。 OC3RS = 0x0; OC4RS = 0x0ffff;//デューティ比最大のフルパワー T2CONbits.ON = 1;// typeBでON } |
#include <xc.h> #include "common.h" __attribute__((address( 0x80005000 ))) void test (void); void test() { _RB15 = ! _RB15; // D1 LED 反転(動作確認用) // CN7の[1-2]に対応するRB14を0、[3-4]に対応するRB13を1にする。 PORTBCLR = 0b0100000000000000;// RB14,RB2を0 PORTBSET = 0b0010000000000000;// RB13,RB3を1 } |
実際の内部動作は、対応するPRBのビットをを1にしてコンペアモジュールのOCxRをカウントアップを始めます。
このカウントはTimer2で作られる割り込みサイクルでしアップし、
対応するOCxRSと一致した時に、対応するPRBのビットを0に戻します。
(この1の期間がモータに電圧を供給する期間です)
OCxRSの値は0〜0x0ffffの16ビットで、この設定比がデューティ比の0〜100%に対応します。
デフォルトでは、このPWMが動作するモードになっていません。
前述で示したビットパターンでONかOFFにするだけ制御モードです。
このモードからPWMが動作するモードにこの切り替えするためには、
_set_pwd_mode(1)のマクロ指定と、T2CONbits.ON = 1;のタイマー機能を有効にする必要があります。
(タイマーの割込みは有効にしなくても動作可能ですが、タイマ機能を有効にしなくてはなりません)
デューティ比を50%にして、実行するごとにモータへの印加電圧を逆にするプログラム例を以下に示します。
#include <xc.h> //PWM2.c #include "common.h" __attribute__((address( 0x80005000 ))) void test (void); void test() { _RB15 = ! _RB15; // D1 LED 反転(動作確認用) _set_pwd_mode(1); // PWM モードへ変更 if( _RB15 == 0){ // CN6[1-2]を基準として[3-4]にDC-JACKの供給電圧を与える。 OC5RS = 0x0; OC1RS = 0x07fff;//デューティ比:50%のパワー // CN7[1-2]を基準として[3-4]にDC-JACKの供給電圧を与える。 OC3RS = 0x0; OC4RS = 0x07fff;//デューティ比:50%のパワー } else { // CN6[1-2]を基準として[3-4]に、負のDC-JACKの供給電圧を与える。 OC5RS = 0x07fff;//デューティ比:50%のパワー OC1RS = 0x0; // CN7[1-2]を基準として[3-4]に、負のDC-JACKの供給電圧を与える。 OC3RS = 0x07fff;//デューティ比:50%のパワー OC4RS = 0x0; } T2CONbits.ON = 1;// typeBでON }
以下は応用で、1秒ごとに前進、右回転、左回転、後進、停止と動作することを
繰り返す処理。
(モータの接続方法で変わるので、モータの極性などの接続と、適当に合わせる必要があります)
#include <xc.h> //PWM3.c #include "common.h" int cn6power=0x07fff;//デューティ比:50%のパワー int cn7power=0x07fff;//デューティ比:50%のパワー void forward(){ OC5RS = 0x0; // CN6[1-2]制御(RB2) OC1RS = cn6power; // CN6[3-4]制御(RB3) OC3RS = 0x0; // CN7[1-2]制御(RB14) OC4RS = cn7power; // CN7[3-4]制御(RB13) } void right(){ OC5RS = 0x0; // CN6[1-2]制御(RB2) OC1RS = cn6power; // CN6[3-4]制御(RB3) OC3RS = cn7power; // CN7[1-2]制御(RB14) OC4RS = 0x0; // CN7[3-4]制御(RB13) } void left(){ OC5RS = cn6power; // CN6[1-2]制御(RB2) OC1RS = 0x0; // CN6[3-4]制御(RB3) OC3RS = 0x0; // CN7[1-2]制御(RB14) OC4RS = cn7power; // CN7[3-4]制御(RB13) } void stop(){ OC5RS = 0x0; // CN6[1-2]制御(RB2) OC1RS = 0x0; // CN6[3-4]制御(RB3) OC3RS = 0x0; // CN7[1-2]制御(RB14) OC4RS = 0x0; // CN7[3-4]制御(RB13) } void back(){ OC5RS = cn6power; // CN6[1-2]制御(RB2) OC1RS = 0x0; // CN6[3-4]制御(RB3) OC3RS = cn7power; // CN7[1-2]制御(RB14) OC4RS = 0x0; // CN7[3-4]制御(RB13) } #define TIMING 10000 // 約1秒 void timer_sub(){ static int timing_count=0; if(timing_count == TIMING ) { forward();//前進 _send_decimal(timing_count, 6); _send_string("\r\n"); } else if(timing_count == TIMING *2){ right();//右回転 _send_decimal(timing_count, 6); _send_string("\r\n"); } else if(timing_count == TIMING *3){ left();//左回転 _send_decimal(timing_count, 6); _send_string("\r\n"); } else if(timing_count == TIMING *4) { back();//後進 _send_decimal(timing_count, 6); _send_string("\r\n"); } else if(timing_count == TIMING *5) { stop();//停止 _send_decimal(timing_count, 6); _send_string("\r\n"); } else if(timing_count == TIMING *6) { // return; _send_decimal(timing_count, 6); _send_string("\r\n"); timing_count = 0; } timing_count++; } __attribute__((address( 0x80005000 ))) void start(void); void start() { _RB15 = ! _RB15; // D1 LED 反転(動作確認用). T4CONbits.TCKPS = 5;//1:32プリスケール値 PR4=124; // =0.0001/(1/40e6)/32-1 これは0.0001秒 _HANDLES[_IDX_TIMER_4_FUNC] = timer_sub; // 上記タイマー設定の呼び出し関数登録 IEC0bits.T4IE = 1;// Timer4 Enable(割込み許可) T4CONbits.ON = 1;// timer割込みオン _set_pwd_mode(1); // PWM モードへ変更 T2CONbits.ON = 1;// typeBでON(PWMのスタート) }
以下は、比較的難しい技術情報です。必要に応じてご覧ください。
// Timer2 の初期化 ------デフォルトでPWMのタイミングカウンターに使用---------------- void init_timer_2(){ // ---- Timer2を使う指定 ここから T2CONbits.ON = 0;// typeBでON T2CONbits.SIDL = 0;// デバイスがアイドルモードに移行しても動作を継続する T2CONbits.TGATE = 0;// ゲート時間積算を無効にする T2CONbits.TCKPS = 0;// タイマ入力クロック [1:1]プリスケール値 // TCKPS 3bit:111 T2CONbits.T32 = 0;//TMRxとTMRyは別々の16ビットタイマを構成する T2CONbits.TCS = 0;//内部の周辺モジュール用クロック T2CON =0x00000000;//typeB,16bit, [1:1]プリスケール //T2CON =0x00000070;//typeB,16bit, [1:256]プリスケール TMR2=0x0000; //16bitタイマの設定値(レジスタがカウントアップ) PR2=0x0FFFF; //16bit周期レジスタビット設定 IPC2SET = 0x0000000C; // Set priority level = 3 IPC2SET = 0x00000001; // Set sub-priority level = 1 IFS0CLR = 0x00000200; // Clear the timer interrupt status flag IEC0SET = 0x00000200;//T2IE Timer2 Enable(割込み許可) //T2CONSET =0x8000; // Start timer2 // ---- Timer2を使う指定 ここまで } //モータ用パルス幅変調モードの初期設定 void init_compare()// IDX_INIT_PWD { // ----- PWM の設定 ここから //CN6(左側)前方向デューティ比用Output Compare Output5 の設定 RPB2Rbits.RPB2R = 0x6; // RB2をOC5の出力にする。 OC5CONbits.SIDL = 0; // アイドルモード中も動作を継続する OC5CONbits.OC32 = 0; //OCxR<15:0> およびOCxRS<15:0> を使って16 ビットタイマ源と比較する OC5CONbits.OCTSEL = 0; // Timer2 をこの出力コンペア モジュールのクロック源として使う OC5CONbits.OCM = 6; // OC1 をPWM モードにし、フォルトピンを無効にする IPC5bits.OC5IP = 5;// Set OC1 interrupt priority to 5 IPC5bits.OC5IS = 2;// Set Subpriority to 3, maximum IFS0CLR= _IFS0_OC5IF_MASK; // Clear the OC5 interrupt flag //IEC0SET= _IEC0_OC5IE_MASK; // Enable Interrupt //CN6(左側)後ろ方向デューティ比用Output Compare Output1 の設定 RPB3Rbits.RPB3R = 0x5; // RB3をOC1の出力にする OC1CONbits.SIDL = 0; // アイドルモード中も動作を継続する OC1CONbits.OC32 = 0; //OCxR<15:0> およびOCxRS<15:0> を使って16 ビットタイマ源と比較する OC1CONbits.OCTSEL = 0; // Timer2 をこの出力コンペア モジュールのクロック源として使う OC1CONbits.OCM = 6; // OC1 をPWM モードにし、フォルトピンを無効にする IPC1bits.OC1IP = 5;// Set OC1 interrupt priority to 5 IPC1bits.OC1IS = 2;// Set Subpriority to 3, maximum IFS0CLR= _IFS0_OC1IF_MASK; // Clear the OC1 interrupt //IEC0SET= _IEC0_OC1IE_MASK; // Enable Interrupt //CN7(右側)前方向デューティ比用Output Compare Output4 の設定 RPB13Rbits.RPB13R = 0x5; // RB13をOC4の出力にする。 OC4CONbits.SIDL = 0; // アイドルモード中も動作を継続する OC4CONbits.OC32 = 0; //OCxR<15:0> およびOCxRS<15:0> を使って16 ビットタイマ源と比較する OC4CONbits.OCTSEL = 0; // Timer2 をこの出力コンペア モジュールのクロック源として使う OC4CONbits.OCM = 6; // OC1 をPWM モードにし、フォルトピンを無効にする IPC4bits.OC4IP = 5;// Set OC1 interrupt priority to 5 IPC4bits.OC4IS = 2;// Set Subpriority to 3, maximum IFS0CLR= _IFS0_OC3IF_MASK; // Clear the OC3 interrupt //IEC0SET= _IEC0_OC3IE_MASK; // Enable Interrupt //CN7(右側)後ろ方向デューティ比用Output Compare Output3 の設定 RPB14Rbits.RPB14R = 0x5; // RB14をOC3の出力にする。 OC3CONbits.SIDL = 0; // アイドルモード中も動作を継続する OC3CONbits.OC32 = 0; //OCxR<15:0> およびOCxRS<15:0> を使って16 ビットタイマ源と比較する OC3CONbits.OCTSEL = 0; // Timer2 をこの出力コンペア モジュールのクロック源として使う OC3CONbits.OCM = 6; // OC1 をPWM モードにし、フォルトピンを無効にする IPC3bits.OC3IP = 5;// Set OC1 interrupt priority to 5 IPC3bits.OC3IS = 2;// Set Subpriority to 3, maximum IFS0CLR= _IFS0_OC4IF_MASK; // Clear the OC4 interrupt flag //IEC0SET= _IEC0_OC4IE_MASK; // Enable Interrupt OC5R = _UME_CN6_OC5R;//0;//出力コンペアx コンペアレジスタ・・ OC5RS = _UME_CN6_OC5RS;//出力コンペアx セカンダリコンペアレジスタ設定用(デューティー比 ) OC1R = _UME_CN6_OC1R;//出力コンペアx コンペアレジスタ・・ OC1RS = _UME_CN6_OC1RS;//出力コンペアx セカンダリコンペアレジスタ設定用(デューティー比 ) OC4R = _UME_CN7_OC4R;//0;//出力コンペアx コンペアレジスタ・・ OC4RS = _UME_CN7_OC4RS;//出力コンペアx セカンダリコンペアレジスタ設定用(デューティー比 ) OC3R = _UME_CN7_OC3R;//0;//出力コンペアx コンペアレジスタ・・ OC3RS = _UME_CN7_OC3RS;//出力コンペアx セカンダリコンペアレジスタ設定用(デューティー比 ) //各出力コンペア モジュールを有効にする OC5CONbits.ON = 1; // RB2のOC5の出力をON(CN6の前方向) OC1CONbits.ON = 1; // RB3のOC1の出力をON(CN6の後ろ方向) OC4CONbits.ON = 1; // RB13のOC4の出力をON(CN7の前方向) OC3CONbits.ON = 1; // RB14のOC3の出力をON(CN7の後ろ方向) // ----- PWM の設定 ここまで } // 現在未使用( PWM を使わないでモータを前進させる初期化) void init_not_compare(){ // モータテスト //TRISBCLR = 0x0000E22C; // 出力指定 1110 0010 0010 1100 // ビット操作命令をポートに対して行う場合、ポートから全ての bit を読み出し、 // 指定のビットをセットしてから、ポートに書き戻す。 // その直後にビット操作命令がきた場合、ポートに書き戻したデータが確定しない // まま読み出しが起こり、ビットが反転する可能性がある。よって間にNOPを追加する。 OC5CONbits.ON = 0; // RB2のOC5の出力をON(CN6) OC1CONbits.ON = 0; // RB3のOC1の出力をON(CN6) OC4CONbits.ON = 0; // RB13のOC4の出力をON(CN7) OC3CONbits.ON = 0; // RB14のOC3の出力をON(CN7) PORTBCLR = 0x600c;//0b0110 0000 0000 1100; }起動時は、init_not_compare()を行っています。