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
Diff: main.cpp
- Revision:
- 60:8a4869455ee6
- Parent:
- 59:72567654250f
- Child:
- 61:85daf80c7727
diff -r 72567654250f -r 8a4869455ee6 main.cpp
--- a/main.cpp Mon Sep 07 01:33:56 2020 +0000
+++ b/main.cpp Mon Sep 07 02:01:27 2020 +0000
@@ -4,9 +4,9 @@
*/
/*
- Version 0.02
+ Version 0.03
Date 2020/09/07
- Uploader Taku Nishimura
+ Uploader Tomotsugu Ogawa
更新するときにここも変える!
@@ -530,7 +530,7 @@
int cnt_kyori;
int kyori;
if(SC < 15){
- servo.pulsewidth_us(1425); // サーボを中央位置に戻す
+ servo.pulsewidth_us(1450); // サーボを中央位置に戻す
ThisThread::sleep_for(100); // 100ms待つ
run = STOP;
ThisThread::sleep_for(80);
@@ -576,7 +576,7 @@
}else { // 全方向以外
far = SC; // 正面を最も遠い距離に設定
houkou = 1; // 進行方向を前に設定
- if(SC < limit){
+ if(SC < limit + 5){
if(far < SLD || far < SL){ // 左または左前がより遠い場合
if(SL < SLD){ // 左前が左より遠い場合
far = SLD; // 左前を最も遠い距離に設定
@@ -700,12 +700,22 @@
run = STOP;
ThisThread::sleep_for(90);
run = BACK;
- ThisThread::sleep_for(150);
+ switch(flag_sp){
+ case 0:
+ ThisThread::sleep_for(200);
+ break;
+ case 1:
+ ThisThread::sleep_for(170);
+ break;
+ case 2:
+ ThisThread::sleep_for(150);
+ break;
+ }
run = A2RIGHT;
- ThisThread::sleep_for(130);
+ ThisThread::sleep_for(150);
return;
}
- servo.pulsewidth_us(1425);
+ servo.pulsewidth_us(1450);
ThisThread::sleep_for(100);
SC = watch();
if(SC < limit){
@@ -722,12 +732,22 @@
run = STOP; // 停止
ThisThread::sleep_for(90);
run = BACK;
- ThisThread::sleep_for(150);
+ switch(flag_sp){
+ case 0:
+ ThisThread::sleep_for(200);
+ break;
+ case 1:
+ ThisThread::sleep_for(170);
+ break;
+ case 2:
+ ThisThread::sleep_for(150);
+ break;
+ }
run = A2LEFT;
- ThisThread::sleep_for(130);
+ ThisThread::sleep_for(150);
return;
}
- servo.pulsewidth_us(1425); // サーボを中央位置に戻す
+ servo.pulsewidth_us(1450); // サーボを中央位置に戻す
ThisThread::sleep_for(100); // 100ms待つ
}
@@ -740,7 +760,7 @@
servo.pulsewidth_us(2400); // サーボを左に90度回転
ThisThread::sleep_for(100); // 250ms待つ
SL = watch();
- servo.pulsewidth_us(1425);
+ servo.pulsewidth_us(1450);
ThisThread::sleep_for(250);
SC = watch();
servo.pulsewidth_us(923); // サーボを右に40度回転
@@ -749,7 +769,7 @@
servo.pulsewidth_us(500); // サーボを右に90度回転
ThisThread::sleep_for(100); // 250ms待つ
SR = watch();
- servo.pulsewidth_us(1425); // サーボを中央位置に戻す
+ servo.pulsewidth_us(1450); // サーボを中央位置に戻す
ThisThread::sleep_for(250); // 100ms待つ
}