高速wifiついてる
Dependencies: RemoteIR TextLCD
main.cpp@52:c868403753e8, 2020-09-02 (annotated)
- Committer:
- tomotsugu
- Date:
- Wed Sep 02 06:56:39 2020 +0000
- Revision:
- 52:c868403753e8
- Parent:
- 51:1baf4407f384
- Child:
- 53:debc8879ba5d
saikyo
Who changed what in which revision?
User | Revision | Line number | New contents of line |
---|---|---|---|
yangtzuli | 0:0d0037aabe41 | 1 | /* mbed Microcontroller Library |
yangtzuli | 0:0d0037aabe41 | 2 | * Copyright (c) 2019 ARM Limited |
yangtzuli | 0:0d0037aabe41 | 3 | * SPDX-License-Identifier: Apache-2.0 |
yangtzuli | 0:0d0037aabe41 | 4 | */ |
yangtzuli | 0:0d0037aabe41 | 5 | |
yangtzuli | 0:0d0037aabe41 | 6 | #include "mbed.h" |
yangtzuli | 0:0d0037aabe41 | 7 | #include "ReceiverIR.h" |
yangtzuli | 0:0d0037aabe41 | 8 | #include "rtos.h" |
yangtzuli | 0:0d0037aabe41 | 9 | #include <stdint.h> |
yangtzuli | 0:0d0037aabe41 | 10 | #include "platform/mbed_thread.h" |
yangtzuli | 2:38825726cb1b | 11 | #include "TextLCD.h" |
yangtzuli | 0:0d0037aabe41 | 12 | |
nishimura_taku_pet | 27:90962c01bfeb | 13 | RawSerial pc(USBTX, USBRX); |
yangtzuli | 0:0d0037aabe41 | 14 | |
yangtzuli | 3:2ae6218973be | 15 | /* マクロ定義、列挙型定義 */ |
takuminomura | 48:3003ea51c619 | 16 | #define MIN_V 2.0 // 電圧の最小値 |
takuminomura | 48:3003ea51c619 | 17 | #define MAX_V 2.67 // 電圧の最大値 |
takuminomura | 48:3003ea51c619 | 18 | #define LOW 0 // モーターOFF |
takuminomura | 48:3003ea51c619 | 19 | #define HIGH 1 // モーターON |
takuminomura | 48:3003ea51c619 | 20 | #define NORMAL 0 // 普通 |
takuminomura | 48:3003ea51c619 | 21 | #define FAST 1 // 速い |
takuminomura | 48:3003ea51c619 | 22 | #define VERYFAST 2 // とても速い |
takuminomura | 48:3003ea51c619 | 23 | |
takuminomura | 49:7224132f4b0e | 24 | |
takuminomura | 49:7224132f4b0e | 25 | |
takuminomura | 49:7224132f4b0e | 26 | /* // 右回り37.21[s] |
takuminomura | 49:7224132f4b0e | 27 | #define S 0.9 |
takuminomura | 49:7224132f4b0e | 28 | #define VF 1.2 |
takuminomura | 48:3003ea51c619 | 29 | #define REVERSE 0.5 |
takuminomura | 48:3003ea51c619 | 30 | |
takuminomura | 48:3003ea51c619 | 31 | #define MBED04 0.781//Mbed04号機の左右のモーター速度比(R:L = 1: 0.781) |
takuminomura | 48:3003ea51c619 | 32 | #define MBED05 0.953//Mbed05号機の左右のモーター速度比(R:L = 1: 0.953) |
takuminomura | 49:7224132f4b0e | 33 | #define MBED07 1 |
takuminomura | 49:7224132f4b0e | 34 | // MSR = Motor Speed Right |
takuminomura | 49:7224132f4b0e | 35 | // MSL = Motor Speed Left |
takuminomura | 49:7224132f4b0e | 36 | #define MSR0 0.5 // 基準速度Normal |
takuminomura | 49:7224132f4b0e | 37 | #define MSR1 0.6 // 基準速度Fast |
takuminomura | 49:7224132f4b0e | 38 | #define MSR2 0.7 // 基準速度VeryFast |
takuminomura | 49:7224132f4b0e | 39 | */ |
takuminomura | 49:7224132f4b0e | 40 | |
takuminomura | 49:7224132f4b0e | 41 | |
takuminomura | 49:7224132f4b0e | 42 | |
takuminomura | 49:7224132f4b0e | 43 | #define S 0.9 |
takuminomura | 49:7224132f4b0e | 44 | #define VF 1 |
takuminomura | 49:7224132f4b0e | 45 | #define REVERSE 0.5 |
takuminomura | 49:7224132f4b0e | 46 | |
nishimura_taku_pet | 51:1baf4407f384 | 47 | #define MBED02 0.719 //Mbed02号機の左右のモーター速度比(R:L = 1: 0.719) |
takuminomura | 49:7224132f4b0e | 48 | #define MBED04 0.781 //Mbed04号機の左右のモーター速度比(R:L = 1: 0.781) |
takuminomura | 49:7224132f4b0e | 49 | #define MBED05 0.953 //Mbed05号機の左右のモーター速度比(R:L = 1: 0.953) |
takuminomura | 49:7224132f4b0e | 50 | #define MBED07 1 |
takuminomura | 49:7224132f4b0e | 51 | // MSR = Motor Speed Right |
takuminomura | 49:7224132f4b0e | 52 | // MSL = Motor Speed Left |
takuminomura | 49:7224132f4b0e | 53 | #define MSR0 0.55 // 基準速度Normal |
takuminomura | 49:7224132f4b0e | 54 | #define MSR1 0.6 // 基準速度Fast |
takuminomura | 49:7224132f4b0e | 55 | #define MSR2 0.65 // 基準速度VeryFast |
takuminomura | 49:7224132f4b0e | 56 | |
takuminomura | 49:7224132f4b0e | 57 | #define MSR3 MSR0*S // 低速旋回(Normalの時) |
takuminomura | 49:7224132f4b0e | 58 | #define MSR4 MSR1*S*S // 低速旋回(Fastの時) |
takuminomura | 49:7224132f4b0e | 59 | #define MSR5 MSR2*S*S*S // 低速旋回(VeryFastの時) |
takuminomura | 49:7224132f4b0e | 60 | #define MSR6 MSR0*VF // 高速(Normalの時) |
takuminomura | 49:7224132f4b0e | 61 | #define MSR7 MSR1*VF // 高速(Fastの時) |
takuminomura | 49:7224132f4b0e | 62 | #define MSR8 MSR2*VF // 高速(VeryFastの時) |
takuminomura | 49:7224132f4b0e | 63 | #define MSL0 MSR0*MBED07 |
takuminomura | 49:7224132f4b0e | 64 | #define MSL1 MSR1*MBED07 |
takuminomura | 49:7224132f4b0e | 65 | #define MSL2 MSR2*MBED07 |
takuminomura | 49:7224132f4b0e | 66 | #define MSL3 MSR3*MBED07 |
takuminomura | 49:7224132f4b0e | 67 | #define MSL4 MSR4*MBED07 |
takuminomura | 49:7224132f4b0e | 68 | #define MSL5 MSR5*MBED07 |
takuminomura | 49:7224132f4b0e | 69 | #define MSL6 MSR6*MBED07 |
takuminomura | 49:7224132f4b0e | 70 | #define MSL7 MSR7*MBED07 |
takuminomura | 49:7224132f4b0e | 71 | #define MSL8 MSR8*MBED07 |
yangtzuli | 2:38825726cb1b | 72 | |
tomotsugu | 8:a47dbf4fa455 | 73 | /* 操作モード定義 */ |
yangtzuli | 3:2ae6218973be | 74 | enum MODE{ |
tomotsugu | 8:a47dbf4fa455 | 75 | READY = -1, // -1:待ち |
tomotsugu | 8:a47dbf4fa455 | 76 | ADVANCE = 1, // 1:前進 |
tomotsugu | 8:a47dbf4fa455 | 77 | RIGHT, // 2:右折 |
tomotsugu | 8:a47dbf4fa455 | 78 | LEFT, // 3:左折 |
tomotsugu | 8:a47dbf4fa455 | 79 | BACK, // 4:後退 |
tomotsugu | 8:a47dbf4fa455 | 80 | STOP, // 5:停止 |
tomotsugu | 8:a47dbf4fa455 | 81 | LINE_TRACE, // 6:ライントレース |
tomotsugu | 8:a47dbf4fa455 | 82 | AVOIDANCE, // 7:障害物回避 |
tomotsugu | 8:a47dbf4fa455 | 83 | SPEED, // 8:スピード制御 |
takuminomura | 49:7224132f4b0e | 84 | LT_R, // 9:低速右折(ライントレース時) |
mori2020 | 50:ee78382fd399 | 85 | LT_L, // 10:低速左折(ライントレース時) |
mori2020 | 50:ee78382fd399 | 86 | ARIGHT, |
mori2020 | 50:ee78382fd399 | 87 | ALEFT, |
yangtzuli | 2:38825726cb1b | 88 | }; |
yangtzuli | 2:38825726cb1b | 89 | |
yangtzuli | 3:2ae6218973be | 90 | /* ピン配置 */ |
yangtzuli | 3:2ae6218973be | 91 | ReceiverIR ir(p5); // リモコン操作 |
yangtzuli | 3:2ae6218973be | 92 | DigitalOut trig(p6); // 超音波センサtrigger |
yangtzuli | 5:3fffb364744b | 93 | DigitalIn echo(p7); // 超音波センサecho |
yangtzuli | 3:2ae6218973be | 94 | DigitalIn ss1(p8); // ライントレースセンサ(左) |
yangtzuli | 3:2ae6218973be | 95 | DigitalIn ss2(p9); // ライントレースセンサ |
yangtzuli | 3:2ae6218973be | 96 | DigitalIn ss3(p10); // ライントレースセンサ |
yangtzuli | 3:2ae6218973be | 97 | DigitalIn ss4(p11); // ライントレースセンサ |
yangtzuli | 3:2ae6218973be | 98 | DigitalIn ss5(p12); // ライントレースセンサ(右) |
nishimura_taku_pet | 24:9481c8f56a49 | 99 | RawSerial esp(p13, p14); // Wi-Fiモジュール(tx, rx) |
yangtzuli | 3:2ae6218973be | 100 | AnalogIn battery(p15); // 電池残量読み取り(Max 3.3V) |
takuminomura | 48:3003ea51c619 | 101 | PwmOut motorR2(p22); // 右モーター後退 |
takuminomura | 48:3003ea51c619 | 102 | PwmOut motorR1(p21); // 右モーター前進 |
yangtzuli | 3:2ae6218973be | 103 | PwmOut motorL2(p23); // 左モーター後退 |
yangtzuli | 3:2ae6218973be | 104 | PwmOut motorL1(p24); // 左モーター前進 |
yangtzuli | 3:2ae6218973be | 105 | PwmOut servo(p25); // サーボ |
yangtzuli | 3:2ae6218973be | 106 | I2C i2c_lcd(p28,p27); // LCD(tx, rx) |
yangtzuli | 2:38825726cb1b | 107 | |
yangtzuli | 3:2ae6218973be | 108 | /* 変数宣言 */ |
nishimura_taku_pet | 51:1baf4407f384 | 109 | MODE mode; // 操作モード |
yangtzuli | 3:2ae6218973be | 110 | int run; // 走行状態 |
nishimura_taku_pet | 51:1baf4407f384 | 111 | MODE beforeMode; // 前回のモード |
tomotsugu | 8:a47dbf4fa455 | 112 | int flag_sp = 0; // スピード変化フラグ |
tomotsugu | 8:a47dbf4fa455 | 113 | Timer viewTimer; // スピ―ド変更時に3秒計測タイマー |
takuminomura | 48:3003ea51c619 | 114 | |
takuminomura | 48:3003ea51c619 | 115 | float motorSpeedR1[9] = {MSR0, MSR1, MSR2, MSR3 , MSR4 , MSR5 , MSR6 , MSR7 , MSR8 }; |
takuminomura | 48:3003ea51c619 | 116 | //float motorSpeedR2[9] = {MSR0, MSR1, MSR2, MSR3*REVERSE, MSR4*REVERSE, MSR5*REVERSE, MSR6*REVERSE, MSR7*REVERSE, MSR8*REVERSE}; |
takuminomura | 48:3003ea51c619 | 117 | float motorSpeedR2[9] = {MSR0, MSR1, MSR2, MSR3*REVERSE, MSR4*REVERSE, MSR5*REVERSE, MSR6, MSR7, MSR8}; |
takuminomura | 48:3003ea51c619 | 118 | float motorSpeedL1[9] = {MSL0, MSL1, MSL2, MSL3 , MSL4 , MSL5 , MSL6 , MSL7 , MSL8 }; |
takuminomura | 48:3003ea51c619 | 119 | //float motorSpeedL2[9] = {MSL0, MSL1, MSL2, MSL3*REVERSE, MSL4*REVERSE, MSL5*REVERSE, MSL6*REVERSE, MSL7*REVERSE, MSL8*REVERSE}; |
takuminomura | 48:3003ea51c619 | 120 | float motorSpeedL2[9] = {MSL0, MSL1, MSL2, MSL3*REVERSE, MSL4*REVERSE, MSL5*REVERSE, MSL6, MSL7, MSL8}; |
yangtzuli | 3:2ae6218973be | 121 | // モーター速度設定(後半はライントレース用) |
takuminomura | 48:3003ea51c619 | 122 | // 0,1,2:基準速度 |
takuminomura | 48:3003ea51c619 | 123 | // 3,4,5:低速 |
takuminomura | 48:3003ea51c619 | 124 | // 6,7,8:高速 |
takuminomura | 48:3003ea51c619 | 125 | // R1 : 右前, R2 : 右後, L1 : 左前, L2 : 左後 |
tomotsugu | 8:a47dbf4fa455 | 126 | |
tomotsugu | 8:a47dbf4fa455 | 127 | Mutex mutex; // ミューテックス |
takuminomura | 48:3003ea51c619 | 128 | |
tomotsugu | 8:a47dbf4fa455 | 129 | /* decodeIR用変数 */ |
yangtzuli | 3:2ae6218973be | 130 | RemoteIR::Format format; |
yangtzuli | 3:2ae6218973be | 131 | uint8_t buf[32]; |
yangtzuli | 3:2ae6218973be | 132 | uint32_t bitcount; |
yangtzuli | 3:2ae6218973be | 133 | uint32_t code; |
yangtzuli | 3:2ae6218973be | 134 | |
tomotsugu | 8:a47dbf4fa455 | 135 | /* bChange, lcdbacklight用変数 */ |
yangtzuli | 3:2ae6218973be | 136 | TextLCD_I2C lcd(&i2c_lcd, (0x27 << 1), TextLCD::LCD16x2, TextLCD::HD44780); |
tomotsugu | 8:a47dbf4fa455 | 137 | int b = 0; // バッテリー残量 |
tomotsugu | 8:a47dbf4fa455 | 138 | int flag_b = 0; // バックライト点滅フラグ |
tomotsugu | 8:a47dbf4fa455 | 139 | int flag_t = 0; // バックライトタイマーフラグ |
yangtzuli | 3:2ae6218973be | 140 | |
tomotsugu | 8:a47dbf4fa455 | 141 | /* trace用変数 */ |
takuminomura | 49:7224132f4b0e | 142 | int sensArray[32] = {0,6,2,4,1,4,2,4, // ライントレースセンサパターン |
takuminomura | 49:7224132f4b0e | 143 | 3,4,1,6,3,1,1,6, // 0:前回動作継続 |
takuminomura | 49:7224132f4b0e | 144 | 7,1,5,1,5,1,1,1, // 1:高速前進 |
takuminomura | 48:3003ea51c619 | 145 | 5,1,7,1,5,1,7,1}; // 2:低速右折 |
takuminomura | 48:3003ea51c619 | 146 | // 3:低速左折 |
takuminomura | 48:3003ea51c619 | 147 | // 4:中速右折 |
takuminomura | 48:3003ea51c619 | 148 | // 5:中速左折 |
takuminomura | 48:3003ea51c619 | 149 | // 6:高速右折 |
takuminomura | 48:3003ea51c619 | 150 | // 7:高速左折 |
takuminomura | 48:3003ea51c619 | 151 | |
takuminomura | 48:3003ea51c619 | 152 | //int sensArray[32] = {0,6,0,4,1,0,1,4, // ライントレースセンサパターン |
takuminomura | 48:3003ea51c619 | 153 | // 0,6,1,6,1,1,1,6, // 0:前回動作継続 |
takuminomura | 48:3003ea51c619 | 154 | // 7,1,7,1,0,1,1,1, // 1:高速前進 |
takuminomura | 48:3003ea51c619 | 155 | // 5,1,7,1,5,1,7,1}; // 2:低速右折 |
takuminomura | 48:3003ea51c619 | 156 | // // 3:低速左折 |
takuminomura | 48:3003ea51c619 | 157 | // // 4:中速右折 |
takuminomura | 48:3003ea51c619 | 158 | // // 5:中速左折 |
takuminomura | 48:3003ea51c619 | 159 | // // 6:高速右折 |
takuminomura | 48:3003ea51c619 | 160 | // // 7:高速左折 |
yangtzuli | 0:0d0037aabe41 | 161 | |
tomotsugu | 8:a47dbf4fa455 | 162 | /* avoidance用変数 */ |
yangtzuli | 3:2ae6218973be | 163 | Timer timer; // 距離計測用タイマ |
yangtzuli | 3:2ae6218973be | 164 | int DT; // 距離 |
takuminomura | 48:3003ea51c619 | 165 | int SC; // 正面 |
yangtzuli | 2:38825726cb1b | 166 | int SL; // 左 |
yangtzuli | 2:38825726cb1b | 167 | int SR; // 右 |
yangtzuli | 2:38825726cb1b | 168 | int SLD; // 左前 |
yangtzuli | 2:38825726cb1b | 169 | int SRD; // 右前 |
tomotsugu | 8:a47dbf4fa455 | 170 | int flag_a = 0; // 障害物有無のフラグ |
yangtzuli | 2:38825726cb1b | 171 | const int limit = 20; // 障害物の距離のリミット(単位:cm) |
yangtzuli | 3:2ae6218973be | 172 | int far; // 最も遠い距離 |
yangtzuli | 2:38825726cb1b | 173 | int houkou; // 進行方向(1:前 2:左 3:右) |
nishimura_taku_pet | 29:600e4b9b5c5b | 174 | int t1 = 0; |
yangtzuli | 2:38825726cb1b | 175 | |
nishimura_taku_pet | 24:9481c8f56a49 | 176 | /*WiFi用変数*/ |
nishimura_taku_pet | 24:9481c8f56a49 | 177 | Timer time1; |
nishimura_taku_pet | 24:9481c8f56a49 | 178 | Timer time2; |
nishimura_taku_pet | 24:9481c8f56a49 | 179 | int bufflen, DataRX, ount, getcount, replycount, servreq, timeout; |
nishimura_taku_pet | 24:9481c8f56a49 | 180 | int bufl, ipdLen, linkID, weberror, webcounter,click_flag; |
nishimura_taku_pet | 24:9481c8f56a49 | 181 | float R1=100000, R2=10000; // resistor values to give a 10:1 reduction of measured AnalogIn voltage |
nishimura_taku_pet | 24:9481c8f56a49 | 182 | char webcount[8]; |
nishimura_taku_pet | 24:9481c8f56a49 | 183 | char type[16]; |
nishimura_taku_pet | 24:9481c8f56a49 | 184 | char channel[2]; |
nishimura_taku_pet | 24:9481c8f56a49 | 185 | char cmdbuff[32]; |
nishimura_taku_pet | 24:9481c8f56a49 | 186 | char replybuff[1024]; |
nishimura_taku_pet | 24:9481c8f56a49 | 187 | char webdata[1024]; // This may need to be bigger depending on WEB browser used |
nishimura_taku_pet | 27:90962c01bfeb | 188 | char webbuff[4096]; // Currently using 1986 characters, Increase this if more web page data added |
nishimura_taku_pet | 24:9481c8f56a49 | 189 | int port =80; // set server port |
nishimura_taku_pet | 24:9481c8f56a49 | 190 | int SERVtimeout =5; // set server timeout in seconds in case link breaks. |
takuminomura | 48:3003ea51c619 | 191 | char ssid[32] = "mbed05"; // enter WiFi router ssid inside the quotes |
nishimura_taku_pet | 24:9481c8f56a49 | 192 | char pwd [32] = "0123456789a"; // enter WiFi router password inside the quotes |
yangtzuli | 3:2ae6218973be | 193 | |
yangtzuli | 3:2ae6218973be | 194 | /* プロトタイプ宣言 */ |
nishimura_taku_pet | 33:a6f1090e0174 | 195 | void decodeIR(/*void const *argument*/); |
nishimura_taku_pet | 33:a6f1090e0174 | 196 | void motor(/*void const *argument*/); |
yangtzuli | 3:2ae6218973be | 197 | void changeSpeed(); |
nishimura_taku_pet | 16:ffc732a3cf92 | 198 | void avoidance(/*void const *argument*/); |
nishimura_taku_pet | 16:ffc732a3cf92 | 199 | void trace(/*void const *argument*/); |
nishimura_taku_pet | 40:75e1ad7c27e4 | 200 | void watchsurrounding3(); |
nishimura_taku_pet | 40:75e1ad7c27e4 | 201 | void watchsurrounding5(); |
yangtzuli | 2:38825726cb1b | 202 | int watch(); |
takuminomura | 48:3003ea51c619 | 203 | char battery_ch[8]; |
yangtzuli | 5:3fffb364744b | 204 | void bChange(); |
yangtzuli | 3:2ae6218973be | 205 | void display(); |
yangtzuli | 3:2ae6218973be | 206 | void lcdBacklight(void const *argument); |
nishimura_taku_pet | 45:76e8c07d76ef | 207 | void SendCMD(),getreply(),ReadWebData(),startserver(),sendpage(),SendWEB(),sendcheck(); |
nishimura_taku_pet | 43:243c1455f88a | 208 | void wifi(/*void const *argument*/); |
takuminomura | 48:3003ea51c619 | 209 | Thread *deco_thread; // decodeIRをスレッド化 :+3 |
nishimura_taku_pet | 43:243c1455f88a | 210 | Thread *wifi_thread; |
takuminomura | 48:3003ea51c619 | 211 | Thread *motor_thread; // motorをスレッド化 :+2 |
takuminomura | 48:3003ea51c619 | 212 | RtosTimer bTimer(lcdBacklight, osTimerPeriodic); // lcdBacklightをタイマー割り込みで設定 |
takuminomura | 48:3003ea51c619 | 213 | Thread *avoi_thread; // avoidanceをスレッド化:+2 |
takuminomura | 48:3003ea51c619 | 214 | Thread *trace_thread; // traceをスレッド化 :+2 |
yangtzuli | 2:38825726cb1b | 215 | |
nishimura_taku_pet | 24:9481c8f56a49 | 216 | DigitalOut led1(LED1); |
nishimura_taku_pet | 24:9481c8f56a49 | 217 | DigitalOut led2(LED2); |
nishimura_taku_pet | 24:9481c8f56a49 | 218 | DigitalOut led3(LED3); |
nishimura_taku_pet | 24:9481c8f56a49 | 219 | DigitalOut led4(LED4); |
yangtzuli | 3:2ae6218973be | 220 | |
nishimura_taku_pet | 33:a6f1090e0174 | 221 | void setup(){ |
nishimura_taku_pet | 33:a6f1090e0174 | 222 | deco_thread = new Thread(decodeIR); |
nishimura_taku_pet | 33:a6f1090e0174 | 223 | deco_thread -> set_priority(osPriorityRealtime); |
nishimura_taku_pet | 33:a6f1090e0174 | 224 | motor_thread = new Thread(motor); |
nishimura_taku_pet | 33:a6f1090e0174 | 225 | motor_thread -> set_priority(osPriorityHigh); |
mori2020 | 50:ee78382fd399 | 226 | wifi_thread -> set_priority(osPriorityRealtime); |
nishimura_taku_pet | 33:a6f1090e0174 | 227 | display(); |
nishimura_taku_pet | 33:a6f1090e0174 | 228 | } |
nishimura_taku_pet | 33:a6f1090e0174 | 229 | |
tomotsugu | 8:a47dbf4fa455 | 230 | /* リモコン受信スレッド */ |
takuminomura | 48:3003ea51c619 | 231 | void decodeIR(/*void const *argument*/){ |
takuminomura | 48:3003ea51c619 | 232 | while(1){ |
yangtzuli | 0:0d0037aabe41 | 233 | // 受信待ち |
tomotsugu | 8:a47dbf4fa455 | 234 | if (ir.getState() == ReceiverIR::Received){ // コード受信 |
yangtzuli | 3:2ae6218973be | 235 | bitcount = ir.getData(&format, buf, sizeof(buf) * 8); |
tomotsugu | 8:a47dbf4fa455 | 236 | if(bitcount > 1){ // 受信成功 |
yangtzuli | 1:5bb497a38344 | 237 | code=0; |
tomotsugu | 15:5eef1955f6c2 | 238 | for(int j = 0; j < 4; j++){ |
yangtzuli | 1:5bb497a38344 | 239 | code+=(buf[j]<<(8*(3-j))); |
yangtzuli | 1:5bb497a38344 | 240 | } |
tomotsugu | 8:a47dbf4fa455 | 241 | if(mode != SPEED){ // スピードモード以外なら |
takuminomura | 48:3003ea51c619 | 242 | beforeMode=mode; // 前回のモードに現在のモードを設定 |
yangtzuli | 3:2ae6218973be | 243 | } |
yangtzuli | 0:0d0037aabe41 | 244 | switch(code){ |
tomotsugu | 8:a47dbf4fa455 | 245 | case 0x40bf27d8: // クイック |
yangtzuli | 17:f7259ab2fe86 | 246 | //pc.printf("mode = SPEED\r\n"); |
takuminomura | 48:3003ea51c619 | 247 | mode = SPEED; // スピードモード |
tomotsugu | 8:a47dbf4fa455 | 248 | changeSpeed(); // 速度変更 |
tomotsugu | 8:a47dbf4fa455 | 249 | display(); // ディスプレイ表示 |
tomotsugu | 8:a47dbf4fa455 | 250 | mode = beforeMode; // 現在のモードに前回のモードを設定 |
yangtzuli | 1:5bb497a38344 | 251 | break; |
tomotsugu | 8:a47dbf4fa455 | 252 | case 0x40be34cb: // レグザリンク |
yangtzuli | 17:f7259ab2fe86 | 253 | //pc.printf("mode = LINE_TRACE\r\n"); |
nishimura_taku_pet | 16:ffc732a3cf92 | 254 | if(trace_thread->get_state() == Thread::Deleted){ |
nishimura_taku_pet | 16:ffc732a3cf92 | 255 | delete trace_thread; |
nishimura_taku_pet | 16:ffc732a3cf92 | 256 | trace_thread = new Thread(trace); |
nishimura_taku_pet | 16:ffc732a3cf92 | 257 | trace_thread -> set_priority(osPriorityHigh); |
nishimura_taku_pet | 16:ffc732a3cf92 | 258 | } |
tomotsugu | 8:a47dbf4fa455 | 259 | mode=LINE_TRACE; // ライントレースモード |
tomotsugu | 8:a47dbf4fa455 | 260 | display(); // ディスプレイ表示 |
yangtzuli | 1:5bb497a38344 | 261 | break; |
tomotsugu | 8:a47dbf4fa455 | 262 | case 0x40bf6e91: // 番組表 |
yangtzuli | 17:f7259ab2fe86 | 263 | //pc.printf("mode = AVOIDANCE\r\n"); |
nishimura_taku_pet | 16:ffc732a3cf92 | 264 | if(avoi_thread->get_state() == Thread::Deleted){ |
nishimura_taku_pet | 16:ffc732a3cf92 | 265 | delete avoi_thread; |
nishimura_taku_pet | 16:ffc732a3cf92 | 266 | avoi_thread = new Thread(avoidance); |
nishimura_taku_pet | 16:ffc732a3cf92 | 267 | avoi_thread -> set_priority(osPriorityHigh); |
nishimura_taku_pet | 16:ffc732a3cf92 | 268 | } |
tomotsugu | 18:6cca64c7dbc3 | 269 | flag_a = 0; |
tomotsugu | 8:a47dbf4fa455 | 270 | mode=AVOIDANCE; // 障害物回避モード |
tomotsugu | 13:1a7667d0aa78 | 271 | run = ADVANCE; // 前進 |
tomotsugu | 8:a47dbf4fa455 | 272 | display(); // ディスプレイ表示 |
yangtzuli | 1:5bb497a38344 | 273 | break; |
takuminomura | 48:3003ea51c619 | 274 | case 0x40bf3ec1: // ↑ |
yangtzuli | 17:f7259ab2fe86 | 275 | //pc.printf("mode = ADVANCE\r\n"); |
tomotsugu | 8:a47dbf4fa455 | 276 | mode = ADVANCE; // 前進モード |
tomotsugu | 8:a47dbf4fa455 | 277 | run = ADVANCE; // 前進 |
tomotsugu | 8:a47dbf4fa455 | 278 | display(); // ディスプレイ表示 |
yangtzuli | 1:5bb497a38344 | 279 | break; |
takuminomura | 48:3003ea51c619 | 280 | case 0x40bf3fc0: // ↓ |
yangtzuli | 17:f7259ab2fe86 | 281 | //pc.printf("mode = BACK\r\n"); |
tomotsugu | 8:a47dbf4fa455 | 282 | mode = BACK; // 後退モード |
tomotsugu | 8:a47dbf4fa455 | 283 | run = BACK; // 後退 |
tomotsugu | 8:a47dbf4fa455 | 284 | display(); // ディスプレイ表示 |
yangtzuli | 0:0d0037aabe41 | 285 | break; |
takuminomura | 48:3003ea51c619 | 286 | case 0x40bf5fa0: // ← |
yangtzuli | 17:f7259ab2fe86 | 287 | //pc.printf("mode = LEFT\r\n"); |
tomotsugu | 8:a47dbf4fa455 | 288 | mode = LEFT; // 左折モード |
tomotsugu | 8:a47dbf4fa455 | 289 | run = LEFT; // 左折 |
tomotsugu | 8:a47dbf4fa455 | 290 | display(); // ディスプレイ表示 |
yangtzuli | 1:5bb497a38344 | 291 | break; |
takuminomura | 48:3003ea51c619 | 292 | case 0x40bf5ba4: // → |
yangtzuli | 17:f7259ab2fe86 | 293 | //pc.printf("mode = RIGHT\r\n"); |
tomotsugu | 8:a47dbf4fa455 | 294 | mode = RIGHT; // 右折モード |
tomotsugu | 8:a47dbf4fa455 | 295 | run = RIGHT; // 右折 |
tomotsugu | 8:a47dbf4fa455 | 296 | display(); // ディスプレイ表示 |
yangtzuli | 1:5bb497a38344 | 297 | break; |
takuminomura | 48:3003ea51c619 | 298 | case 0x40bf3dc2: // 決定 |
yangtzuli | 17:f7259ab2fe86 | 299 | //pc.printf("mode = STOP\r\n"); |
tomotsugu | 8:a47dbf4fa455 | 300 | mode = STOP; // 停止モード |
tomotsugu | 8:a47dbf4fa455 | 301 | run = STOP; // 停止 |
tomotsugu | 8:a47dbf4fa455 | 302 | display(); // ディスプレイ表示 |
yangtzuli | 1:5bb497a38344 | 303 | break; |
yangtzuli | 0:0d0037aabe41 | 304 | default: |
yangtzuli | 0:0d0037aabe41 | 305 | ; |
yangtzuli | 0:0d0037aabe41 | 306 | } |
nishimura_taku_pet | 16:ffc732a3cf92 | 307 | if(mode != LINE_TRACE && trace_thread->get_state() != Thread::Deleted){ |
nishimura_taku_pet | 16:ffc732a3cf92 | 308 | trace_thread->terminate(); |
nishimura_taku_pet | 16:ffc732a3cf92 | 309 | } |
nishimura_taku_pet | 16:ffc732a3cf92 | 310 | if(mode != AVOIDANCE && avoi_thread->get_state() != Thread::Deleted){ |
nishimura_taku_pet | 16:ffc732a3cf92 | 311 | avoi_thread->terminate(); |
nishimura_taku_pet | 28:cb51cafca490 | 312 | servo.pulsewidth_us(1450); // サーボを中央位置に戻す |
nishimura_taku_pet | 16:ffc732a3cf92 | 313 | } |
yangtzuli | 0:0d0037aabe41 | 314 | } |
yangtzuli | 0:0d0037aabe41 | 315 | } |
takuminomura | 48:3003ea51c619 | 316 | if(viewTimer.read_ms()>=3000){ // スピードモードのまま3秒経過 |
takuminomura | 48:3003ea51c619 | 317 | viewTimer.stop(); // タイマーストップ |
takuminomura | 48:3003ea51c619 | 318 | viewTimer.reset(); // タイマーリセット |
takuminomura | 48:3003ea51c619 | 319 | display(); // ディスプレイ表示 |
yangtzuli | 4:3f80c0180e2f | 320 | } |
takuminomura | 48:3003ea51c619 | 321 | ThisThread::sleep_for(90); // 90ms待つ |
takuminomura | 48:3003ea51c619 | 322 | } |
yangtzuli | 2:38825726cb1b | 323 | } |
tomotsugu | 8:a47dbf4fa455 | 324 | |
tomotsugu | 8:a47dbf4fa455 | 325 | /* モーター制御スレッド */ |
nishimura_taku_pet | 33:a6f1090e0174 | 326 | void motor(/*void const *argument*/){ |
tomotsugu | 8:a47dbf4fa455 | 327 | while(1){ |
tomotsugu | 8:a47dbf4fa455 | 328 | /* 走行状態の場合分け */ |
nishimura_taku_pet | 51:1baf4407f384 | 329 | if(mode != LINE_TRACE){ // スピード変更フラグが2より大きいなら |
nishimura_taku_pet | 51:1baf4407f384 | 330 | flag_sp %= 3; // スピード変更フラグ調整 |
nishimura_taku_pet | 51:1baf4407f384 | 331 | } |
yangtzuli | 3:2ae6218973be | 332 | switch(run){ |
tomotsugu | 8:a47dbf4fa455 | 333 | /* 前進 */ |
yangtzuli | 3:2ae6218973be | 334 | case ADVANCE: |
takuminomura | 48:3003ea51c619 | 335 | motorR1 = motorSpeedR1[flag_sp]; // 右前進モーターON |
mori2020 | 50:ee78382fd399 | 336 | motorR2 = LOW; // 右後退モーターOFF |
takuminomura | 48:3003ea51c619 | 337 | motorL1 = motorSpeedL1[flag_sp]; // 左前進モーターON |
mori2020 | 50:ee78382fd399 | 338 | motorL2 = LOW; // 左後退モーターOFF |
yangtzuli | 3:2ae6218973be | 339 | break; |
tomotsugu | 8:a47dbf4fa455 | 340 | /* 右折 */ |
yangtzuli | 3:2ae6218973be | 341 | case RIGHT: |
mori2020 | 50:ee78382fd399 | 342 | motorR1 = LOW; // 右前進モーターOFF |
takuminomura | 48:3003ea51c619 | 343 | motorR2 = motorSpeedR2[flag_sp]; // 右後退モーターON |
takuminomura | 48:3003ea51c619 | 344 | motorL1 = motorSpeedL1[flag_sp]; // 左前進モーターON |
mori2020 | 50:ee78382fd399 | 345 | motorL2 = LOW; // 左後退モーターOFF |
yangtzuli | 3:2ae6218973be | 346 | break; |
tomotsugu | 8:a47dbf4fa455 | 347 | /* 左折 */ |
yangtzuli | 3:2ae6218973be | 348 | case LEFT: |
takuminomura | 48:3003ea51c619 | 349 | motorR1 = motorSpeedR1[flag_sp]; // 右前進モーターON |
mori2020 | 50:ee78382fd399 | 350 | motorR2 = LOW; // 右後退モーターOFF |
mori2020 | 50:ee78382fd399 | 351 | motorL1 = LOW; // 左前進モーターOFF |
takuminomura | 48:3003ea51c619 | 352 | motorL2 = motorSpeedL2[flag_sp]; // 左後退モーターON |
yangtzuli | 3:2ae6218973be | 353 | break; |
tomotsugu | 8:a47dbf4fa455 | 354 | /* 後退 */ |
yangtzuli | 3:2ae6218973be | 355 | case BACK: |
mori2020 | 50:ee78382fd399 | 356 | motorR1 = LOW; // 右前進モーターOFF |
tomotsugu | 52:c868403753e8 | 357 | motorR2 = motorSpeedR2[flag_sp]; // 右後退モーターON |
mori2020 | 50:ee78382fd399 | 358 | motorL1 = LOW; // 左前進モーターOFF |
takuminomura | 48:3003ea51c619 | 359 | motorL2 = motorSpeedL2[flag_sp]; // 左後退モーターON |
yangtzuli | 3:2ae6218973be | 360 | break; |
tomotsugu | 8:a47dbf4fa455 | 361 | /* 停止 */ |
yangtzuli | 3:2ae6218973be | 362 | case STOP: |
tomotsugu | 8:a47dbf4fa455 | 363 | motorR1 = LOW; // 右前進モーターOFF |
tomotsugu | 8:a47dbf4fa455 | 364 | motorR2 = LOW; // 右後退モーターOFF |
tomotsugu | 8:a47dbf4fa455 | 365 | motorL1 = LOW; // 左前進モーターOFF |
tomotsugu | 8:a47dbf4fa455 | 366 | motorL2 = LOW; // 左後退モーターOFF |
yangtzuli | 3:2ae6218973be | 367 | break; |
tomotsugu | 52:c868403753e8 | 368 | case A1RIGHT: |
mori2020 | 50:ee78382fd399 | 369 | motorR1 = LOW; |
tomotsugu | 52:c868403753e8 | 370 | motorR2 = 0.55; |
tomotsugu | 52:c868403753e8 | 371 | motorL1 = 0.57; |
mori2020 | 50:ee78382fd399 | 372 | motorL2 = LOW; |
takuminomura | 49:7224132f4b0e | 373 | break; |
tomotsugu | 52:c868403753e8 | 374 | case A2LEFT: |
tomotsugu | 52:c868403753e8 | 375 | motorR1 = 0.57; |
mori2020 | 50:ee78382fd399 | 376 | motorR2 = LOW; |
mori2020 | 50:ee78382fd399 | 377 | motorL1 = LOW; |
tomotsugu | 52:c868403753e8 | 378 | motorL2 = 0.55; |
tomotsugu | 52:c868403753e8 | 379 | break; |
tomotsugu | 52:c868403753e8 | 380 | case A2RIGHT: |
tomotsugu | 52:c868403753e8 | 381 | motorR1 = LOW; |
tomotsugu | 52:c868403753e8 | 382 | motorR2 = 0.33; |
tomotsugu | 52:c868403753e8 | 383 | motorL1 = 0.35; |
tomotsugu | 52:c868403753e8 | 384 | motorL2 = LOW; |
tomotsugu | 52:c868403753e8 | 385 | break; |
tomotsugu | 52:c868403753e8 | 386 | case A2LEFT: |
tomotsugu | 52:c868403753e8 | 387 | motorR1 = 0.35; |
tomotsugu | 52:c868403753e8 | 388 | motorR2 = LOW; |
tomotsugu | 52:c868403753e8 | 389 | motorL1 = LOW; |
tomotsugu | 52:c868403753e8 | 390 | motorL2 = 0.33; |
takuminomura | 49:7224132f4b0e | 391 | break; |
yangtzuli | 3:2ae6218973be | 392 | } |
nishimura_taku_pet | 51:1baf4407f384 | 393 | /*if(flag_sp > VERYFAST){ // スピード変更フラグが2より大きいなら |
nishimura_taku_pet | 47:8a5a4275480a | 394 | flag_sp %= 3; // スピード変更フラグ調整 |
nishimura_taku_pet | 51:1baf4407f384 | 395 | }*/ |
takuminomura | 48:3003ea51c619 | 396 | ThisThread::sleep_for(3); // 30ms待つ |
yangtzuli | 2:38825726cb1b | 397 | } |
yangtzuli | 2:38825726cb1b | 398 | } |
tomotsugu | 8:a47dbf4fa455 | 399 | |
tomotsugu | 8:a47dbf4fa455 | 400 | /* スピード変更関数 */ |
yangtzuli | 3:2ae6218973be | 401 | void changeSpeed(){ |
tomotsugu | 8:a47dbf4fa455 | 402 | if(flag_sp%3 == 2){ // スピード変更フラグを3で割った余りが2なら |
takuminomura | 48:3003ea51c619 | 403 | flag_sp = 0; // スピード変更フラグを0にする |
tomotsugu | 8:a47dbf4fa455 | 404 | }else{ // それ以外 |
takuminomura | 48:3003ea51c619 | 405 | flag_sp = flag_sp + 1; // スピード変更フラグを+1 |
takuminomura | 48:3003ea51c619 | 406 | } |
yangtzuli | 3:2ae6218973be | 407 | } |
tomotsugu | 8:a47dbf4fa455 | 408 | |
tomotsugu | 8:a47dbf4fa455 | 409 | /* ライントレーススレッド */ |
takuminomura | 49:7224132f4b0e | 410 | //void trace(){ |
takuminomura | 49:7224132f4b0e | 411 | // // PID用 |
takuminomura | 49:7224132f4b0e | 412 | // while(1){ |
takuminomura | 49:7224132f4b0e | 413 | // ThisThread::sleep_for(3); |
takuminomura | 49:7224132f4b0e | 414 | // } |
takuminomura | 49:7224132f4b0e | 415 | //} |
tomotsugu | 20:02bb875a9b13 | 416 | void trace(){ |
takuminomura | 48:3003ea51c619 | 417 | while(1){ |
takuminomura | 48:3003ea51c619 | 418 | /* 各センサー値読み取り */ |
takuminomura | 48:3003ea51c619 | 419 | int sensor1 = ss1; |
takuminomura | 48:3003ea51c619 | 420 | int sensor2 = ss2; |
takuminomura | 48:3003ea51c619 | 421 | int sensor3 = ss3; |
takuminomura | 48:3003ea51c619 | 422 | int sensor4 = ss4; |
takuminomura | 48:3003ea51c619 | 423 | int sensor5 = ss5; |
takuminomura | 48:3003ea51c619 | 424 | int sensD = 0; |
takuminomura | 48:3003ea51c619 | 425 | |
takuminomura | 48:3003ea51c619 | 426 | /* センサー値の決定 */ |
takuminomura | 48:3003ea51c619 | 427 | if(sensor1 > 0) sensD |= 0x10; |
takuminomura | 48:3003ea51c619 | 428 | if(sensor2 > 0) sensD |= 0x08; |
takuminomura | 48:3003ea51c619 | 429 | if(sensor3 > 0) sensD |= 0x04; |
takuminomura | 48:3003ea51c619 | 430 | if(sensor4 > 0) sensD |= 0x02; |
takuminomura | 48:3003ea51c619 | 431 | if(sensor5 > 0) sensD |= 0x01; |
takuminomura | 48:3003ea51c619 | 432 | |
takuminomura | 48:3003ea51c619 | 433 | /* センサー値によって場合分け */ |
takuminomura | 48:3003ea51c619 | 434 | switch(sensArray[sensD]){ |
takuminomura | 48:3003ea51c619 | 435 | case 1: |
takuminomura | 48:3003ea51c619 | 436 | flag_sp = flag_sp % 3 + 6; |
takuminomura | 48:3003ea51c619 | 437 | run = ADVANCE; // 高速で前進 |
takuminomura | 48:3003ea51c619 | 438 | break; |
takuminomura | 48:3003ea51c619 | 439 | case 2: |
takuminomura | 48:3003ea51c619 | 440 | flag_sp = flag_sp % 3 + 3; |
takuminomura | 49:7224132f4b0e | 441 | // run = RIGHT; // 低速で右折 |
takuminomura | 49:7224132f4b0e | 442 | run = LT_R; // 低速で右折 |
takuminomura | 48:3003ea51c619 | 443 | break; |
takuminomura | 48:3003ea51c619 | 444 | case 3: |
takuminomura | 48:3003ea51c619 | 445 | flag_sp = flag_sp % 3 + 3; |
takuminomura | 49:7224132f4b0e | 446 | // run = LEFT; // 低速で左折 |
takuminomura | 49:7224132f4b0e | 447 | run = LT_L; // 低速で左折 |
takuminomura | 48:3003ea51c619 | 448 | break; |
takuminomura | 48:3003ea51c619 | 449 | case 4: |
takuminomura | 48:3003ea51c619 | 450 | flag_sp = flag_sp % 3; |
takuminomura | 48:3003ea51c619 | 451 | run = RIGHT; // 中速で右折 |
takuminomura | 48:3003ea51c619 | 452 | break; |
takuminomura | 48:3003ea51c619 | 453 | case 5: |
takuminomura | 48:3003ea51c619 | 454 | flag_sp = flag_sp % 3; |
takuminomura | 48:3003ea51c619 | 455 | run = LEFT; // 中速で左折 |
takuminomura | 48:3003ea51c619 | 456 | break; |
takuminomura | 48:3003ea51c619 | 457 | case 6: |
takuminomura | 48:3003ea51c619 | 458 | flag_sp = flag_sp % 3 + 6; |
takuminomura | 48:3003ea51c619 | 459 | run = RIGHT; // 高速で右折 |
takuminomura | 48:3003ea51c619 | 460 | break; |
takuminomura | 48:3003ea51c619 | 461 | case 7: |
takuminomura | 48:3003ea51c619 | 462 | flag_sp = flag_sp % 3 + 6; |
takuminomura | 48:3003ea51c619 | 463 | run = LEFT; // 高速で左折 |
takuminomura | 48:3003ea51c619 | 464 | break; |
takuminomura | 48:3003ea51c619 | 465 | default: |
takuminomura | 48:3003ea51c619 | 466 | break; // 前回動作を継続 |
tomotsugu | 18:6cca64c7dbc3 | 467 | } |
takuminomura | 48:3003ea51c619 | 468 | // ThisThread::sleep_for(30); // 30ms待つ |
takuminomura | 48:3003ea51c619 | 469 | ThisThread::sleep_for(3); |
takuminomura | 48:3003ea51c619 | 470 | } |
yangtzuli | 3:2ae6218973be | 471 | } |
yangtzuli | 3:2ae6218973be | 472 | |
tomotsugu | 8:a47dbf4fa455 | 473 | /* 障害物回避走行スレッド */ |
tomotsugu | 20:02bb875a9b13 | 474 | void avoidance(){ |
nishimura_taku_pet | 46:c6deb699160b | 475 | int i; |
yangtzuli | 3:2ae6218973be | 476 | while(1){ |
nishimura_taku_pet | 40:75e1ad7c27e4 | 477 | watchsurrounding3(); |
mori2020 | 50:ee78382fd399 | 478 | if(flag_a == 0){ // 障害物がない場合 |
mori2020 | 50:ee78382fd399 | 479 | run = ADVANCE; // 前進 |
mori2020 | 50:ee78382fd399 | 480 | // if(SLD < 25){ // 正面15cm以内に障害物が現れた場合 |
mori2020 | 50:ee78382fd399 | 481 | // run = RIGHT; // 右折 |
mori2020 | 50:ee78382fd399 | 482 | // ThisThread::sleep_for(100); // 100ms待つ |
mori2020 | 50:ee78382fd399 | 483 | // run = STOP; // 停止 |
mori2020 | 50:ee78382fd399 | 484 | // }else if(SRD < 25){ |
mori2020 | 50:ee78382fd399 | 485 | // run = LEFT; // 左折 |
mori2020 | 50:ee78382fd399 | 486 | // ThisThread::sleep_for(100); // 100ms待つ |
mori2020 | 50:ee78382fd399 | 487 | // run = STOP; // 停止 |
mori2020 | 50:ee78382fd399 | 488 | // } |
mori2020 | 50:ee78382fd399 | 489 | }else{ // 障害物がある場合 |
tomotsugu | 18:6cca64c7dbc3 | 490 | i = 0; |
mori2020 | 50:ee78382fd399 | 491 | int cnt_kyori; |
mori2020 | 50:ee78382fd399 | 492 | int kyori; |
mori2020 | 50:ee78382fd399 | 493 | if(SC < 15){ |
mori2020 | 50:ee78382fd399 | 494 | servo.pulsewidth_us(1425); // サーボを中央位置に戻す |
nishimura_taku_pet | 41:3c58a4be1199 | 495 | ThisThread::sleep_for(100); // 100ms待つ |
mori2020 | 50:ee78382fd399 | 496 | run = STOP; |
mori2020 | 50:ee78382fd399 | 497 | ThisThread::sleep_for(80); |
mori2020 | 50:ee78382fd399 | 498 | run = BACK; |
mori2020 | 50:ee78382fd399 | 499 | // switch(flag_sp){ |
mori2020 | 50:ee78382fd399 | 500 | // case 0: |
mori2020 | 50:ee78382fd399 | 501 | // ThisThread::sleep_for(200); |
mori2020 | 50:ee78382fd399 | 502 | // break; |
mori2020 | 50:ee78382fd399 | 503 | // case 1: |
mori2020 | 50:ee78382fd399 | 504 | // ThisThread::sleep_for(150); |
mori2020 | 50:ee78382fd399 | 505 | // break; |
mori2020 | 50:ee78382fd399 | 506 | // case 2: |
mori2020 | 50:ee78382fd399 | 507 | // ThisThread::sleep_for(120); |
mori2020 | 50:ee78382fd399 | 508 | // break; |
mori2020 | 50:ee78382fd399 | 509 | // default: |
mori2020 | 50:ee78382fd399 | 510 | // break; |
mori2020 | 50:ee78382fd399 | 511 | // } |
mori2020 | 50:ee78382fd399 | 512 | cnt_kyori = 0; |
mori2020 | 50:ee78382fd399 | 513 | kyori = watch(); |
mori2020 | 50:ee78382fd399 | 514 | while(kyori < limit){ // 正面20cm以内に障害物がある間 |
mori2020 | 50:ee78382fd399 | 515 | if(kyori == -1){ |
nishimura_taku_pet | 40:75e1ad7c27e4 | 516 | cnt_kyori++; |
mori2020 | 50:ee78382fd399 | 517 | if(cnt_kyori > 15){ |
mori2020 | 50:ee78382fd399 | 518 | cnt_kyori = 0; |
nishimura_taku_pet | 40:75e1ad7c27e4 | 519 | break; |
nishimura_taku_pet | 40:75e1ad7c27e4 | 520 | } |
nishimura_taku_pet | 40:75e1ad7c27e4 | 521 | } |
nishimura_taku_pet | 40:75e1ad7c27e4 | 522 | kyori = watch(); |
tomotsugu | 18:6cca64c7dbc3 | 523 | } |
mori2020 | 50:ee78382fd399 | 524 | run = STOP; |
mori2020 | 50:ee78382fd399 | 525 | } |
nishimura_taku_pet | 40:75e1ad7c27e4 | 526 | watchsurrounding5(); |
takuminomura | 48:3003ea51c619 | 527 | if(SC < limit && SLD < limit && SL < limit && SRD < limit && SR < limit){ // 全方向に障害物がある場合 |
tomotsugu | 52:c868403753e8 | 528 | run = A1LEFT; // 左折 |
tomotsugu | 52:c868403753e8 | 529 | while(i < 15){ // 進行方向確認 |
tomotsugu | 18:6cca64c7dbc3 | 530 | if(watch() > limit){ |
mori2020 | 50:ee78382fd399 | 531 | break; |
nishimura_taku_pet | 28:cb51cafca490 | 532 | }else{ |
mori2020 | 50:ee78382fd399 | 533 | i++; |
yangtzuli | 2:38825726cb1b | 534 | } |
yangtzuli | 2:38825726cb1b | 535 | } |
nishimura_taku_pet | 28:cb51cafca490 | 536 | run = STOP; // 停止 |
mori2020 | 50:ee78382fd399 | 537 | }else { // 全方向以外 |
nishimura_taku_pet | 28:cb51cafca490 | 538 | far = SC; // 正面を最も遠い距離に設定 |
nishimura_taku_pet | 28:cb51cafca490 | 539 | houkou = 1; // 進行方向を前に設定 |
mori2020 | 50:ee78382fd399 | 540 | if(SC < limit){ |
mori2020 | 50:ee78382fd399 | 541 | if(far < SLD || far < SL){ // 左または左前がより遠い場合 |
mori2020 | 50:ee78382fd399 | 542 | if(SL < SLD){ // 左前が左より遠い場合 |
mori2020 | 50:ee78382fd399 | 543 | far = SLD; // 左前を最も遠い距離に設定 |
mori2020 | 50:ee78382fd399 | 544 | }else{ // 左が左前より遠い場合 |
mori2020 | 50:ee78382fd399 | 545 | far = SL; // 左を最も遠い距離に設定 |
mori2020 | 50:ee78382fd399 | 546 | } |
mori2020 | 50:ee78382fd399 | 547 | houkou = 2; // 進行方向を左に設定 |
nishimura_taku_pet | 28:cb51cafca490 | 548 | } |
mori2020 | 50:ee78382fd399 | 549 | if(far < SRD || far < SR){ // 右または右前がより遠い場合 |
mori2020 | 50:ee78382fd399 | 550 | if(SR < SRD){ // 右前が右より遠い場合 |
mori2020 | 50:ee78382fd399 | 551 | far = SRD; // 右前を最も遠い距離に設定 |
mori2020 | 50:ee78382fd399 | 552 | }else{ // 右が右前よりも遠い場合 |
mori2020 | 50:ee78382fd399 | 553 | far = SR; // 右を最も遠い距離に設定 |
mori2020 | 50:ee78382fd399 | 554 | } |
mori2020 | 50:ee78382fd399 | 555 | houkou = 3; // 進行方向を右に設定 |
nishimura_taku_pet | 28:cb51cafca490 | 556 | } |
nishimura_taku_pet | 28:cb51cafca490 | 557 | } |
nishimura_taku_pet | 28:cb51cafca490 | 558 | switch(houkou){ // 進行方向の場合分け |
nishimura_taku_pet | 28:cb51cafca490 | 559 | case 1: // 前の場合 |
nishimura_taku_pet | 28:cb51cafca490 | 560 | run = ADVANCE; // 前進 |
mori2020 | 50:ee78382fd399 | 561 | switch(flag_sp){ |
mori2020 | 50:ee78382fd399 | 562 | case 0: |
mori2020 | 50:ee78382fd399 | 563 | ThisThread::sleep_for(300); // 0.5秒待つ |
mori2020 | 50:ee78382fd399 | 564 | break; |
mori2020 | 50:ee78382fd399 | 565 | case 1: |
mori2020 | 50:ee78382fd399 | 566 | ThisThread::sleep_for(200); |
mori2020 | 50:ee78382fd399 | 567 | break; |
mori2020 | 50:ee78382fd399 | 568 | case 2: |
mori2020 | 50:ee78382fd399 | 569 | ThisThread::sleep_for(100); |
mori2020 | 50:ee78382fd399 | 570 | break; |
mori2020 | 50:ee78382fd399 | 571 | } |
nishimura_taku_pet | 28:cb51cafca490 | 572 | break; |
mori2020 | 50:ee78382fd399 | 573 | case 2: // 左の場合 |
tomotsugu | 52:c868403753e8 | 574 | run = A1LEFT; // 左折 |
mori2020 | 50:ee78382fd399 | 575 | while(i < 15){ // 進行方向確認 |
nishimura_taku_pet | 28:cb51cafca490 | 576 | if(watch() > (far - 2)){ // 正面の計測距離と最も遠い距離が一致したら(誤差-2cm) |
mori2020 | 50:ee78382fd399 | 577 | break; // ループ+ |
nishimura_taku_pet | 28:cb51cafca490 | 578 | }else{ |
nishimura_taku_pet | 40:75e1ad7c27e4 | 579 | i++; |
nishimura_taku_pet | 28:cb51cafca490 | 580 | } |
nishimura_taku_pet | 28:cb51cafca490 | 581 | } |
mori2020 | 50:ee78382fd399 | 582 | run = ADVANCE; // 停止 |
nishimura_taku_pet | 28:cb51cafca490 | 583 | break; |
mori2020 | 50:ee78382fd399 | 584 | case 3: // 右の場合 |
tomotsugu | 52:c868403753e8 | 585 | run = A1RIGHT; // 右折 |
mori2020 | 50:ee78382fd399 | 586 | while(i < 15){ // 進行方向確認 |
mori2020 | 50:ee78382fd399 | 587 | if(watch() > (far - 2)){ // 正面の計測距離と最も遠い距離が一致したら(誤差-2cm) |
nishimura_taku_pet | 40:75e1ad7c27e4 | 588 | break; // ループ+ |
nishimura_taku_pet | 28:cb51cafca490 | 589 | }else{ |
nishimura_taku_pet | 40:75e1ad7c27e4 | 590 | i++; |
nishimura_taku_pet | 28:cb51cafca490 | 591 | } |
nishimura_taku_pet | 28:cb51cafca490 | 592 | } |
mori2020 | 50:ee78382fd399 | 593 | run = ADVANCE; // 停止 |
nishimura_taku_pet | 28:cb51cafca490 | 594 | break; |
nishimura_taku_pet | 28:cb51cafca490 | 595 | } |
yangtzuli | 5:3fffb364744b | 596 | } |
nishimura_taku_pet | 28:cb51cafca490 | 597 | } |
nishimura_taku_pet | 28:cb51cafca490 | 598 | flag_a = 0; // 障害物有無フラグを0にセット |
mori2020 | 50:ee78382fd399 | 599 | if(SLD < 30 && SRD > 30){ // 正面15cm以内に障害物が現れた場合 |
tomotsugu | 52:c868403753e8 | 600 | run = A2RIGHT; // 右折 |
tomotsugu | 52:c868403753e8 | 601 | ThisThread::sleep_for(100); |
mori2020 | 50:ee78382fd399 | 602 | run = ADVANCE; |
mori2020 | 50:ee78382fd399 | 603 | }else if(SRD < 30 && SLD > 30){ |
tomotsugu | 52:c868403753e8 | 604 | run = A2LEFT; // 左折 |
tomotsugu | 52:c868403753e8 | 605 | ThisThread::sleep_for(100); |
mori2020 | 50:ee78382fd399 | 606 | run = ADVANCE; |
mori2020 | 50:ee78382fd399 | 607 | } |
mori2020 | 50:ee78382fd399 | 608 | } |
mori2020 | 50:ee78382fd399 | 609 | } |
mori2020 | 50:ee78382fd399 | 610 | |
tomotsugu | 8:a47dbf4fa455 | 611 | /* 距離計測関数 */ |
yangtzuli | 2:38825726cb1b | 612 | int watch(){ |
mori2020 | 50:ee78382fd399 | 613 | do{ |
mori2020 | 50:ee78382fd399 | 614 | do{ |
mori2020 | 50:ee78382fd399 | 615 | trig = 0; |
mori2020 | 50:ee78382fd399 | 616 | ThisThread::sleep_for(5); // 5ms待つ |
mori2020 | 50:ee78382fd399 | 617 | trig = 1; |
mori2020 | 50:ee78382fd399 | 618 | ThisThread::sleep_for(15); // 15ms待つ |
mori2020 | 50:ee78382fd399 | 619 | trig = 0; |
mori2020 | 50:ee78382fd399 | 620 | timer.start(); |
tomotsugu | 21:68d38e8f64b5 | 621 | t1=timer.read_ms(); |
mori2020 | 50:ee78382fd399 | 622 | while(echo.read() == 0 && t1<10){ |
mori2020 | 50:ee78382fd399 | 623 | t1=timer.read_ms(); |
mori2020 | 50:ee78382fd399 | 624 | led1 = 1; |
mori2020 | 50:ee78382fd399 | 625 | } |
mori2020 | 50:ee78382fd399 | 626 | timer.stop(); |
mori2020 | 50:ee78382fd399 | 627 | timer.reset(); |
mori2020 | 50:ee78382fd399 | 628 | }while(t1 >= 10); |
mori2020 | 50:ee78382fd399 | 629 | timer.start(); // 距離計測タイマースタート |
mori2020 | 50:ee78382fd399 | 630 | while(echo.read() == 1){ |
tomotsugu | 21:68d38e8f64b5 | 631 | } |
mori2020 | 50:ee78382fd399 | 632 | timer.stop(); // 距離計測タイマーストップ |
mori2020 | 50:ee78382fd399 | 633 | DT = (int)(timer.read_us()*0.01657); // 距離計算 |
mori2020 | 50:ee78382fd399 | 634 | if(timer.read_ms() > 1000){ |
mori2020 | 50:ee78382fd399 | 635 | DT = -1; |
mori2020 | 50:ee78382fd399 | 636 | break; |
mori2020 | 50:ee78382fd399 | 637 | } |
mori2020 | 50:ee78382fd399 | 638 | }while(DT > 1000); |
mori2020 | 50:ee78382fd399 | 639 | if(DT > 400){ |
mori2020 | 50:ee78382fd399 | 640 | DT = 400; |
mori2020 | 50:ee78382fd399 | 641 | } |
tomotsugu | 21:68d38e8f64b5 | 642 | timer.reset(); |
mori2020 | 50:ee78382fd399 | 643 | led1 = 0; |
mori2020 | 50:ee78382fd399 | 644 | return DT; |
yangtzuli | 0:0d0037aabe41 | 645 | } |
mori2020 | 50:ee78382fd399 | 646 | |
tomotsugu | 8:a47dbf4fa455 | 647 | /* 障害物検知関数 */ |
nishimura_taku_pet | 40:75e1ad7c27e4 | 648 | void watchsurrounding3(){ |
yangtzuli | 2:38825726cb1b | 649 | SC = watch(); |
nishimura_taku_pet | 28:cb51cafca490 | 650 | if(SC < limit){ // 正面20cm以内に障害物がある場合 |
mori2020 | 50:ee78382fd399 | 651 | if(SC!=-1){ |
nishimura_taku_pet | 28:cb51cafca490 | 652 | run = STOP; // 停止 |
nishimura_taku_pet | 40:75e1ad7c27e4 | 653 | flag_a = 1; |
nishimura_taku_pet | 40:75e1ad7c27e4 | 654 | return; |
nishimura_taku_pet | 28:cb51cafca490 | 655 | } |
yangtzuli | 2:38825726cb1b | 656 | } |
mori2020 | 50:ee78382fd399 | 657 | servo.pulsewidth_us(1927); // サーボを左に40度回転 |
nishimura_taku_pet | 28:cb51cafca490 | 658 | ThisThread::sleep_for(100); // 250ms待つ |
yangtzuli | 2:38825726cb1b | 659 | SLD = watch(); |
mori2020 | 50:ee78382fd399 | 660 | if(SLD < 18){ // 左前20cm以内に障害物がある場合 |
mori2020 | 50:ee78382fd399 | 661 | run = STOP; |
mori2020 | 50:ee78382fd399 | 662 | ThisThread::sleep_for(90); |
mori2020 | 50:ee78382fd399 | 663 | run = BACK; |
mori2020 | 50:ee78382fd399 | 664 | ThisThread::sleep_for(150); |
tomotsugu | 52:c868403753e8 | 665 | run = A2RIGHT; |
tomotsugu | 52:c868403753e8 | 666 | ThisThread::sleep_for(130); |
mori2020 | 50:ee78382fd399 | 667 | return; |
yangtzuli | 2:38825726cb1b | 668 | } |
mori2020 | 50:ee78382fd399 | 669 | servo.pulsewidth_us(1425); |
mori2020 | 50:ee78382fd399 | 670 | ThisThread::sleep_for(100); |
tomotsugu | 19:c6f9f010bd9e | 671 | SC = watch(); |
tomotsugu | 19:c6f9f010bd9e | 672 | if(SC < limit){ |
mori2020 | 50:ee78382fd399 | 673 | if(SC != -1){ |
mori2020 | 50:ee78382fd399 | 674 | run = STOP; // 停止 |
nishimura_taku_pet | 40:75e1ad7c27e4 | 675 | flag_a = 1; |
takuminomura | 48:3003ea51c619 | 676 | return; |
mori2020 | 50:ee78382fd399 | 677 | } |
tomotsugu | 19:c6f9f010bd9e | 678 | } |
mori2020 | 50:ee78382fd399 | 679 | servo.pulsewidth_us(923); // サーボを右に40度回転 |
nishimura_taku_pet | 28:cb51cafca490 | 680 | ThisThread::sleep_for(100); // 250ms待つ |
yangtzuli | 2:38825726cb1b | 681 | SRD = watch(); |
mori2020 | 50:ee78382fd399 | 682 | if(SRD < 18){ // 右前20cm以内に障害物がある場合 |
tomotsugu | 20:02bb875a9b13 | 683 | run = STOP; // 停止 |
mori2020 | 50:ee78382fd399 | 684 | ThisThread::sleep_for(90); |
mori2020 | 50:ee78382fd399 | 685 | run = BACK; |
mori2020 | 50:ee78382fd399 | 686 | ThisThread::sleep_for(150); |
tomotsugu | 52:c868403753e8 | 687 | run = A2LEFT; |
tomotsugu | 52:c868403753e8 | 688 | ThisThread::sleep_for(130); |
mori2020 | 50:ee78382fd399 | 689 | return; |
yangtzuli | 2:38825726cb1b | 690 | } |
mori2020 | 50:ee78382fd399 | 691 | servo.pulsewidth_us(1425); // サーボを中央位置に戻す |
nishimura_taku_pet | 40:75e1ad7c27e4 | 692 | ThisThread::sleep_for(100); // 100ms待つ |
nishimura_taku_pet | 40:75e1ad7c27e4 | 693 | } |
mori2020 | 50:ee78382fd399 | 694 | |
nishimura_taku_pet | 40:75e1ad7c27e4 | 695 | /* 障害物検知関数 */ |
nishimura_taku_pet | 40:75e1ad7c27e4 | 696 | void watchsurrounding5(){ |
nishimura_taku_pet | 40:75e1ad7c27e4 | 697 | SC = watch(); |
mori2020 | 50:ee78382fd399 | 698 | servo.pulsewidth_us(1927); // サーボを左に40度回転 |
nishimura_taku_pet | 40:75e1ad7c27e4 | 699 | ThisThread::sleep_for(100); // 250ms待つ |
nishimura_taku_pet | 40:75e1ad7c27e4 | 700 | SLD = watch(); |
nishimura_taku_pet | 40:75e1ad7c27e4 | 701 | servo.pulsewidth_us(2400); // サーボを左に90度回転 |
nishimura_taku_pet | 40:75e1ad7c27e4 | 702 | ThisThread::sleep_for(100); // 250ms待つ |
nishimura_taku_pet | 40:75e1ad7c27e4 | 703 | SL = watch(); |
mori2020 | 50:ee78382fd399 | 704 | servo.pulsewidth_us(1425); |
nishimura_taku_pet | 40:75e1ad7c27e4 | 705 | ThisThread::sleep_for(250); |
nishimura_taku_pet | 40:75e1ad7c27e4 | 706 | SC = watch(); |
mori2020 | 50:ee78382fd399 | 707 | servo.pulsewidth_us(923); // サーボを右に40度回転 |
nishimura_taku_pet | 40:75e1ad7c27e4 | 708 | ThisThread::sleep_for(100); // 250ms待つ |
nishimura_taku_pet | 40:75e1ad7c27e4 | 709 | SRD = watch(); |
yangtzuli | 2:38825726cb1b | 710 | servo.pulsewidth_us(500); // サーボを右に90度回転 |
nishimura_taku_pet | 28:cb51cafca490 | 711 | ThisThread::sleep_for(100); // 250ms待つ |
yangtzuli | 2:38825726cb1b | 712 | SR = watch(); |
mori2020 | 50:ee78382fd399 | 713 | servo.pulsewidth_us(1425); // サーボを中央位置に戻す |
nishimura_taku_pet | 28:cb51cafca490 | 714 | ThisThread::sleep_for(250); // 100ms待つ |
yangtzuli | 3:2ae6218973be | 715 | } |
yangtzuli | 3:2ae6218973be | 716 | |
tomotsugu | 8:a47dbf4fa455 | 717 | /* ディスプレイ表示関数 */ |
yangtzuli | 3:2ae6218973be | 718 | void display(){ |
tomotsugu | 8:a47dbf4fa455 | 719 | mutex.lock(); // ミューテックスロック |
yangtzuli | 3:2ae6218973be | 720 | lcd.setAddress(0,1); |
tomotsugu | 8:a47dbf4fa455 | 721 | |
tomotsugu | 8:a47dbf4fa455 | 722 | /* 操作モードによる場合分け */ |
yangtzuli | 3:2ae6218973be | 723 | switch(mode){ |
tomotsugu | 8:a47dbf4fa455 | 724 | /* 前進 */ |
yangtzuli | 3:2ae6218973be | 725 | case ADVANCE: |
yangtzuli | 3:2ae6218973be | 726 | lcd.printf("Mode:Advance "); |
yangtzuli | 3:2ae6218973be | 727 | break; |
tomotsugu | 8:a47dbf4fa455 | 728 | /* 右折 */ |
yangtzuli | 3:2ae6218973be | 729 | case RIGHT: |
yangtzuli | 5:3fffb364744b | 730 | lcd.printf("Mode:TurnRight "); |
yangtzuli | 3:2ae6218973be | 731 | break; |
tomotsugu | 8:a47dbf4fa455 | 732 | /* 左折 */ |
yangtzuli | 3:2ae6218973be | 733 | case LEFT: |
yangtzuli | 5:3fffb364744b | 734 | lcd.printf("Mode:TurnLeft "); |
yangtzuli | 3:2ae6218973be | 735 | break; |
tomotsugu | 8:a47dbf4fa455 | 736 | /* 後退 */ |
yangtzuli | 3:2ae6218973be | 737 | case BACK: |
yangtzuli | 3:2ae6218973be | 738 | lcd.printf("Mode:Back "); |
yangtzuli | 3:2ae6218973be | 739 | break; |
tomotsugu | 8:a47dbf4fa455 | 740 | /* 停止 */ |
yangtzuli | 3:2ae6218973be | 741 | case STOP: |
yangtzuli | 3:2ae6218973be | 742 | lcd.printf("Mode:Stop "); |
yangtzuli | 3:2ae6218973be | 743 | break; |
tomotsugu | 8:a47dbf4fa455 | 744 | /* 待ち */ |
yangtzuli | 3:2ae6218973be | 745 | case READY: |
yangtzuli | 3:2ae6218973be | 746 | lcd.printf("Mode:Ready "); |
yangtzuli | 3:2ae6218973be | 747 | break; |
tomotsugu | 8:a47dbf4fa455 | 748 | /* ライントレース */ |
yangtzuli | 3:2ae6218973be | 749 | case LINE_TRACE: |
yangtzuli | 3:2ae6218973be | 750 | lcd.printf("Mode:LineTrace "); |
yangtzuli | 3:2ae6218973be | 751 | break; |
tomotsugu | 8:a47dbf4fa455 | 752 | /* 障害物回避 */ |
yangtzuli | 3:2ae6218973be | 753 | case AVOIDANCE: |
yangtzuli | 3:2ae6218973be | 754 | lcd.printf("Mode:Avoidance "); |
yangtzuli | 3:2ae6218973be | 755 | break; |
tomotsugu | 8:a47dbf4fa455 | 756 | /* スピード制御 */ |
yangtzuli | 3:2ae6218973be | 757 | case SPEED: |
tomotsugu | 8:a47dbf4fa455 | 758 | /* スピードの状態で場合分け */ |
takuminomura | 48:3003ea51c619 | 759 | switch(flag_sp % 3){ |
tomotsugu | 8:a47dbf4fa455 | 760 | /* 普通 */ |
yangtzuli | 3:2ae6218973be | 761 | case(NORMAL): |
yangtzuli | 3:2ae6218973be | 762 | lcd.printf("Speed:Normal "); |
yangtzuli | 3:2ae6218973be | 763 | break; |
tomotsugu | 8:a47dbf4fa455 | 764 | /* 速い */ |
yangtzuli | 3:2ae6218973be | 765 | case(FAST): |
yangtzuli | 3:2ae6218973be | 766 | lcd.printf("Speed:Fast "); |
yangtzuli | 3:2ae6218973be | 767 | break; |
tomotsugu | 8:a47dbf4fa455 | 768 | /* とても速い */ |
yangtzuli | 3:2ae6218973be | 769 | case(VERYFAST): |
yangtzuli | 3:2ae6218973be | 770 | lcd.printf("Speed:VeryFast "); |
yangtzuli | 3:2ae6218973be | 771 | break; |
yangtzuli | 3:2ae6218973be | 772 | } |
tomotsugu | 8:a47dbf4fa455 | 773 | viewTimer.reset(); // タイマーリセット |
tomotsugu | 8:a47dbf4fa455 | 774 | viewTimer.start(); // タイマースタート |
takuminomura | 48:3003ea51c619 | 775 | break; |
yangtzuli | 3:2ae6218973be | 776 | } |
tomotsugu | 8:a47dbf4fa455 | 777 | mutex.unlock(); // ミューテックスアンロック |
yangtzuli | 3:2ae6218973be | 778 | } |
yangtzuli | 3:2ae6218973be | 779 | |
tomotsugu | 8:a47dbf4fa455 | 780 | /* バックライト点滅 */ |
yangtzuli | 3:2ae6218973be | 781 | void lcdBacklight(void const *argument){ |
tomotsugu | 8:a47dbf4fa455 | 782 | if(flag_b == 1){ // バックライト点滅フラグが1なら |
tomotsugu | 8:a47dbf4fa455 | 783 | lcd.setBacklight(TextLCD::LightOn); // バックライトON |
tomotsugu | 8:a47dbf4fa455 | 784 | }else{ // バックライト点滅フラグが0なら |
tomotsugu | 8:a47dbf4fa455 | 785 | lcd.setBacklight(TextLCD::LightOff); // バックライトOFF |
yangtzuli | 3:2ae6218973be | 786 | } |
tomotsugu | 8:a47dbf4fa455 | 787 | flag_b = !flag_b; // バックライト点滅フラグ切り替え |
yangtzuli | 3:2ae6218973be | 788 | } |
yangtzuli | 2:38825726cb1b | 789 | |
tomotsugu | 8:a47dbf4fa455 | 790 | /* バッテリー残量更新関数 */ |
yangtzuli | 5:3fffb364744b | 791 | void bChange(){ |
yangtzuli | 17:f7259ab2fe86 | 792 | //pc.printf(" bChange1\r\n"); |
nishimura_taku_pet | 51:1baf4407f384 | 793 | if(run == STOP){ |
nishimura_taku_pet | 51:1baf4407f384 | 794 | b = (int)((((battery.read() * 3.3 - MIN_V)/0.67)*10+0.5)*10); |
nishimura_taku_pet | 51:1baf4407f384 | 795 | } |
tomotsugu | 10:d193030ce672 | 796 | if(b <= 0){ // バッテリー残量0%なら全ての機能停止 |
tomotsugu | 10:d193030ce672 | 797 | b = 0; |
tomotsugu | 10:d193030ce672 | 798 | //lcd.setBacklight(TextLCD::LightOff); |
tomotsugu | 10:d193030ce672 | 799 | //run = STOP; |
tomotsugu | 10:d193030ce672 | 800 | //exit(1); // 電池残量が5%未満の時、LCDを消灯し、モーターを停止し、プログラムを終了する。 |
tomotsugu | 10:d193030ce672 | 801 | } |
tomotsugu | 10:d193030ce672 | 802 | mutex.lock(); // ミューテックスロック |
tomotsugu | 10:d193030ce672 | 803 | lcd.setAddress(0,0); |
tomotsugu | 10:d193030ce672 | 804 | lcd.printf("Battery:%3d%%",b); // バッテリー残量表示 |
takuminomura | 48:3003ea51c619 | 805 | mutex.unlock(); // ミューテックスアンロック |
tomotsugu | 10:d193030ce672 | 806 | if(b <= 30){ // バッテリー残量30%以下なら |
tomotsugu | 10:d193030ce672 | 807 | if(flag_t == 0){ // バックライトタイマーフラグが0なら |
nishimura_taku_pet | 43:243c1455f88a | 808 | //bTimer.attach(lcdBacklight,0.5); |
tomotsugu | 10:d193030ce672 | 809 | bTimer.start(500); // 0.5秒周期でバックライトタイマー割り込み |
tomotsugu | 10:d193030ce672 | 810 | flag_t = 1; // バックライトタイマーフラグを1に切り替え |
yangtzuli | 3:2ae6218973be | 811 | } |
tomotsugu | 10:d193030ce672 | 812 | }else{ |
tomotsugu | 10:d193030ce672 | 813 | if(flag_t == 1){ // バックライトタイマーフラグが1なら |
nishimura_taku_pet | 43:243c1455f88a | 814 | //bTimer.detach(); |
tomotsugu | 10:d193030ce672 | 815 | bTimer.stop(); // バックライトタイマーストップ |
tomotsugu | 10:d193030ce672 | 816 | lcd.setBacklight(TextLCD::LightOn); // バックライトON |
tomotsugu | 10:d193030ce672 | 817 | flag_t = 0; // バックライトタイマーフラグを0に切り替え |
yangtzuli | 3:2ae6218973be | 818 | } |
tomotsugu | 10:d193030ce672 | 819 | } |
yangtzuli | 2:38825726cb1b | 820 | } |
mori2020 | 50:ee78382fd399 | 821 | |
mori2020 | 50:ee78382fd399 | 822 | |
nishimura_taku_pet | 24:9481c8f56a49 | 823 | // Serial Interrupt read ESP data |
nishimura_taku_pet | 24:9481c8f56a49 | 824 | void callback() |
nishimura_taku_pet | 24:9481c8f56a49 | 825 | { |
mori2020 | 50:ee78382fd399 | 826 | ////*-*-*-5("\n\r------------ callback is being called --------------\n\r"); |
nishimura_taku_pet | 24:9481c8f56a49 | 827 | led3=1; |
nishimura_taku_pet | 24:9481c8f56a49 | 828 | while (esp.readable()) { |
nishimura_taku_pet | 24:9481c8f56a49 | 829 | webbuff[ount] = esp.getc(); |
nishimura_taku_pet | 24:9481c8f56a49 | 830 | ount++; |
nishimura_taku_pet | 24:9481c8f56a49 | 831 | } |
nishimura_taku_pet | 24:9481c8f56a49 | 832 | if(strlen(webbuff)>bufflen) { |
mori2020 | 50:ee78382fd399 | 833 | // //*-*-*-5("\f\n\r------------ webbuff over bufflen --------------\n\r"); |
nishimura_taku_pet | 24:9481c8f56a49 | 834 | DataRX=1; |
nishimura_taku_pet | 24:9481c8f56a49 | 835 | led3=0; |
nishimura_taku_pet | 24:9481c8f56a49 | 836 | } |
nishimura_taku_pet | 24:9481c8f56a49 | 837 | } |
mori2020 | 50:ee78382fd399 | 838 | |
nishimura_taku_pet | 43:243c1455f88a | 839 | void wifi(/*void const *argument*/) |
nishimura_taku_pet | 24:9481c8f56a49 | 840 | { |
mori2020 | 50:ee78382fd399 | 841 | //*-*-*-5("\f\n\r------------ ESP8266 Hardware Reset psq --------------\n\r"); |
nishimura_taku_pet | 33:a6f1090e0174 | 842 | ThisThread::sleep_for(100); |
nishimura_taku_pet | 24:9481c8f56a49 | 843 | led1=1,led2=0,led3=0; |
nishimura_taku_pet | 24:9481c8f56a49 | 844 | timeout=6000; |
nishimura_taku_pet | 24:9481c8f56a49 | 845 | getcount=500; |
nishimura_taku_pet | 24:9481c8f56a49 | 846 | getreply(); |
nishimura_taku_pet | 24:9481c8f56a49 | 847 | esp.baud(115200); // ESP8266 baudrate. Maximum on KLxx' is 115200, 230400 works on K20 and K22F |
nishimura_taku_pet | 24:9481c8f56a49 | 848 | startserver(); |
mori2020 | 50:ee78382fd399 | 849 | |
nishimura_taku_pet | 24:9481c8f56a49 | 850 | while(1) { |
nishimura_taku_pet | 24:9481c8f56a49 | 851 | if(DataRX==1) { |
mori2020 | 50:ee78382fd399 | 852 | //*-*-*-5("\f\n\r------------ main while > if --------------\n\r"); |
nishimura_taku_pet | 24:9481c8f56a49 | 853 | click_flag = 1; |
nishimura_taku_pet | 24:9481c8f56a49 | 854 | ReadWebData(); |
mori2020 | 50:ee78382fd399 | 855 | //*-*-*-5("\f\n\r------------ click_flag=%d --------------\n\r",click_flag); |
mori2020 | 50:ee78382fd399 | 856 | //if ((servreq == 1 && weberror == 0) && click_flag == 1) { |
mori2020 | 50:ee78382fd399 | 857 | if (servreq == 1 && weberror == 0) { |
mori2020 | 50:ee78382fd399 | 858 | //*-*-*-5("\f\n\r------------ befor send page --------------\n\r"); |
nishimura_taku_pet | 24:9481c8f56a49 | 859 | sendpage(); |
nishimura_taku_pet | 24:9481c8f56a49 | 860 | } |
mori2020 | 50:ee78382fd399 | 861 | //*-*-*-5("\f\n\r------------ send_check begin --------------\n\r"); |
mori2020 | 50:ee78382fd399 | 862 | |
mori2020 | 50:ee78382fd399 | 863 | //sendcheck(); |
mori2020 | 50:ee78382fd399 | 864 | //*-*-*-5("\f\n\r------------ ssend_check end--------------\n\r"); |
mori2020 | 50:ee78382fd399 | 865 | |
nishimura_taku_pet | 24:9481c8f56a49 | 866 | esp.attach(&callback); |
mori2020 | 50:ee78382fd399 | 867 | //*-*-*-5(" IPD Data:\r\n\n Link ID = %d,\r\n IPD Header Length = %d \r\n IPD Type = %s\r\n", linkID, ipdLen, type); |
mori2020 | 50:ee78382fd399 | 868 | //*-*-*-5("\n\n HTTP Packet: \n\n%s\n", webdata); |
mori2020 | 50:ee78382fd399 | 869 | //*-*-*-5(" Web Characters sent : %d\n\n", bufl); |
mori2020 | 50:ee78382fd399 | 870 | //*-*-*-5(" -------------------------------------\n\n"); |
nishimura_taku_pet | 24:9481c8f56a49 | 871 | servreq=0; |
nishimura_taku_pet | 24:9481c8f56a49 | 872 | } |
nishimura_taku_pet | 24:9481c8f56a49 | 873 | ThisThread::sleep_for(100); |
nishimura_taku_pet | 24:9481c8f56a49 | 874 | } |
nishimura_taku_pet | 24:9481c8f56a49 | 875 | } |
nishimura_taku_pet | 24:9481c8f56a49 | 876 | // Static WEB page |
nishimura_taku_pet | 24:9481c8f56a49 | 877 | void sendpage() |
nishimura_taku_pet | 24:9481c8f56a49 | 878 | { |
nishimura_taku_pet | 24:9481c8f56a49 | 879 | // WEB page data |
mori2020 | 50:ee78382fd399 | 880 | |
nishimura_taku_pet | 24:9481c8f56a49 | 881 | strcpy(webbuff, "<!DOCTYPE html>"); |
nishimura_taku_pet | 24:9481c8f56a49 | 882 | strcat(webbuff, "<html><head><title>RobotCar</title><meta name='viewport' content='width=device-width'/>"); |
mori2020 | 50:ee78382fd399 | 883 | //strcat(webbuff, "<meta http-equiv=\"refresh\" content=\"5\"; >"); |
molberry | 38:39db3f7450c2 | 884 | strcat(webbuff, "<style type=\"text/css\">.noselect{ width:100px;height:60px;}.light{ width:100px;height:60px;background-color:#00ff66;}.load{ width: 50px; height: 30px;font-size:10px}</style>"); |
nishimura_taku_pet | 24:9481c8f56a49 | 885 | strcat(webbuff, "</head><body><center><p><strong>Robot Car Remote Controller"); |
nishimura_taku_pet | 24:9481c8f56a49 | 886 | strcat(webbuff, "</strong></p><td style='vertical-align:top;'><strong>Battery level "); |
mori2020 | 50:ee78382fd399 | 887 | if(b > 30) { //残電量表示 |
mori2020 | 50:ee78382fd399 | 888 | sprintf(webbuff, "%s%3d", webbuff, b); |
mori2020 | 50:ee78382fd399 | 889 | } else { //30%より下の場合残電量を赤文字 |
mori2020 | 50:ee78382fd399 | 890 | strcat(webbuff, "<font color=\"red\">"); |
mori2020 | 50:ee78382fd399 | 891 | sprintf(webbuff, "%s%3d", webbuff, b); |
mori2020 | 50:ee78382fd399 | 892 | strcat(webbuff, "</font>"); |
mori2020 | 50:ee78382fd399 | 893 | } |
mori2020 | 50:ee78382fd399 | 894 | strcat(webbuff, "%</strong>"); |
mori2020 | 50:ee78382fd399 | 895 | strcat(webbuff, "<button id=\"reloadbtn\" type=\"button\" class=\"load\" onclick=\"location.reload()\">RELOAD</button>"); |
nishimura_taku_pet | 24:9481c8f56a49 | 896 | strcat(webbuff, "</td></p>"); |
nishimura_taku_pet | 24:9481c8f56a49 | 897 | strcat(webbuff, "<br>"); |
nishimura_taku_pet | 24:9481c8f56a49 | 898 | strcat(webbuff, "<table><tr><td></td><td>"); |
nishimura_taku_pet | 24:9481c8f56a49 | 899 | |
molberry | 35:4cda290bdb87 | 900 | switch(mode) { //ブラウザ更新時の現在の車の状態からボタンの点灯判定 |
molberry | 35:4cda290bdb87 | 901 | case ADVANCE: //前進 |
mori2020 | 50:ee78382fd399 | 902 | strcat(webbuff, "<button id='gobtn' type='button' class=\"light\" value=\"GO\" onClick='send_mes(this.value)'>GO"); |
nishimura_taku_pet | 24:9481c8f56a49 | 903 | strcat(webbuff, "</button></td><td></td></tr><tr><td>"); |
mori2020 | 50:ee78382fd399 | 904 | strcat(webbuff, "<button id='leftbtn' type='button' class=\"noselect\" value=\"LEFT\" onClick='send_mes(this.value)' >LEFT"); |
nishimura_taku_pet | 24:9481c8f56a49 | 905 | strcat(webbuff, "</button></td><td>"); |
mori2020 | 50:ee78382fd399 | 906 | strcat(webbuff, "<button id='stopbtn' type='button' class=\"noselect\" value=\"STOP\" onClick='send_mes(this.value)' >STOP"); |
nishimura_taku_pet | 24:9481c8f56a49 | 907 | strcat(webbuff, "</button></td><td>"); |
mori2020 | 50:ee78382fd399 | 908 | strcat(webbuff, "<button id='rightbtn' type='button' class=\"noselect\" value=\"RIGHT\" onClick='send_mes(this.value)' >RIGHT"); |
nishimura_taku_pet | 24:9481c8f56a49 | 909 | strcat(webbuff, "</button></td></tr><td></td><td>"); |
mori2020 | 50:ee78382fd399 | 910 | strcat(webbuff, "<button id='backbtn' type='button' class=\"noselect\" value=\"BACK\" onClick='send_mes(this.value)' >BACK"); |
nishimura_taku_pet | 24:9481c8f56a49 | 911 | strcat(webbuff, "</button></td><td style='vertical-align:top; text-align:right;'></td></tr></table>"); |
nishimura_taku_pet | 24:9481c8f56a49 | 912 | strcat(webbuff, "<strong>Mode</strong>"); |
mori2020 | 50:ee78382fd399 | 913 | strcat(webbuff, "<table><tr><td><button id='avoidbtn' type='button' class=\"noselect\" value=\"AVOIDANCE\" onClick='send_mes(this.value)' >"); |
nishimura_taku_pet | 24:9481c8f56a49 | 914 | strcat(webbuff, "AVOIDANCE</button></td><td>"); |
mori2020 | 50:ee78382fd399 | 915 | strcat(webbuff, "<button id='tracebtn' type='button' class=\"noselect\" value=\"LINE_TRACE\" onClick='send_mes(this.value)' >LINE_TRACE"); |
nishimura_taku_pet | 24:9481c8f56a49 | 916 | break; |
molberry | 35:4cda290bdb87 | 917 | case LEFT: //左折 |
mori2020 | 50:ee78382fd399 | 918 | strcat(webbuff, "<button id='gobtn' type='button' class=\"noselect\" value=\"GO\" onClick='send_mes(this.value)'>GO"); |
nishimura_taku_pet | 24:9481c8f56a49 | 919 | strcat(webbuff, "</button></td><td></td></tr><tr><td>"); |
mori2020 | 50:ee78382fd399 | 920 | strcat(webbuff, "<button id='leftbtn' type='button' class=\"light\" value=\"LEFT\" onClick='send_mes(this.value)' >LEFT"); |
nishimura_taku_pet | 24:9481c8f56a49 | 921 | strcat(webbuff, "</button></td><td>"); |
mori2020 | 50:ee78382fd399 | 922 | strcat(webbuff, "<button id='stopbtn' type='button' class=\"noselect\" value=\"STOP\" onClick='send_mes(this.value)' >STOP"); |
nishimura_taku_pet | 24:9481c8f56a49 | 923 | strcat(webbuff, "</button></td><td>"); |
mori2020 | 50:ee78382fd399 | 924 | strcat(webbuff, "<button id='rightbtn' type='button' class=\"noselect\" value=\"RIGHT\" onClick='send_mes(this.value)' >RIGHT"); |
nishimura_taku_pet | 24:9481c8f56a49 | 925 | strcat(webbuff, "</button></td></tr><td></td><td>"); |
mori2020 | 50:ee78382fd399 | 926 | strcat(webbuff, "<button id='backbtn' type='button' class=\"noselect\" value=\"BACK\" onClick='send_mes(this.value)' >BACK"); |
nishimura_taku_pet | 24:9481c8f56a49 | 927 | strcat(webbuff, "</button></td><td style='vertical-align:top; text-align:right;'></td></tr></table>"); |
nishimura_taku_pet | 24:9481c8f56a49 | 928 | strcat(webbuff, "<strong>Mode</strong>"); |
mori2020 | 50:ee78382fd399 | 929 | strcat(webbuff, "<table><tr><td><button id='avoidbtn' type='button' class=\"noselect\" value=\"AVOIDANCE\" onClick='send_mes(this.value)' >"); |
nishimura_taku_pet | 24:9481c8f56a49 | 930 | strcat(webbuff, "AVOIDANCE</button></td><td>"); |
mori2020 | 50:ee78382fd399 | 931 | strcat(webbuff, "<button id='tracebtn' type='button' class=\"noselect\" value=\"LINE_TRACE\" onClick='send_mes(this.value)' >LINE_TRACE"); |
nishimura_taku_pet | 24:9481c8f56a49 | 932 | break; |
molberry | 35:4cda290bdb87 | 933 | case STOP: //停止 |
mori2020 | 50:ee78382fd399 | 934 | strcat(webbuff, "<button id='gobtn' type='button' class=\"noselect\" value=\"GO\" onClick='send_mes(this.value)'>GO"); |
nishimura_taku_pet | 24:9481c8f56a49 | 935 | strcat(webbuff, "</button></td><td></td></tr><tr><td>"); |
mori2020 | 50:ee78382fd399 | 936 | strcat(webbuff, "<button id='leftbtn' type='button' class=\"noselect\" value=\"LEFT\" onClick='send_mes(this.value)' >LEFT"); |
nishimura_taku_pet | 24:9481c8f56a49 | 937 | strcat(webbuff, "</button></td><td>"); |
mori2020 | 50:ee78382fd399 | 938 | strcat(webbuff, "<button id='stopbtn' type='button' class=\"light\" value=\"STOP\" onClick='send_mes(this.value)' >STOP"); |
nishimura_taku_pet | 24:9481c8f56a49 | 939 | strcat(webbuff, "</button></td><td>"); |
mori2020 | 50:ee78382fd399 | 940 | strcat(webbuff, "<button id='rightbtn' type='button' class=\"noselect\" value=\"RIGHT\" onClick='send_mes(this.value)' >RIGHT"); |
nishimura_taku_pet | 24:9481c8f56a49 | 941 | strcat(webbuff, "</button></td></tr><td></td><td>"); |
mori2020 | 50:ee78382fd399 | 942 | strcat(webbuff, "<button id='backbtn' type='button' class=\"noselect\" value=\"BACK\" onClick='send_mes(this.value)' >BACK"); |
nishimura_taku_pet | 24:9481c8f56a49 | 943 | strcat(webbuff, "</button></td><td style='vertical-align:top; text-align:right;'></td></tr></table>"); |
nishimura_taku_pet | 24:9481c8f56a49 | 944 | strcat(webbuff, "<strong>Mode</strong>"); |
mori2020 | 50:ee78382fd399 | 945 | strcat(webbuff, "<table><tr><td><button id='avoidbtn' type='button' class=\"noselect\" value=\"AVOIDANCE\" onClick='send_mes(this.value)' >"); |
nishimura_taku_pet | 24:9481c8f56a49 | 946 | strcat(webbuff, "AVOIDANCE</button></td><td>"); |
mori2020 | 50:ee78382fd399 | 947 | strcat(webbuff, "<button id='tracebtn' type='button' class=\"noselect\" value=\"LINE_TRACE\" onClick='send_mes(this.value)' >LINE_TRACE"); |
nishimura_taku_pet | 24:9481c8f56a49 | 948 | break; |
molberry | 35:4cda290bdb87 | 949 | case RIGHT: //右折 |
mori2020 | 50:ee78382fd399 | 950 | strcat(webbuff, "<button id='gobtn' type='button' class=\"noselect\" value=\"GO\" onClick='send_mes(this.value)'>GO"); |
nishimura_taku_pet | 24:9481c8f56a49 | 951 | strcat(webbuff, "</button></td><td></td></tr><tr><td>"); |
mori2020 | 50:ee78382fd399 | 952 | strcat(webbuff, "<button id='leftbtn' type='button' class=\"noselect\" value=\"LEFT\" onClick='send_mes(this.value)' >LEFT"); |
nishimura_taku_pet | 24:9481c8f56a49 | 953 | strcat(webbuff, "</button></td><td>"); |
mori2020 | 50:ee78382fd399 | 954 | strcat(webbuff, "<button id='stopbtn' type='button' class=\"noselect\" value=\"STOP\" onClick='send_mes(this.value)' >STOP"); |
nishimura_taku_pet | 24:9481c8f56a49 | 955 | strcat(webbuff, "</button></td><td>"); |
mori2020 | 50:ee78382fd399 | 956 | strcat(webbuff, "<button id='rightbtn' type='button' class=\"light\" value=\"RIGHT\" onClick='send_mes(this.value)' >RIGHT"); |
nishimura_taku_pet | 24:9481c8f56a49 | 957 | strcat(webbuff, "</button></td></tr><td></td><td>"); |
mori2020 | 50:ee78382fd399 | 958 | strcat(webbuff, "<button id='backbtn' type='button' class=\"noselect\" value=\"BACK\" onClick='send_mes(this.value)' >BACK"); |
nishimura_taku_pet | 24:9481c8f56a49 | 959 | strcat(webbuff, "</button></td><td style='vertical-align:top; text-align:right;'></td></tr></table>"); |
nishimura_taku_pet | 24:9481c8f56a49 | 960 | strcat(webbuff, "<strong>Mode</strong>"); |
mori2020 | 50:ee78382fd399 | 961 | strcat(webbuff, "<table><tr><td><button id='avoidbtn' type='button' class=\"noselect\" value=\"AVOIDANCE\" onClick='send_mes(this.value)' >"); |
nishimura_taku_pet | 24:9481c8f56a49 | 962 | strcat(webbuff, "AVOIDANCE</button></td><td>"); |
mori2020 | 50:ee78382fd399 | 963 | strcat(webbuff, "<button id='tracebtn' type='button' class=\"noselect\" value=\"LINE_TRACE\" onClick='send_mes(this.value)' >LINE_TRACE"); |
nishimura_taku_pet | 24:9481c8f56a49 | 964 | break; |
molberry | 35:4cda290bdb87 | 965 | case BACK: //後進 |
mori2020 | 50:ee78382fd399 | 966 | strcat(webbuff, "<button id='gobtn' type='button' class=\"noselect\" value=\"GO\" onClick='send_mes(this.value)'>GO"); |
nishimura_taku_pet | 24:9481c8f56a49 | 967 | strcat(webbuff, "</button></td><td></td></tr><tr><td>"); |
mori2020 | 50:ee78382fd399 | 968 | strcat(webbuff, "<button id='leftbtn' type='button' class=\"noselect\" value=\"LEFT\" onClick='send_mes(this.value)' >LEFT"); |
nishimura_taku_pet | 24:9481c8f56a49 | 969 | strcat(webbuff, "</button></td><td>"); |
mori2020 | 50:ee78382fd399 | 970 | strcat(webbuff, "<button id='stopbtn' type='button' class=\"noselect\" value=\"STOP\" onClick='send_mes(this.value)' >STOP"); |
nishimura_taku_pet | 24:9481c8f56a49 | 971 | strcat(webbuff, "</button></td><td>"); |
mori2020 | 50:ee78382fd399 | 972 | strcat(webbuff, "<button id='rightbtn' type='button' class=\"noselect\" value=\"RIGHT\" onClick='send_mes(this.value)' >RIGHT"); |
nishimura_taku_pet | 24:9481c8f56a49 | 973 | strcat(webbuff, "</button></td></tr><td></td><td>"); |
mori2020 | 50:ee78382fd399 | 974 | strcat(webbuff, "<button id='backbtn' type='button' class=\"light\" value=\"BACK\" onClick='send_mes(this.value)' >BACK"); |
nishimura_taku_pet | 24:9481c8f56a49 | 975 | strcat(webbuff, "</button></td><td style='vertical-align:top; text-align:right;'></td></tr><td>"); |
nishimura_taku_pet | 24:9481c8f56a49 | 976 | strcat(webbuff, "<strong>Mode</strong>"); |
mori2020 | 50:ee78382fd399 | 977 | strcat(webbuff, "<table><tr><td><button id='avoidbtn' type='button' class=\"noselect\" value=\"AVOIDANCE\" onClick='send_mes(this.value)' >"); |
nishimura_taku_pet | 24:9481c8f56a49 | 978 | strcat(webbuff, "AVOIDANCE</button></td><td>"); |
mori2020 | 50:ee78382fd399 | 979 | strcat(webbuff, "<button id='tracebtn' type='button' class=\"noselect\" value=\"LINE_TRACE\" onClick='send_mes(this.value)' >LINE_TRACE"); |
nishimura_taku_pet | 24:9481c8f56a49 | 980 | break; |
molberry | 35:4cda290bdb87 | 981 | case AVOIDANCE: //障害物回避 |
mori2020 | 50:ee78382fd399 | 982 | strcat(webbuff, "<button id='gobtn' type='button' class=\"noselect\" value=\"GO\" onClick='send_mes(this.value)'>GO"); |
nishimura_taku_pet | 24:9481c8f56a49 | 983 | strcat(webbuff, "</button></td><td></td></tr><tr><td>"); |
mori2020 | 50:ee78382fd399 | 984 | strcat(webbuff, "<button id='leftbtn' type='button' class=\"noselect\" value=\"LEFT\" onClick='send_mes(this.value)' >LEFT"); |
nishimura_taku_pet | 24:9481c8f56a49 | 985 | strcat(webbuff, "</button></td><td>"); |
mori2020 | 50:ee78382fd399 | 986 | strcat(webbuff, "<button id='stopbtn' type='button' class=\"noselect\" value=\"STOP\" onClick='send_mes(this.value)' >STOP"); |
nishimura_taku_pet | 24:9481c8f56a49 | 987 | strcat(webbuff, "</button></td><td>"); |
mori2020 | 50:ee78382fd399 | 988 | strcat(webbuff, "<button id='rightbtn' type='button' class=\"noselect\" value=\"RIGHT\" onClick='send_mes(this.value)' >RIGHT"); |
nishimura_taku_pet | 24:9481c8f56a49 | 989 | strcat(webbuff, "</button></td></tr><td></td><td>"); |
mori2020 | 50:ee78382fd399 | 990 | strcat(webbuff, "<button id='backbtn' type='button' class=\"noselect\" value=\"BACK\" onClick='send_mes(this.value)' >BACK"); |
nishimura_taku_pet | 24:9481c8f56a49 | 991 | strcat(webbuff, "</button></td><td style='vertical-align:top; text-align:right;'></td></tr></table>"); |
nishimura_taku_pet | 24:9481c8f56a49 | 992 | strcat(webbuff, "<strong>Mode</strong>"); |
mori2020 | 50:ee78382fd399 | 993 | strcat(webbuff, "<table><tr><td><button id='avoidbtn' type='button' class=\"light\" value=\"AVOIDANCE\" onClick='send_mes(this.value)' >"); |
nishimura_taku_pet | 24:9481c8f56a49 | 994 | strcat(webbuff, "AVOIDANCE</button></td><td>"); |
mori2020 | 50:ee78382fd399 | 995 | strcat(webbuff, "<button id='tracebtn' type='button' class=\"noselect\" value=\"LINE_TRACE\" onClick='send_mes(this.value)' >LINE_TRACE"); |
nishimura_taku_pet | 24:9481c8f56a49 | 996 | break; |
molberry | 35:4cda290bdb87 | 997 | case LINE_TRACE: //ライントレース |
mori2020 | 50:ee78382fd399 | 998 | strcat(webbuff, "<button id='gobtn' type='button' class=\"noselect\" value=\"GO\" onClick='send_mes(this.value)'>GO"); |
nishimura_taku_pet | 24:9481c8f56a49 | 999 | strcat(webbuff, "</button></td><td></td></tr><tr><td>"); |
mori2020 | 50:ee78382fd399 | 1000 | strcat(webbuff, "<button id='leftbtn' type='button' class=\"noselect\" value=\"LEFT\" onClick='send_mes(this.value)' >LEFT"); |
nishimura_taku_pet | 24:9481c8f56a49 | 1001 | strcat(webbuff, "</button></td><td>"); |
mori2020 | 50:ee78382fd399 | 1002 | strcat(webbuff, "<button id='stopbtn' type='button' class=\"noselect\" value=\"STOP\" onClick='send_mes(this.value)' >STOP"); |
nishimura_taku_pet | 24:9481c8f56a49 | 1003 | strcat(webbuff, "</button></td><td>"); |
mori2020 | 50:ee78382fd399 | 1004 | strcat(webbuff, "<button id='rightbtn' type='button' class=\"noselect\" value=\"RIGHT\" onClick='send_mes(this.value)' >RIGHT"); |
nishimura_taku_pet | 24:9481c8f56a49 | 1005 | strcat(webbuff, "</button></td></tr><td></td><td>"); |
mori2020 | 50:ee78382fd399 | 1006 | strcat(webbuff, "<button id='backbtn' type='button' class=\"noselect\" value=\"BACK\" onClick='send_mes(this.value)' >BACK"); |
nishimura_taku_pet | 24:9481c8f56a49 | 1007 | strcat(webbuff, "</button></td><td style='vertical-align:top; text-align:right;'></td></tr></table>"); |
nishimura_taku_pet | 24:9481c8f56a49 | 1008 | strcat(webbuff, "<strong>Mode</strong>"); |
mori2020 | 50:ee78382fd399 | 1009 | strcat(webbuff, "<table><tr><td><button id='avoidbtn' type='button' class=\"noselect\" value=\"AVOIDANCE\" onClick='send_mes(this.value)' >"); |
nishimura_taku_pet | 24:9481c8f56a49 | 1010 | strcat(webbuff, "AVOIDANCE</button></td><td>"); |
mori2020 | 50:ee78382fd399 | 1011 | strcat(webbuff, "<button id='tracebtn' type='button' class=\"light\" value=\"LINE_TRACE\" onClick='send_mes(this.value)' >LINE_TRACE"); |
nishimura_taku_pet | 24:9481c8f56a49 | 1012 | break; |
molberry | 35:4cda290bdb87 | 1013 | default: //その他 |
mori2020 | 50:ee78382fd399 | 1014 | strcat(webbuff, "<button id='gobtn' type='button' class=\"noselect\" value=\"GO\" onClick='send_mes(this.value)'>GO"); |
nishimura_taku_pet | 24:9481c8f56a49 | 1015 | strcat(webbuff, "</button></td><td></td></tr><tr><td>"); |
mori2020 | 50:ee78382fd399 | 1016 | strcat(webbuff, "<button id='leftbtn' type='button' class=\"noselect\" value=\"LEFT\" onClick='send_mes(this.value)' >LEFT"); |
nishimura_taku_pet | 24:9481c8f56a49 | 1017 | strcat(webbuff, "</button></td><td>"); |
mori2020 | 50:ee78382fd399 | 1018 | strcat(webbuff, "<button id='stopbtn' type='button' class=\"noselect\" value=\"STOP\" onClick='send_mes(this.value)' >STOP"); |
nishimura_taku_pet | 24:9481c8f56a49 | 1019 | strcat(webbuff, "</button></td><td>"); |
mori2020 | 50:ee78382fd399 | 1020 | strcat(webbuff, "<button id='rightbtn' type='button' class=\"noselect\" value=\"RIGHT\" onClick='send_mes(this.value)' >RIGHT"); |
nishimura_taku_pet | 24:9481c8f56a49 | 1021 | strcat(webbuff, "</button></td></tr><td></td><td>"); |
mori2020 | 50:ee78382fd399 | 1022 | strcat(webbuff, "<button id='backbtn' type='button' class=\"noselect\" value=\"BACK\" onClick='send_mes(this.value)' >BACK"); |
nishimura_taku_pet | 24:9481c8f56a49 | 1023 | strcat(webbuff, "</button></td><td style='vertical-align:top; text-align:right;'></td></tr></table>"); |
nishimura_taku_pet | 24:9481c8f56a49 | 1024 | strcat(webbuff, "<strong>Mode</strong>"); |
mori2020 | 50:ee78382fd399 | 1025 | strcat(webbuff, "<table><tr><td><button id='avoidbtn' type='button' class=\"noselect\" value=\"AVOIDANCE\" onClick='send_mes(this.value)' >"); |
nishimura_taku_pet | 24:9481c8f56a49 | 1026 | strcat(webbuff, "AVOIDANCE</button></td><td>"); |
mori2020 | 50:ee78382fd399 | 1027 | strcat(webbuff, "<button id='tracebtn' type='button' class=\"noselect\" value=\"LINE_TRACE\" onClick='send_mes(this.value)' >LINE_TRACE"); |
nishimura_taku_pet | 24:9481c8f56a49 | 1028 | break; |
nishimura_taku_pet | 24:9481c8f56a49 | 1029 | } |
nishimura_taku_pet | 24:9481c8f56a49 | 1030 | strcat(webbuff, "</button></td></tr></table>"); |
nishimura_taku_pet | 24:9481c8f56a49 | 1031 | strcat(webbuff, "<strong>Speed</strong>"); |
nishimura_taku_pet | 24:9481c8f56a49 | 1032 | strcat(webbuff, "<table><tr><td>"); |
nishimura_taku_pet | 24:9481c8f56a49 | 1033 | //ready示速度だけ点灯 |
molberry | 35:4cda290bdb87 | 1034 | switch (flag_sp) { //現在の速度のボタン表示 |
molberry | 35:4cda290bdb87 | 1035 | case 0: //ノーマル |
mori2020 | 50:ee78382fd399 | 1036 | strcat(webbuff, "<button id='sp1btn' type='button' class=\"light\" value=\"Normal\" onClick='send_mes_spe(this.value)' >Normal"); |
nishimura_taku_pet | 24:9481c8f56a49 | 1037 | strcat(webbuff, "</button></td><td>"); |
mori2020 | 50:ee78382fd399 | 1038 | strcat(webbuff, "<button id='sp2btn' type='button' class=\"noselect\" value=\"Fast\" onClick='send_mes_spe(this.value)' >Fast"); |
nishimura_taku_pet | 24:9481c8f56a49 | 1039 | strcat(webbuff, "</button></td><td>"); |
mori2020 | 50:ee78382fd399 | 1040 | strcat(webbuff, "<button id='sp3btn' type='button' class=\"noselect\" value=\"VeryFast\" onClick='send_mes_spe(this.value)' >VeryFast"); |
nishimura_taku_pet | 24:9481c8f56a49 | 1041 | break; |
molberry | 35:4cda290bdb87 | 1042 | case 1: //ファスト |
mori2020 | 50:ee78382fd399 | 1043 | strcat(webbuff, "<button id='sp1btn' type='button' class=\"noselect\" value=\"Normal\" onClick='send_mes_spe(this.value)' >Normal"); |
nishimura_taku_pet | 24:9481c8f56a49 | 1044 | strcat(webbuff, "</button></td><td>"); |
mori2020 | 50:ee78382fd399 | 1045 | strcat(webbuff, "<button id='sp2btn' type='button' class=\"light\" value=\"Fast\" onClick='send_mes_spe(this.value)' >Fast"); |
nishimura_taku_pet | 24:9481c8f56a49 | 1046 | strcat(webbuff, "</button></td><td>"); |
mori2020 | 50:ee78382fd399 | 1047 | strcat(webbuff, "<button id='sp3btn' type='button' class=\"noselect\" value=\"VeryFast\" onClick='send_mes_spe(this.value)' >VeryFast"); |
nishimura_taku_pet | 24:9481c8f56a49 | 1048 | break; |
molberry | 35:4cda290bdb87 | 1049 | case 2: //ベリーファスト |
mori2020 | 50:ee78382fd399 | 1050 | strcat(webbuff, "<button id='sp1btn' type='button' class=\"noselect\" value=\"Normal\" onClick='send_mes_spe(this.value)' >Normal"); |
nishimura_taku_pet | 24:9481c8f56a49 | 1051 | strcat(webbuff, "</button></td><td>"); |
mori2020 | 50:ee78382fd399 | 1052 | strcat(webbuff, "<button id='sp2btn' type='button' class=\"noselect\" value=\"Fast\" onClick='send_mes_spe(this.value)' >Fast"); |
nishimura_taku_pet | 24:9481c8f56a49 | 1053 | strcat(webbuff, "</button></td><td>"); |
mori2020 | 50:ee78382fd399 | 1054 | strcat(webbuff, "<button id='sp3btn' type='button' class=\"light\" value=\"VeryFast\" onClick='send_mes_spe(this.value)' >VeryFast"); |
nishimura_taku_pet | 24:9481c8f56a49 | 1055 | break; |
molberry | 35:4cda290bdb87 | 1056 | default: //その他 |
mori2020 | 50:ee78382fd399 | 1057 | strcat(webbuff, "<button id='sp1btn' type='button' class=\"noselect\" value=\"Normal\" onClick='send_mes_spe(this.value)' >Normal"); |
nishimura_taku_pet | 24:9481c8f56a49 | 1058 | strcat(webbuff, "</button></td><td>"); |
mori2020 | 50:ee78382fd399 | 1059 | strcat(webbuff, "<button id='sp2btn' type='button' class=\"noselect\" value=\"Fast\" onClick='send_mes_spe(this.value)' >Fast"); |
nishimura_taku_pet | 24:9481c8f56a49 | 1060 | strcat(webbuff, "</button></td><td>"); |
mori2020 | 50:ee78382fd399 | 1061 | strcat(webbuff, "<button id='sp3btn' type='button' class=\"noselect\" value=\"VeryFast\" onClick='send_mes_spe(this.value)' >VeryFast"); |
nishimura_taku_pet | 24:9481c8f56a49 | 1062 | break; |
nishimura_taku_pet | 24:9481c8f56a49 | 1063 | } |
nishimura_taku_pet | 24:9481c8f56a49 | 1064 | strcat(webbuff, "</button></td></tr></table>"); |
mori2020 | 50:ee78382fd399 | 1065 | |
nishimura_taku_pet | 24:9481c8f56a49 | 1066 | strcat(webbuff, "</center>"); |
nishimura_taku_pet | 24:9481c8f56a49 | 1067 | strcat(webbuff, "</body>"); |
nishimura_taku_pet | 24:9481c8f56a49 | 1068 | strcat(webbuff, "</html>"); |
mori2020 | 50:ee78382fd399 | 1069 | |
molberry | 35:4cda290bdb87 | 1070 | strcat(webbuff, "<script language=\"javascript\" type=\"text/javascript\">"); //機能 |
mori2020 | 50:ee78382fd399 | 1071 | |
mori2020 | 50:ee78382fd399 | 1072 | strcat(webbuff, "var button_9 = document.getElementsByTagName(\"button\");"); |
mori2020 | 50:ee78382fd399 | 1073 | |
mori2020 | 50:ee78382fd399 | 1074 | //ボタン入力時それぞれの関数から呼び出されサーバーとの通信を行う |
nishimura_taku_pet | 24:9481c8f56a49 | 1075 | strcat(webbuff, "function htmlacs(url) {"); |
mori2020 | 50:ee78382fd399 | 1076 | strcat(webbuff, "for(var m=0;m<11;m++){button_9[m].disabled=true;}"); |
mori2020 | 50:ee78382fd399 | 1077 | strcat(webbuff, "var xhr = new XMLHttpRequest();"); |
mori2020 | 50:ee78382fd399 | 1078 | strcat(webbuff, "xhr.open(\"GET\", url);"); |
mori2020 | 50:ee78382fd399 | 1079 | strcat(webbuff, "xhr.onreadystatechange = function(){"); |
mori2020 | 50:ee78382fd399 | 1080 | strcat(webbuff, "if(this.readyState == 4 || this.status == 200){"); |
mori2020 | 50:ee78382fd399 | 1081 | strcat(webbuff, "for(var m=0;m<11;m++){button_9[m].disabled=false;}"); |
mori2020 | 50:ee78382fd399 | 1082 | strcat(webbuff, "}"); |
mori2020 | 50:ee78382fd399 | 1083 | strcat(webbuff, "};"); |
mori2020 | 50:ee78382fd399 | 1084 | strcat(webbuff, "xhr.send(\"\");"); |
nishimura_taku_pet | 24:9481c8f56a49 | 1085 | strcat(webbuff, "}"); |
mori2020 | 50:ee78382fd399 | 1086 | |
mori2020 | 50:ee78382fd399 | 1087 | //mode変更ボタン入力時動作 //sendmes |
mori2020 | 50:ee78382fd399 | 1088 | strcat(webbuff, "function send_mes(btnval){"); //mode変更ボタン入力時の点灯消灯判定 |
nishimura_taku_pet | 24:9481c8f56a49 | 1089 | strcat(webbuff, "console.log(btnval);"); |
nishimura_taku_pet | 24:9481c8f56a49 | 1090 | strcat(webbuff, "var url = \"http://\" + window.location.hostname + \"/cargo?a=\" + btnval;"); |
nishimura_taku_pet | 24:9481c8f56a49 | 1091 | strcat(webbuff, "htmlacs(url);"); |
nishimura_taku_pet | 24:9481c8f56a49 | 1092 | strcat(webbuff, "console.log(url);"); |
nishimura_taku_pet | 24:9481c8f56a49 | 1093 | strcat(webbuff, "var buttons = document.getElementsByTagName(\"button\");"); |
nishimura_taku_pet | 43:243c1455f88a | 1094 | strcat(webbuff, "for(var i=1;i<8;i++){"); |
nishimura_taku_pet | 24:9481c8f56a49 | 1095 | strcat(webbuff, "if(buttons[i].value == btnval){"); |
nishimura_taku_pet | 24:9481c8f56a49 | 1096 | strcat(webbuff, "buttons[i].className=\"light\";"); |
nishimura_taku_pet | 24:9481c8f56a49 | 1097 | strcat(webbuff, "}else{"); |
nishimura_taku_pet | 24:9481c8f56a49 | 1098 | strcat(webbuff, "buttons[i].className=\"noselect\";"); |
nishimura_taku_pet | 24:9481c8f56a49 | 1099 | strcat(webbuff, "}"); |
nishimura_taku_pet | 24:9481c8f56a49 | 1100 | strcat(webbuff, "}"); |
nishimura_taku_pet | 24:9481c8f56a49 | 1101 | strcat(webbuff, "}"); |
mori2020 | 50:ee78382fd399 | 1102 | |
mori2020 | 50:ee78382fd399 | 1103 | strcat(webbuff, "function send_mes_spe(btnval){"); //speed変更ボタン入力時の点灯消灯判定 |
nishimura_taku_pet | 24:9481c8f56a49 | 1104 | strcat(webbuff, "var url = \"http://\" + window.location.hostname + \"/cargo?a=\" + btnval;"); |
nishimura_taku_pet | 24:9481c8f56a49 | 1105 | strcat(webbuff, "htmlacs(url);"); |
nishimura_taku_pet | 24:9481c8f56a49 | 1106 | strcat(webbuff, "console.log(url);"); |
nishimura_taku_pet | 24:9481c8f56a49 | 1107 | strcat(webbuff, "var buttons = document.getElementsByTagName(\"button\");"); |
nishimura_taku_pet | 43:243c1455f88a | 1108 | strcat(webbuff, "for(var i=8;i<11;i++){"); |
nishimura_taku_pet | 24:9481c8f56a49 | 1109 | strcat(webbuff, "if(buttons[i].value == btnval){"); |
nishimura_taku_pet | 24:9481c8f56a49 | 1110 | strcat(webbuff, "buttons[i].className=\"light\";"); |
nishimura_taku_pet | 24:9481c8f56a49 | 1111 | strcat(webbuff, "}else{"); |
nishimura_taku_pet | 24:9481c8f56a49 | 1112 | strcat(webbuff, "buttons[i].className=\"noselect\";"); |
nishimura_taku_pet | 24:9481c8f56a49 | 1113 | strcat(webbuff, "}"); |
nishimura_taku_pet | 24:9481c8f56a49 | 1114 | strcat(webbuff, "}"); |
nishimura_taku_pet | 24:9481c8f56a49 | 1115 | strcat(webbuff, "}"); |
nishimura_taku_pet | 24:9481c8f56a49 | 1116 | strcat(webbuff, "</script>"); |
mori2020 | 50:ee78382fd399 | 1117 | |
mori2020 | 50:ee78382fd399 | 1118 | |
nishimura_taku_pet | 24:9481c8f56a49 | 1119 | // end of WEB page data |
nishimura_taku_pet | 24:9481c8f56a49 | 1120 | bufl = strlen(webbuff); // get total page buffer length |
mori2020 | 50:ee78382fd399 | 1121 | //sprintf(cmdbuff,"AT+CIPSEND=%d,%d\r\n", linkID, bufl); // send IPD link channel and buffer character length. |
nishimura_taku_pet | 24:9481c8f56a49 | 1122 | |
nishimura_taku_pet | 24:9481c8f56a49 | 1123 | sprintf(cmdbuff,"AT+CIPSENDBUF=%d,%d\r\n", linkID, (bufl>2048?2048:bufl)); // send IPD link channel and buffer character length. |
nishimura_taku_pet | 24:9481c8f56a49 | 1124 | timeout=500; |
nishimura_taku_pet | 24:9481c8f56a49 | 1125 | getcount=40; |
nishimura_taku_pet | 24:9481c8f56a49 | 1126 | SendCMD(); |
nishimura_taku_pet | 24:9481c8f56a49 | 1127 | getreply(); |
mori2020 | 50:ee78382fd399 | 1128 | //*-*-*-5(replybuff); |
mori2020 | 50:ee78382fd399 | 1129 | ////*-*-*-5("\n++++++++++ AT+CIPSENDBUF=%d,%d+++++++++\r\n", linkID, (bufl>2048?2048:bufl)); |
mori2020 | 50:ee78382fd399 | 1130 | |
mori2020 | 50:ee78382fd399 | 1131 | //*-*-*-5("\n++++++++++ bufl is %d ++++++++++\r\n",bufl); |
mori2020 | 50:ee78382fd399 | 1132 | |
nishimura_taku_pet | 24:9481c8f56a49 | 1133 | //pastthrough mode |
nishimura_taku_pet | 24:9481c8f56a49 | 1134 | SendWEB(); // send web page |
mori2020 | 50:ee78382fd399 | 1135 | //*-*-*-5("\n++++++++++ webbuff clear ++++++++++\r\n"); |
mori2020 | 50:ee78382fd399 | 1136 | |
nishimura_taku_pet | 24:9481c8f56a49 | 1137 | memset(webbuff, '\0', sizeof(webbuff)); |
nishimura_taku_pet | 24:9481c8f56a49 | 1138 | sendcheck(); |
nishimura_taku_pet | 24:9481c8f56a49 | 1139 | } |
nishimura_taku_pet | 24:9481c8f56a49 | 1140 | |
nishimura_taku_pet | 24:9481c8f56a49 | 1141 | // Large WEB buffer data send |
nishimura_taku_pet | 24:9481c8f56a49 | 1142 | void SendWEB() |
nishimura_taku_pet | 24:9481c8f56a49 | 1143 | { |
nishimura_taku_pet | 24:9481c8f56a49 | 1144 | int i=0; |
nishimura_taku_pet | 24:9481c8f56a49 | 1145 | if(esp.writeable()) { |
nishimura_taku_pet | 24:9481c8f56a49 | 1146 | while(webbuff[i]!='\0') { |
nishimura_taku_pet | 24:9481c8f56a49 | 1147 | esp.putc(webbuff[i]); |
mori2020 | 50:ee78382fd399 | 1148 | |
nishimura_taku_pet | 24:9481c8f56a49 | 1149 | //**** |
nishimura_taku_pet | 24:9481c8f56a49 | 1150 | //output at command when 2000 |
nishimura_taku_pet | 24:9481c8f56a49 | 1151 | if(((i%2047)==0) && (i>0)) { |
mori2020 | 50:ee78382fd399 | 1152 | //wait_ms(10); |
takuminomura | 48:3003ea51c619 | 1153 | ThisThread::sleep_for(100); |
mori2020 | 50:ee78382fd399 | 1154 | sprintf(cmdbuff,"AT+CIPSENDBUF=%d,%d\r\n", linkID, (bufl-2048)>2048?2048:(bufl-2048)); // send IPD link channel and buffer character length. |
mori2020 | 50:ee78382fd399 | 1155 | ////*-*-*-5("\r\n++++++++++ AT+CIPSENDBUF=%d,%d ++++++++++\r\n", linkID, (bufl-2048)>2048?2048:(bufl-2048)); |
nishimura_taku_pet | 24:9481c8f56a49 | 1156 | timeout=600; |
nishimura_taku_pet | 24:9481c8f56a49 | 1157 | getcount=50; |
nishimura_taku_pet | 24:9481c8f56a49 | 1158 | SendCMD(); |
nishimura_taku_pet | 24:9481c8f56a49 | 1159 | getreply(); |
mori2020 | 50:ee78382fd399 | 1160 | ////*-*-*-5(replybuff); |
mori2020 | 50:ee78382fd399 | 1161 | ////*-*-*-5("\r\n+++++++++++++++++++\r\n"); |
nishimura_taku_pet | 24:9481c8f56a49 | 1162 | } |
nishimura_taku_pet | 24:9481c8f56a49 | 1163 | //**** |
nishimura_taku_pet | 24:9481c8f56a49 | 1164 | i++; |
mori2020 | 50:ee78382fd399 | 1165 | ////*-*-*-5("%c",webbuff[i]); |
nishimura_taku_pet | 24:9481c8f56a49 | 1166 | } |
nishimura_taku_pet | 24:9481c8f56a49 | 1167 | } |
mori2020 | 50:ee78382fd399 | 1168 | //*-*-*-5("\n++++++++++ send web i= %dinfo ++++++++++\r\n",i); |
nishimura_taku_pet | 24:9481c8f56a49 | 1169 | } |
nishimura_taku_pet | 24:9481c8f56a49 | 1170 | |
nishimura_taku_pet | 24:9481c8f56a49 | 1171 | |
nishimura_taku_pet | 24:9481c8f56a49 | 1172 | void sendcheck() |
nishimura_taku_pet | 24:9481c8f56a49 | 1173 | { |
nishimura_taku_pet | 24:9481c8f56a49 | 1174 | weberror=1; |
nishimura_taku_pet | 24:9481c8f56a49 | 1175 | timeout=500; |
nishimura_taku_pet | 24:9481c8f56a49 | 1176 | getcount=24; |
nishimura_taku_pet | 24:9481c8f56a49 | 1177 | time2.reset(); |
nishimura_taku_pet | 24:9481c8f56a49 | 1178 | time2.start(); |
nishimura_taku_pet | 24:9481c8f56a49 | 1179 | |
mori2020 | 50:ee78382fd399 | 1180 | /* |
mori2020 | 50:ee78382fd399 | 1181 | while(weberror==1 && time2.read() <5) { |
mori2020 | 50:ee78382fd399 | 1182 | getreply(); |
mori2020 | 50:ee78382fd399 | 1183 | if (strstr(replybuff, "SEND OK") != NULL) { |
mori2020 | 50:ee78382fd399 | 1184 | weberror=0; // wait for valid SEND OK |
mori2020 | 50:ee78382fd399 | 1185 | } |
mori2020 | 50:ee78382fd399 | 1186 | } |
mori2020 | 50:ee78382fd399 | 1187 | */ |
nishimura_taku_pet | 24:9481c8f56a49 | 1188 | if(weberror==1) { // restart connection |
nishimura_taku_pet | 24:9481c8f56a49 | 1189 | strcpy(cmdbuff, "AT+CIPMUX=1\r\n"); |
nishimura_taku_pet | 24:9481c8f56a49 | 1190 | timeout=500; |
nishimura_taku_pet | 24:9481c8f56a49 | 1191 | getcount=10; |
nishimura_taku_pet | 24:9481c8f56a49 | 1192 | SendCMD(); |
nishimura_taku_pet | 24:9481c8f56a49 | 1193 | getreply(); |
mori2020 | 50:ee78382fd399 | 1194 | //*-*-*-5(replybuff); |
nishimura_taku_pet | 24:9481c8f56a49 | 1195 | sprintf(cmdbuff,"AT+CIPSERVER=1,%d\r\n", port); |
nishimura_taku_pet | 24:9481c8f56a49 | 1196 | timeout=500; |
nishimura_taku_pet | 24:9481c8f56a49 | 1197 | getcount=10; |
nishimura_taku_pet | 24:9481c8f56a49 | 1198 | SendCMD(); |
nishimura_taku_pet | 24:9481c8f56a49 | 1199 | getreply(); |
mori2020 | 50:ee78382fd399 | 1200 | //*-*-*-5(replybuff); |
nishimura_taku_pet | 24:9481c8f56a49 | 1201 | } else { |
nishimura_taku_pet | 24:9481c8f56a49 | 1202 | sprintf(cmdbuff, "AT+CIPCLOSE=%s\r\n",channel); // close current connection |
nishimura_taku_pet | 24:9481c8f56a49 | 1203 | SendCMD(); |
nishimura_taku_pet | 24:9481c8f56a49 | 1204 | getreply(); |
mori2020 | 50:ee78382fd399 | 1205 | //*-*-*-5(replybuff); |
nishimura_taku_pet | 24:9481c8f56a49 | 1206 | } |
nishimura_taku_pet | 24:9481c8f56a49 | 1207 | time2.reset(); |
nishimura_taku_pet | 24:9481c8f56a49 | 1208 | } |
nishimura_taku_pet | 24:9481c8f56a49 | 1209 | |
nishimura_taku_pet | 24:9481c8f56a49 | 1210 | // Reads and processes GET and POST web data |
nishimura_taku_pet | 24:9481c8f56a49 | 1211 | void ReadWebData() |
nishimura_taku_pet | 24:9481c8f56a49 | 1212 | { |
mori2020 | 50:ee78382fd399 | 1213 | //*-*-*-5("+++++++++++++++++Read Web Data+++++++++++++++++++++\r\n"); |
nishimura_taku_pet | 30:c80da0ecc260 | 1214 | ThisThread::sleep_for(200); |
nishimura_taku_pet | 24:9481c8f56a49 | 1215 | esp.attach(NULL); |
nishimura_taku_pet | 24:9481c8f56a49 | 1216 | ount=0; |
nishimura_taku_pet | 24:9481c8f56a49 | 1217 | DataRX=0; |
nishimura_taku_pet | 24:9481c8f56a49 | 1218 | weberror=0; |
nishimura_taku_pet | 24:9481c8f56a49 | 1219 | memset(webdata, '\0', sizeof(webdata)); |
nishimura_taku_pet | 24:9481c8f56a49 | 1220 | int x = strcspn (webbuff,"+"); |
nishimura_taku_pet | 24:9481c8f56a49 | 1221 | if(x) { |
nishimura_taku_pet | 24:9481c8f56a49 | 1222 | strcpy(webdata, webbuff + x); |
nishimura_taku_pet | 24:9481c8f56a49 | 1223 | weberror=0; |
nishimura_taku_pet | 24:9481c8f56a49 | 1224 | int numMatched = sscanf(webdata,"+IPD,%d,%d:%s", &linkID, &ipdLen, type); |
mori2020 | 50:ee78382fd399 | 1225 | //int i=0; |
mori2020 | 50:ee78382fd399 | 1226 | //*-*-*-5("+++++++++++++++++succed rec begin+++++++++++++++++++++\r\n"); |
mori2020 | 50:ee78382fd399 | 1227 | //*-*-*-5("%s",webdata); |
mori2020 | 50:ee78382fd399 | 1228 | //*-*-*-5("+++++++++++++++++succed rec end+++++++++++++++++++++\r\n"); |
nishimura_taku_pet | 51:1baf4407f384 | 1229 | beforeMode = mode; |
nishimura_taku_pet | 43:243c1455f88a | 1230 | if( strstr(webdata, "Normal") != NULL ) { |
mori2020 | 50:ee78382fd399 | 1231 | //*-*-*-5("++++++++++++++++++Normal++++++++++++++++++++"); |
nishimura_taku_pet | 43:243c1455f88a | 1232 | mode = SPEED; // スピードモード |
nishimura_taku_pet | 43:243c1455f88a | 1233 | flag_sp = 0; |
nishimura_taku_pet | 43:243c1455f88a | 1234 | display(); // ディスプレイ表示 |
nishimura_taku_pet | 43:243c1455f88a | 1235 | mode = beforeMode; // 現在のモードに前回のモードを設定 |
nishimura_taku_pet | 43:243c1455f88a | 1236 | }else if( strstr(webdata, "VeryFast") != NULL ) { |
mori2020 | 50:ee78382fd399 | 1237 | //*-*-*-5("+++++++++++++++++++VeryFast+++++++++++++++++++"); |
nishimura_taku_pet | 43:243c1455f88a | 1238 | mode = SPEED; // スピードモード |
nishimura_taku_pet | 43:243c1455f88a | 1239 | flag_sp = 2; |
nishimura_taku_pet | 43:243c1455f88a | 1240 | display(); // ディスプレイ表示 |
nishimura_taku_pet | 43:243c1455f88a | 1241 | mode = beforeMode; // 現在のモードに前回のモードを設定 |
nishimura_taku_pet | 43:243c1455f88a | 1242 | }else if( strstr(webdata, "Fast") != NULL ) { |
mori2020 | 50:ee78382fd399 | 1243 | //*-*-*-5("++++++++++++++++++++Fast++++++++++++++++++"); |
nishimura_taku_pet | 43:243c1455f88a | 1244 | mode = SPEED; // スピードモード |
nishimura_taku_pet | 43:243c1455f88a | 1245 | flag_sp = 1; |
nishimura_taku_pet | 43:243c1455f88a | 1246 | display(); // ディスプレイ表示 |
nishimura_taku_pet | 43:243c1455f88a | 1247 | mode = beforeMode; // 現在のモードに前回のモードを設定 |
nishimura_taku_pet | 43:243c1455f88a | 1248 | } |
nishimura_taku_pet | 24:9481c8f56a49 | 1249 | if( strstr(webdata, "GO") != NULL ) { |
mori2020 | 50:ee78382fd399 | 1250 | //*-*-*-5("+++++++++++++++++前進+++++++++++++++++++++\r\n"); |
yangtzuli | 37:0cde453dce7d | 1251 | //delete avoi_thread; //障害物回避スレッド停止 |
yangtzuli | 37:0cde453dce7d | 1252 | //delete trace_thread; //ライントレーススレッド停止 |
molberry | 35:4cda290bdb87 | 1253 | run = ADVANCE; // 前進 |
molberry | 35:4cda290bdb87 | 1254 | mode = ADVANCE; // モード変更 |
molberry | 35:4cda290bdb87 | 1255 | display(); // ディスプレイ表示 |
nishimura_taku_pet | 24:9481c8f56a49 | 1256 | } |
takuminomura | 48:3003ea51c619 | 1257 | |
nishimura_taku_pet | 24:9481c8f56a49 | 1258 | if( strstr(webdata, "LEFT") != NULL ) { |
mori2020 | 50:ee78382fd399 | 1259 | //*-*-*-5("+++++++++++++++++左折+++++++++++++++++++++\r\n"); |
yangtzuli | 37:0cde453dce7d | 1260 | //delete avoi_thread; //障害物回避スレッド停止 |
yangtzuli | 37:0cde453dce7d | 1261 | //delete trace_thread; //ライントレーススレッド停止 |
molberry | 35:4cda290bdb87 | 1262 | run = LEFT; // 左折 |
molberry | 35:4cda290bdb87 | 1263 | mode = LEFT; // モード変更 |
molberry | 35:4cda290bdb87 | 1264 | display(); // ディスプレイ表示 |
nishimura_taku_pet | 24:9481c8f56a49 | 1265 | } |
nishimura_taku_pet | 24:9481c8f56a49 | 1266 | |
nishimura_taku_pet | 24:9481c8f56a49 | 1267 | if( strstr(webdata, "STOP") != NULL ) { |
mori2020 | 50:ee78382fd399 | 1268 | //*-*-*-5("+++++++++++++++++停止+++++++++++++++++++++\r\n"); |
yangtzuli | 37:0cde453dce7d | 1269 | //delete avoi_thread; //障害物回避スレッド停止 |
yangtzuli | 37:0cde453dce7d | 1270 | //delete trace_thread; //ライントレーススレッド停止 |
molberry | 35:4cda290bdb87 | 1271 | run = STOP; // 停止 |
molberry | 35:4cda290bdb87 | 1272 | mode = STOP; // モード変更 |
molberry | 35:4cda290bdb87 | 1273 | display(); // ディスプレイ表示 |
nishimura_taku_pet | 24:9481c8f56a49 | 1274 | } |
nishimura_taku_pet | 24:9481c8f56a49 | 1275 | |
nishimura_taku_pet | 24:9481c8f56a49 | 1276 | if( strstr(webdata, "RIGHT") != NULL ) { |
mori2020 | 50:ee78382fd399 | 1277 | //*-*-*-5("+++++++++++++++++右折+++++++++++++++++++++\r\n"); |
yangtzuli | 37:0cde453dce7d | 1278 | //delete avoi_thread; //障害物回避スレッド停止 |
yangtzuli | 37:0cde453dce7d | 1279 | //delete trace_thread; //ライントレーススレッド停止 |
molberry | 35:4cda290bdb87 | 1280 | run = RIGHT; // 右折 |
molberry | 35:4cda290bdb87 | 1281 | mode = RIGHT; // モード変更 |
molberry | 35:4cda290bdb87 | 1282 | display(); // ディスプレイ表示 |
nishimura_taku_pet | 24:9481c8f56a49 | 1283 | } |
nishimura_taku_pet | 24:9481c8f56a49 | 1284 | |
nishimura_taku_pet | 24:9481c8f56a49 | 1285 | if( strstr(webdata, "BACK") != NULL ) { |
mori2020 | 50:ee78382fd399 | 1286 | //*-*-*-5("+++++++++++++++++後進+++++++++++++++++++++\r\n"); |
yangtzuli | 37:0cde453dce7d | 1287 | //delete avoi_thread; //障害物回避スレッド停止 |
yangtzuli | 37:0cde453dce7d | 1288 | //delete trace_thread; //ライントレーススレッド停止 |
molberry | 35:4cda290bdb87 | 1289 | run = BACK; // 後進 |
molberry | 35:4cda290bdb87 | 1290 | mode = BACK; // モード変更 |
molberry | 35:4cda290bdb87 | 1291 | display(); // ディスプレイ表示 |
nishimura_taku_pet | 24:9481c8f56a49 | 1292 | } |
mori2020 | 50:ee78382fd399 | 1293 | //*-*-*-5("+++++++++++++++++succed+++++++++++++++++++++"); |
nishimura_taku_pet | 24:9481c8f56a49 | 1294 | |
nishimura_taku_pet | 24:9481c8f56a49 | 1295 | if( strstr(webdata, "AVOIDANCE") != NULL ) { |
mori2020 | 50:ee78382fd399 | 1296 | //*-*-*-5("+++++++++++++++++AVOIDANCE+++++++++++++++++++++"); |
nishimura_taku_pet | 26:0badbc9f9cb3 | 1297 | if(avoi_thread->get_state() == Thread::Deleted) { |
molberry | 35:4cda290bdb87 | 1298 | delete avoi_thread; //障害物回避スレッド停止 |
nishimura_taku_pet | 26:0badbc9f9cb3 | 1299 | avoi_thread = new Thread(avoidance); |
nishimura_taku_pet | 26:0badbc9f9cb3 | 1300 | avoi_thread -> set_priority(osPriorityHigh); |
nishimura_taku_pet | 26:0badbc9f9cb3 | 1301 | } |
nishimura_taku_pet | 24:9481c8f56a49 | 1302 | mode=AVOIDANCE; |
nishimura_taku_pet | 26:0badbc9f9cb3 | 1303 | run = ADVANCE; |
nishimura_taku_pet | 26:0badbc9f9cb3 | 1304 | display(); // ディスプレイ表示 |
nishimura_taku_pet | 24:9481c8f56a49 | 1305 | } |
nishimura_taku_pet | 24:9481c8f56a49 | 1306 | if( strstr(webdata, "LINE_TRACE") != NULL ) { |
mori2020 | 50:ee78382fd399 | 1307 | //*-*-*-5("+++++++++++++++++LINET RACE+++++++++++++++++++++"); |
mori2020 | 50:ee78382fd399 | 1308 | //*-*-*-5("mode = LINE_TRACE\r\n"); |
nishimura_taku_pet | 26:0badbc9f9cb3 | 1309 | if(trace_thread->get_state() == Thread::Deleted) { |
molberry | 35:4cda290bdb87 | 1310 | delete trace_thread; //ライントレーススレッド停止 |
nishimura_taku_pet | 26:0badbc9f9cb3 | 1311 | trace_thread = new Thread(trace); |
nishimura_taku_pet | 26:0badbc9f9cb3 | 1312 | trace_thread -> set_priority(osPriorityHigh); |
nishimura_taku_pet | 26:0badbc9f9cb3 | 1313 | } |
nishimura_taku_pet | 24:9481c8f56a49 | 1314 | mode=LINE_TRACE; |
nishimura_taku_pet | 26:0badbc9f9cb3 | 1315 | display(); // ディスプレイ表示 |
nishimura_taku_pet | 24:9481c8f56a49 | 1316 | } |
nishimura_taku_pet | 26:0badbc9f9cb3 | 1317 | if(mode != LINE_TRACE && trace_thread->get_state() != Thread::Deleted){ |
nishimura_taku_pet | 26:0badbc9f9cb3 | 1318 | trace_thread->terminate(); |
nishimura_taku_pet | 26:0badbc9f9cb3 | 1319 | } |
nishimura_taku_pet | 26:0badbc9f9cb3 | 1320 | if(mode != AVOIDANCE && avoi_thread->get_state() != Thread::Deleted){ |
nishimura_taku_pet | 26:0badbc9f9cb3 | 1321 | avoi_thread->terminate(); |
nishimura_taku_pet | 31:3665282561d6 | 1322 | servo.pulsewidth_us(1450); // サーボを中央位置に戻す |
nishimura_taku_pet | 26:0badbc9f9cb3 | 1323 | } |
nishimura_taku_pet | 24:9481c8f56a49 | 1324 | sprintf(channel, "%d",linkID); |
nishimura_taku_pet | 24:9481c8f56a49 | 1325 | if (strstr(webdata, "GET") != NULL) { |
nishimura_taku_pet | 24:9481c8f56a49 | 1326 | servreq=1; |
nishimura_taku_pet | 24:9481c8f56a49 | 1327 | } |
nishimura_taku_pet | 24:9481c8f56a49 | 1328 | if (strstr(webdata, "POST") != NULL) { |
nishimura_taku_pet | 24:9481c8f56a49 | 1329 | servreq=1; |
nishimura_taku_pet | 24:9481c8f56a49 | 1330 | } |
nishimura_taku_pet | 24:9481c8f56a49 | 1331 | webcounter++; |
nishimura_taku_pet | 24:9481c8f56a49 | 1332 | sprintf(webcount, "%d",webcounter); |
nishimura_taku_pet | 24:9481c8f56a49 | 1333 | } else { |
nishimura_taku_pet | 24:9481c8f56a49 | 1334 | memset(webbuff, '\0', sizeof(webbuff)); |
nishimura_taku_pet | 24:9481c8f56a49 | 1335 | esp.attach(&callback); |
nishimura_taku_pet | 24:9481c8f56a49 | 1336 | weberror=1; |
nishimura_taku_pet | 24:9481c8f56a49 | 1337 | } |
nishimura_taku_pet | 24:9481c8f56a49 | 1338 | } |
nishimura_taku_pet | 24:9481c8f56a49 | 1339 | // Starts and restarts webserver if errors detected. |
nishimura_taku_pet | 24:9481c8f56a49 | 1340 | void startserver() |
nishimura_taku_pet | 24:9481c8f56a49 | 1341 | { |
mori2020 | 50:ee78382fd399 | 1342 | //*-*-*-5("++++++++++ Resetting ESP ++++++++++\r\n"); |
nishimura_taku_pet | 24:9481c8f56a49 | 1343 | strcpy(cmdbuff,"AT+RST\r\n"); |
nishimura_taku_pet | 24:9481c8f56a49 | 1344 | timeout=8000; |
nishimura_taku_pet | 24:9481c8f56a49 | 1345 | getcount=1000; |
nishimura_taku_pet | 24:9481c8f56a49 | 1346 | SendCMD(); |
nishimura_taku_pet | 24:9481c8f56a49 | 1347 | getreply(); |
mori2020 | 50:ee78382fd399 | 1348 | //*-*-*-5(replybuff); |
mori2020 | 50:ee78382fd399 | 1349 | //*-*-*-5("%d",ount); |
nishimura_taku_pet | 24:9481c8f56a49 | 1350 | if (strstr(replybuff, "OK") != NULL) { |
mori2020 | 50:ee78382fd399 | 1351 | //*-*-*-5("\n++++++++++ Starting Server ++++++++++\r\n"); |
nishimura_taku_pet | 24:9481c8f56a49 | 1352 | strcpy(cmdbuff, "AT+CIPMUX=1\r\n"); // set multiple connections. |
nishimura_taku_pet | 24:9481c8f56a49 | 1353 | timeout=500; |
nishimura_taku_pet | 24:9481c8f56a49 | 1354 | getcount=20; |
nishimura_taku_pet | 24:9481c8f56a49 | 1355 | SendCMD(); |
nishimura_taku_pet | 24:9481c8f56a49 | 1356 | getreply(); |
mori2020 | 50:ee78382fd399 | 1357 | //*-*-*-5(replybuff); |
nishimura_taku_pet | 24:9481c8f56a49 | 1358 | sprintf(cmdbuff,"AT+CIPSERVER=1,%d\r\n", port); |
nishimura_taku_pet | 24:9481c8f56a49 | 1359 | timeout=500; |
nishimura_taku_pet | 24:9481c8f56a49 | 1360 | getcount=20; |
nishimura_taku_pet | 24:9481c8f56a49 | 1361 | SendCMD(); |
nishimura_taku_pet | 24:9481c8f56a49 | 1362 | getreply(); |
mori2020 | 50:ee78382fd399 | 1363 | //*-*-*-5(replybuff); |
nishimura_taku_pet | 33:a6f1090e0174 | 1364 | ThisThread::sleep_for(500); |
nishimura_taku_pet | 24:9481c8f56a49 | 1365 | sprintf(cmdbuff,"AT+CIPSTO=%d\r\n",SERVtimeout); |
nishimura_taku_pet | 24:9481c8f56a49 | 1366 | timeout=500; |
nishimura_taku_pet | 24:9481c8f56a49 | 1367 | getcount=50; |
nishimura_taku_pet | 24:9481c8f56a49 | 1368 | SendCMD(); |
nishimura_taku_pet | 24:9481c8f56a49 | 1369 | getreply(); |
mori2020 | 50:ee78382fd399 | 1370 | //*-*-*-5(replybuff); |
nishimura_taku_pet | 25:8ed98982faa7 | 1371 | ThisThread::sleep_for(5000); |
mori2020 | 50:ee78382fd399 | 1372 | //*-*-*-5("\n Getting Server IP \r\n"); |
nishimura_taku_pet | 24:9481c8f56a49 | 1373 | strcpy(cmdbuff, "AT+CIFSR\r\n"); |
nishimura_taku_pet | 24:9481c8f56a49 | 1374 | timeout=2500; |
nishimura_taku_pet | 24:9481c8f56a49 | 1375 | getcount=200; |
nishimura_taku_pet | 24:9481c8f56a49 | 1376 | while(weberror==0) { |
nishimura_taku_pet | 24:9481c8f56a49 | 1377 | SendCMD(); |
nishimura_taku_pet | 24:9481c8f56a49 | 1378 | getreply(); |
nishimura_taku_pet | 24:9481c8f56a49 | 1379 | if (strstr(replybuff, "0.0.0.0") == NULL) { |
nishimura_taku_pet | 24:9481c8f56a49 | 1380 | weberror=1; // wait for valid IP |
nishimura_taku_pet | 24:9481c8f56a49 | 1381 | } |
nishimura_taku_pet | 24:9481c8f56a49 | 1382 | } |
mori2020 | 50:ee78382fd399 | 1383 | //*-*-*-5("\n Enter WEB address (IP) found below in your browser \r\n\n"); |
mori2020 | 50:ee78382fd399 | 1384 | //*-*-*-5("\n The MAC address is also shown below,if it is needed \r\n\n"); |
nishimura_taku_pet | 24:9481c8f56a49 | 1385 | replybuff[strlen(replybuff)-1] = '\0'; |
mori2020 | 50:ee78382fd399 | 1386 | //char* IP = replybuff + 5; |
nishimura_taku_pet | 24:9481c8f56a49 | 1387 | sprintf(webdata,"%s", replybuff); |
mori2020 | 50:ee78382fd399 | 1388 | //*-*-*-5(webdata); |
nishimura_taku_pet | 24:9481c8f56a49 | 1389 | led2=1; |
nishimura_taku_pet | 24:9481c8f56a49 | 1390 | bufflen=200; |
mori2020 | 50:ee78382fd399 | 1391 | //bufflen=100; |
nishimura_taku_pet | 24:9481c8f56a49 | 1392 | ount=0; |
mori2020 | 50:ee78382fd399 | 1393 | //*-*-*-5("\n\n++++++++++ Ready ++++++++++\r\n\n"); |
nishimura_taku_pet | 33:a6f1090e0174 | 1394 | setup(); |
nishimura_taku_pet | 24:9481c8f56a49 | 1395 | esp.attach(&callback); |
nishimura_taku_pet | 24:9481c8f56a49 | 1396 | } else { |
mori2020 | 50:ee78382fd399 | 1397 | //*-*-*-5("\n++++++++++ ESP8266 error, check power/connections ++++++++++\r\n"); |
nishimura_taku_pet | 24:9481c8f56a49 | 1398 | led1=1; |
nishimura_taku_pet | 24:9481c8f56a49 | 1399 | led2=1; |
nishimura_taku_pet | 24:9481c8f56a49 | 1400 | led3=1; |
nishimura_taku_pet | 24:9481c8f56a49 | 1401 | led4=1; |
nishimura_taku_pet | 24:9481c8f56a49 | 1402 | while(1) { |
nishimura_taku_pet | 24:9481c8f56a49 | 1403 | led1=!led1; |
nishimura_taku_pet | 24:9481c8f56a49 | 1404 | led2=!led2; |
nishimura_taku_pet | 24:9481c8f56a49 | 1405 | led3=!led3; |
nishimura_taku_pet | 24:9481c8f56a49 | 1406 | led4=!led4; |
nishimura_taku_pet | 25:8ed98982faa7 | 1407 | ThisThread::sleep_for(1000); |
nishimura_taku_pet | 24:9481c8f56a49 | 1408 | } |
nishimura_taku_pet | 24:9481c8f56a49 | 1409 | } |
nishimura_taku_pet | 24:9481c8f56a49 | 1410 | time2.reset(); |
nishimura_taku_pet | 24:9481c8f56a49 | 1411 | time2.start(); |
nishimura_taku_pet | 24:9481c8f56a49 | 1412 | } |
mori2020 | 50:ee78382fd399 | 1413 | |
nishimura_taku_pet | 24:9481c8f56a49 | 1414 | // ESP Command data send |
nishimura_taku_pet | 24:9481c8f56a49 | 1415 | void SendCMD() |
nishimura_taku_pet | 24:9481c8f56a49 | 1416 | { |
nishimura_taku_pet | 24:9481c8f56a49 | 1417 | esp.printf("%s", cmdbuff); |
nishimura_taku_pet | 24:9481c8f56a49 | 1418 | } |
nishimura_taku_pet | 24:9481c8f56a49 | 1419 | // Get Command and ESP status replies |
nishimura_taku_pet | 24:9481c8f56a49 | 1420 | void getreply() |
nishimura_taku_pet | 24:9481c8f56a49 | 1421 | { |
nishimura_taku_pet | 24:9481c8f56a49 | 1422 | memset(replybuff, '\0', sizeof(replybuff)); |
nishimura_taku_pet | 24:9481c8f56a49 | 1423 | time1.reset(); |
nishimura_taku_pet | 24:9481c8f56a49 | 1424 | time1.start(); |
nishimura_taku_pet | 24:9481c8f56a49 | 1425 | replycount=0; |
nishimura_taku_pet | 24:9481c8f56a49 | 1426 | while(time1.read_ms()< timeout && replycount < getcount) { |
nishimura_taku_pet | 24:9481c8f56a49 | 1427 | if(esp.readable()) { |
nishimura_taku_pet | 24:9481c8f56a49 | 1428 | replybuff[replycount] = esp.getc(); |
nishimura_taku_pet | 24:9481c8f56a49 | 1429 | replycount++; |
nishimura_taku_pet | 24:9481c8f56a49 | 1430 | } |
nishimura_taku_pet | 24:9481c8f56a49 | 1431 | } |
nishimura_taku_pet | 24:9481c8f56a49 | 1432 | time1.stop(); |
nishimura_taku_pet | 24:9481c8f56a49 | 1433 | } |
takuminomura | 48:3003ea51c619 | 1434 | |
tomotsugu | 8:a47dbf4fa455 | 1435 | /* mainスレッド */ |
yangtzuli | 0:0d0037aabe41 | 1436 | int main() { |
tomotsugu | 8:a47dbf4fa455 | 1437 | /* 初期設定 */ |
mori2020 | 50:ee78382fd399 | 1438 | wifi_thread = new Thread(wifi); |
mori2020 | 50:ee78382fd399 | 1439 | wifi_thread -> set_priority(osPriorityHigh); |
mori2020 | 50:ee78382fd399 | 1440 | // setup(); |
nishimura_taku_pet | 16:ffc732a3cf92 | 1441 | avoi_thread = new Thread(avoidance); |
nishimura_taku_pet | 16:ffc732a3cf92 | 1442 | avoi_thread->terminate(); |
nishimura_taku_pet | 16:ffc732a3cf92 | 1443 | trace_thread = new Thread(trace); |
nishimura_taku_pet | 16:ffc732a3cf92 | 1444 | trace_thread->terminate(); |
tomotsugu | 8:a47dbf4fa455 | 1445 | mode = READY; // 現在待ちモード |
tomotsugu | 8:a47dbf4fa455 | 1446 | beforeMode = READY; // 前回待ちモード |
tomotsugu | 8:a47dbf4fa455 | 1447 | run = STOP; // 停止 |
tomotsugu | 8:a47dbf4fa455 | 1448 | flag_sp = NORMAL; // スピード(普通) |
tomotsugu | 10:d193030ce672 | 1449 | lcd.setBacklight(TextLCD::LightOn); // バックライトON |
nishimura_taku_pet | 33:a6f1090e0174 | 1450 | lcd.setAddress(0,1); |
nishimura_taku_pet | 33:a6f1090e0174 | 1451 | lcd.printf("Mode:SetUp"); |
nishimura_taku_pet | 51:1baf4407f384 | 1452 | //display(); // ディスプレイ表示 |
yangtzuli | 2:38825726cb1b | 1453 | |
yangtzuli | 0:0d0037aabe41 | 1454 | while(1){ |
tomotsugu | 8:a47dbf4fa455 | 1455 | bChange(); // バッテリー残量更新 |
yangtzuli | 0:0d0037aabe41 | 1456 | } |
yangtzuli | 0:0d0037aabe41 | 1457 | } |