Communication Class and Controller Class (ControllerForMbed Class)

Dependencies:   SoftPWM

main.cpp

Committer:
kikuchi8810
Date:
2021-12-23
Revision:
2:fd0c21600586
Parent:
1:6633661058ec

File content as of revision 2:fd0c21600586:

//CommunicationMonitoringクラスの動作確認用プログラム
//宇井コンのmbed環境での動作確認をするプログラム(ControllerForMbed内で実装し,controllerクラスと区別している)
//contoller(conrollerForMbed)クラス内のタイムアウト機能を使わないようにしている

#include "mbed.h"
#include "SoftPWM.h" //ソフトフェアでPWM出力を行うクラス
#include "Button.h"
#include "Controller.h"// DS4のみ通信が確認できているバージョンで,プロジェクトに公開しているクラス
#include "ControllerForMbed.h"//宇井コンとの通信をmbedで行えるように変更を加えたクラスでプロジェクトに公開していない.
#include "CommunicationMonitoring.h" //複数のデバイスの通信状況を確認するクラス(通信監視クラス)
#include "define.h" //コントローラクラスにのみ対応
 
#define INT_TIME 0.001
#define CONTROL_PERIOD INT_TIME*10.0
#define INT_TIME_MS INT_TIME*1000
 
Serial pc(USBTX, USBRX);

#if CON_TYPE == CON_DS4
    Controller con(P7_4,P7_5, 115200); //TXpin, RXpin, baudrateを設定
#elif CON_TYPE == CON_ADACHI
    ControllerForMbed conmbed(P7_4,P7_5, 115200);
#endif

CommunicationMonitoring commMonitor;
int contoller_num; //通信監視クラス内でのコントローラのデバイス番号

/*ハードウェアのPWMは非対応*/
SoftPWM led_red(LED_RED);
SoftPWM led_green(LED_GREEN);
SoftPWM led_blue(LED_BLUE);

DigitalOut led_user(LED_USER);
DigitalOut pin_emergency(D0); //非常停止信号

Button user_sw(USER_BUTTON0);

Ticker interrupt;
bool flag_10ms = false;
bool flag_1s = false;

void RGB_LED() //RGBのLEDをいい感じに光らせる
{
    static float counts = 0.0;
    counts += CONTROL_PERIOD; // ここで光る周期を変えられる(はず)

    if(counts < CONTROL_PERIOD*100.0){
        led_red.write(counts);
        led_blue.write(1.0 - counts);
        
    }else if(counts < CONTROL_PERIOD*100.0*2.0){
        led_green.write(counts - 1.0);
        led_red.write(1.0*2.0 - counts);
    }else if(counts < CONTROL_PERIOD*100.0*3.0){
        led_blue.write(counts - 1.0*2.0);
        led_green.write(1.0*3.0 - counts);
    }else{
        counts = 0.0;
    }
}

void interrupt_func()
{
    static int count_10ms = 0;
    if(count_10ms++ > (INT_TIME_MS*10 - 1))
    {
        flag_10ms = true;
        count_10ms = 0;
        
        static int count_1s = 0;
        if(count_1s++ > (INT_TIME_MS*100 -1))
        {
            flag_1s = true;
            count_1s = 0;
        }
    }
}
 
int main()
{   
    pc.baud(115200);
    
    /* 第一引数はタイムアウト時間[ms],第二引数はupdate関数の呼び出し周期[ms] */
    #if CON_TYPE == CON_DS4
        con.init(1000, INT_TIME_MS*10); //init関数を呼び出さなければタイムアウトの処理は行われない(available関数は常にtrueを返す)
    #elif CON_TYPE == CON_ADACHI
        conmbed.inti(1000, INT_TIME_MS*10);
    #endif
    contoller_num = commMonitor.init(1000, INT_TIME_MS*10); //コントローラのタイムアウトと受信周期を設定し,デバイス番号を取得
    
    led_red.write(0.0);
    led_green.write(0.0);
    led_blue.write(0.0);
    led_user.write(1);
    
    while(!user_sw.button_fall())pc.printf("waiting\r\n"); //user_swが押されるまで待機
    led_user.write(0);
    
    interrupt.attach(&interrupt_func, INT_TIME);
    
    while(1) 
    {
        if(flag_10ms)
        {
            RGB_LED();
            
            #if CON_TYPE == CON_DS4
                //con.update(); //main関数のflag内で呼び出す.
                commMonitor.Monitoring(con.update(), contoller_num); //コントローラの通信状況を監視
                //if(con.available())
                if(commMonitor.isAvailable(contoller_num)) //コントローラと通信しているかを確認
                {
                    int buttonState = con.getButtonState();
                    uint8_t joyRx = con.readJoyRXbyte();
                    uint8_t joyRy = con.readJoyRYbyte();
                    uint8_t joyLx = con.readJoyLXbyte();
                    uint8_t joyLy = con.readJoyLYbyte();
                    
                    pc.printf("%d\t", buttonState);
                    pc.printf("%d\t", joyRx);
                    pc.printf("%d\t", joyRy);
                    pc.printf("%d\t", joyLx);
                    pc.printf("%d\r\n", joyLy);
                    
                    led_user.write(0);
                    pin_emergency.write(1); //非常停止を解除する
                }
                else
                {
                    pc.printf("disconnected\r\n");
                    led_user.write(1);
                    pin_emergency.write(0); //非常停止を作動させる
                }

            #elif CON_TYPE == CON_ADACHI
                //conmbed.update(); //main関数のflag内で呼び出す.
                commMonitor.Monitoring(conmbed.update(), contoller_num); //コントローラの通信状況を監視
                
                //if(conmbed.available())
                if(commMonitor.getAvailable(contoller_num))//コントローラと通信しているかを確認
                {
                    int buttonState = conmbed.getButtonState();
                    uint8_t joyRx = conmbed.readJoyRXbyte();
                    uint8_t joyRy = conmbed.readJoyRYbyte();
                    uint8_t joyLx = conmbed.readJoyLXbyte();
                    uint8_t joyLy = conmbed.readJoyLYbyte();
                    
                    pc.printf("%d\t", buttonState);
                    pc.printf("%d\t", joyRx);
                    pc.printf("%d\t", joyRy);
                    pc.printf("%d\t", joyLx);
                    pc.printf("%d\r\n", joyLy);
                    
                    led_user.write(0);
                    pin_emergency.write(1); //非常停止を解除する
                }
                else
                {
                    pc.printf("disconnected\r\n");
                    led_user.write(1);
                    pin_emergency.write(0); //非常停止を作動させる
                }
            #endif
            
            flag_10ms = false;
        }
        
        if(flag_1s)
        {
            // code here!
            flag_1s = false;
        }
        
        thread_sleep_for(1); //眠らせないとなんか変
    }
}