Important changes to repositories hosted on mbed.com
Mbed hosted mercurial repositories are deprecated and are due to be permanently deleted in July 2026.
To keep a copy of this software download the repository Zip archive or clone locally using Mercurial.
It is also possible to export all your personal repositories from the account settings page.
Dependencies: RemoteIR TextLCD linetrace
Diff: main.cpp
- Revision:
- 48:3003ea51c619
- Parent:
- 47:8a5a4275480a
- Child:
- 49:178dcafb4f0e
--- a/main.cpp Mon Aug 24 02:04:01 2020 +0000
+++ b/main.cpp Mon Aug 31 01:22:48 2020 +0000
@@ -13,13 +13,37 @@
RawSerial pc(USBTX, USBRX);
/* マクロ定義、列挙型定義 */
-#define MIN_V 2.0 // 電圧の最小値
-#define MAX_V 2.67 // 電圧の最大値
-#define LOW 0 // モーターOFF
-#define HIGH 1 // モーターON
-#define NORMAL 0 // 普通
-#define FAST 1 // 速い
-#define VERYFAST 2 // とても速い
+#define MIN_V 2.0 // 電圧の最小値
+#define MAX_V 2.67 // 電圧の最大値
+#define LOW 0 // モーターOFF
+#define HIGH 1 // モーターON
+#define NORMAL 0 // 普通
+#define FAST 1 // 速い
+#define VERYFAST 2 // とても速い
+
+#define SLOW 0.8
+#define REVERSE 0.5
+
+#define MBED04 0.781//Mbed04号機の左右のモーター速度比(R:L = 1: 0.781)
+#define MBED05 0.953//Mbed05号機の左右のモーター速度比(R:L = 1: 0.953)
+#define MSR0 0.4
+#define MSR1 0.5
+#define MSR2 0.6
+#define MSR3 MSR0*SLOW
+#define MSR4 MSR1*SLOW
+#define MSR5 MSR2*SLOW
+#define MSR6 0.7
+#define MSR7 0.8
+#define MSR8 0.9
+#define MSL0 MSR0*MBED05
+#define MSL1 MSR1*MBED05
+#define MSL2 MSR2*MBED05
+#define MSL3 MSR3*MBED05
+#define MSL4 MSR4*MBED05
+#define MSL5 MSR5*MBED05
+#define MSL6 MSR6*MBED05
+#define MSL7 MSR7*MBED05
+#define MSL8 MSR8*MBED05
/* 操作モード定義 */
enum MODE{
@@ -45,8 +69,8 @@
DigitalIn ss5(p12); // ライントレースセンサ(右)
RawSerial esp(p13, p14); // Wi-Fiモジュール(tx, rx)
AnalogIn battery(p15); // 電池残量読み取り(Max 3.3V)
-PwmOut motorR2(p21); // 右モーター後退
-PwmOut motorR1(p22); // 右モーター前進
+PwmOut motorR2(p22); // 右モーター後退
+PwmOut motorR1(p21); // 右モーター前進
PwmOut motorL2(p23); // 左モーター後退
PwmOut motorL1(p24); // 左モーター前進
PwmOut servo(p25); // サーボ
@@ -55,14 +79,25 @@
/* 変数宣言 */
int mode; // 操作モード
int run; // 走行状態
+int beforeRun = STOP; // 前回の走行状態
int beforeMode; // 前回のモード
int flag_sp = 0; // スピード変化フラグ
Timer viewTimer; // スピ―ド変更時に3秒計測タイマー
-float motorSpeed[9] = {0.4, 0.7, 0.8, 0.7, 0.8, 0.9, 0.8, 0.9, 1.0};
+
+float motorSpeedR1[9] = {MSR0, MSR1, MSR2, MSR3 , MSR4 , MSR5 , MSR6 , MSR7 , MSR8 };
+//float motorSpeedR2[9] = {MSR0, MSR1, MSR2, MSR3*REVERSE, MSR4*REVERSE, MSR5*REVERSE, MSR6*REVERSE, MSR7*REVERSE, MSR8*REVERSE};
+float motorSpeedR2[9] = {MSR0, MSR1, MSR2, MSR3*REVERSE, MSR4*REVERSE, MSR5*REVERSE, MSR6, MSR7, MSR8};
+float motorSpeedL1[9] = {MSL0, MSL1, MSL2, MSL3 , MSL4 , MSL5 , MSL6 , MSL7 , MSL8 };
+//float motorSpeedL2[9] = {MSL0, MSL1, MSL2, MSL3*REVERSE, MSL4*REVERSE, MSL5*REVERSE, MSL6*REVERSE, MSL7*REVERSE, MSL8*REVERSE};
+float motorSpeedL2[9] = {MSL0, MSL1, MSL2, MSL3*REVERSE, MSL4*REVERSE, MSL5*REVERSE, MSL6, MSL7, MSL8};
// モーター速度設定(後半はライントレース用)
+ // 0,1,2:基準速度
+ // 3,4,5:低速
+ // 6,7,8:高速
+ // R1 : 右前, R2 : 右後, L1 : 左前, L2 : 左後
Mutex mutex; // ミューテックス
-
+
/* decodeIR用変数 */
RemoteIR::Format format;
uint8_t buf[32];
@@ -76,15 +111,30 @@
int flag_t = 0; // バックライトタイマーフラグ
/* trace用変数 */
-int sensArray[32] = {0,6,2,4,1,1,2,2, // ライントレースセンサパターン
- 3,1,1,1,3,1,1,2,
- 7,1,1,1,1,1,1,1,
- 5,1,1,1,3,1,3,1};
+int sensArray[32] = {0,6,2,4,1,2,1,4, // ライントレースセンサパターン
+ 3,6,1,6,1,1,1,6, // 0:前回動作継続
+ 7,1,7,1,3,1,1,1, // 1:高速前進
+ 5,1,7,1,5,1,7,1}; // 2:低速右折
+ // 3:低速左折
+ // 4:中速右折
+ // 5:中速左折
+ // 6:高速右折
+ // 7:高速左折
+
+//int sensArray[32] = {0,6,0,4,1,0,1,4, // ライントレースセンサパターン
+// 0,6,1,6,1,1,1,6, // 0:前回動作継続
+// 7,1,7,1,0,1,1,1, // 1:高速前進
+// 5,1,7,1,5,1,7,1}; // 2:低速右折
+// // 3:低速左折
+// // 4:中速右折
+// // 5:中速左折
+// // 6:高速右折
+// // 7:高速左折
/* avoidance用変数 */
Timer timer; // 距離計測用タイマ
int DT; // 距離
-int SC; // 正面
+int SC; // 正面
int SL; // 左
int SR; // 右
int SLD; // 左前
@@ -110,10 +160,9 @@
char webbuff[4096]; // Currently using 1986 characters, Increase this if more web page data added
int port =80; // set server port
int SERVtimeout =5; // set server timeout in seconds in case link breaks.
-char ssid[32] = "mbed02"; // enter WiFi router ssid inside the quotes
+char ssid[32] = "mbed05"; // enter WiFi router ssid inside the quotes
char pwd [32] = "0123456789a"; // enter WiFi router password inside the quotes
-
/* プロトタイプ宣言 */
void decodeIR(/*void const *argument*/);
void motor(/*void const *argument*/);
@@ -123,21 +172,19 @@
void watchsurrounding3();
void watchsurrounding5();
int watch();
+char battery_ch[8];
void bChange();
void display();
void lcdBacklight(void const *argument);
void SendCMD(),getreply(),ReadWebData(),startserver(),sendpage(),SendWEB(),sendcheck();
void wifi(/*void const *argument*/);
-Thread *deco_thread; // decodeIRをスレッド化 :+3
+Thread *deco_thread; // decodeIRをスレッド化 :+3
Thread *wifi_thread;
-//wifi_thread(wifi,NULL,osPriorityHigh); // wifiをスレッド化
-Thread *motor_thread; // motorをスレッド化 :+2
-//Thread avoi_thread(avoidance, NULL, osPriorityHigh); // avoidanceをスレッド化:+2
-//Thread trace_thread(trace, NULL, osPriorityHigh); // traceをスレッド化 :+2
-RtosTimer bTimer(lcdBacklight, osTimerPeriodic); // lcdBacklightをタイマー割り込みで設定
-//Ticker bTimer;
-Thread *avoi_thread;
-Thread *trace_thread;
+//wifi_thread(wifi,NULL,osPriorityHigh); // wifiをスレッド化
+Thread *motor_thread; // motorをスレッド化 :+2
+RtosTimer bTimer(lcdBacklight, osTimerPeriodic); // lcdBacklightをタイマー割り込みで設定
+Thread *avoi_thread; // avoidanceをスレッド化:+2
+Thread *trace_thread; // traceをスレッド化 :+2
DigitalOut led1(LED1);
DigitalOut led2(LED2);
@@ -149,13 +196,13 @@
deco_thread -> set_priority(osPriorityRealtime);
motor_thread = new Thread(motor);
motor_thread -> set_priority(osPriorityHigh);
- wifi_thread -> set_priority(osPriorityRealtime);
+// wifi_thread -> set_priority(osPriorityRealtime);
display();
}
/* リモコン受信スレッド */
-void decodeIR(/*void const *argument*/){
- while(1){
+void decodeIR(/*void const *argument*/){
+ while(1){
// 受信待ち
if (ir.getState() == ReceiverIR::Received){ // コード受信
bitcount = ir.getData(&format, buf, sizeof(buf) * 8);
@@ -165,12 +212,12 @@
code+=(buf[j]<<(8*(3-j)));
}
if(mode != SPEED){ // スピードモード以外なら
- beforeMode=mode; // 前回のモードに現在のモードを設定
+ beforeMode=mode; // 前回のモードに現在のモードを設定
}
switch(code){
case 0x40bf27d8: // クイック
//pc.printf("mode = SPEED\r\n");
- mode = SPEED; // スピードモード
+ mode = SPEED; // スピードモード
changeSpeed(); // 速度変更
display(); // ディスプレイ表示
mode = beforeMode; // 現在のモードに前回のモードを設定
@@ -197,31 +244,31 @@
run = ADVANCE; // 前進
display(); // ディスプレイ表示
break;
- case 0x40bf3ec1: // ↑
+ case 0x40bf3ec1: // ↑
//pc.printf("mode = ADVANCE\r\n");
mode = ADVANCE; // 前進モード
run = ADVANCE; // 前進
display(); // ディスプレイ表示
break;
- case 0x40bf3fc0: // ↓
+ case 0x40bf3fc0: // ↓
//pc.printf("mode = BACK\r\n");
mode = BACK; // 後退モード
run = BACK; // 後退
display(); // ディスプレイ表示
break;
- case 0x40bf5fa0: // ←
+ case 0x40bf5fa0: // ←
//pc.printf("mode = LEFT\r\n");
mode = LEFT; // 左折モード
run = LEFT; // 左折
display(); // ディスプレイ表示
break;
- case 0x40bf5ba4: // →
+ case 0x40bf5ba4: // →
//pc.printf("mode = RIGHT\r\n");
mode = RIGHT; // 右折モード
run = RIGHT; // 右折
display(); // ディスプレイ表示
break;
- case 0x40bf3dc2: // 決定
+ case 0x40bf3dc2: // 決定
//pc.printf("mode = STOP\r\n");
mode = STOP; // 停止モード
run = STOP; // 停止
@@ -239,13 +286,13 @@
}
}
}
- if(viewTimer.read_ms()>=3000){ // スピードモードのまま3秒経過
- viewTimer.stop(); // タイマーストップ
- viewTimer.reset(); // タイマーリセット
- display(); // ディスプレイ表示
+ if(viewTimer.read_ms()>=3000){ // スピードモードのまま3秒経過
+ viewTimer.stop(); // タイマーストップ
+ viewTimer.reset(); // タイマーリセット
+ display(); // ディスプレイ表示
}
- ThisThread::sleep_for(90); // 90ms待つ
- }
+ ThisThread::sleep_for(90); // 90ms待つ
+ }
}
/* モーター制御スレッド */
@@ -255,31 +302,31 @@
switch(run){
/* 前進 */
case ADVANCE:
- motorR1 = motorSpeed[flag_sp]; // 右前進モーターON
- motorR2 = LOW; // 右後退モーターOFF
- motorL1 = motorSpeed[flag_sp]; // 左前進モーターON
- motorL2 = LOW; // 左後退モーターOFF
+ motorR1 = motorSpeedR1[flag_sp]; // 右前進モーターON
+ motorR2 = LOW; // 右後退モーターOFF
+ motorL1 = motorSpeedL1[flag_sp]; // 左前進モーターON
+ motorL2 = LOW; // 左後退モーターOFF
break;
/* 右折 */
case RIGHT:
- motorR1 = LOW; // 右前進モーターOFF
- motorR2 = motorSpeed[flag_sp]; // 右後退モーターON
- motorL1 = motorSpeed[flag_sp]; // 左前進モーターON
- motorL2 = LOW; // 左後退モーターOFF
+ motorR1 = LOW; // 右前進モーターOFF
+ motorR2 = motorSpeedR2[flag_sp]; // 右後退モーターON
+ motorL1 = motorSpeedL1[flag_sp]; // 左前進モーターON
+ motorL2 = LOW; // 左後退モーターOFF
break;
/* 左折 */
case LEFT:
- motorR1 = motorSpeed[flag_sp]; // 右前進モーターON
- motorR2 = LOW; // 右後退モーターOFF
- motorL1 = LOW; // 左前進モーターOFF
- motorL2 = motorSpeed[flag_sp]; // 左後退モーターON
+ motorR1 = motorSpeedR1[flag_sp]; // 右前進モーターON
+ motorR2 = LOW; // 右後退モーターOFF
+ motorL1 = LOW; // 左前進モーターOFF
+ motorL2 = motorSpeedL2[flag_sp]; // 左後退モーターON
break;
/* 後退 */
case BACK:
- motorR1 = LOW; // 右前進モーターOFF
- motorR2 = motorSpeed[flag_sp]; // 右後退モーターON
- motorL1 = LOW; // 左前進モーターOFF
- motorL2 = motorSpeed[flag_sp]; // 左後退モーターON
+ motorR1 = LOW; // 右前進モーターOFF
+ motorR2 = motorSpeedR2[flag_sp]; // 右後退モーターON
+ motorL1 = LOW; // 左前進モーターOFF
+ motorL2 = motorSpeedL2[flag_sp]; // 左後退モーターON
break;
/* 停止 */
case STOP:
@@ -292,73 +339,81 @@
if(flag_sp > VERYFAST){ // スピード変更フラグが2より大きいなら
flag_sp %= 3; // スピード変更フラグ調整
}
- ThisThread::sleep_for(30); // 30ms待つ
+ ThisThread::sleep_for(3); // 30ms待つ
}
}
/* スピード変更関数 */
void changeSpeed(){
if(flag_sp%3 == 2){ // スピード変更フラグを3で割った余りが2なら
- flag_sp -= 2; // スピード変更フラグを-2
-
+ flag_sp = 0; // スピード変更フラグを0にする
}else{ // それ以外
- flag_sp = flag_sp + 1; // スピード変更フラグを+1
- }
+ flag_sp = flag_sp + 1; // スピード変更フラグを+1
+ }
}
/* ライントレーススレッド */
void trace(){
- while(1){
- /* 各センサー値読み取り */
- int sensor1 = ss1;
- int sensor2 = ss2;
- int sensor3 = ss3;
- int sensor4 = ss4;
- int sensor5 = ss5;
- pc.printf("%d %d %d %d %d \r\n",sensor1,sensor2,sensor3,sensor4,sensor5);
- int sensD = 0;
-
- /* センサー値の決定 */
- if(sensor1 > 0) sensD |= 0x10;
- if(sensor2 > 0) sensD |= 0x08;
- if(sensor3 > 0) sensD |= 0x04;
- if(sensor4 > 0) sensD |= 0x02;
- if(sensor5 > 0) sensD |= 0x01;
-
- /* センサー値によって場合分け */
- switch(sensArray[sensD]){
- case 1:
- run = ADVANCE; // 低速で前進
- break;
- case 2:
-// flag_sp = flag_sp % 3 + 6;
- run = RIGHT; // 低速で右折
- break;
- case 3:
-// flag_sp = flag_sp % 3 + 6;
- run = LEFT; // 低速で左折
- break;
- case 4:
- flag_sp = flag_sp % 3 + 3;
- run = RIGHT; // 中速で右折
- break;
- case 5:
- flag_sp = flag_sp % 3 + 3;
- run = LEFT; // 中速で左折
- break;
- case 6:
- flag_sp = flag_sp % 3 + 6;
- run = RIGHT; // 高速で右折
- break;
- case 7:
- flag_sp = flag_sp % 3 + 6;
- run = LEFT; // 高速で左折
- break;
- default:
- break; // 前回動作を継続
- }
- ThisThread::sleep_for(30); // 30ms待つ
+ while(1){
+ /* 各センサー値読み取り */
+ int sensor1 = ss1;
+ int sensor2 = ss2;
+ int sensor3 = ss3;
+ int sensor4 = ss4;
+ int sensor5 = ss5;
+ //pc.printf("%d %d %d %d %d \r\n",sensor1,sensor2,sensor3,sensor4,sensor5);
+ int sensD = 0;
+
+ /* センサー値の決定 */
+ if(sensor1 > 0) sensD |= 0x10;
+ if(sensor2 > 0) sensD |= 0x08;
+ if(sensor3 > 0) sensD |= 0x04;
+ if(sensor4 > 0) sensD |= 0x02;
+ if(sensor5 > 0) sensD |= 0x01;
+
+ /* センサー値によって場合分け */
+ switch(sensArray[sensD]){
+ case 1:
+ flag_sp = flag_sp % 3 + 6;
+ beforeRun = run;
+ run = ADVANCE; // 高速で前進
+ break;
+ case 2:
+ flag_sp = flag_sp % 3 + 3;
+ beforeRun = run;
+ run = RIGHT; // 低速で右折
+ break;
+ case 3:
+ flag_sp = flag_sp % 3 + 3;
+ beforeRun = run;
+ run = LEFT; // 低速で左折
+ break;
+ case 4:
+ flag_sp = flag_sp % 3;
+ beforeRun = run;
+ run = RIGHT; // 中速で右折
+ break;
+ case 5:
+ flag_sp = flag_sp % 3;
+ beforeRun = run;
+ run = LEFT; // 中速で左折
+ break;
+ case 6:
+ flag_sp = flag_sp % 3 + 6;
+ beforeRun = run;
+ run = RIGHT; // 高速で右折
+ break;
+ case 7:
+ flag_sp = flag_sp % 3 + 6;
+ beforeRun = run;
+ run = LEFT; // 高速で左折
+ break;
+ default:
+ break; // 前回動作を継続
}
+// ThisThread::sleep_for(30); // 30ms待つ
+ ThisThread::sleep_for(3);
+ }
}
/* 障害物回避走行スレッド */
@@ -366,18 +421,18 @@
int i;
while(1){
watchsurrounding3();
- pc.printf("%d %d %d %d %d \r\n",SL,SLD,SC,SRD,SR);
- if(flag_a == 0){ // 障害物がない場合
- run = ADVANCE; // 前進
- }else{ // 障害物がある場合
+// pc.printf("%d %d %d %d %d \r\n",SL,SLD,SC,SRD,SR);
+ if(flag_a == 0){ // 障害物がない場合
+ run = ADVANCE; // 前進
+ }else{ // 障害物がある場合
i = 0;
- if(SC < 15){ // 正面15cm以内に障害物が現れた場合
+ if(SC < 15){ // 正面15cm以内に障害物が現れた場合
servo.pulsewidth_us(1450); // サーボを中央位置に戻す
ThisThread::sleep_for(100); // 100ms待つ
- run = BACK; // 後退
+ run = BACK; // 後退
int cnt_kyori=0;
int kyori = watch();
- while(kyori < limit){ // 正面20cm以内に障害物がある間
+ while(kyori < limit){ // 正面20cm以内に障害物がある間
if(kyori==-1){
cnt_kyori++;
if(cnt_kyori>15){
@@ -394,11 +449,11 @@
i++;
}
i = 0;*/
- run = STOP; // 停止
+ run = STOP; // 停止
}
watchsurrounding5();
- if(SC < limit && SLD < limit && SL < limit && SRD < limit && SR < limit){ // 全方向に障害物がある場合
- run = LEFT; // 左折
+ if(SC < limit && SLD < limit && SL < limit && SRD < limit && SR < limit){ // 全方向に障害物がある場合
+ run = LEFT; // 左折
while(i < 1){ // 進行方向確認
if(watch() > limit){
i++;
@@ -407,7 +462,7 @@
}
}
run = STOP; // 停止
- }else { // 全方向以外
+ }else { // 全方向以外
far = SC; // 正面を最も遠い距離に設定
houkou = 1; // 進行方向を前に設定
if(far < SLD || far < SL){ // 左または左前がより遠い場合
@@ -431,13 +486,13 @@
run = ADVANCE; // 前進
ThisThread::sleep_for(500); // 0.5秒待つ
break;
- case 2: // 左の場合
+ case 2: // 左の場合
run = LEFT; // 左折
//int kyori = watch();
//int kyori_f=0;
while(i < 20){ // 進行方向確認
/*if(kyori > (far - 2) || kyori_f == 2){ // 正面の計測距離と最も遠い距離が一致したら(誤差-2cm)
- break; // ループ+
+ break; // ループ+
}else if(kyori==-1){
kyori_f++;
}else{
@@ -445,14 +500,14 @@
i++;
}*/
if(watch() > (far - 2)){ // 正面の計測距離と最も遠い距離が一致したら(誤差-2cm)
- break; // ループ+
+ break; // ループ+
}else{
i++;
}
}
run = STOP; // 停止
break;
- case 3: // 右の場合
+ case 3: // 右の場合
run = RIGHT; // 右折
//int kyori = watch();
//int kyori_f=0;
@@ -466,7 +521,7 @@
i++;
}*/
if(watch() > (far - 2)){ // 正面の計測距離と最も遠い距離が一致したら(誤差-2cm)
- break; // ループ+
+ break; // ループ+
}else{
i++;
}
@@ -529,7 +584,7 @@
//ThisThread::sleep_for(200); // 100ms待つ
SC = watch();
if(SC < limit){ // 正面20cm以内に障害物がある場合
- if(SC!=-1){
+ if(SC!=-1){
run = STOP; // 停止
flag_a = 1;
return;
@@ -547,10 +602,10 @@
ThisThread::sleep_for(150);
SC = watch();
if(SC < limit){
- if(SC!=-1){
- run = STOP; // 停止
+ if(SC!=-1){
+ run = STOP; // 停止
flag_a = 1;
- return;
+ return;
}
}
servo.pulsewidth_us(925); // サーボを右に40度回転
@@ -634,7 +689,7 @@
/* スピード制御 */
case SPEED:
/* スピードの状態で場合分け */
- switch(flag_sp){
+ switch(flag_sp % 3){
/* 普通 */
case(NORMAL):
lcd.printf("Speed:Normal ");
@@ -650,7 +705,7 @@
}
viewTimer.reset(); // タイマーリセット
viewTimer.start(); // タイマースタート
- break;
+ break;
}
mutex.unlock(); // ミューテックスアンロック
}
@@ -678,7 +733,7 @@
mutex.lock(); // ミューテックスロック
lcd.setAddress(0,0);
lcd.printf("Battery:%3d%%",b); // バッテリー残量表示
- mutex.unlock(); // ミューテックスアンロック
+ mutex.unlock(); // ミューテックスアンロック
if(b <= 30){ // バッテリー残量30%以下なら
if(flag_t == 0){ // バックライトタイマーフラグが0なら
//bTimer.attach(lcdBacklight,0.5);
@@ -694,7 +749,6 @@
}
}
}
-
// Serial Interrupt read ESP data
void callback()
{
@@ -705,12 +759,12 @@
ount++;
}
if(strlen(webbuff)>bufflen) {
- pc.printf("\f\n\r------------ webbuff over bufflen --------------\n\r");
+// pc.printf("\f\n\r------------ webbuff over bufflen --------------\n\r");
DataRX=1;
led3=0;
}
}
-
+
void wifi(/*void const *argument*/)
{
pc.printf("\f\n\r------------ ESP8266 Hardware Reset psq --------------\n\r");
@@ -721,52 +775,33 @@
getreply();
esp.baud(115200); // ESP8266 baudrate. Maximum on KLxx' is 115200, 230400 works on K20 and K22F
startserver();
-
+
while(1) {
if(DataRX==1) {
- pc.printf("\f\n\r------------ main while > if --------------\n\r");
click_flag = 1;
ReadWebData();
- pc.printf("\f\n\r------------ click_flag=%d --------------\n\r",click_flag);
- //if ((servreq == 1 && weberror == 0) && click_flag == 1) {
- if (servreq == 1 && weberror == 0) {
- pc.printf("\f\n\r------------ befor send page --------------\n\r");
+ if (servreq == 1 && weberror == 0) { // ページ表示のリクエストがあったとき
sendpage();
}
- pc.printf("\f\n\r------------ send_check begin --------------\n\r");
-
- //sendcheck();
- pc.printf("\f\n\r------------ ssend_check end--------------\n\r");
-
esp.attach(&callback);
- pc.printf(" IPD Data:\r\n\n Link ID = %d,\r\n IPD Header Length = %d \r\n IPD Type = %s\r\n", linkID, ipdLen, type);
- pc.printf("\n\n HTTP Packet: \n\n%s\n", webdata);
- pc.printf(" Web Characters sent : %d\n\n", bufl);
- pc.printf(" -------------------------------------\n\n");
servreq=0;
}
+ run = beforeRun;
ThisThread::sleep_for(100);
+ beforeRun = run;
+ run = STOP;
}
}
// Static WEB page
void sendpage()
{
// WEB page data
-
strcpy(webbuff, "<!DOCTYPE html>");
strcat(webbuff, "<html><head><title>RobotCar</title><meta name='viewport' content='width=device-width'/>");
- strcat(webbuff, "<meta http-equiv=\"refresh\" content=\"5\"; >");
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>");
strcat(webbuff, "</head><body><center><p><strong>Robot Car Remote Controller");
strcat(webbuff, "</strong></p><td style='vertical-align:top;'><strong>Battery level ");
- if(b > 30) { //残電量表示
- sprintf(webbuff, "%s%3d", webbuff, b);
- } else { //30%より下の場合残電量を赤文字
- strcat(webbuff, "<font color=\"red\">");
- sprintf(webbuff, "%s%3d", webbuff, b);
- strcat(webbuff, "</font>");
- }
- strcat(webbuff, "%</strong>");
+ strcat(webbuff, "<input type=\"text\" id=\"leftms\" size=4 value=250>%</strong>");
strcat(webbuff, "<button id=\"reloadbtn\" type=\"button\" class=\"load\" onclick=\"rel()\">RELOAD</button>");
strcat(webbuff, "</td></p>");
strcat(webbuff, "<br>");
@@ -937,25 +972,49 @@
break;
}
strcat(webbuff, "</button></td></tr></table>");
-
strcat(webbuff, "</center>");
strcat(webbuff, "</body>");
strcat(webbuff, "</html>");
strcat(webbuff, "<script language=\"javascript\" type=\"text/javascript\">"); //機能
-
strcat(webbuff, "function rel(){");
strcat(webbuff, "location.reload();");
strcat(webbuff, "}");
-
strcat(webbuff, "function htmlacs(url) {");
strcat(webbuff, "var xhr = new XMLHttpRequest();");
strcat(webbuff, "xhr.open(\"GET\", url);");
strcat(webbuff, "xhr.send(\"\");");
strcat(webbuff, "}");
-
+//0825
+//0824 battery update auto
+ strcat(webbuff, "function battery_update() {");
+ strcat(webbuff, "var url1 = \"http://\" + window.location.hostname+ \"/cargo?a=responseBattery\";");
+ strcat(webbuff, "var xhr1 = new XMLHttpRequest();");
+ strcat(webbuff, "xhr1.open(\"GET\", url1);");
+//0820
+ strcat(webbuff, "xhr1.onreadystatechange = function(){");
+ strcat(webbuff, "if(this.readyState == 4 && this.status == 200){");
+ strcat(webbuff, "var res1 = xhr1.responseText;");
+//color
+ strcat(webbuff, "var battery_num=res1;");
+ strcat(webbuff, "if(battery_num>0 && battery_num<31){");
+ strcat(webbuff, "document.getElementById('leftms').style.color=\"red\";");
+ strcat(webbuff, "}");
+ strcat(webbuff, "if(battery_num>39 && battery_num<61){");
+ strcat(webbuff, "document.getElementById('leftms').style.color=\"orange\";");
+ strcat(webbuff, "}");
+ strcat(webbuff, "if(battery_num>69 && battery_num<101){");
+ strcat(webbuff, "document.getElementById('leftms').style.color=\"blue\";");
+ strcat(webbuff, "}");
+//color
+ strcat(webbuff, "document.getElementById('leftms').value=res1;}};");
+//0820
+ strcat(webbuff, "xhr1.send();");
+ strcat(webbuff, "}");
+ strcat(webbuff, "setInterval(battery_update,15000);");
+//0824 battery update auto
+//0825
strcat(webbuff, "function send_mes(btnmes,btnval){"); //mode変更ボタン入力時の点灯消灯判定
strcat(webbuff, "console.log(btnval);");
-
strcat(webbuff, "var url = \"http://\" + window.location.hostname + \"/cargo?a=\" + btnval;");
strcat(webbuff, "htmlacs(url);");
strcat(webbuff, "console.log(url);");
@@ -968,7 +1027,6 @@
strcat(webbuff, "}");
strcat(webbuff, "}");
strcat(webbuff, "}");
-
strcat(webbuff, "function send_mes_spe(btnmes,btnval){"); //speed変更ボタン入力時の点灯消灯判定
strcat(webbuff, "var url = \"http://\" + window.location.hostname + \"/cargo?a=\" + btnval;");
strcat(webbuff, "htmlacs(url);");
@@ -985,22 +1043,14 @@
strcat(webbuff, "</script>");
// end of WEB page data
bufl = strlen(webbuff); // get total page buffer length
- //sprintf(cmdbuff,"AT+CIPSEND=%d,%d\r\n", linkID, bufl); // send IPD link channel and buffer character length.
sprintf(cmdbuff,"AT+CIPSENDBUF=%d,%d\r\n", linkID, (bufl>2048?2048:bufl)); // send IPD link channel and buffer character length.
timeout=500;
getcount=40;
SendCMD();
getreply();
- pc.printf(replybuff);
- //pc.printf("\n++++++++++ AT+CIPSENDBUF=%d,%d+++++++++\r\n", linkID, (bufl>2048?2048:bufl));
-
- pc.printf("\n++++++++++ bufl is %d ++++++++++\r\n",bufl);
-
//pastthrough mode
SendWEB(); // send web page
- pc.printf("\n++++++++++ webbuff clear ++++++++++\r\n");
-
memset(webbuff, '\0', sizeof(webbuff));
sendcheck();
}
@@ -1012,30 +1062,45 @@
if(esp.writeable()) {
while(webbuff[i]!='\0') {
esp.putc(webbuff[i]);
-
//****
//output at command when 2000
if(((i%2047)==0) && (i>0)) {
- //wait_ms(10);
- ThisThread::sleep_for(10);
- sprintf(cmdbuff,"AT+CIPSENDBUF=%d,%d\r\n", linkID, (bufl-2048)>2048?2048:(bufl-2048)); // send IPD link channel and buffer character length.
- //pc.printf("\r\n++++++++++ AT+CIPSENDBUF=%d,%d ++++++++++\r\n", linkID, (bufl-2048)>2048?2048:(bufl-2048));
+ run = beforeRun;
+ ThisThread::sleep_for(100);
+ beforeRun = run;
+ run = STOP;
+ sprintf(cmdbuff,"AT+CIPSENDBUF=%d,%d\r\n", linkID, (bufl-2048*(i/2047))>2048?2048:(bufl-2048*(i/2047))); // send IPD link channel and buffer character length.
timeout=600;
getcount=50;
SendCMD();
getreply();
- //pc.printf(replybuff);
- //pc.printf("\r\n+++++++++++++++++++\r\n");
}
//****
i++;
- //pc.printf("%c",webbuff[i]);
}
}
- pc.printf("\n++++++++++ send web i= %dinfo ++++++++++\r\n",i);
}
+void sendpage2()
+{
+// WEB page data
+ sprintf(battery_ch,"%d",b);
+ strcpy(webbuff, battery_ch);
+// end of WEB page data
+ bufl = strlen(webbuff); // get total page buffer length
+
+ sprintf(cmdbuff,"AT+CIPSENDBUF=%d,%d\r\n", linkID, (bufl>2048?2048:bufl)); // send IPD link channel and buffer character length.
+ timeout=500;
+ getcount=40;
+ SendCMD();
+ getreply();
+ //pastthrough mode
+ SendWEB(); // send web page
+ memset(webbuff, '\0', sizeof(webbuff));
+ sendcheck();
+}
+
void sendcheck()
{
weberror=1;
@@ -1044,32 +1109,21 @@
time2.reset();
time2.start();
- /*
- while(weberror==1 && time2.read() <5) {
- getreply();
- if (strstr(replybuff, "SEND OK") != NULL) {
- weberror=0; // wait for valid SEND OK
- }
- }
- */
if(weberror==1) { // restart connection
strcpy(cmdbuff, "AT+CIPMUX=1\r\n");
timeout=500;
getcount=10;
SendCMD();
getreply();
- pc.printf(replybuff);
sprintf(cmdbuff,"AT+CIPSERVER=1,%d\r\n", port);
timeout=500;
getcount=10;
SendCMD();
getreply();
- pc.printf(replybuff);
} else {
sprintf(cmdbuff, "AT+CIPCLOSE=%s\r\n",channel); // close current connection
SendCMD();
getreply();
- pc.printf(replybuff);
}
time2.reset();
}
@@ -1077,8 +1131,10 @@
// Reads and processes GET and POST web data
void ReadWebData()
{
- pc.printf("+++++++++++++++++Read Web Data+++++++++++++++++++++\r\n");
+ run = beforeRun;
ThisThread::sleep_for(200);
+ beforeRun = run;
+ run = STOP;
esp.attach(NULL);
ount=0;
DataRX=0;
@@ -1089,24 +1145,22 @@
strcpy(webdata, webbuff + x);
weberror=0;
int numMatched = sscanf(webdata,"+IPD,%d,%d:%s", &linkID, &ipdLen, type);
- //int i=0;
- pc.printf("+++++++++++++++++succed rec begin+++++++++++++++++++++\r\n");
- pc.printf("%s",webdata);
- pc.printf("+++++++++++++++++succed rec end+++++++++++++++++++++\r\n");
+ if( strstr(webdata, "responseBattery") != NULL ) {
+ click_flag = 0;
+ led4=!led4;
+ sendpage2();
+ }
if( strstr(webdata, "Normal") != NULL ) {
- pc.printf("++++++++++++++++++Normal++++++++++++++++++++");
mode = SPEED; // スピードモード
flag_sp = 0;
display(); // ディスプレイ表示
mode = beforeMode; // 現在のモードに前回のモードを設定
}else if( strstr(webdata, "VeryFast") != NULL ) {
- pc.printf("+++++++++++++++++++VeryFast+++++++++++++++++++");
mode = SPEED; // スピードモード
flag_sp = 2;
display(); // ディスプレイ表示
mode = beforeMode; // 現在のモードに前回のモードを設定
}else if( strstr(webdata, "Fast") != NULL ) {
- pc.printf("++++++++++++++++++++Fast++++++++++++++++++");
mode = SPEED; // スピードモード
flag_sp = 1;
display(); // ディスプレイ表示
@@ -1115,16 +1169,14 @@
beforeMode = mode;
}
if( strstr(webdata, "GO") != NULL ) {
- pc.printf("+++++++++++++++++前進+++++++++++++++++++++\r\n");
//delete avoi_thread; //障害物回避スレッド停止
//delete trace_thread; //ライントレーススレッド停止
run = ADVANCE; // 前進
mode = ADVANCE; // モード変更
display(); // ディスプレイ表示
}
-
+
if( strstr(webdata, "LEFT") != NULL ) {
- pc.printf("+++++++++++++++++左折+++++++++++++++++++++\r\n");
//delete avoi_thread; //障害物回避スレッド停止
//delete trace_thread; //ライントレーススレッド停止
run = LEFT; // 左折
@@ -1133,7 +1185,6 @@
}
if( strstr(webdata, "STOP") != NULL ) {
- pc.printf("+++++++++++++++++停止+++++++++++++++++++++\r\n");
//delete avoi_thread; //障害物回避スレッド停止
//delete trace_thread; //ライントレーススレッド停止
run = STOP; // 停止
@@ -1142,7 +1193,6 @@
}
if( strstr(webdata, "RIGHT") != NULL ) {
- pc.printf("+++++++++++++++++右折+++++++++++++++++++++\r\n");
//delete avoi_thread; //障害物回避スレッド停止
//delete trace_thread; //ライントレーススレッド停止
run = RIGHT; // 右折
@@ -1151,17 +1201,14 @@
}
if( strstr(webdata, "BACK") != NULL ) {
- pc.printf("+++++++++++++++++後進+++++++++++++++++++++\r\n");
//delete avoi_thread; //障害物回避スレッド停止
//delete trace_thread; //ライントレーススレッド停止
run = BACK; // 後進
mode = BACK; // モード変更
display(); // ディスプレイ表示
}
- pc.printf("+++++++++++++++++succed+++++++++++++++++++++");
if( strstr(webdata, "AVOIDANCE") != NULL ) {
- pc.printf("+++++++++++++++++AVOIDANCE+++++++++++++++++++++");
if(avoi_thread->get_state() == Thread::Deleted) {
delete avoi_thread; //障害物回避スレッド停止
avoi_thread = new Thread(avoidance);
@@ -1172,8 +1219,6 @@
display(); // ディスプレイ表示
}
if( strstr(webdata, "LINE_TRACE") != NULL ) {
- pc.printf("+++++++++++++++++LINET RACE+++++++++++++++++++++");
- pc.printf("mode = LINE_TRACE\r\n");
if(trace_thread->get_state() == Thread::Deleted) {
delete trace_thread; //ライントレーススレッド停止
trace_thread = new Thread(trace);
@@ -1251,12 +1296,10 @@
pc.printf("\n Enter WEB address (IP) found below in your browser \r\n\n");
pc.printf("\n The MAC address is also shown below,if it is needed \r\n\n");
replybuff[strlen(replybuff)-1] = '\0';
- //char* IP = replybuff + 5;
sprintf(webdata,"%s", replybuff);
pc.printf(webdata);
led2=1;
bufflen=200;
- //bufflen=100;
ount=0;
pc.printf("\n\n++++++++++ Ready ++++++++++\r\n\n");
setup();
@@ -1298,12 +1341,13 @@
}
time1.stop();
}
-
+
/* mainスレッド */
int main() {
/* 初期設定 */
- wifi_thread = new Thread(wifi);
- wifi_thread -> set_priority(osPriorityHigh);
+// wifi_thread = new Thread(wifi);
+// wifi_thread -> set_priority(osPriorityHigh);
+ setup();
avoi_thread = new Thread(avoidance);
avoi_thread->terminate();
trace_thread = new Thread(trace);
@@ -1315,7 +1359,7 @@
lcd.setBacklight(TextLCD::LightOn); // バックライトON
lcd.setAddress(0,1);
lcd.printf("Mode:SetUp");
- //display(); // ディスプレイ表示
+ display(); // ディスプレイ表示
while(1){
bChange(); // バッテリー残量更新