V7's MotorTestProgram for F446
Dependencies: mbed ros_lib_kinetic USBDevice
main.cpp
- Committer:
- ksingyuunyuu
- Date:
- 2019-04-15
- Revision:
- 1:417488dfc3d0
- Parent:
- 0:27046fed2426
File content as of revision 1:417488dfc3d0:
// インクルード先の宣言 #include "mbed.h" // マクロ定義 #define MDcontroll 1 #define MDwrite 2 #define MDwriteBC 3 /* // 機能の宣言、設定 CAN can1(PB_8, PB_9); // can_name( RXD, TXD ) Ticker ticker; // 関数tickerを割り込みに使用することの宣言 // グローバル変数の宣言 char counter = 0; void send() { char txdata[8]; int CANID; txdata[0] = 0x10; txdata[1] = 0x40; //rpmcmd1 txdata[2] = 0x07; //MT1=2000rpm txdata[3] = 0xD0; //MT1=2000rpm CANID=0x200|((MDwrite)&0xf)<<5|0x0a ; printf("send()\n"); if(can1.write(CANMessage(CANID,&txdata[0],4))) { printf("wloop()\n"); counter++; printf("Message sent: %d\n", counter); } } int main() { printf("main()\n"); can1.frequency(500000); CANMessage msg; ticker.attach(&send, 1); wait(0.2); } */ CAN can1(PB_8, PB_9); // can_name( RXD, TXD ) Ticker ticker; // 関数tickerを割り込みに使用することの宣言 // グローバル変数の宣言 int pattern = 0; char input; int state = 1; int dir = 1; // 関数のプロトタイプ宣言 void all_motor_stop( void ); void motor1_forward( void ); void motor1_back( void ); void motor2_forward( void ); void motor2_back( void ); void MD_mode_change(int mode); int main() { // 割り込みの設定 //ticker.attach(&LEDwave, 0.2); //CANの設定 CANMessage msg; // CANメッセージを格納する変数 can1.frequency(500000); // CANのビットレートを500kHzに設定 // while(pc.readable() == 0); pattern = 0; while( 1 ){ switch( pattern ){ case 0: all_motor_stop(); // モータストップ状態 printf("\r\n"); printf("TEC-MD7U-A TestProgram for NUCLEO-F446RE\r\n"); printf("\r\n"); printf("1: Motor1 Forward\r\n"); printf("2: Motor1 Back\r\n"); printf("3: Motor2 Forward\r\n"); printf("4: Motor2 Back\r\n"); printf("\r\n"); printf("Press any key of 1-4\r\n"); printf("And Press Enter\r\n"); pattern = 1; // 次のパターンへ break; case 1: scanf("%d",&input); // 入力待ち if( input > 0 && input < 5 ){ // 1-4以外のキーボード入力は受け付けない printf("%d\r\n",input); // 入力データを表示する pattern = (input * 10) + 1; // 遷移先に飛ぶ break; } break; case 11: // モータ1前進パターン motor1_forward(); // モータ1前転2000回転 printf("MotorForwardActive"); printf("Press '0' ,StopMotor"); scanf("%d",&input); // 入力待機状態 if( input == 0 ){ // 入力に0が渡されたら、待機状態に移行する pattern = 0; break; } break; case 21: motor1_back(); // モータ1後転2000回転 printf("MotorForwardActive"); printf("Press'0',StopMotor"); scanf("%d",&input); // 入力待機状態 if( input == 0 ){ // 入力に0が渡されたら、待機状態に移行する pattern = 0; break; } break; case 31: motor2_forward(); // モータ2前転2000回転 printf("MotorForwardActive"); printf("Press'0',StopMotor"); scanf("%d",&input); // 入力待機状態 if( input == 0 ){ // 入力に0が渡されたら、待機状態に移行する pattern = 0; break; } break; case 41: motor2_back(); printf("MotorForwardActive"); printf("Press'0',StopMotor"); scanf("%d",&input); if( input == 0 ){ pattern = 0; break; } break; default: printf("\r\n"); printf("Invalid Value\r\n"); printf("\r\n"); pattern = 0; break; } // switch } // while } // main /* CANIDプロトコル / CANID:xxyyyyzzzzzの11bit中 / 上位2bit:優先度 :小さいものが高優先 [00]:ブロードキャスト用?? [01]:M-bedから書き込みに使える [10]:MDからくるレポート [11]:不明 メッセージの衝突回避用 / 次の4bit:プロトコルID :[0]高優先度プロトコル [1]制御プロトコル [2-3]書き込みプロトコル [8]高優先度通知プロトコル [9]イベント通知プロトコル [10-12]ステータスレポートプロトコル / 下位5bit:デバイスID :デバイスIDとデバイスの各メールボックス / / CANデータフィールド1Byte目:上位4bit:1つ目のデータはレジスタ何個分か 下位4bit:2つ目のデータはレジスタ何個分か RPMCMD1 =2Byte RPMCMD2 =2Byte / CANデータフィールド2Byte目:書き込む先のアドレス1 レジスタのアドレス 例)RPMCMD1 =0x40 (64番目 / CANデータフィールド3Byte目:例)回転数1000の上位2bit / CANデータフィールド4Byte目:例)回転数1000の下位2bit / CANデータフィールド5Byte目:書き込む先のアドレス2 レジスタのアドレス RPMCMD1 =0x40 (64番目 / CANデータフィールド6Byte目:例)回転数1000の上位2bit / CANデータフィールド7Byte目:例)回転数1000の下位2bit / CANデータフィールド8Byte目: / */ #define MDcontroll 1 #define MDwrite 2 #define MDwriteBC 3 void all_motor_stop( void ){ // 全モータストップ //MT1=0rpm MT2=0rpm char txdata[8]; int CANID; txdata[0] = 0x11; txdata[1] = 0x40; //rpmcmd1 txdata[2] = 0x00; //MT1=-2000rpm txdata[3] = 0x00; //MT1=-2000rpm txdata[4] = 0x41; txdata[5] = 0x00; txdata[6] = 0x00; CANID=0x200 | ((MDwrite)&0xf)<<5 | 0x0a ; // 上位2ビット:優先度:01 次の4bit:プロトコルID:受信(MD側) 下位5bit:デバイスID:01番 can1.write(CANMessage(CANID,&txdata[0],7)); } void motor1_forward( void ){ // モータ1正転2000rpm //MT1=2000rpm char txdata[8]; int CANID; txdata[0] = 0x10; txdata[1] = 0x40; //rpmcmd1 txdata[2] = 0x07; //MT1=2000rpm txdata[3] = 0xD0; //MT1=2000rpm CANID=0x200 | ((MDwrite)&0xf)<<5 | 0x0a ; // 上位2ビット:優先度:01 次の4bit:プロトコルID:受信(MD側) 下位5bit:デバイスID:01番 can1.write(CANMessage(CANID,&txdata[0],4)); } void motor1_back( void ){ // モータ1反転2000rpm //MT1=-2000rpm char txdata[8]; int CANID; txdata[0] = 0x10; txdata[1] = 0x40; //rpmcmd1 txdata[2] = 0xf8; //MT1=-2000rpm txdata[3] = 0x30; //MT1=-2000rpm CANID=0x200 | ((MDwrite)&0xf)<<5 | 0x0a ; // 上位2ビット:優先度:01 次の4bit:プロトコルID:受信(MD側) 下位5bit:デバイスID:01番 can1.write(CANMessage(CANID,&txdata[0],4)); } void motor2_forward( void ){ // モータ2前進2000rpm //MT2=2000rpm char txdata[8]; int CANID; txdata[0] = 0x10; txdata[1] = 0x41; //rpmcmd2 txdata[2] = 0x07; //MT2=2000rpm txdata[3] = 0xD0; //MT2=2000rpm CANID=0x200 | ((MDwrite)&0xf)<<5 | 0x0a ; // 上位2ビット:優先度:01 次の4bit:プロトコルID:受信(MD側) 下位5bit:デバイスID:01番 can1.write(CANMessage(CANID,&txdata[0],4)); } void motor2_back( void ){ // モータ2前進2000rpm //MT2=-2000rpm char txdata[8]; int CANID; txdata[0] = 0x10; txdata[1] = 0x41; //rpmcmd2 txdata[2] = 0xf8; //MT1=-2000rpm txdata[3] = 0x30; //MT1=-2000rpm txdata[4] = 0x00; txdata[5] = 0x00; txdata[6] = 0x00; txdata[7] = 0x00; CANID=0x200 | ((MDwrite)&0xf)<<5 | 0x0a ; // 上位2ビット:優先度:01 次の4bit:プロトコルID:受信(MD側) 下位5bit:デバイスID:01番 can1.write(CANMessage(CANID,&txdata[0],4)); } void MD_mode_change(int mode){ // モータドライバのモード変更関数 char txdata[8]; int CANID; txdata[0] = 0x05; txdata[1] = mode; txdata[2] = 0x00; txdata[3] = 0x00; txdata[4] = 0x00; txdata[5] = 0x00; txdata[6] = 0x00; txdata[7] = 0x00; CANID=0x200 | ((MDcontroll)&0xf)<<5 | 0xa ; // 上位2ビット:優先度:01 次の4bit:プロトコルID:制御モード 下位5bit:デバイスID:10番 can1.write(CANMessage(CANID,&txdata[0],8)); }