From b15fc8e1c09c03a78d0f036924f2c6f113ca09aa Mon Sep 17 00:00:00 2001
From: masatake aoki
Date: Fri, 18 Apr 2025 14:19:51 +0900
Subject: [PATCH 1/5] update
---
README.md | 6 +-
pico_v2_STEP3_Buzzer/pico_v2_STEP3_Buzzer.ino | 10 +-
.../pico_v2_STEP5_Straight.ino | 21 +-
pico_v2_STEP5_Straight/run.h | 50 ++
pico_v2_STEP5_Straight/run.ino | 140 +++--
pico_v2_STEP6_rotate/pico_v2_STEP6_rotate.ino | 32 +-
pico_v2_STEP6_rotate/run.h | 52 ++
pico_v2_STEP6_rotate/run.ino | 183 +++++--
pico_v2_STEP7_P_control/interrupt.ino | 121 -----
.../pico_v2_STEP7_P_control.ino | 78 +--
pico_v2_STEP7_P_control/run.h | 73 +++
pico_v2_STEP7_P_control/run.ino | 162 ++++--
pico_v2_STEP7_P_control/sensor.h | 42 ++
pico_v2_STEP7_P_control/sensor.ino | 114 ++++
pico_v2_STEP8_micromouse/Flash.ino | 352 ++++++++++++
pico_v2_STEP8_micromouse/SPIFFS.ino | 83 ---
pico_v2_STEP8_micromouse/adjust.h | 31 ++
pico_v2_STEP8_micromouse/adjust.ino | 84 +--
pico_v2_STEP8_micromouse/device.h | 26 +-
pico_v2_STEP8_micromouse/device.ino | 94 +---
.../fast.h | 21 +-
pico_v2_STEP8_micromouse/fast.ino | 62 ++-
pico_v2_STEP8_micromouse/interrupt.ino | 123 -----
pico_v2_STEP8_micromouse/map_manager.h | 58 +-
pico_v2_STEP8_micromouse/map_manager.ino | 507 +++++++-----------
pico_v2_STEP8_micromouse/misc.h | 31 ++
pico_v2_STEP8_micromouse/misc.ino | 106 +++-
pico_v2_STEP8_micromouse/mytypedef.h | 32 --
pico_v2_STEP8_micromouse/parameter.h | 56 +-
.../pico_v2_STEP8_micromouse.ino | 114 +---
pico_v2_STEP8_micromouse/run.h | 78 +++
pico_v2_STEP8_micromouse/run.ino | 314 +++++++----
.../search.h | 21 +-
pico_v2_STEP8_micromouse/search.ino | 90 ++--
pico_v2_STEP8_micromouse/sensor.h | 42 ++
pico_v2_STEP8_micromouse/sensor.ino | 99 ++++
pico_v2_STEP8_micromouse/webserver.ino | 326 +++++++++++
37 files changed, 2453 insertions(+), 1381 deletions(-)
create mode 100644 pico_v2_STEP5_Straight/run.h
create mode 100644 pico_v2_STEP6_rotate/run.h
delete mode 100644 pico_v2_STEP7_P_control/interrupt.ino
create mode 100644 pico_v2_STEP7_P_control/run.h
create mode 100644 pico_v2_STEP7_P_control/sensor.h
create mode 100644 pico_v2_STEP7_P_control/sensor.ino
create mode 100644 pico_v2_STEP8_micromouse/Flash.ino
delete mode 100644 pico_v2_STEP8_micromouse/SPIFFS.ino
create mode 100644 pico_v2_STEP8_micromouse/adjust.h
rename pico_v2_STEP5_Straight/interrupt.ino => pico_v2_STEP8_micromouse/fast.h (71%)
delete mode 100644 pico_v2_STEP8_micromouse/interrupt.ino
create mode 100644 pico_v2_STEP8_micromouse/misc.h
delete mode 100644 pico_v2_STEP8_micromouse/mytypedef.h
create mode 100644 pico_v2_STEP8_micromouse/run.h
rename pico_v2_STEP6_rotate/interrupt.ino => pico_v2_STEP8_micromouse/search.h (71%)
create mode 100644 pico_v2_STEP8_micromouse/sensor.h
create mode 100644 pico_v2_STEP8_micromouse/sensor.ino
create mode 100644 pico_v2_STEP8_micromouse/webserver.ino
diff --git a/README.md b/README.md
index 11d7225..c50a693 100644
--- a/README.md
+++ b/README.md
@@ -8,8 +8,10 @@
Pi:Co V2用のArduinoサンプルスケッチ集です。
## 動作環境
-
-- arduino-esp32 : v3.0.1
+- Arduino IDE v2.3.4
+- arduino-esp32 v3.1.1
+- Async TCP 3.3.6
+- ESP Async WebServer 3.7.2
## サンプルスケッチについて
diff --git a/pico_v2_STEP3_Buzzer/pico_v2_STEP3_Buzzer.ino b/pico_v2_STEP3_Buzzer/pico_v2_STEP3_Buzzer.ino
index 9e836ee..688d0d1 100644
--- a/pico_v2_STEP3_Buzzer/pico_v2_STEP3_Buzzer.ino
+++ b/pico_v2_STEP3_Buzzer/pico_v2_STEP3_Buzzer.ino
@@ -31,7 +31,7 @@
char g_mode;
-void setLED(char data)
+void ledSet(char data)
{
if (data & 0x01) {
digitalWrite(LED0, HIGH);
@@ -55,7 +55,7 @@ void setLED(char data)
}
}
-void execByMode(char mode)
+void modeExec(char mode)
{
switch (mode) {
case 1:
@@ -94,7 +94,7 @@ void setup()
ledcWrite(BUZZER, 0);
g_mode = 1;
- setLED(g_mode);
+ ledSet(g_mode);
}
void loop()
@@ -112,7 +112,7 @@ void loop()
delay(30);
ledcWrite(BUZZER, 0);
}
- setLED(g_mode);
+ ledSet(g_mode);
}
if (digitalRead(SW_L) == 0) {
ledcWriteTone(BUZZER, INC_FREQ);
@@ -121,7 +121,7 @@ void loop()
delay(80);
ledcWrite(BUZZER, 0);
delay(300);
- execByMode(g_mode);
+ modeExec(g_mode);
}
while (!(digitalRead(SW_L) & digitalRead(SW_R))) {
continue;
diff --git a/pico_v2_STEP5_Straight/pico_v2_STEP5_Straight.ino b/pico_v2_STEP5_Straight/pico_v2_STEP5_Straight.ino
index a88017f..764ca61 100644
--- a/pico_v2_STEP5_Straight/pico_v2_STEP5_Straight.ino
+++ b/pico_v2_STEP5_Straight/pico_v2_STEP5_Straight.ino
@@ -12,6 +12,8 @@
// See the License for the specific language governing permissions and
// limitations under the License.
+#include "run.h"
+
#define LED0 42
#define LED1 41
#define LED2 15
@@ -37,16 +39,11 @@ hw_timer_t * g_timer3 = NULL;
portMUX_TYPE g_timer_mux = portMUX_INITIALIZER_UNLOCKED;
+volatile bool g_motor_move = 0;
+volatile unsigned int g_step_r, g_step_l;
unsigned short g_step_hz_r = MIN_HZ;
unsigned short g_step_hz_l = MIN_HZ;
-volatile unsigned int g_step_r, g_step_l;
-double g_max_speed;
-double g_min_speed;
-double g_accel = 0.0;
-volatile double g_speed = MIN_SPEED;
-
-volatile bool g_motor_move = 0;
//割り込み
//目標値の更新周期1kHz
@@ -97,8 +94,8 @@ void setup()
pinMode(LED2, OUTPUT);
pinMode(LED3, OUTPUT);
- pinMode(SW_L, INPUT);
- pinMode(SW_R, INPUT);
+ pinMode(SW_L, INPUT_PULLUP);
+ pinMode(SW_R, INPUT_PULLUP);
//motor disable
pinMode(MOTOR_EN, OUTPUT);
@@ -138,12 +135,12 @@ void loop()
digitalWrite(MOTOR_EN, HIGH);
delay(1000);
digitalWrite(LED0, HIGH);
- accelerate(45, 200);
+ g_run.accelerate(45, 200);
digitalWrite(LED1, HIGH);
digitalWrite(LED2, HIGH);
- oneStep(90, 200);
+ g_run.oneStep(90, 200);
digitalWrite(LED3, HIGH);
- decelerate(45, 200);
+ g_run.decelerate(45, 200);
digitalWrite(LED0, LOW);
digitalWrite(LED1, LOW);
digitalWrite(LED2, LOW);
diff --git a/pico_v2_STEP5_Straight/run.h b/pico_v2_STEP5_Straight/run.h
new file mode 100644
index 0000000..922c1b2
--- /dev/null
+++ b/pico_v2_STEP5_Straight/run.h
@@ -0,0 +1,50 @@
+// Copyright 2023 RT Corporation
+//
+// Licensed under the Apache License, Version 2.0 (the "License");
+// you may not use this file except in compliance with the License.
+// You may obtain a copy of the License at
+//
+// http://www.apache.org/licenses/LICENSE-2.0
+//
+// Unless required by applicable law or agreed to in writing, software
+// distributed under the License is distributed on an "AS IS" BASIS,
+// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+// See the License for the specific language governing permissions and
+// limitations under the License.
+
+#ifndef SRC_RUN_H_
+#define SRC_RUN_H_
+
+typedef enum {
+ MOT_FORWARD = 1,
+ MOT_BACK = 2
+} t_CW_CCW;
+
+class RUN
+{
+private:
+public:
+ volatile double accel;
+ volatile double speed;
+ volatile double max_speed;
+ volatile double min_speed;
+
+
+ RUN();
+ void interrupt(void);
+ void counterClear(void);
+ void dirSet(t_CW_CCW dir_left, t_CW_CCW dir_right);
+ void speedSet(double l_speed, double r_speed);
+ void stepGet(void);
+ void stop(void);
+ void accelerate(int len, int finish_speed);
+ void oneStep(int len, int init_speed);
+ void decelerate(int len, int init_speed);
+
+private:
+ int step_lr_len, step_lr;
+};
+
+extern RUN g_run;
+
+#endif /* SRC_RUN_H_ */
\ No newline at end of file
diff --git a/pico_v2_STEP5_Straight/run.ino b/pico_v2_STEP5_Straight/run.ino
index 91fff47..c28fd19 100644
--- a/pico_v2_STEP5_Straight/run.ino
+++ b/pico_v2_STEP5_Straight/run.ino
@@ -12,64 +12,132 @@
// See the License for the specific language governing permissions and
// limitations under the License.
-void accelerate(int len, int tar_speed)
+RUN g_run;
+
+RUN::RUN()
+{
+ speed = 0.0;
+ accel = 0.0;
+}
+
+//割り込み
+void controlInterrupt(void) { g_run.interrupt(); }
+
+void RUN::interrupt(void)
+{ //割り込み内からコール
+ speed += accel;
+
+ if (speed > max_speed) {
+ speed = max_speed;
+ }
+ if (speed < min_speed) {
+ speed = min_speed;
+ }
+
+ speedSet(speed, speed);
+}
+
+
+void RUN::dirSet(t_CW_CCW dir_left, t_CW_CCW dir_right)
+{
+ if (dir_left == MOT_FORWARD) {
+ digitalWrite(CW_L, LOW);
+ } else {
+ digitalWrite(CW_L, HIGH);
+ }
+ if (dir_right == MOT_FORWARD) {
+ digitalWrite(CW_R, HIGH);
+ } else {
+ digitalWrite(CW_R, LOW);
+ }
+}
+
+void RUN::counterClear(void) { g_step_r = g_step_l = 0; }
+
+void RUN::speedSet(double l_speed, double r_speed)
+{
+ g_step_hz_l = (int)(l_speed / PULSE);
+ g_step_hz_r = (int)(r_speed / PULSE);
+}
+
+void RUN::stepGet(void)
+{
+ step_lr = g_step_r + g_step_l;
+ step_lr_len = (int)((float)step_lr / 2.0 * PULSE);
+}
+
+void RUN::stop(void) { g_motor_move = 0; }
+
+void RUN::accelerate(int len, int finish_speed)
{
int obj_step;
- g_max_speed = tar_speed;
- g_accel = 1.5;
- g_step_r = g_step_l = 0;
- g_speed = g_min_speed = MIN_SPEED;
- g_step_hz_r = g_step_hz_l = (unsigned short)(g_speed / PULSE);
+ accel = 1.5;
+ speed = min_speed = MIN_SPEED;
+ max_speed = finish_speed;
+ counterClear();
+ speedSet(speed, speed);
+ dirSet(MOT_FORWARD, MOT_FORWARD);
obj_step = (int)((float)len * 2.0 / PULSE);
- digitalWrite(CW_R, HIGH);
- digitalWrite(CW_L, LOW);
g_motor_move = 1;
- while ((g_step_r + g_step_l) < obj_step) {
- continue;
+ while (1) {
+ stepGet();
+ if (step_lr > obj_step) {
+ break;
+ }
}
}
-void oneStep(int len, int tar_speed)
+void RUN::oneStep(int len, int init_speed)
{
int obj_step;
- g_max_speed = tar_speed;
- g_accel = 0.0;
- g_step_r = g_step_l = 0;
- g_speed = g_min_speed = tar_speed;
- g_step_hz_r = g_step_hz_l = (unsigned short)(g_speed / PULSE);
+
+ accel = 0.0;
+ max_speed = init_speed;
+ speed = min_speed = init_speed;
+ counterClear();
+ speedSet(init_speed, init_speed);
+ dirSet(MOT_FORWARD, MOT_FORWARD);
obj_step = (int)((float)len * 2.0 / PULSE);
- digitalWrite(CW_R, HIGH);
- digitalWrite(CW_L, LOW);
- while ((g_step_r + g_step_l) < obj_step) {
- continue;
+ while (1) {
+ stepGet();
+ if (step_lr > obj_step) {
+ break;
+ }
}
}
-void decelerate(int len, int tar_speed)
+void RUN::decelerate(int len, int init_speed)
{
int obj_step;
- g_max_speed = tar_speed;
- g_accel = 0.0;
- g_step_r = g_step_l = 0;
- g_speed = g_min_speed = tar_speed;
- g_step_hz_r = g_step_hz_l = (unsigned short)(g_speed / PULSE);
+
+ accel = 1.5;
+ max_speed = init_speed;
+ speed = min_speed = init_speed;
+ counterClear();
+ speedSet(init_speed, init_speed);
+ dirSet(MOT_FORWARD, MOT_FORWARD);
obj_step = (int)((float)len * 2.0 / PULSE);
- digitalWrite(CW_R, HIGH);
- digitalWrite(CW_L, LOW);
- while ((len - (g_step_r + g_step_l) / 2.0 * PULSE) >
- (((g_speed * g_speed) - (MIN_SPEED * MIN_SPEED)) / (2.0 * 1000.0 * 1.5))) {
- continue;
+ while (1) {
+ stepGet();
+ if (
+ (len - step_lr_len) <
+ (int)(((speed * speed) - (MIN_SPEED * MIN_SPEED)) / (2.0 * 1000.0 * accel))) {
+ break;
+ }
}
- g_accel = -1.5;
- g_min_speed = MIN_SPEED;
+ accel = -1.5;
+ min_speed = MIN_SPEED;
- while ((g_step_r + g_step_l) < obj_step) {
- continue;
+ while (1) {
+ stepGet();
+ if (step_lr > obj_step) {
+ break;
+ }
}
- g_motor_move = 0;
+ stop();
}
\ No newline at end of file
diff --git a/pico_v2_STEP6_rotate/pico_v2_STEP6_rotate.ino b/pico_v2_STEP6_rotate/pico_v2_STEP6_rotate.ino
index ec50ea3..e6ce33c 100644
--- a/pico_v2_STEP6_rotate/pico_v2_STEP6_rotate.ino
+++ b/pico_v2_STEP6_rotate/pico_v2_STEP6_rotate.ino
@@ -12,6 +12,8 @@
// See the License for the specific language governing permissions and
// limitations under the License.
+#include "run.h"
+
#define LED0 42
#define LED1 41
#define LED2 15
@@ -32,31 +34,17 @@
#define MIN_SPEED (MIN_HZ * PULSE)
#define TREAD_WIDTH (31.5)
-typedef enum {
- front,
- right,
- rear,
- left,
- unknown,
-} t_local_dir;
-
hw_timer_t * g_timer0 = NULL;
hw_timer_t * g_timer2 = NULL;
hw_timer_t * g_timer3 = NULL;
portMUX_TYPE g_timer_mux = portMUX_INITIALIZER_UNLOCKED;
+volatile bool g_motor_move = 0;
+volatile unsigned int g_step_r, g_step_l;
unsigned short g_step_hz_r = MIN_HZ;
unsigned short g_step_hz_l = MIN_HZ;
-volatile unsigned int g_step_r, g_step_l;
-double g_max_speed;
-double g_min_speed;
-double g_accel = 0.0;
-volatile double g_speed = MIN_SPEED;
-
-volatile bool g_motor_move = 0;
-
//割り込み
//目標値の更新周期1kHz
void IRAM_ATTR onTimer0(void)
@@ -106,8 +94,8 @@ void setup()
pinMode(LED2, OUTPUT);
pinMode(LED3, OUTPUT);
- pinMode(SW_L, INPUT);
- pinMode(SW_R, INPUT);
+ pinMode(SW_L, INPUT_PULLUP);
+ pinMode(SW_R, INPUT_PULLUP);
//motor disable
pinMode(MOTOR_EN, OUTPUT);
@@ -146,13 +134,13 @@ void loop()
}
digitalWrite(MOTOR_EN, HIGH);
delay(1000);
- rotate(right, 1);
+ g_run.rotate(right, 1);
delay(1000);
- rotate(left, 1);
+ g_run.rotate(left, 1);
delay(1000);
- rotate(right, 2);
+ g_run.rotate(right, 2);
delay(1000);
- rotate(left, 2);
+ g_run.rotate(left, 2);
delay(1000);
digitalWrite(MOTOR_EN, LOW);
}
\ No newline at end of file
diff --git a/pico_v2_STEP6_rotate/run.h b/pico_v2_STEP6_rotate/run.h
new file mode 100644
index 0000000..6b28f76
--- /dev/null
+++ b/pico_v2_STEP6_rotate/run.h
@@ -0,0 +1,52 @@
+// Copyright 2023 RT Corporation
+//
+// Licensed under the Apache License, Version 2.0 (the "License");
+// you may not use this file except in compliance with the License.
+// You may obtain a copy of the License at
+//
+// http://www.apache.org/licenses/LICENSE-2.0
+//
+// Unless required by applicable law or agreed to in writing, software
+// distributed under the License is distributed on an "AS IS" BASIS,
+// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+// See the License for the specific language governing permissions and
+// limitations under the License.
+
+#ifndef SRC_RUN_H_
+#define SRC_RUN_H_
+
+typedef enum { front, right, left, rear } t_local_direction;
+
+typedef enum {
+ MOT_FORWARD = 1,
+ MOT_BACK = 2
+} t_CW_CCW;
+
+class RUN
+{
+private:
+public:
+ volatile double accel;
+ volatile double speed;
+ volatile double max_speed;
+ volatile double min_speed;
+
+ RUN();
+ void interrupt(void);
+ void counterClear(void);
+ void dirSet(t_CW_CCW dir_left, t_CW_CCW dir_right);
+ void speedSet(double l_speed, double r_speed);
+ void stepGet(void);
+ void stop(void);
+ void accelerate(int len, int finish_speed);
+ void oneStep(int len, int init_speed);
+ void decelerate(int len, int init_speed);
+ void rotate(t_local_direction dir, int times);
+
+private:
+ int step_lr_len, step_lr;
+};
+
+extern RUN g_run;
+
+#endif /* SRC_RUN_H_ */
\ No newline at end of file
diff --git a/pico_v2_STEP6_rotate/run.ino b/pico_v2_STEP6_rotate/run.ino
index 0daec8d..37a6259 100644
--- a/pico_v2_STEP6_rotate/run.ino
+++ b/pico_v2_STEP6_rotate/run.ino
@@ -12,104 +12,177 @@
// See the License for the specific language governing permissions and
// limitations under the License.
-void accelerate(int len, int tar_speed)
+RUN g_run;
+
+RUN::RUN()
+{
+ speed = 0.0;
+ accel = 0.0;
+}
+
+//割り込み
+void controlInterrupt(void) { g_run.interrupt(); }
+
+void RUN::interrupt(void)
+{ //割り込み内からコール
+ speed += accel;
+
+ if (speed > max_speed) {
+ speed = max_speed;
+ }
+ if (speed < min_speed) {
+ speed = min_speed;
+ }
+
+ speedSet(speed, speed);
+}
+
+void RUN::dirSet(t_CW_CCW dir_left, t_CW_CCW dir_right)
+{
+ if (dir_left == MOT_FORWARD) {
+ digitalWrite(CW_L, LOW);
+ } else {
+ digitalWrite(CW_L, HIGH);
+ }
+ if (dir_right == MOT_FORWARD) {
+ digitalWrite(CW_R, HIGH);
+ } else {
+ digitalWrite(CW_R, LOW);
+ }
+}
+
+void RUN::counterClear(void) { g_step_r = g_step_l = 0; }
+
+void RUN::speedSet(double l_speed, double r_speed)
+{
+ g_step_hz_l = (int)(l_speed / PULSE);
+ g_step_hz_r = (int)(r_speed / PULSE);
+}
+
+void RUN::stepGet(void)
+{
+ step_lr = g_step_r + g_step_l;
+ step_lr_len = (int)((float)step_lr / 2.0 * PULSE);
+}
+
+void RUN::stop(void) { g_motor_move = 0; }
+
+void RUN::accelerate(int len, int finish_speed)
{
int obj_step;
- g_max_speed = tar_speed;
- g_accel = 1.5;
- g_step_r = g_step_l = 0;
- g_speed = g_min_speed = MIN_SPEED;
- g_step_hz_r = g_step_hz_l = (unsigned short)(g_speed / PULSE);
+ accel = 1.5;
+ speed = min_speed = MIN_SPEED;
+ max_speed = finish_speed;
+ counterClear();
+ speedSet(speed, speed);
+ dirSet(MOT_FORWARD, MOT_FORWARD);
obj_step = (int)((float)len * 2.0 / PULSE);
- digitalWrite(CW_R, HIGH);
- digitalWrite(CW_L, LOW);
g_motor_move = 1;
- while ((g_step_r + g_step_l) < obj_step) {
- continue;
+ while (1) {
+ stepGet();
+ if (step_lr > obj_step) {
+ break;
+ }
}
}
-void oneStep(int len, int tar_speed)
+void RUN::oneStep(int len, int init_speed)
{
int obj_step;
- g_max_speed = tar_speed;
- g_accel = 0.0;
- g_step_r = g_step_l = 0;
- g_speed = g_min_speed = tar_speed;
- g_step_hz_r = g_step_hz_l = (unsigned short)(g_speed / PULSE);
+
+ accel = 0.0;
+ max_speed = init_speed;
+ speed = min_speed = init_speed;
+ counterClear();
+ speedSet(init_speed, init_speed);
+ dirSet(MOT_FORWARD, MOT_FORWARD);
obj_step = (int)((float)len * 2.0 / PULSE);
- digitalWrite(CW_R, HIGH);
- digitalWrite(CW_L, LOW);
- while ((g_step_r + g_step_l) < obj_step) {
- continue;
+ while (1) {
+ stepGet();
+ if (step_lr > obj_step) {
+ break;
+ }
}
}
-void decelerate(int len, int tar_speed)
+void RUN::decelerate(int len, int init_speed)
{
int obj_step;
- g_max_speed = tar_speed;
- g_accel = 0.0;
- g_step_r = g_step_l = 0;
- g_speed = g_min_speed = tar_speed;
- g_step_hz_r = g_step_hz_l = (unsigned short)(g_speed / PULSE);
+
+ accel = 1.5;
+ max_speed = init_speed;
+ speed = min_speed = init_speed;
+ counterClear();
+ speedSet(init_speed, init_speed);
+ dirSet(MOT_FORWARD, MOT_FORWARD);
obj_step = (int)((float)len * 2.0 / PULSE);
- digitalWrite(CW_R, HIGH);
- digitalWrite(CW_L, LOW);
- while ((len - (g_step_r + g_step_l) / 2.0 * PULSE) >
- (((g_speed * g_speed) - (MIN_SPEED * MIN_SPEED)) / (2.0 * 1000.0 * 1.5))) {
- continue;
+ while (1) {
+ stepGet();
+ if (
+ (len - step_lr_len) <
+ (int)(((speed * speed) - (MIN_SPEED * MIN_SPEED)) / (2.0 * 1000.0 * accel))) {
+ break;
+ }
}
- g_accel = -1.5;
- g_min_speed = MIN_SPEED;
+ accel = -1.5;
+ min_speed = MIN_SPEED;
- while ((g_step_r + g_step_l) < obj_step) {
- continue;
+ while (1) {
+ stepGet();
+ if (step_lr > obj_step) {
+ break;
+ }
}
- g_motor_move = 0;
+ stop();
}
-void rotate(t_local_dir dir, int times)
+void RUN::rotate(t_local_direction dir, int times)
{
int obj_step;
- g_max_speed = 200.0;
- g_accel = 0.3;
- g_step_r = g_step_l = 0;
- g_speed = g_min_speed = MIN_SPEED;
- g_step_hz_r = g_step_hz_l = (unsigned short)(g_speed / PULSE);
+
+ accel = 0.3;
+ max_speed = 200.0;
+ speed = min_speed = MIN_SPEED;
+ counterClear();
+ speedSet(MIN_SPEED, MIN_SPEED);
obj_step = (int)(TREAD_WIDTH * PI / 4.0 * (float)times * 2.0 / PULSE);
switch (dir) {
case right:
- digitalWrite(CW_R, LOW);
- digitalWrite(CW_L, LOW);
+ dirSet(MOT_FORWARD, MOT_BACK);
g_motor_move = 1;
break;
case left:
- digitalWrite(CW_R, HIGH);
- digitalWrite(CW_L, HIGH);
+ dirSet(MOT_BACK, MOT_FORWARD);
g_motor_move = 1;
break;
default:
+ dirSet(MOT_FORWARD, MOT_FORWARD);
g_motor_move = 0;
break;
}
- while (((obj_step - (g_step_r + g_step_l)) * PULSE) >
- (((g_speed * g_speed) - (MIN_SPEED * MIN_SPEED)) / (2.0 * 1000.0 * 0.3))) {
- continue;
+ while (1) {
+ stepGet();
+ if (
+ (int)((float)obj_step / 2.0f * PULSE - step_lr_len) <
+ (int)(((speed * speed) - (MIN_SPEED * MIN_SPEED)) / (2.0 * 1000.0 * accel))) {
+ break;
+ }
}
- g_accel = -0.3;
- g_min_speed = MIN_SPEED;
+ accel = -0.3;
+ min_speed = MIN_SPEED;
- while ((g_step_r + g_step_l) < obj_step) {
- continue;
+ while (1) {
+ stepGet();
+ if (step_lr > obj_step) {
+ break;
+ }
}
-
- g_motor_move = 0;
+ stop();
}
diff --git a/pico_v2_STEP7_P_control/interrupt.ino b/pico_v2_STEP7_P_control/interrupt.ino
deleted file mode 100644
index ccb3d8a..0000000
--- a/pico_v2_STEP7_P_control/interrupt.ino
+++ /dev/null
@@ -1,121 +0,0 @@
-// Copyright 2023 RT Corporation
-//
-// Licensed under the Apache License, Version 2.0 (the "License");
-// you may not use this file except in compliance with the License.
-// You may obtain a copy of the License at
-//
-// http://www.apache.org/licenses/LICENSE-2.0
-//
-// Unless required by applicable law or agreed to in writing, software
-// distributed under the License is distributed on an "AS IS" BASIS,
-// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
-// See the License for the specific language governing permissions and
-// limitations under the License.
-
-void controlInterrupt(void)
-{
- double spd_r, spd_l;
-
- g_speed += g_accel;
-
- if (g_speed > g_max_speed) {
- g_speed = g_max_speed;
- }
- if (g_speed < g_min_speed) {
- g_speed = g_min_speed;
- }
-
- if ((g_sen_r.is_control == true) && (g_sen_l.is_control == true)) {
- g_con_wall.error = g_sen_r.error - g_sen_l.error;
- } else {
- g_con_wall.error = 2.0 * (g_sen_r.error - g_sen_l.error);
- }
-
- g_con_wall.control = 0.001 * g_speed * g_con_wall.kp * g_con_wall.error;
-
- spd_r = g_speed + g_con_wall.control;
- spd_l = g_speed - g_con_wall.control;
-
- if (spd_r < g_min_speed) {
- spd_r = g_min_speed;
- }
- if (spd_l < g_min_speed) {
- spd_l = g_min_speed;
- }
-
- g_step_hz_r = (unsigned short)(spd_r / PULSE);
- g_step_hz_l = (unsigned short)(spd_l / PULSE);
-}
-
-void sensorInterrupt(void)
-{
- static char cnt = 0;
- short temp_r, temp_l;
-
- switch (cnt) {
- case 0:
- temp_r = analogRead(AD4);
- temp_l = analogRead(AD1);
-
- digitalWrite(SLED_F, HIGH);
- for (int i = 0; i < 10; i++) {
- asm("nop \n");
- }
- g_sen_fr.value = analogRead(AD4) - temp_r;
- g_sen_fl.value = analogRead(AD1) - temp_l;
- digitalWrite(SLED_F, LOW);
- if (g_sen_fr.value > g_sen_fr.th_wall) {
- g_sen_fr.is_wall = true;
- } else {
- g_sen_fr.is_wall = false;
- }
- if (g_sen_fl.value > g_sen_fl.th_wall) {
- g_sen_fl.is_wall = true;
- } else {
- g_sen_fl.is_wall = false;
- }
- break;
- case 1:
- temp_r = analogRead(AD3);
- temp_l = analogRead(AD2);
-
- digitalWrite(SLED_S, HIGH);
- for (int i = 0; i < 10; i++) {
- asm("nop \n");
- }
- g_sen_r.value = analogRead(AD3) - temp_r;
- g_sen_l.value = analogRead(AD2) - temp_l;
- digitalWrite(SLED_S, LOW);
- if (g_sen_r.value > g_sen_r.th_wall) {
- g_sen_r.is_wall = true;
- } else {
- g_sen_r.is_wall = false;
- }
- if (g_sen_r.value > g_sen_r.th_control) {
- g_sen_r.error = g_sen_r.value - g_sen_r.ref;
- g_sen_r.is_control = true;
- } else {
- g_sen_r.error = 0;
- g_sen_r.is_control = false;
- }
- if (g_sen_l.value > g_sen_l.th_wall) {
- g_sen_l.is_wall = true;
- } else {
- g_sen_l.is_wall = false;
- }
- if (g_sen_l.value > g_sen_l.th_control) {
- g_sen_l.error = g_sen_l.value - g_sen_l.ref;
- g_sen_l.is_control = true;
- } else {
- g_sen_l.error = 0;
- g_sen_l.is_control = false;
- }
- g_battery_value = (double)analogReadMilliVolts(AD0) / 1.0 * (1.0 + 10.0);
- break;
- default:
- Serial.printf("error¥n¥r");
- break;
- }
- cnt++;
- if (cnt == 2) cnt = 0;
-}
\ No newline at end of file
diff --git a/pico_v2_STEP7_P_control/pico_v2_STEP7_P_control.ino b/pico_v2_STEP7_P_control/pico_v2_STEP7_P_control.ino
index f53f6e8..98af44c 100644
--- a/pico_v2_STEP7_P_control/pico_v2_STEP7_P_control.ino
+++ b/pico_v2_STEP7_P_control/pico_v2_STEP7_P_control.ino
@@ -12,6 +12,9 @@
// See the License for the specific language governing permissions and
// limitations under the License.
+#include "run.h"
+#include "sensor.h"
+
#define LED0 42
#define LED1 41
#define LED2 15
@@ -37,7 +40,7 @@
#define MIN_HZ 40
#define TIRE_DIAMETER (24.70)
-#define PULSE (TIRE_DIAMETER * PI / (35.0 / 10.0 * 20.0 * 8.0))
+#define PULSE (TIRE_DIAMETER * PI / (35.0 / 10.0 * 20.0 *8.0))
#define MIN_SPEED (MIN_HZ * PULSE)
//環境に合わせて変更する
@@ -55,32 +58,6 @@
#define CON_WALL_KP (0.5)
//ここまで
-typedef struct
-{
- short value;
- short p_value;
- short error;
- short ref;
- short th_wall;
- short th_control;
- bool is_wall;
- bool is_control;
-} t_sensor;
-
-typedef struct
-{
- double control;
- double error;
- double p_error;
- double diff;
- double sum;
- double sum_max;
- double kp;
- double kd;
- double ki;
- bool enable;
-} t_control;
-
hw_timer_t * g_timer0 = NULL;
hw_timer_t * g_timer1 = NULL;
hw_timer_t * g_timer2 = NULL;
@@ -88,21 +65,11 @@ hw_timer_t * g_timer3 = NULL;
portMUX_TYPE g_timer_mux = portMUX_INITIALIZER_UNLOCKED;
+volatile bool g_motor_move = 0;
+volatile unsigned int g_step_r, g_step_l;
unsigned short g_step_hz_r = MIN_HZ;
unsigned short g_step_hz_l = MIN_HZ;
-t_sensor g_sen_r, g_sen_l, g_sen_fr, g_sen_fl;
-t_control g_con_wall;
-volatile short g_battery_value;
-
-volatile unsigned int g_step_r, g_step_l;
-double g_max_speed;
-double g_min_speed;
-double g_accel = 0.0;
-volatile double g_speed = MIN_SPEED;
-
-volatile bool g_motor_move = 0;
-
//割り込み
//目標値の更新周期1kHz
void IRAM_ATTR onTimer0(void)
@@ -159,8 +126,8 @@ void setup()
pinMode(LED2, OUTPUT);
pinMode(LED3, OUTPUT);
- pinMode(SW_L, INPUT);
- pinMode(SW_R, INPUT);
+ pinMode(SW_L, INPUT_PULLUP);
+ pinMode(SW_R, INPUT_PULLUP);
//motor disable
pinMode(MOTOR_EN, OUTPUT);
@@ -202,19 +169,6 @@ void setup()
timerAlarm(g_timer3, 13333, true, 0); //13333 * 0.5us = 6666us(150Hz)
timerStart(g_timer3);
- g_sen_r.ref = REF_SEN_R;
- g_sen_l.ref = REF_SEN_L;
-
- g_sen_r.th_wall = TH_SEN_R;
- g_sen_l.th_wall = TH_SEN_L;
-
- g_sen_fr.th_wall = TH_SEN_FR;
- g_sen_fl.th_wall = TH_SEN_FL;
-
- g_sen_r.th_control = CONTH_SEN_R;
- g_sen_l.th_control = CONTH_SEN_L;
-
- g_con_wall.kp = CON_WALL_KP;
}
void loop()
@@ -226,19 +180,19 @@ void loop()
if (digitalRead(SW_R) == 0) {
while (1) {
- Serial.printf("r_sen is %d\n\r", g_sen_r.value);
- Serial.printf("fr_sen is %d\n\r", g_sen_fr.value);
- Serial.printf("fl_sen is %d\n\r", g_sen_fl.value);
- Serial.printf("l_sen is %d\n\r", g_sen_l.value);
- Serial.printf("VDD is %d\n\r", g_battery_value);
+ Serial.printf("r_sen is %d\n\r", g_sensor.sen_r.value);
+ Serial.printf("fr_sen is %d\n\r", g_sensor.sen_fr.value);
+ Serial.printf("fl_sen is %d\n\r", g_sensor.sen_fl.value);
+ Serial.printf("l_sen is %d\n\r", g_sensor.sen_l.value);
+ Serial.printf("VDD is %d\n\r", g_sensor.battery_value);
delay(100);
}
}
digitalWrite(MOTOR_EN, HIGH);
delay(1000);
- accelerate(45, 200);
- oneStep(90 * 3, 200);
- decelerate(45, 200);
+ g_run.accelerate(45, 200);
+ g_run.oneStep(90 * 3, 200);
+ g_run.decelerate(45, 200);
delay(1000);
digitalWrite(MOTOR_EN, LOW);
}
\ No newline at end of file
diff --git a/pico_v2_STEP7_P_control/run.h b/pico_v2_STEP7_P_control/run.h
new file mode 100644
index 0000000..9acbd29
--- /dev/null
+++ b/pico_v2_STEP7_P_control/run.h
@@ -0,0 +1,73 @@
+// Copyright 2023 RT Corporation
+//
+// Licensed under the Apache License, Version 2.0 (the "License");
+// you may not use this file except in compliance with the License.
+// You may obtain a copy of the License at
+//
+// http://www.apache.org/licenses/LICENSE-2.0
+//
+// Unless required by applicable law or agreed to in writing, software
+// distributed under the License is distributed on an "AS IS" BASIS,
+// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+// See the License for the specific language governing permissions and
+// limitations under the License.
+
+#ifndef SRC_RUN_H_
+#define SRC_RUN_H_
+
+typedef enum { front, right, left, rear } t_local_direction;
+
+typedef struct
+{
+ double control;
+ double error;
+ double p_error;
+ double diff;
+ double sum;
+ double sum_max;
+ double kp;
+ double fkp;
+ double kd;
+ double ki;
+ bool enable;
+} t_control;
+
+
+typedef enum {
+ MOT_FORWARD = 1, //TMC5240の方向に合わせた数字
+ MOT_BACK = 2
+} t_CW_CCW;
+
+class RUN {
+private:
+
+public:
+ volatile double accel;
+ volatile double speed;
+ volatile double speed_target_r;
+ volatile double speed_target_l;
+ volatile double max_speed;
+ volatile double min_speed;
+
+ t_control con_wall;
+
+ RUN();
+ void interrupt(void);
+ void counterClear(void);
+ void dirSet(t_CW_CCW dir_left, t_CW_CCW dir_right);
+ void speedSet(double l_speed, double r_speed);
+ void stepGet(void);
+ void stop(void);
+ void accelerate(int len, int finish_speed);
+ void oneStep(int len, int init_speed);
+ void decelerate(int len, int init_speed);
+ void rotate(t_local_direction dir, int times);
+
+private:
+ int step_lr_len,step_lr;
+};
+
+
+extern RUN g_run;
+
+#endif /* SRC_RUN_H_ */
\ No newline at end of file
diff --git a/pico_v2_STEP7_P_control/run.ino b/pico_v2_STEP7_P_control/run.ino
index 91fff47..8a1294d 100644
--- a/pico_v2_STEP7_P_control/run.ino
+++ b/pico_v2_STEP7_P_control/run.ino
@@ -12,64 +12,154 @@
// See the License for the specific language governing permissions and
// limitations under the License.
-void accelerate(int len, int tar_speed)
+#include "run.h"
+#include "sensor.h"
+
+RUN g_run;
+
+RUN::RUN()
+{
+ speed = 0.0;
+ accel = 0.0;
+ con_wall.kp = CON_WALL_KP;
+}
+
+//割り込み
+void controlInterrupt(void) { g_run.interrupt(); }
+
+void RUN::interrupt(void)
+{ //割り込み内からコール
+ speed += accel;
+
+ if (speed > max_speed) {
+ speed = max_speed;
+ }
+ if (speed < min_speed) {
+ speed = min_speed;
+ }
+
+ if ((g_sensor.sen_r.is_control == true) && (g_sensor.sen_l.is_control == true)) {
+ con_wall.error = g_sensor.sen_r.error - g_sensor.sen_l.error;
+ } else {
+ con_wall.error = 2.0 * (g_sensor.sen_r.error - g_sensor.sen_l.error);
+ }
+
+ con_wall.control = 0.001 * speed * con_wall.kp * con_wall.error;
+
+ speed_target_r = speed + con_wall.control;
+ speed_target_l = speed - con_wall.control;
+
+ if (speed_target_r < min_speed) {
+ speed_target_r = min_speed;
+ }
+
+ if (speed_target_l < min_speed) {
+ speed_target_l = min_speed;
+ }
+
+ speedSet(speed_target_l, speed_target_r);
+}
+
+void RUN::dirSet(t_CW_CCW dir_left, t_CW_CCW dir_right)
+{
+ if (dir_left == MOT_FORWARD) {
+ digitalWrite(CW_L, LOW);
+ } else {
+ digitalWrite(CW_L, HIGH);
+ }
+ if (dir_right == MOT_FORWARD) {
+ digitalWrite(CW_R, HIGH);
+ } else {
+ digitalWrite(CW_R, LOW);
+ }
+}
+
+void RUN::counterClear(void) { g_step_r = g_step_l = 0; }
+
+void RUN::speedSet(double l_speed, double r_speed)
+{
+ g_step_hz_l = (int)(l_speed / PULSE);
+ g_step_hz_r = (int)(r_speed / PULSE);
+}
+
+void RUN::stepGet(void)
+{
+ step_lr = g_step_r + g_step_l;
+ step_lr_len = (int)((float)step_lr / 2.0 * PULSE);
+}
+
+void RUN::stop(void) { g_motor_move = 0; }
+
+void RUN::accelerate(int len, int finish_speed)
{
int obj_step;
- g_max_speed = tar_speed;
- g_accel = 1.5;
- g_step_r = g_step_l = 0;
- g_speed = g_min_speed = MIN_SPEED;
- g_step_hz_r = g_step_hz_l = (unsigned short)(g_speed / PULSE);
+ accel = 1.5;
+ speed = min_speed = MIN_SPEED;
+ max_speed = finish_speed;
+ counterClear();
+ speedSet(speed, speed);
+ dirSet(MOT_FORWARD, MOT_FORWARD);
obj_step = (int)((float)len * 2.0 / PULSE);
- digitalWrite(CW_R, HIGH);
- digitalWrite(CW_L, LOW);
g_motor_move = 1;
- while ((g_step_r + g_step_l) < obj_step) {
- continue;
+ while (1) {
+ stepGet();
+ if (step_lr > obj_step) {
+ break;
+ }
}
}
-void oneStep(int len, int tar_speed)
+void RUN::oneStep(int len, int init_speed)
{
int obj_step;
- g_max_speed = tar_speed;
- g_accel = 0.0;
- g_step_r = g_step_l = 0;
- g_speed = g_min_speed = tar_speed;
- g_step_hz_r = g_step_hz_l = (unsigned short)(g_speed / PULSE);
+
+ accel = 0.0;
+ max_speed = init_speed;
+ speed = min_speed = init_speed;
+ counterClear();
+ speedSet(init_speed, init_speed);
+ dirSet(MOT_FORWARD, MOT_FORWARD);
obj_step = (int)((float)len * 2.0 / PULSE);
- digitalWrite(CW_R, HIGH);
- digitalWrite(CW_L, LOW);
- while ((g_step_r + g_step_l) < obj_step) {
- continue;
+ while (1) {
+ stepGet();
+ if (step_lr > obj_step) {
+ break;
+ }
}
}
-void decelerate(int len, int tar_speed)
+void RUN::decelerate(int len, int init_speed)
{
int obj_step;
- g_max_speed = tar_speed;
- g_accel = 0.0;
- g_step_r = g_step_l = 0;
- g_speed = g_min_speed = tar_speed;
- g_step_hz_r = g_step_hz_l = (unsigned short)(g_speed / PULSE);
+
+ accel = 1.5;
+ max_speed = init_speed;
+ speed = min_speed = init_speed;
+ counterClear();
+ speedSet(init_speed, init_speed);
+ dirSet(MOT_FORWARD, MOT_FORWARD);
obj_step = (int)((float)len * 2.0 / PULSE);
- digitalWrite(CW_R, HIGH);
- digitalWrite(CW_L, LOW);
- while ((len - (g_step_r + g_step_l) / 2.0 * PULSE) >
- (((g_speed * g_speed) - (MIN_SPEED * MIN_SPEED)) / (2.0 * 1000.0 * 1.5))) {
- continue;
+ while (1) {
+ stepGet();
+ if (
+ (len - step_lr_len) <
+ (int)(((speed * speed) - (MIN_SPEED * MIN_SPEED)) / (2.0 * 1000.0 * accel))) {
+ break;
+ }
}
- g_accel = -1.5;
- g_min_speed = MIN_SPEED;
+ accel = -1.5;
+ min_speed = MIN_SPEED;
- while ((g_step_r + g_step_l) < obj_step) {
- continue;
+ while (1) {
+ stepGet();
+ if (step_lr > obj_step) {
+ break;
+ }
}
- g_motor_move = 0;
+ stop();
}
\ No newline at end of file
diff --git a/pico_v2_STEP7_P_control/sensor.h b/pico_v2_STEP7_P_control/sensor.h
new file mode 100644
index 0000000..1f7723e
--- /dev/null
+++ b/pico_v2_STEP7_P_control/sensor.h
@@ -0,0 +1,42 @@
+// Copyright 2023 RT Corporation
+//
+// Licensed under the Apache License, Version 2.0 (the "License");
+// you may not use this file except in compliance with the License.
+// You may obtain a copy of the License at
+//
+// http://www.apache.org/licenses/LICENSE-2.0
+//
+// Unless required by applicable law or agreed to in writing, software
+// distributed under the License is distributed on an "AS IS" BASIS,
+// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+// See the License for the specific language governing permissions and
+// limitations under the License.
+#ifndef SRC_SENSOR_H_
+#define SRC_SENSOR_H_
+
+#include "run.h"
+
+typedef struct
+{
+ short value;
+ short p_value;
+ short error;
+ short ref;
+ short th_wall;
+ short th_control;
+ bool is_wall;
+ bool is_control;
+} t_sensor;
+
+
+class SENSOR{
+public:
+ SENSOR();
+ volatile t_sensor sen_r, sen_l, sen_fr, sen_fl;
+ volatile short battery_value;
+ void interrupt(void);
+};
+
+extern SENSOR g_sensor;
+
+#endif /* SRC_SENSOR_H_ */
\ No newline at end of file
diff --git a/pico_v2_STEP7_P_control/sensor.ino b/pico_v2_STEP7_P_control/sensor.ino
new file mode 100644
index 0000000..689e4d2
--- /dev/null
+++ b/pico_v2_STEP7_P_control/sensor.ino
@@ -0,0 +1,114 @@
+// Copyright 2023 RT Corporation
+//
+// Licensed under the Apache License, Version 2.0 (the "License");
+// you may not use this file except in compliance with the License.
+// You may obtain a copy of the License at
+//
+// http://www.apache.org/licenses/LICENSE-2.0
+//
+// Unless required by applicable law or agreed to in writing, software
+// distributed under the License is distributed on an "AS IS" BASIS,
+// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+// See the License for the specific language governing permissions and
+// limitations under the License.
+
+
+#include "sensor.h"
+
+SENSOR g_sensor;
+
+
+SENSOR::SENSOR() { //コンストラクタ
+
+ sen_r.ref = REF_SEN_R;
+ sen_l.ref = REF_SEN_L;
+
+ sen_r.th_wall = TH_SEN_R;
+ sen_l.th_wall = TH_SEN_L;
+
+ sen_fr.th_wall = TH_SEN_FR;
+ sen_fl.th_wall = TH_SEN_FL;
+
+ sen_r.th_control = CONTH_SEN_R;
+ sen_l.th_control = CONTH_SEN_L;
+
+
+}
+
+void sensorInterrupt(void) {
+ g_sensor.interrupt();
+}
+
+
+void SENSOR::interrupt(void)
+{
+ static char cnt = 0;
+ short temp_r, temp_l;
+
+ switch (cnt) {
+ case 0:
+ temp_r = analogRead(AD4);
+ temp_l = analogRead(AD1);
+
+ digitalWrite(SLED_F, HIGH);
+ for (int i = 0; i < 10; i++) {
+ asm("nop \n");
+ }
+ sen_fr.value = analogRead(AD4) - temp_r;
+ sen_fl.value = analogRead(AD1) - temp_l;
+ digitalWrite(SLED_F, LOW);
+ if (sen_fr.value > sen_fr.th_wall) {
+ sen_fr.is_wall = true;
+ } else {
+ sen_fr.is_wall = false;
+ }
+ if (sen_fl.value > sen_fl.th_wall) {
+ sen_fl.is_wall = true;
+ } else {
+ sen_fl.is_wall = false;
+ }
+ break;
+ case 1:
+ temp_r = analogRead(AD3);
+ temp_l = analogRead(AD2);
+
+ digitalWrite(SLED_S, HIGH);
+ for (int i = 0; i < 10; i++) {
+ asm("nop \n");
+ }
+ sen_r.value = analogRead(AD3) - temp_r;
+ sen_l.value = analogRead(AD2) - temp_l;
+ digitalWrite(SLED_S, LOW);
+ if (sen_r.value > sen_r.th_wall) {
+ sen_r.is_wall = true;
+ } else {
+ sen_r.is_wall = false;
+ }
+ if (sen_r.value > sen_r.th_control) {
+ sen_r.error = sen_r.value - sen_r.ref;
+ sen_r.is_control = true;
+ } else {
+ sen_r.error = 0;
+ sen_r.is_control = false;
+ }
+ if (sen_l.value > sen_l.th_wall) {
+ sen_l.is_wall = true;
+ } else {
+ sen_l.is_wall = false;
+ }
+ if (sen_l.value > sen_l.th_control) {
+ sen_l.error = sen_l.value - sen_l.ref;
+ sen_l.is_control = true;
+ } else {
+ sen_l.error = 0;
+ sen_l.is_control = false;
+ }
+ battery_value = (double)analogReadMilliVolts(AD0) / 1.0 * (1.0 + 10.0);
+ break;
+ default:
+ Serial.printf("error\n\r");
+ break;
+ }
+ cnt++;
+ if (cnt >= 2) cnt = 0;
+}
diff --git a/pico_v2_STEP8_micromouse/Flash.ino b/pico_v2_STEP8_micromouse/Flash.ino
new file mode 100644
index 0000000..13f5c88
--- /dev/null
+++ b/pico_v2_STEP8_micromouse/Flash.ino
@@ -0,0 +1,352 @@
+// Copyright 2023 RT Corporation
+//
+// Licensed under the Apache License, Version 2.0 (the "License");
+// you may not use this file except in compliance with the License.
+// You may obtain a copy of the License at
+//
+// http://www.apache.org/licenses/LICENSE-2.0
+//
+// Unless required by applicable law or agreed to in writing, software
+// distributed under the License is distributed on an "AS IS" BASIS,
+// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+// See the License for the specific language governing permissions and
+// limitations under the License.
+
+void flashInit(void)
+{
+ String cmd_tmp;
+ String file_tmp;
+ file_tmp = "/parameters.txt";
+
+ Serial.printf("\n\r parameter init ");
+ Serial.println(file_tmp);
+
+ controlInterruptStop();
+ sensorInterruptStop();
+ PWMInterruptStop();
+ delay(100);
+
+ cmd_tmp = "ref_sen_r " + String(REF_SEN_R_INIT) + '\n';
+ writeFile(SPIFFS, file_tmp, cmd_tmp);
+ cmd_tmp = "ref_sen_l " + String(REF_SEN_L_INIT) + '\n';
+ appendFile(SPIFFS, file_tmp, cmd_tmp);
+ cmd_tmp = "th_sen_r " + String(TH_SEN_R_INIT) + '\n';
+ appendFile(SPIFFS, file_tmp, cmd_tmp);
+ cmd_tmp = "th_sen_l " + String(TH_SEN_L_INIT) + '\n';
+ appendFile(SPIFFS, file_tmp, cmd_tmp);
+ cmd_tmp = "th_sen_fr " + String(TH_SEN_FR_INIT) + '\n';
+ appendFile(SPIFFS, file_tmp, cmd_tmp);
+ cmd_tmp = "th_sen_fl " + String(TH_SEN_FL_INIT) + '\n';
+ appendFile(SPIFFS, file_tmp, cmd_tmp);
+ cmd_tmp = "goal_x " + String(GOAL_X_INIT) + '\n';
+ appendFile(SPIFFS, file_tmp, cmd_tmp);
+ cmd_tmp = "goal_y " + String(GOAL_Y_INIT) + '\n';
+ appendFile(SPIFFS, file_tmp, cmd_tmp);
+ cmd_tmp = "tire_d " + String(TIRE_DIAMETER_INIT) + '\n';
+ appendFile(SPIFFS, file_tmp, cmd_tmp);
+ cmd_tmp = "tread_w " + String(TREAD_WIDTH_INIT) + '\n';
+ appendFile(SPIFFS, file_tmp, cmd_tmp);
+ cmd_tmp = "con_kp " + String(CON_WALL_KP_INIT) + '\n';
+ appendFile(SPIFFS, file_tmp, cmd_tmp);
+
+ cmd_tmp = "search_accel " + String(SEARCH_ACCEL_INIT) + '\n';
+ appendFile(SPIFFS, file_tmp, cmd_tmp);
+ cmd_tmp = "turn_accel " + String(TURN_ACCEL_INIT) + '\n';
+ appendFile(SPIFFS, file_tmp, cmd_tmp);
+ cmd_tmp = "search_speed " + String(SEARCH_SPEED_INIT) + '\n';
+ appendFile(SPIFFS, file_tmp, cmd_tmp);
+ cmd_tmp = "max_speed " + String(MAX_SPEED_INIT) + '\n';
+ appendFile(SPIFFS, file_tmp, cmd_tmp);
+
+ PWMInterruptStart();
+ controlInterruptStart();
+ sensorInterruptStart();
+}
+
+void flashBegin(void)
+{
+ controlInterruptStop();
+ sensorInterruptStop();
+ PWMInterruptStop();
+ delay(100);
+
+ Serial.println("begin SPIFFS");
+ if (!SPIFFS.begin(true)) {
+ Serial.println("SPIFFS Mount Failed");
+ delay(100);
+ }
+ Serial.println("end SPIFFS");
+
+ if (switchGet() == SW_LM) {
+ delay(10);
+ flashInit();
+ }
+
+ PWMInterruptStart();
+ controlInterruptStart();
+ sensorInterruptStart();
+}
+
+void mapWrite(void)
+{
+ String file_tmp;
+ unsigned char data_temp;
+ file_tmp = "/map.txt";
+
+ controlInterruptStop();
+ sensorInterruptStop();
+ PWMInterruptStop();
+
+ Serial.printf("\n\r map_data write ");
+ Serial.println(file_tmp);
+
+ File file = SPIFFS.open(file_tmp, FILE_WRITE);
+ if (!file) {
+ Serial.println("- failed to open file for writing");
+ return;
+ }
+ for (int i = 0; i < MAZESIZE_X; i++) {
+ for (int j = 0; j < MAZESIZE_Y; j++) {
+ data_temp = g_map.wallDataGet(i, j, north) + (g_map.wallDataGet(i, j, east) << 2) +
+ (g_map.wallDataGet(i, j, south) << 4) + (g_map.wallDataGet(i, j, west) << 6);
+ if (file.write(data_temp)) { //バイナリ書き込み
+ } else {
+ Serial.println("- write failed");
+ }
+ }
+ }
+
+ file.close();
+ controlInterruptStart();
+ sensorInterruptStart();
+ PWMInterruptStart();
+}
+
+void mapCopy(void)
+{
+ String file_tmp;
+ unsigned char read_data;
+
+ controlInterruptStop();
+ sensorInterruptStop();
+ PWMInterruptStop();
+
+ File file = SPIFFS.open("/map.txt", FILE_READ);
+ if (!file || file.isDirectory()) {
+ Serial.println("- failed to open file for reading");
+ return;
+ }
+ for (int i = 0; i < MAZESIZE_X; i++) {
+ for (int j = 0; j < MAZESIZE_Y; j++) {
+ if (file.available()) {
+ read_data = file.read();
+ g_map.wallDataSet(i, j, north, read_data & 0x03);
+ g_map.wallDataSet(i, j, east, (read_data >> 2) & 0x03);
+ g_map.wallDataSet(i, j, south, (read_data >> 4) & 0x03);
+ g_map.wallDataSet(i, j, west, (read_data >> 6) & 0x03);
+ } else {
+ Serial.println("Read Error");
+ }
+ }
+ }
+ file.close();
+ controlInterruptStart();
+ sensorInterruptStart();
+ PWMInterruptStart();
+}
+
+void paramWrite(void)
+{
+ String cmd_tmp;
+ String file_tmp;
+ char * temp_char;
+
+ //タイマーによる割り込みは禁止にする必要がある。
+ controlInterruptStop();
+ sensorInterruptStop();
+ PWMInterruptStop();
+ delay(10);
+
+ int temp;
+ file_tmp = "/parameters.txt";
+
+ Serial.printf("\n\r parameter write ");
+ Serial.println(file_tmp);
+ cmd_tmp = "ref_sen_r " + String(g_sensor.sen_r.ref) + '\n';
+ writeFile(SPIFFS, file_tmp, cmd_tmp);
+ cmd_tmp = "ref_sen_l " + String(g_sensor.sen_l.ref) + '\n';
+ appendFile(SPIFFS, file_tmp, cmd_tmp);
+ cmd_tmp = "th_sen_r " + String(g_sensor.sen_r.th_wall) + '\n';
+ appendFile(SPIFFS, file_tmp, cmd_tmp);
+ cmd_tmp = "th_sen_l " + String(g_sensor.sen_l.th_wall) + '\n';
+ appendFile(SPIFFS, file_tmp, cmd_tmp);
+ cmd_tmp = "th_sen_fr " + String(g_sensor.sen_fr.th_wall) + '\n';
+ appendFile(SPIFFS, file_tmp, cmd_tmp);
+ cmd_tmp = "th_sen_fl " + String(g_sensor.sen_fl.th_wall) + '\n';
+ appendFile(SPIFFS, file_tmp, cmd_tmp);
+ cmd_tmp = "goal_x " + String((short)g_map.goal_mx) + '\n';
+ appendFile(SPIFFS, file_tmp, cmd_tmp);
+ cmd_tmp = "goal_y " + String((short)g_map.goal_my) + '\n';
+ appendFile(SPIFFS, file_tmp, cmd_tmp);
+ cmd_tmp = "tire_d " + String(g_run.tire_diameter) + '\n';
+ appendFile(SPIFFS, file_tmp, cmd_tmp);
+ cmd_tmp = "tread_w " + String(g_run.tread_width) + '\n';
+ appendFile(SPIFFS, file_tmp, cmd_tmp);
+ cmd_tmp = "con_kp " + String(g_run.con_wall.kp) + '\n';
+ appendFile(SPIFFS, file_tmp, cmd_tmp);
+
+ cmd_tmp = "search_accel " + String(g_run.search_accel) + '\n';
+ appendFile(SPIFFS, file_tmp, cmd_tmp);
+ cmd_tmp = "turn_accel " + String(g_run.turn_accel) + '\n';
+ appendFile(SPIFFS, file_tmp, cmd_tmp);
+ cmd_tmp = "search_speed " + String(g_run.search_speed) + '\n';
+ appendFile(SPIFFS, file_tmp, cmd_tmp);
+ cmd_tmp = "max_speed " + String(g_run.max_speed) + '\n';
+ appendFile(SPIFFS, file_tmp, cmd_tmp);
+
+ controlInterruptStart();
+ sensorInterruptStart();
+ PWMInterruptStart();
+}
+
+void paramRead(void)
+{
+ String cmd_tmp;
+ String file_tmp;
+ int temp;
+
+ String cmds[2] = {"\0"}; // 分割された文字列を格納する配列
+
+ //タイマーによる割り込みは禁止にする必要がある。
+ controlInterruptStop();
+ sensorInterruptStop();
+ PWMInterruptStop();
+ delay(10);
+
+ File file = SPIFFS.open("/parameters.txt");
+ if (!file || file.isDirectory()) {
+ Serial.println("- failed to open file for reading");
+ flashInit();
+ }
+
+ Serial.println("- read from file:");
+ while (file.available()) {
+ int index = split(file.readStringUntil('\n'), ' ', cmds);
+ if (cmds[0].equals("ref_sen_r")) {
+ g_sensor.sen_r.ref = cmds[1].toInt();
+ } else if (cmds[0].equals("ref_sen_l")) {
+ g_sensor.sen_l.ref = cmds[1].toInt();
+ } else if (cmds[0].equals("th_sen_r")) {
+ g_sensor.sen_r.th_wall = cmds[1].toInt();
+ g_sensor.sen_r.th_control = g_sensor.sen_r.th_wall;
+ } else if (cmds[0].equals("th_sen_l")) {
+ g_sensor.sen_l.th_wall = cmds[1].toInt();
+ g_sensor.sen_l.th_control = g_sensor.sen_l.th_wall;
+ } else if (cmds[0].equals("th_sen_fr")) {
+ g_sensor.sen_fr.th_wall = cmds[1].toInt();
+ } else if (cmds[0].equals("th_sen_fl")) {
+ g_sensor.sen_fl.th_wall = cmds[1].toInt();
+ } else if (cmds[0].equals("goal_x")) {
+ g_map.goal_mx = cmds[1].toInt();
+ } else if (cmds[0].equals("goal_y")) {
+ g_map.goal_my = cmds[1].toInt();
+ } else if (cmds[0].equals("tire_d")) {
+ g_run.tire_diameter = cmds[1].toFloat();
+ } else if (cmds[0].equals("tread_w")) {
+ g_run.tread_width = cmds[1].toFloat();
+ } else if (cmds[0].equals("con_kp")) {
+ g_run.con_wall.kp = cmds[1].toFloat();
+
+ } else if (cmds[0].equals("search_accel")) {
+ g_run.search_accel = cmds[1].toFloat();
+ } else if (cmds[0].equals("turn_accel")) {
+ g_run.turn_accel = cmds[1].toFloat();
+ } else if (cmds[0].equals("search_speed")) {
+ g_run.search_speed = cmds[1].toInt();
+ } else if (cmds[0].equals("max_speed")) {
+ g_run.max_speed = cmds[1].toInt();
+
+ } else {
+ Serial.print("parameter cmds Error ");
+ Serial.println(cmds[0]);
+ delay(10);
+ flashInit();
+ break;
+ }
+ g_run.pulse = g_run.tire_diameter * PI / (35.0 / 10.0 * 20.0 *8.0);
+ cmds[0] = {"\0"};
+ cmds[1] = {"\0"};
+ }
+ file.close();
+ controlInterruptStart();
+ sensorInterruptStart();
+ PWMInterruptStart();
+}
+
+int split(String data, char delimiter, String * dst)
+{
+ int index = 0;
+ int arraySize = (sizeof(data) / sizeof((data)[0]));
+ int datalength = data.length();
+ for (int i = 0; i < datalength; i++) {
+ char tmp = data.charAt(i);
+ if (tmp == delimiter) {
+ index++;
+ if (index > (arraySize - 1)) return -1;
+ } else
+ dst[index] += tmp;
+ }
+ return (index + 1);
+}
+
+void readFile(fs::FS & fs, String path)
+{
+ Serial.printf("Reading file: ");
+ Serial.println(path);
+
+ File file = fs.open(path);
+ if (!file || file.isDirectory()) {
+ Serial.println("- failed to open file for reading");
+ return;
+ }
+
+ Serial.println("- read from file:");
+ while (file.available()) {
+ Serial.write(file.read());
+ }
+ file.close();
+}
+
+void writeFile(fs::FS & fs, String path, String message)
+{
+ Serial.printf("Writing file: ");
+ Serial.println(path);
+
+ File file = fs.open(path, FILE_WRITE);
+ if (!file) {
+ Serial.println("- failed to open file for writing");
+ return;
+ }
+ if (file.print(message)) {
+ } else {
+ Serial.println("- frite failed");
+ }
+ file.close();
+}
+
+void appendFile(fs::FS & fs, String path, String message)
+{
+ Serial.printf("Appending to file: ");
+ Serial.println(path);
+
+ File file = fs.open(path, FILE_APPEND);
+ if (!file) {
+ Serial.println("- failed to open file for appending");
+ return;
+ }
+ if (file.print(message)) {
+ } else {
+ Serial.println("- append failed");
+ }
+ file.close();
+}
diff --git a/pico_v2_STEP8_micromouse/SPIFFS.ino b/pico_v2_STEP8_micromouse/SPIFFS.ino
deleted file mode 100644
index 3a8e044..0000000
--- a/pico_v2_STEP8_micromouse/SPIFFS.ino
+++ /dev/null
@@ -1,83 +0,0 @@
-// Copyright 2023 RT Corporation
-//
-// Licensed under the Apache License, Version 2.0 (the "License");
-// you may not use this file except in compliance with the License.
-// You may obtain a copy of the License at
-//
-// http://www.apache.org/licenses/LICENSE-2.0
-//
-// Unless required by applicable law or agreed to in writing, software
-// distributed under the License is distributed on an "AS IS" BASIS,
-// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
-// See the License for the specific language governing permissions and
-// limitations under the License.
-
-void mapWrite(void)
-{
- String file_tmp;
- unsigned char data_temp;
- file_tmp = "/map.txt";
-
- controlInterruptStop();
- sensorInterruptStop();
- PWMInterruptStop();
-
- Serial.printf("\n\r map_data write ");
- Serial.println(file_tmp);
-
- File file = SPIFFS.open(file_tmp, FILE_WRITE);
- if (!file) {
- Serial.println("- failed to open file for writing");
- return;
- }
- for (int i = 0; i < 16; i++) {
- for (int j = 0; j < 16; j++) {
- data_temp = g_map_control.getWallData(i, j, north) +
- (g_map_control.getWallData(i, j, east) << 2) +
- (g_map_control.getWallData(i, j, south) << 4) +
- (g_map_control.getWallData(i, j, west) << 6);
- if (file.write(data_temp)) { //バイナリ書き込み
- } else {
- Serial.println("- write failed");
- }
- }
- }
-
- file.close();
- controlInterruptStart();
- sensorInterruptStart();
- PWMInterruptStart();
-}
-
-void copyMap(void)
-{
- String file_tmp;
- unsigned char read_data;
-
- controlInterruptStop();
- sensorInterruptStop();
- PWMInterruptStop();
-
- File file = SPIFFS.open("/map.txt", FILE_READ);
- if (!file || file.isDirectory()) {
- Serial.println("- failed to open file for reading");
- return;
- }
- for (int i = 0; i < 16; i++) {
- for (int j = 0; j < 16; j++) {
- if (file.available()) {
- read_data = file.read();
- g_map_control.setWallData(i, j, north, read_data & 0x03);
- g_map_control.setWallData(i, j, east, (read_data >> 2) & 0x03);
- g_map_control.setWallData(i, j, south, (read_data >> 4) & 0x03);
- g_map_control.setWallData(i, j, west, (read_data >> 6) & 0x03);
- } else {
- Serial.println("Read Error");
- }
- }
- }
- file.close();
- controlInterruptStart();
- sensorInterruptStart();
- PWMInterruptStart();
-}
diff --git a/pico_v2_STEP8_micromouse/adjust.h b/pico_v2_STEP8_micromouse/adjust.h
new file mode 100644
index 0000000..97167b0
--- /dev/null
+++ b/pico_v2_STEP8_micromouse/adjust.h
@@ -0,0 +1,31 @@
+// Copyright 2023 RT Corporation
+//
+// Licensed under the Apache License, Version 2.0 (the "License");
+// you may not use this file except in compliance with the License.
+// You may obtain a copy of the License at
+//
+// http://www.apache.org/licenses/LICENSE-2.0
+//
+// Unless required by applicable law or agreed to in writing, software
+// distributed under the License is distributed on an "AS IS" BASIS,
+// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+// See the License for the specific language governing permissions and
+// limitations under the License.
+
+#ifndef SRC_ADJUST_H_
+#define SRC_ADJUST_H_
+
+class ADJUST
+{
+public:
+ void menu(void);
+ void mapView(void);
+ void adcView(void);
+ void straightCheck(int section_check);
+ void rotationCheck(void);
+ unsigned char modeExec(unsigned char _mode);
+};
+
+extern ADJUST g_adjust;
+
+#endif /* SRC_ADJUST_H_ */
\ No newline at end of file
diff --git a/pico_v2_STEP8_micromouse/adjust.ino b/pico_v2_STEP8_micromouse/adjust.ino
index 6c00843..ba7caf1 100644
--- a/pico_v2_STEP8_micromouse/adjust.ino
+++ b/pico_v2_STEP8_micromouse/adjust.ino
@@ -12,13 +12,17 @@
// See the License for the specific language governing permissions and
// limitations under the License.
-void mapView(void)
+#include "adjust.h"
+
+ADJUST g_adjust;
+
+void ADJUST::mapView(void)
{
Serial.printf("\x1b[2j");
Serial.printf("\x1b[0;0H");
Serial.printf("\n\r+");
for (int i = 0; i < MAZESIZE_X; i++) {
- switch (g_map_control.getWallData(i, MAZESIZE_Y - 1, north)) { //黒色は"[30m"
+ switch (g_map.wallDataGet(i, MAZESIZE_Y - 1, north)) { //黒色は"[30m"
case NOWALL:
Serial.printf("\x1b[37m +"); //NOWALL
break;
@@ -35,7 +39,7 @@ void mapView(void)
}
Serial.printf("\n\r");
for (int j = (MAZESIZE_Y - 1); j > -1; j--) {
- switch (g_map_control.getWallData(0, j, west)) {
+ switch (g_map.wallDataGet(0, j, west)) {
case NOWALL:
Serial.printf("\x1b[37m "); //NOWALL
break;
@@ -50,7 +54,7 @@ void mapView(void)
break;
}
for (int i = 0; i < MAZESIZE_X; i++) {
- switch (g_map_control.getWallData(i, j, east)) {
+ switch (g_map.wallDataGet(i, j, east)) {
case NOWALL:
Serial.printf("\x1b[37m "); //NOWALL
break;
@@ -67,7 +71,7 @@ void mapView(void)
}
Serial.printf("\n\r+");
for (int i = 0; i < MAZESIZE_X; i++) {
- switch (g_map_control.getWallData(i, j, south)) {
+ switch (g_map.wallDataGet(i, j, south)) {
case NOWALL:
Serial.printf("\x1b[37m +"); //NOWALL
break;
@@ -86,16 +90,16 @@ void mapView(void)
}
}
-void viewAdc(void)
+void ADJUST::adcView(void)
{
- disableMotor();
+ motorDisable();
while (1) {
- Serial.printf("r_sen is\t%d \r\n", g_sen_r.value);
- Serial.printf("fr_sen is\t%d \r\n", g_sen_fr.value);
- Serial.printf("fl_sen is\t%d \r\n", g_sen_fl.value);
- Serial.printf("l_sen is\t%d \r\n", g_sen_l.value);
- Serial.printf("VDD is\t%d mV\r\n", g_battery_value);
+ Serial.printf("r_sen is\t%d \r\n", g_sensor.sen_r.value);
+ Serial.printf("fr_sen is\t%d \r\n", g_sensor.sen_fr.value);
+ Serial.printf("fl_sen is\t%d \r\n", g_sensor.sen_fl.value);
+ Serial.printf("l_sen is\t%d \r\n", g_sensor.sen_l.value);
+ Serial.printf("VDD is\t%d mV\r\n", g_sensor.battery_value);
Serial.printf("\n\r"); //改行
delay(100);
Serial.printf("\x1b[2j");
@@ -103,52 +107,53 @@ void viewAdc(void)
}
}
-void straightCheck(int section_check)
+void ADJUST::straightCheck(int section_check)
{
- enableMotor();
+ motorEnable();
delay(1000);
- accelerate(HALF_SECTION, SEARCH_SPEED);
+ g_run.accelerate(HALF_SECTION, g_run.search_speed);
if (section_check > 1) {
- straight(SECTION * (section_check - 1), SEARCH_SPEED, MAX_SPEED, SEARCH_SPEED);
+ g_run.straight(
+ SECTION * (section_check - 1), g_run.search_speed, g_run.max_speed, g_run.search_speed);
}
- decelerate(HALF_SECTION, SEARCH_SPEED);
+ g_run.decelerate(HALF_SECTION, g_run.search_speed);
- disableMotor();
+ motorDisable();
}
-void rotationCheck(void)
+void ADJUST::rotationCheck(void)
{
- enableMotor();
+ motorEnable();
delay(1000);
for (int i = 0; i < 8; i++) {
- rotate(right, 1);
+ g_run.rotate(right, 1);
}
- disableMotor();
+ motorDisable();
}
-void adjustMenu(void)
+void ADJUST::menu(void)
{
- unsigned char mode = 1;
+ unsigned char l_mode = 1;
char LED3_data;
char sw;
while (1) {
- setLED(mode);
+ ledSet(l_mode);
while (1) {
- sw = getSW();
+ sw = switchGet();
if (sw != 0) break;
delay(33);
LED3_data ^= 1;
- setLED((mode & 0x7) + ((LED3_data << 3) & 0x08));
+ ledSet((l_mode & 0x7) + ((LED3_data << 3) & 0x08));
}
LED3_data = 0;
switch (sw) {
case SW_RM:
- mode = incButton(mode, 7, 1);
+ l_mode = g_misc.buttonInc(l_mode, 7, 1);
break;
case SW_LM:
- okButton();
- if (execByModeAdjust(mode) == 1) {
+ g_misc.buttonOk();
+ if (modeExec(l_mode) == 1) {
return;
}
break;
@@ -158,12 +163,21 @@ void adjustMenu(void)
}
}
-unsigned char execByModeAdjust(unsigned char mode)
+unsigned char ADJUST::modeExec(unsigned char l_mode)
{
- disableMotor();
- switch (mode) {
+ motorDisable();
+ switch (l_mode) {
case 1:
- viewAdc();
+ buzzerEnable(INC_FREQ);
+ delay(30);
+ buzzerDisable();
+ delay(500);
+ buzzerEnable(INC_FREQ);
+ delay(30);
+ buzzerDisable();
+ webServerSetup();
+ //webserverでセンサの値のばらつきが大きすぎて判断できない時は、webServerSetup()をコメントアウトしadcView()のコメントをはずし、シリアルモニタで確認してください。
+ // adcView();
break;
case 2:
straightCheck(9);
@@ -173,7 +187,7 @@ unsigned char execByModeAdjust(unsigned char mode)
rotationCheck();
break;
case 4:
- copyMap();
+ mapCopy();
mapView();
break;
diff --git a/pico_v2_STEP8_micromouse/device.h b/pico_v2_STEP8_micromouse/device.h
index 0e729f9..26aa293 100644
--- a/pico_v2_STEP8_micromouse/device.h
+++ b/pico_v2_STEP8_micromouse/device.h
@@ -1,6 +1,24 @@
+// Copyright 2023 RT Corporation
+//
+// Licensed under the Apache License, Version 2.0 (the "License");
+// you may not use this file except in compliance with the License.
+// You may obtain a copy of the License at
+//
+// http://www.apache.org/licenses/LICENSE-2.0
+//
+// Unless required by applicable law or agreed to in writing, software
+// distributed under the License is distributed on an "AS IS" BASIS,
+// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+// See the License for the specific language governing permissions and
+// limitations under the License.
+
#ifndef DEVICE_H_
#define DEVICE_H_
+#define SW_LM 1
+//#define SW_CM 2
+#define SW_RM 4
+
#define LED0 42
#define LED1 41
#define LED2 15
@@ -15,22 +33,18 @@
#define SLED_F 2
#define SLED_S 1
+#define BUZZER 40
+
#define AD4 5
#define AD3 4
#define AD2 7
#define AD1 6
#define AD0 8
-#define BUZZER 40
-
#define MOTOR_EN 12
#define CW_R 21
#define CW_L 11
#define PWM_R 45
#define PWM_L 46
-#define SW_LM 1
-//#define SW_CM 2
-#define SW_RM 4
-
#endif // DEVICE_H_
\ No newline at end of file
diff --git a/pico_v2_STEP8_micromouse/device.ino b/pico_v2_STEP8_micromouse/device.ino
index 2dbee2b..9744ce7 100644
--- a/pico_v2_STEP8_micromouse/device.ino
+++ b/pico_v2_STEP8_micromouse/device.ino
@@ -17,22 +17,20 @@ hw_timer_t * g_timer1 = NULL;
hw_timer_t * g_timer2 = NULL;
hw_timer_t * g_timer3 = NULL;
-volatile unsigned short g_step_hz_r, g_step_hz_l;
+volatile bool g_motor_move = 0;
volatile unsigned int g_step_r, g_step_l;
+unsigned short g_step_hz_r = 30;
+unsigned short g_step_hz_l = 30;
portMUX_TYPE g_timer_mux = portMUX_INITIALIZER_UNLOCKED;
-void setRStepHz(short data) { g_step_hz_r = data; }
-
-void setLStepHz(short data) { g_step_hz_l = data; }
-
-void clearStepR(void) { g_step_r = 0; }
-
-void clearStepL(void) { g_step_l = 0; }
-
-unsigned int getStepR(void) { return g_step_r; }
-
-unsigned int getStepL(void) { return g_step_l; }
+void stepHzSetR(short data) { g_step_hz_r = data; }
+void stepHzSetL(short data) { g_step_hz_l = data; }
+void stepClearR(void) { g_step_r = 0; }
+void stepClearL(void) { g_step_l = 0; }
+unsigned int stepGetR(void) { return g_step_r; }
+unsigned int stepGetL(void) { return g_step_l; }
+void motorMoveSet(bool data) { g_motor_move = data; }
void IRAM_ATTR onTimer0(void)
{
@@ -97,7 +95,7 @@ void PWMInterruptStop(void)
timerStop(g_timer3);
}
-void initAll(void)
+void deviceInit(void)
{
pinMode(LED0, OUTPUT);
pinMode(LED1, OUTPUT);
@@ -107,8 +105,8 @@ void initAll(void)
pinMode(BLED0, OUTPUT);
pinMode(BLED1, OUTPUT);
- pinMode(SW_L, INPUT);
- pinMode(SW_R, INPUT);
+ pinMode(SW_L, INPUT_PULLUP);
+ pinMode(SW_R, INPUT_PULLUP);
ledcAttach(BUZZER, 440, 10);
ledcWrite(BUZZER, 0);
@@ -129,13 +127,6 @@ void initAll(void)
digitalWrite(PWM_R, LOW);
digitalWrite(PWM_L, LOW);
- if (!SPIFFS.begin(true)) {
- while (1) {
- Serial.println("SPIFFS Mount Failed");
- delay(100);
- }
- }
-
g_timer0 = timerBegin(1000000);
timerAttachInterrupt(g_timer0, &onTimer0);
timerAlarm(g_timer0, 1000, true, 0);
@@ -157,41 +148,17 @@ void initAll(void)
timerStart(g_timer3);
Serial.begin(115200);
-
- g_sen_r.ref = REF_SEN_R;
- g_sen_l.ref = REF_SEN_L;
- g_sen_r.th_wall = TH_SEN_R;
- g_sen_l.th_wall = TH_SEN_L;
-
- g_sen_fr.th_wall = TH_SEN_FR;
- g_sen_fl.th_wall = TH_SEN_FL;
-
- g_sen_r.th_control = CONTROL_TH_SEN_R;
- g_sen_l.th_control = CONTROL_TH_SEN_L;
-
- g_con_wall.kp = CON_WALL_KP;
-
- g_map_control.setGoalX(GOAL_X);
- g_map_control.setGoalY(GOAL_Y);
-
- g_motor_move = false;
- setRStepHz(MIN_SPEED);
- setLStepHz(MIN_SPEED);
-
- enableBuzzer(INC_FREQ);
- delay(80);
- disableBuzzer();
}
//LED
-void setLED(unsigned char data)
+void ledSet(unsigned char data)
{
digitalWrite(LED0, data & 0x01);
digitalWrite(LED1, (data >> 1) & 0x01);
digitalWrite(LED2, (data >> 2) & 0x01);
digitalWrite(LED3, (data >> 3) & 0x01);
}
-void setBLED(char data)
+void bledSet(char data)
{
if (data & 0x01) {
digitalWrite(BLED0, HIGH);
@@ -206,22 +173,14 @@ void setBLED(char data)
}
//Buzzer
-void enableBuzzer(short f) { ledcWriteTone(BUZZER, f); }
-void disableBuzzer(void)
-{
- ledcWrite(BUZZER, 0); //duty 0% Buzzer OFF
-}
+void buzzerEnable(short f) { ledcWriteTone(BUZZER, f); }
+void buzzerDisable(void) { ledcWrite(BUZZER, 0); } //duty 0% Buzzer OFF
//motor
-void enableMotor(void)
-{
- digitalWrite(MOTOR_EN, HIGH); //Power ON
-}
-void disableMotor(void)
-{
- digitalWrite(MOTOR_EN, LOW); //Power OFF
-}
-void moveDir(t_CW_CCW left_CW, t_CW_CCW right_CW)
+void motorEnable(void) { digitalWrite(MOTOR_EN, HIGH); } //Power ON
+void motorDisable(void) { digitalWrite(MOTOR_EN, LOW); } //Power OFF
+
+void motorDirectionSet(t_CW_CCW left_CW, t_CW_CCW right_CW)
{ //左右のモータの回転方向を指示する
if (right_CW == MOT_FORWARD) {
digitalWrite(CW_R, HIGH);
@@ -237,7 +196,7 @@ void moveDir(t_CW_CCW left_CW, t_CW_CCW right_CW)
}
//SWITCH
-unsigned char getSW(void)
+unsigned char switchGet(void)
{
unsigned char ret = 0;
if (digitalRead(SW_R) == LOW) {
@@ -256,7 +215,7 @@ unsigned char getSW(void)
}
//sensor
-void getSensorS(volatile short * r_value, volatile short * l_value)
+void sensorGetS(volatile short * r_value, volatile short * l_value)
{
short temp_r, temp_l;
temp_r = analogRead(AD3);
@@ -270,7 +229,7 @@ void getSensorS(volatile short * r_value, volatile short * l_value)
digitalWrite(SLED_S, LOW);
}
-void getSensorF(volatile short * fr_value, volatile short * fl_value)
+void sensorGetF(volatile short * fr_value, volatile short * fl_value)
{
short temp_r, temp_l;
temp_r = analogRead(AD4);
@@ -284,8 +243,7 @@ void getSensorF(volatile short * fr_value, volatile short * fl_value)
digitalWrite(SLED_F, LOW); //LED消灯
}
-short getBatteryVolt(void)
+short batteryVoltGet(void)
{
- short inputVoltage = (double)analogReadMilliVolts(AD0) / 1.0 * (1.0 + 10.0);
- return inputVoltage;
+ return (short)((double)analogReadMilliVolts(AD0) / 1.0 * (1.0 + 10.0));
}
diff --git a/pico_v2_STEP5_Straight/interrupt.ino b/pico_v2_STEP8_micromouse/fast.h
similarity index 71%
rename from pico_v2_STEP5_Straight/interrupt.ino
rename to pico_v2_STEP8_micromouse/fast.h
index 8d9e922..86d2941 100644
--- a/pico_v2_STEP5_Straight/interrupt.ino
+++ b/pico_v2_STEP8_micromouse/fast.h
@@ -12,16 +12,17 @@
// See the License for the specific language governing permissions and
// limitations under the License.
-void controlInterrupt(void)
+#ifndef SRC_FAST_H_
+#define SRC_FAST_H_
+
+class FAST
{
- g_speed += g_accel;
+public:
+ void run(short gx, short gy);
+
+private:
+};
- if (g_speed > g_max_speed) {
- g_speed = g_max_speed;
- }
- if (g_speed < g_min_speed) {
- g_speed = g_min_speed;
- }
+extern FAST g_fast;
- g_step_hz_l = g_step_hz_r = (unsigned short)(g_speed / PULSE);
-}
\ No newline at end of file
+#endif /* SRC_FAST_H_ */
diff --git a/pico_v2_STEP8_micromouse/fast.ino b/pico_v2_STEP8_micromouse/fast.ino
index ac4ec9e..7a43b5f 100644
--- a/pico_v2_STEP8_micromouse/fast.ino
+++ b/pico_v2_STEP8_micromouse/fast.ino
@@ -12,58 +12,68 @@
// See the License for the specific language governing permissions and
// limitations under the License.
-void fastRun(short gx, short gy)
+#include "fast.h"
+
+FAST g_fast;
+
+void FAST::run(short gx, short gy)
{
- t_direction_glob glob_nextdir;
+ t_global_direction glob_nextdir;
int straight_count = 0;
- t_direction temp_next_dir = g_map_control.getNextDir2(gx, gy, &glob_nextdir);
- switch (temp_next_dir) {
+ switch (g_map.nextDir2Get(gx, gy, &glob_nextdir)) {
case right:
- rotate(right, 1); //右に曲がって
+ g_run.rotate(right, 1); //右に曲がって
break;
case left:
- rotate(left, 1); //左に曲がって
+ g_run.rotate(left, 1); //左に曲がって
break;
case rear:
- rotate(right, 2); //180度に旋回して
+ g_run.rotate(right, 2); //180度に旋回して
break;
default:
break;
}
- accelerate(HALF_SECTION, SEARCH_SPEED);
+ g_run.accelerate(HALF_SECTION, g_run.search_speed);
straight_count = 0;
- g_map_control.setMyPosDir(glob_nextdir);
- g_map_control.axisUpdate();
+ g_map.mypos.dir = glob_nextdir;
+ g_map.axisUpdate();
- while ((g_map_control.getMyPosX() != gx) || (g_map_control.getMyPosY() != gy)) {
- switch (g_map_control.getNextDir2(gx, gy, &glob_nextdir)) {
+ while ((g_map.mypos.x != gx) || (g_map.mypos.y != gy)) {
+ switch (g_map.nextDir2Get(gx, gy, &glob_nextdir)) {
case front:
straight_count++;
break;
case right:
- straight(straight_count * SECTION, SEARCH_SPEED, MAX_SPEED, SEARCH_SPEED);
- straight_count = 0;
- decelerate(HALF_SECTION, SEARCH_SPEED);
- rotate(right, 1);
- accelerate(HALF_SECTION, SEARCH_SPEED);
+ if (straight_count > 0) {
+ g_run.straight(
+ straight_count * SECTION, g_run.search_speed, g_run.max_speed, g_run.search_speed);
+ straight_count = 0;
+ }
+ g_run.decelerate(HALF_SECTION, g_run.search_speed);
+ g_run.rotate(right, 1);
+ g_run.accelerate(HALF_SECTION, g_run.search_speed);
break;
case left:
- straight(straight_count * SECTION, SEARCH_SPEED, MAX_SPEED, SEARCH_SPEED);
- straight_count = 0;
- decelerate(HALF_SECTION, SEARCH_SPEED);
- rotate(left, 1);
- accelerate(HALF_SECTION, SEARCH_SPEED);
+ if (straight_count > 0) {
+ g_run.straight(
+ straight_count * SECTION, g_run.search_speed, g_run.max_speed, g_run.search_speed);
+ straight_count = 0;
+ }
+ g_run.decelerate(HALF_SECTION, g_run.search_speed);
+ g_run.rotate(left, 1);
+ g_run.accelerate(HALF_SECTION, g_run.search_speed);
break;
default:
break;
}
- g_map_control.setMyPosDir(glob_nextdir);
- g_map_control.axisUpdate();
+ g_map.mypos.dir = glob_nextdir;
+ g_map.axisUpdate();
}
if (straight_count > 0) {
- straight(straight_count * SECTION, SEARCH_SPEED, MAX_SPEED, SEARCH_SPEED);
+ g_run.straight(
+ straight_count * SECTION, g_run.search_speed, g_run.max_speed, g_run.search_speed);
}
- decelerate(HALF_SECTION, SEARCH_SPEED);
+ g_run.decelerate(HALF_SECTION, g_run.search_speed);
}
diff --git a/pico_v2_STEP8_micromouse/interrupt.ino b/pico_v2_STEP8_micromouse/interrupt.ino
deleted file mode 100644
index 0482278..0000000
--- a/pico_v2_STEP8_micromouse/interrupt.ino
+++ /dev/null
@@ -1,123 +0,0 @@
-// Copyright 2023 RT Corporation
-//
-// Licensed under the Apache License, Version 2.0 (the "License");
-// you may not use this file except in compliance with the License.
-// You may obtain a copy of the License at
-//
-// http://www.apache.org/licenses/LICENSE-2.0
-//
-// Unless required by applicable law or agreed to in writing, software
-// distributed under the License is distributed on an "AS IS" BASIS,
-// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
-// See the License for the specific language governing permissions and
-// limitations under the License.
-
-void controlInterrupt(void)
-{
- double spd_r, spd_l;
-
- g_speed += g_accel;
-
- if (g_speed > g_max_speed) {
- g_speed = g_max_speed;
- }
- if (g_speed < g_min_speed) {
- g_speed = g_min_speed;
- }
-
- if (g_con_wall.enable == true) {
- g_con_wall.p_error = g_con_wall.error;
- if ((g_sen_r.is_control == true) && (g_sen_l.is_control == true)) {
- g_con_wall.error = g_sen_r.error - g_sen_l.error;
- } else {
- g_con_wall.error = 2.0 * (g_sen_r.error - g_sen_l.error);
- }
- g_con_wall.diff = g_con_wall.error - g_con_wall.p_error;
- g_con_wall.sum += g_con_wall.error;
- if (g_con_wall.sum > g_con_wall.sum_max) {
- g_con_wall.sum = g_con_wall.sum_max;
- } else if (g_con_wall.sum < (-g_con_wall.sum_max)) {
- g_con_wall.sum = -g_con_wall.sum_max;
- }
- g_con_wall.control = 0.001 * g_speed * g_con_wall.kp * g_con_wall.error;
- spd_r = g_speed + g_con_wall.control;
- spd_l = g_speed - g_con_wall.control;
- } else {
- spd_r = g_speed;
- spd_l = g_speed;
- }
- if (spd_r < MIN_SPEED) spd_r = MIN_SPEED;
- if (spd_l < MIN_SPEED) spd_l = MIN_SPEED;
-
- setRStepHz((unsigned short)(spd_r / PULSE));
- setLStepHz((unsigned short)(spd_l / PULSE));
-}
-
-void sensorInterrupt(void)
-{
- static char cnt = 0;
- static char bled_cnt = 0;
-
- switch (cnt) {
- case 0:
- g_sen_r.p_value = g_sen_r.value;
- g_sen_l.p_value = g_sen_l.value;
- getSensorS(&g_sen_r.value, &g_sen_l.value);
- if (g_sen_r.value > g_sen_r.th_wall) {
- g_sen_r.is_wall = true;
- } else {
- g_sen_r.is_wall = false;
- }
- if (g_sen_r.value > g_sen_r.th_control) {
- g_sen_r.error = g_sen_r.value - g_sen_r.ref;
- g_sen_r.is_control = true;
- } else {
- g_sen_r.error = 0;
- g_sen_r.is_control = false;
- }
- if (g_sen_l.value > g_sen_l.th_wall) {
- g_sen_l.is_wall = true;
- } else {
- g_sen_l.is_wall = false;
- }
- if (g_sen_l.value > g_sen_l.th_control) {
- g_sen_l.error = g_sen_l.value - g_sen_l.ref;
- g_sen_l.is_control = true;
- } else {
- g_sen_l.error = 0;
- g_sen_l.is_control = false;
- }
- break;
- case 1:
- g_sen_fr.p_value = g_sen_fr.value;
- g_sen_fl.p_value = g_sen_fl.value;
- getSensorF(&g_sen_fr.value, &g_sen_fl.value);
- if (g_sen_fr.value > g_sen_fr.th_wall) {
- g_sen_fr.is_wall = true;
- } else {
- g_sen_fr.is_wall = false;
- }
- if (g_sen_fl.value > g_sen_fl.th_wall) {
- g_sen_fl.is_wall = true;
- } else {
- g_sen_fl.is_wall = false;
- }
-
- bled_cnt++;
- if (bled_cnt > 10) {
- bled_cnt = 0;
- }
- g_battery_value = getBatteryVolt();
- if (((g_battery_value - BATT_MIN) * 10 / (BATT_MAX - BATT_MIN)) > bled_cnt) {
- setBLED(1);
- } else {
- setBLED(2);
- }
- break;
- default:
- Serial.printf("sensor state error\n\r");
- break;
- }
- cnt++;
- if (cnt == 2) cnt = 0;
-}
\ No newline at end of file
diff --git a/pico_v2_STEP8_micromouse/map_manager.h b/pico_v2_STEP8_micromouse/map_manager.h
index be90754..675f177 100644
--- a/pico_v2_STEP8_micromouse/map_manager.h
+++ b/pico_v2_STEP8_micromouse/map_manager.h
@@ -1,3 +1,17 @@
+// Copyright 2023 RT Corporation
+//
+// Licensed under the Apache License, Version 2.0 (the "License");
+// you may not use this file except in compliance with the License.
+// You may obtain a copy of the License at
+//
+// http://www.apache.org/licenses/LICENSE-2.0
+//
+// Unless required by applicable law or agreed to in writing, software
+// distributed under the License is distributed on an "AS IS" BASIS,
+// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+// See the License for the specific language governing permissions and
+// limitations under the License.
+
#ifndef MAP_MANAGER_H_
#define MAP_MANAGER_H_
@@ -17,15 +31,15 @@ typedef struct
unsigned char north : 2; //北の壁情報 bit1-0
} t_wall; //壁情報を格納する構造体(ビットフィールド)
-typedef enum { front, right, left, rear } t_direction;
+typedef enum { front, right, left, rear, loca_dir_error } t_local_direction;
-typedef enum { north, east, south, west } t_direction_glob;
+typedef enum { north, east, south, west, glob_dir_error } t_global_direction;
typedef struct
{
unsigned char x;
unsigned char y;
- t_direction_glob dir;
+ t_global_direction dir;
} t_position;
class MapManager
@@ -33,31 +47,31 @@ class MapManager
public:
MapManager();
- void positionInit(void);
- void setMyPosDir(t_direction_glob dir);
- short getMyPosX(void);
- short getMyPosY(void);
- char getWallData(unsigned char x, unsigned char y, t_direction_glob dir);
- void setWallData(unsigned char x, unsigned char y, t_direction_glob dir, char data);
- char getGoalX(void);
- char getGoalY(void);
- void setGoalX(short data);
- void setGoalY(short data);
+ t_position mypos;
+ short goal_mx, goal_my;
+
void axisUpdate(void);
- void nextDir(t_direction dir);
- void setWall(bool IS_SEN_FR, bool IS_SEN_R, bool IS_SEN_L);
- t_direction getNextDir(char x, char y, t_direction_glob * dir);
- t_direction getNextDir2(short x, short y, t_direction_glob * dir);
+ void nextDir(t_local_direction dir);
+ t_local_direction nextDirGet(char x, char y, t_global_direction * dir);
+ t_local_direction nextDir2Get(short x, short y, t_global_direction * dir);
+ void positionInit(void);
+ void wallDataSet(unsigned char x, unsigned char y, t_global_direction dir, char data);
+ char wallDataGet(unsigned char x, unsigned char y, t_global_direction dir);
+ void wallSet(bool IS_SEN_FR, bool IS_SEN_R, bool IS_SEN_L);
private:
unsigned short steps_map[MAZESIZE_X][MAZESIZE_Y]; //歩数マップ
t_wall wall[MAZESIZE_X][MAZESIZE_Y]; //壁の情報を格納する構造体配列
- t_position mypos;
- short goal_mx, goal_my;
- void makeSearchMap(int x, int y);
- void makeMap2(int x, int y);
- int getPriority(unsigned char x, unsigned char y, t_direction_glob dir);
+ void stepMapSet(
+ unsigned char posX, unsigned char posY, t_global_direction l_global_dir, int * little,
+ t_global_direction * now_dir, int * priority);
+ t_local_direction nextGdir(t_global_direction * p_global_dir);
+ void searchMapMake(int x, int y);
+ void map2Make(int x, int y);
+ int priorityGet(unsigned char x, unsigned char y, t_global_direction dir);
};
+extern MapManager g_map;
+
#endif // MAP_MANAGER_H_
\ No newline at end of file
diff --git a/pico_v2_STEP8_micromouse/map_manager.ino b/pico_v2_STEP8_micromouse/map_manager.ino
index caa4ef9..a703234 100644
--- a/pico_v2_STEP8_micromouse/map_manager.ino
+++ b/pico_v2_STEP8_micromouse/map_manager.ino
@@ -12,13 +12,17 @@
// See the License for the specific language governing permissions and
// limitations under the License.
+#include "map_manager.h"
+
+MapManager g_map;
+
//コンストラクタ
MapManager::MapManager()
{
for (int i = 0; i < MAZESIZE_X; i++) {
for (int j = 0; j < MAZESIZE_Y; j++) {
wall[i][j].north = wall[i][j].east = wall[i][j].south = wall[i][j].west =
- _UNKNOWN; //迷路の全体がわからない事を設定する
+ _UNKNOWN; //迷路情報を未知で初期化する
}
}
@@ -34,6 +38,13 @@ MapManager::MapManager()
// x,y
wall[0][0].east = wall[1][0].west = WALL; //スタート地点の右の壁を追加する
wall[0][0].north = wall[0][1].south = NOWALL;
+
+ mypos.x = 0;
+ mypos.y = 0;
+ mypos.dir = north;
+
+ goal_mx = 0x07;
+ goal_my = 0x07;
}
void MapManager::positionInit(void)
@@ -42,15 +53,9 @@ void MapManager::positionInit(void)
mypos.dir = north;
}
-void MapManager::setMyPosDir(t_direction_glob dir) { mypos.dir = dir; }
-
-short MapManager::getMyPosX(void) { return mypos.x; }
-
-short MapManager::getMyPosY(void) { return mypos.y; }
-
-char MapManager::getWallData(unsigned char x, unsigned char y, t_direction_glob dir)
+char MapManager::wallDataGet(unsigned char x, unsigned char y, t_global_direction l_global_dir)
{
- switch (dir) {
+ switch (l_global_dir) {
case north:
return wall[x][y].north;
break;
@@ -67,9 +72,10 @@ char MapManager::getWallData(unsigned char x, unsigned char y, t_direction_glob
return 99;
}
-void MapManager::setWallData(unsigned char x, unsigned char y, t_direction_glob dir, char data)
+void MapManager::wallDataSet(
+ unsigned char x, unsigned char y, t_global_direction l_global_dir, char data)
{
- switch (dir) {
+ switch (l_global_dir) {
case north:
wall[x][y].north = data;
break;
@@ -85,14 +91,6 @@ void MapManager::setWallData(unsigned char x, unsigned char y, t_direction_glob
}
}
-char MapManager::getGoalX(void) { return goal_mx; }
-
-char MapManager::getGoalY(void) { return goal_my; }
-
-void MapManager::setGoalX(short data) { goal_mx = data; }
-
-void MapManager::setGoalY(short data) { goal_my = data; }
-
void MapManager::axisUpdate(void)
{
switch (mypos.dir) {
@@ -111,9 +109,9 @@ void MapManager::axisUpdate(void)
}
}
-void MapManager::nextDir(t_direction dir)
+void MapManager::nextDir(t_local_direction l_local_dir)
{
- if (dir == right) {
+ if (l_local_dir == right) {
switch (mypos.dir) {
case north:
mypos.dir = east;
@@ -128,7 +126,7 @@ void MapManager::nextDir(t_direction dir)
mypos.dir = north;
break;
}
- } else if (dir == left) {
+ } else if (l_local_dir == left) {
switch (mypos.dir) {
case north:
mypos.dir = west;
@@ -146,332 +144,225 @@ void MapManager::nextDir(t_direction dir)
}
}
-void MapManager::setWall(bool IS_SEN_FR, bool IS_SEN_R, bool IS_SEN_L) //壁情報を記録
+void MapManager::wallSet(bool IS_SEN_FR, bool IS_SEN_R, bool IS_SEN_L) //壁情報を記録
{
switch (mypos.dir) {
case north:
wall[mypos.x][mypos.y].north = IS_SEN_FR ? WALL : NOWALL;
wall[mypos.x][mypos.y].east = IS_SEN_R ? WALL : NOWALL;
wall[mypos.x][mypos.y].west = IS_SEN_L ? WALL : NOWALL;
- if (mypos.y < 15) wall[mypos.x][mypos.y + 1].south = IS_SEN_FR ? WALL : NOWALL;
- if (mypos.x < 15) wall[mypos.x + 1][mypos.y].west = IS_SEN_R ? WALL : NOWALL;
+ if (mypos.y < (MAZESIZE_X - 1)) wall[mypos.x][mypos.y + 1].south = IS_SEN_FR ? WALL : NOWALL;
+ if (mypos.x < (MAZESIZE_Y - 1)) wall[mypos.x + 1][mypos.y].west = IS_SEN_R ? WALL : NOWALL;
if (mypos.x > 0) wall[mypos.x - 1][mypos.y].east = IS_SEN_L ? WALL : NOWALL;
break;
case east:
wall[mypos.x][mypos.y].east = IS_SEN_FR ? WALL : NOWALL;
wall[mypos.x][mypos.y].south = IS_SEN_R ? WALL : NOWALL;
wall[mypos.x][mypos.y].north = IS_SEN_L ? WALL : NOWALL;
- if (mypos.x < 15) wall[mypos.x + 1][mypos.y].west = IS_SEN_FR ? WALL : NOWALL;
+ if (mypos.x < (MAZESIZE_X - 1)) wall[mypos.x + 1][mypos.y].west = IS_SEN_FR ? WALL : NOWALL;
if (mypos.y > 0) wall[mypos.x][mypos.y - 1].north = IS_SEN_R ? WALL : NOWALL;
- if (mypos.y < 15) wall[mypos.x][mypos.y + 1].south = IS_SEN_L ? WALL : NOWALL;
+ if (mypos.y < (MAZESIZE_Y - 1)) wall[mypos.x][mypos.y + 1].south = IS_SEN_L ? WALL : NOWALL;
break;
case south:
wall[mypos.x][mypos.y].south = IS_SEN_FR ? WALL : NOWALL;
wall[mypos.x][mypos.y].west = IS_SEN_R ? WALL : NOWALL;
wall[mypos.x][mypos.y].east = IS_SEN_L ? WALL : NOWALL;
- if ((mypos.y - 1) > -1) wall[mypos.x][mypos.y - 1].north = IS_SEN_FR ? WALL : NOWALL;
- if ((mypos.x - 1) > -1) wall[mypos.x - 1][mypos.y].east = IS_SEN_R ? WALL : NOWALL;
- if ((mypos.x + 1) < 16) wall[mypos.x + 1][mypos.y].west = IS_SEN_L ? WALL : NOWALL;
+ if (mypos.y > 0) wall[mypos.x][mypos.y - 1].north = IS_SEN_FR ? WALL : NOWALL;
+ if (mypos.x > 0) wall[mypos.x - 1][mypos.y].east = IS_SEN_R ? WALL : NOWALL;
+ if (mypos.x < (MAZESIZE_X - 1)) wall[mypos.x + 1][mypos.y].west = IS_SEN_L ? WALL : NOWALL;
break;
case west:
wall[mypos.x][mypos.y].west = IS_SEN_FR ? WALL : NOWALL;
wall[mypos.x][mypos.y].north = IS_SEN_R ? WALL : NOWALL;
wall[mypos.x][mypos.y].south = IS_SEN_L ? WALL : NOWALL;
- if ((mypos.x - 1) > -1) wall[mypos.x - 1][mypos.y].east = IS_SEN_FR ? WALL : NOWALL;
- if ((mypos.y + 1) < 16) wall[mypos.x][mypos.y + 1].south = IS_SEN_R ? WALL : NOWALL;
- if ((mypos.y - 1) > -1) wall[mypos.x][mypos.y - 1].north = IS_SEN_L ? WALL : NOWALL;
+ if (mypos.x > 0) wall[mypos.x - 1][mypos.y].east = IS_SEN_FR ? WALL : NOWALL;
+ if (mypos.y < (MAZESIZE_Y - 1)) wall[mypos.x][mypos.y + 1].south = IS_SEN_R ? WALL : NOWALL;
+ if (mypos.y > 0) wall[mypos.x][mypos.y - 1].north = IS_SEN_L ? WALL : NOWALL;
+ break;
+ }
+}
+
+void MapManager::stepMapSet(
+ unsigned char posX, unsigned char posY, t_global_direction l_global_dir, int * little,
+ t_global_direction * now_dir, int * priority)
+{
+ int tmp_priority;
+ tmp_priority = priorityGet(posX, posY, l_global_dir);
+ if (steps_map[posX][posY] < *little) {
+ *little = steps_map[posX][posY];
+ *now_dir = l_global_dir;
+ *priority = tmp_priority;
+ } else if (steps_map[posX][posY] == *little) {
+ if (*priority < tmp_priority) {
+ *now_dir = l_global_dir;
+ *priority = tmp_priority;
+ }
+ }
+}
+
+t_local_direction MapManager::nextGdir(t_global_direction * p_global_dir)
+{
+ switch (*p_global_dir) {
+ case north:
+ switch (mypos.dir) {
+ case north:
+ return front;
+ break;
+ case east:
+ return left;
+ break;
+ case south:
+ return rear;
+ break;
+ case west:
+ return right;
+ break;
+ default:
+ return loca_dir_error;
+ break;
+ }
+ break;
+ case east:
+ switch (mypos.dir) {
+ case east:
+ return front;
+ break;
+ case south:
+ return left;
+ break;
+ case west:
+ return rear;
+ break;
+ case north:
+ return right;
+ break;
+ default:
+ return loca_dir_error;
+ break;
+ }
+ break;
+ case south:
+ switch (mypos.dir) {
+ case south:
+ return front;
+ break;
+ case west:
+ return left;
+ break;
+ case north:
+ return rear;
+ break;
+ case east:
+ return right;
+ break;
+ default:
+ return loca_dir_error;
+ break;
+ }
+ break;
+ case west:
+ switch (mypos.dir) {
+ case west:
+ return front;
+ break;
+ case north:
+ return left;
+ break;
+ case east:
+ return rear;
+ break;
+ case south:
+ return right;
+ break;
+ default:
+ return loca_dir_error;
+ break;
+ }
+ break;
+ default:
+ return loca_dir_error;
break;
}
}
-t_direction MapManager::getNextDir(char x, char y, t_direction_glob * dir)
+t_local_direction MapManager::nextDirGet(char x, char y, t_global_direction * p_global_dir)
{
- int little, priority, tmp_priority;
+ int little, priority;
- makeSearchMap(x, y);
+ searchMapMake(x, y);
little = 65535;
priority = 0;
if ((wall[mypos.x][mypos.y].north != WALL) && (mypos.y < (MAZESIZE_Y - 1))) {
- tmp_priority = getPriority(mypos.x, mypos.y + 1, north);
- if (steps_map[mypos.x][mypos.y + 1] < little) {
- little = steps_map[mypos.x][mypos.y + 1];
- *dir = north;
- priority = tmp_priority;
- } else if (steps_map[mypos.x][mypos.y + 1] == little) {
- if (priority < tmp_priority) {
- *dir = north;
- priority = tmp_priority;
- }
- }
+ stepMapSet(mypos.x, mypos.y + 1, north, &little, p_global_dir, &priority);
}
if ((wall[mypos.x][mypos.y].east != WALL) && (mypos.x < (MAZESIZE_X - 1))) {
- tmp_priority = getPriority(mypos.x + 1, mypos.y, east);
- if (steps_map[mypos.x + 1][mypos.y] < little) {
- little = steps_map[mypos.x + 1][mypos.y];
- *dir = east;
- priority = tmp_priority;
- } else if (steps_map[mypos.x + 1][mypos.y] == little) {
- if (priority < tmp_priority) {
- *dir = east;
- priority = tmp_priority;
- }
- }
+ stepMapSet(mypos.x + 1, mypos.y, east, &little, p_global_dir, &priority);
}
if ((wall[mypos.x][mypos.y].south != WALL) && (mypos.y > 0)) {
- tmp_priority = getPriority(mypos.x, mypos.y - 1, south);
- if (steps_map[mypos.x][mypos.y - 1] < little) {
- little = steps_map[mypos.x][mypos.y - 1];
- *dir = south;
- priority = tmp_priority;
- } else if (steps_map[mypos.x][mypos.y - 1] == little) {
- if (priority < tmp_priority) {
- *dir = south;
- priority = tmp_priority;
- }
- }
+ stepMapSet(mypos.x, mypos.y - 1, south, &little, p_global_dir, &priority);
}
if ((wall[mypos.x][mypos.y].west != WALL) && (mypos.x > 0)) {
- tmp_priority = getPriority(mypos.x - 1, mypos.y, west);
- if (steps_map[mypos.x - 1][mypos.y] < little) {
- little = steps_map[mypos.x - 1][mypos.y];
- *dir = west;
- priority = tmp_priority;
- } else if (steps_map[mypos.x - 1][mypos.y] == little) {
- if (priority < tmp_priority) {
- *dir = west;
- priority = tmp_priority;
- }
- }
+ stepMapSet(mypos.x - 1, mypos.y, west, &little, p_global_dir, &priority);
}
if (steps_map[mypos.x][mypos.y] == 65535) {
while (1) {
- setLED(0x0a);
+ ledSet(0x0a);
delay(500);
- setLED(0x05);
+ ledSet(0x05);
delay(500);
}
} else {
- switch (*dir) {
- case north:
- switch (mypos.dir) {
- case north:
- return front;
- break;
- case east:
- return left;
- break;
- case south:
- return rear;
- break;
- case west:
- return right;
- break;
- }
- break;
- case east:
- switch (mypos.dir) {
- case east:
- return front;
- break;
- case south:
- return left;
- break;
- case west:
- return rear;
- break;
- case north:
- return right;
- break;
- }
- break;
- case south:
- switch (mypos.dir) {
- case south:
- return front;
- break;
- case west:
- return left;
- break;
- case north:
- return rear;
- break;
- case east:
- return right;
- break;
- }
- break;
- case west:
- switch (mypos.dir) {
- case west:
- return front;
- break;
- case north:
- return left;
- break;
- case east:
- return rear;
- break;
- case south:
- return right;
- break;
- }
- break;
- }
+ return nextGdir(p_global_dir);
}
return front;
}
-t_direction MapManager::getNextDir2(short x, short y, t_direction_glob * dir)
+t_local_direction MapManager::nextDir2Get(short x, short y, t_global_direction * p_global_dir)
{
- int little, priority, tmp_priority;
+ int little, priority;
- makeMap2(x, y);
+ map2Make(x, y);
little = 65535;
priority = 0;
if ((wall[mypos.x][mypos.y].north == NOWALL) && ((mypos.y + 1) < MAZESIZE_Y)) {
- tmp_priority = getPriority(mypos.x, mypos.y + 1, north);
- if (steps_map[mypos.x][mypos.y + 1] < little) {
- little = steps_map[mypos.x][mypos.y + 1];
- *dir = north;
- priority = tmp_priority;
- } else if (steps_map[mypos.x][mypos.y + 1] == little) {
- if (priority < tmp_priority) {
- *dir = north;
- priority = tmp_priority;
- }
- }
+ stepMapSet(mypos.x, mypos.y + 1, north, &little, p_global_dir, &priority);
}
if ((wall[mypos.x][mypos.y].east == NOWALL) && ((mypos.x + 1) < MAZESIZE_X)) {
- tmp_priority = getPriority(mypos.x + 1, mypos.y, east);
- if (steps_map[mypos.x + 1][mypos.y] < little) {
- little = steps_map[mypos.x + 1][mypos.y];
- *dir = east;
- priority = tmp_priority;
- } else if (steps_map[mypos.x + 1][mypos.y] == little) {
- if (priority < tmp_priority) {
- *dir = east;
- priority = tmp_priority;
- }
- }
+ stepMapSet(mypos.x + 1, mypos.y, east, &little, p_global_dir, &priority);
}
if ((wall[mypos.x][mypos.y].south == NOWALL) && (mypos.y > 0)) {
- tmp_priority = getPriority(mypos.x, mypos.y - 1, south);
- if (steps_map[mypos.x][mypos.y - 1] < little) {
- little = steps_map[mypos.x][mypos.y - 1];
- *dir = south;
- priority = tmp_priority;
- } else if (steps_map[mypos.x][mypos.y - 1] == little) {
- if (priority < tmp_priority) {
- *dir = south;
- priority = tmp_priority;
- }
- }
+ stepMapSet(mypos.x, mypos.y - 1, south, &little, p_global_dir, &priority);
}
if ((wall[mypos.x][mypos.y].west == NOWALL) && (mypos.x > 0)) {
- tmp_priority = getPriority(mypos.x - 1, mypos.y, west);
- if (steps_map[mypos.x - 1][mypos.y] < little) {
- little = steps_map[mypos.x - 1][mypos.y];
- *dir = west;
- priority = tmp_priority;
- } else if (steps_map[mypos.x - 1][mypos.y] == little) {
- if (priority < tmp_priority) {
- *dir = west;
- priority = tmp_priority;
- }
- }
+ stepMapSet(mypos.x - 1, mypos.y, west, &little, p_global_dir, &priority);
}
if (steps_map[mypos.x][mypos.y] == 65535) { //Goalにいけない
while (1) {
- setLED(0x0a);
+ ledSet(0x0a);
delay(500);
- setLED(0x05);
+ ledSet(0x05);
delay(500);
}
} else {
- switch (*dir) {
- case north:
- switch (mypos.dir) {
- case north:
- return front;
- break;
- case east:
- return left;
- break;
- case south:
- return rear;
- break;
- case west:
- return right;
- break;
- }
- break;
- case east:
- switch (mypos.dir) {
- case east:
- return front;
- break;
- case south:
- return left;
- break;
- case west:
- return rear;
- break;
- case north:
- return right;
- break;
- }
- break;
- case south:
- switch (mypos.dir) {
- case south:
- return front;
- break;
- case west:
- return left;
- break;
- case north:
- return rear;
- break;
- case east:
- return right;
- break;
- }
- break;
- case west:
- switch (mypos.dir) {
- case west:
- return front;
- break;
- case north:
- return left;
- break;
- case east:
- return rear;
- break;
- case south:
- return right;
- break;
- }
- break;
- }
+ return nextGdir(p_global_dir);
}
return front;
}
-void MapManager::makeSearchMap(int x, int y)
+void MapManager::searchMapMake(int x, int y)
{
bool change_flag;
@@ -487,47 +378,32 @@ void MapManager::makeSearchMap(int x, int y)
for (int i = 0; i < MAZESIZE_X; i++) {
for (int j = 0; j < MAZESIZE_Y; j++) {
if (steps_map[i][j] == 65535) continue;
- if (j < (MAZESIZE_Y - 1)) {
- if (wall[i][j].north != WALL) {
- if (steps_map[i][j + 1] == 65535) {
- steps_map[i][j + 1] = steps_map[i][j] + 1;
- change_flag = true;
- }
- }
+ if (
+ (j < (MAZESIZE_Y - 1)) && (wall[i][j].north != WALL) && (steps_map[i][j + 1] == 65535)) {
+ steps_map[i][j + 1] = steps_map[i][j] + 1;
+ change_flag = true;
}
- if (i < (MAZESIZE_X - 1)) {
- if (wall[i][j].east != WALL) {
- if (steps_map[i + 1][j] == 65535) {
- steps_map[i + 1][j] = steps_map[i][j] + 1;
- change_flag = true;
- }
- }
+ if ((i < (MAZESIZE_X - 1)) && (wall[i][j].east != WALL) && (steps_map[i + 1][j] == 65535)) {
+ steps_map[i + 1][j] = steps_map[i][j] + 1;
+ change_flag = true;
}
- if (j > 0) {
- if (wall[i][j].south != WALL) {
- if (steps_map[i][j - 1] == 65535) {
- steps_map[i][j - 1] = steps_map[i][j] + 1;
- change_flag = true;
- }
- }
+ if ((j > 0) && (wall[i][j].south != WALL) && (steps_map[i][j - 1] == 65535)) {
+ steps_map[i][j - 1] = steps_map[i][j] + 1;
+ change_flag = true;
}
- if (i > 0) {
- if (wall[i][j].west != WALL) {
- if (steps_map[i - 1][j] == 65535) {
- steps_map[i - 1][j] = steps_map[i][j] + 1;
- change_flag = true;
- }
- }
+ if ((i > 0) && (wall[i][j].west != WALL) && (steps_map[i - 1][j] == 65535)) {
+ steps_map[i - 1][j] = steps_map[i][j] + 1;
+ change_flag = true;
}
}
}
} while (change_flag == true);
}
-void MapManager::makeMap2(int x, int y)
+void MapManager::map2Make(int x, int y)
{
bool change_flag;
@@ -543,47 +419,34 @@ void MapManager::makeMap2(int x, int y)
for (int i = 0; i < MAZESIZE_X; i++) {
for (int j = 0; j < MAZESIZE_Y; j++) {
if (steps_map[i][j] == 65535) continue;
- if (j < (MAZESIZE_Y - 1)) {
- if (wall[i][j].north == NOWALL) {
- if (steps_map[i][j + 1] == 65535) {
- steps_map[i][j + 1] = steps_map[i][j] + 1;
- change_flag = true;
- }
- }
+ if (
+ (j < (MAZESIZE_Y - 1)) && (wall[i][j].north == NOWALL) &&
+ (steps_map[i][j + 1] == 65535)) {
+ steps_map[i][j + 1] = steps_map[i][j] + 1;
+ change_flag = true;
}
- if (i < (MAZESIZE_X - 1)) {
- if (wall[i][j].east == NOWALL) {
- if (steps_map[i + 1][j] == 65535) {
- steps_map[i + 1][j] = steps_map[i][j] + 1;
- change_flag = true;
- }
- }
+ if (
+ (i < (MAZESIZE_X - 1)) && (wall[i][j].east == NOWALL) && (steps_map[i + 1][j] == 65535)) {
+ steps_map[i + 1][j] = steps_map[i][j] + 1;
+ change_flag = true;
}
- if (j > 0) {
- if (wall[i][j].south == NOWALL) {
- if (steps_map[i][j - 1] == 65535) {
- steps_map[i][j - 1] = steps_map[i][j] + 1;
- change_flag = true;
- }
- }
+ if ((j > 0) && (wall[i][j].south == NOWALL) && (steps_map[i][j - 1] == 65535)) {
+ steps_map[i][j - 1] = steps_map[i][j] + 1;
+ change_flag = true;
}
- if (i > 0) {
- if (wall[i][j].west == NOWALL) {
- if (steps_map[i - 1][j] == 65535) {
- steps_map[i - 1][j] = steps_map[i][j] + 1;
- change_flag = true;
- }
- }
+ if ((i > 0) && (wall[i][j].west == NOWALL) && (steps_map[i - 1][j] == 65535)) {
+ steps_map[i - 1][j] = steps_map[i][j] + 1;
+ change_flag = true;
}
}
}
} while (change_flag == true);
}
-int MapManager::getPriority(unsigned char x, unsigned char y, t_direction_glob dir)
+int MapManager::priorityGet(unsigned char x, unsigned char y, t_global_direction dir)
{
int priority;
diff --git a/pico_v2_STEP8_micromouse/misc.h b/pico_v2_STEP8_micromouse/misc.h
new file mode 100644
index 0000000..2155f4f
--- /dev/null
+++ b/pico_v2_STEP8_micromouse/misc.h
@@ -0,0 +1,31 @@
+// Copyright 2023 RT Corporation
+//
+// Licensed under the Apache License, Version 2.0 (the "License");
+// you may not use this file except in compliance with the License.
+// You may obtain a copy of the License at
+//
+// http://www.apache.org/licenses/LICENSE-2.0
+//
+// Unless required by applicable law or agreed to in writing, software
+// distributed under the License is distributed on an "AS IS" BASIS,
+// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+// See the License for the specific language governing permissions and
+// limitations under the License.
+
+#ifndef SRC_MISC_H_
+#define SRC_MISC_H_
+
+class MISC
+{
+public:
+ unsigned char mode_select;
+ void modeExec(int mode);
+ short buttonInc(short _data, short limit, short limit_data);
+ void buttonOk(void);
+ void goalAppeal(void);
+ void errorAppeal(void);
+};
+
+extern MISC g_misc;
+
+#endif /* SRC_MISC_H_ */
\ No newline at end of file
diff --git a/pico_v2_STEP8_micromouse/misc.ino b/pico_v2_STEP8_micromouse/misc.ino
index e59de6d..bc1ab39 100644
--- a/pico_v2_STEP8_micromouse/misc.ino
+++ b/pico_v2_STEP8_micromouse/misc.ino
@@ -12,57 +12,50 @@
// See the License for the specific language governing permissions and
// limitations under the License.
-short incButton(short data, short limit, short limit_data)
+#include "misc.h"
+
+MISC g_misc;
+
+short MISC::buttonInc(short data, short limit, short limit_data)
{
data++;
if (data > limit) {
data = limit_data;
}
- enableBuzzer(INC_FREQ);
+ buzzerEnable(INC_FREQ);
delay(30);
- disableBuzzer();
- return data;
-}
-short decButton(short data, short limit, short limit_data)
-{
- data--;
- if (data < limit) {
- data = limit_data;
- }
- enableBuzzer(DEC_FREQ);
- delay(30);
- disableBuzzer();
+ buzzerDisable();
return data;
}
-void okButton(void)
+void MISC::buttonOk(void)
{
- enableBuzzer(DEC_FREQ);
+ buzzerEnable(DEC_FREQ);
delay(80);
- enableBuzzer(INC_FREQ);
+ buzzerEnable(INC_FREQ);
delay(80);
- disableBuzzer();
+ buzzerDisable();
}
-void goalAppeal(void) //ゴールしたことをアピールする
+void MISC::goalAppeal(void) //ゴールしたことをアピールする
{
unsigned char led_data;
int wtime = 100;
- disableMotor();
+ motorDisable();
mapWrite();
for (int j = 0; j < 10; j++) {
led_data = 1;
for (int i = 0; i < 4; i++) {
- setLED(led_data);
+ ledSet(led_data);
led_data <<= 1;
delay(wtime);
}
led_data = 8;
for (int i = 0; i < 4; i++) {
- setLED(led_data);
+ ledSet(led_data);
led_data >>= 1;
delay(wtime);
}
@@ -70,5 +63,72 @@ void goalAppeal(void) //ゴールしたことをアピールする
}
delay(500);
- enableMotor();
+ motorEnable();
+}
+
+void MISC::modeExec(int mode)
+{
+ motorEnable();
+ delay(1000);
+
+ switch (mode) {
+ case 1:
+ g_search.lefthand();
+ break;
+ case 2: //足立法
+ g_map.positionInit();
+ g_search.adachi(g_map.goal_mx, g_map.goal_my);
+ g_run.rotate(right, 2);
+ g_map.nextDir(right);
+ g_map.nextDir(right);
+ g_misc.goalAppeal();
+ g_search.adachi(0, 0);
+ g_run.rotate(right, 2);
+ g_map.nextDir(right);
+ g_map.nextDir(right);
+ mapWrite();
+ break;
+ case 3: //最短走行
+ mapCopy();
+ g_map.positionInit();
+ g_fast.run(g_map.goal_mx, g_map.goal_my);
+ g_run.rotate(right, 2);
+ g_map.nextDir(right);
+ g_map.nextDir(right);
+ g_misc.goalAppeal();
+ g_fast.run(0, 0);
+ g_run.rotate(right, 2);
+ g_map.nextDir(right);
+ g_map.nextDir(right);
+ break;
+ case 4:
+ break;
+ case 5:
+ break;
+ case 6:
+ break;
+ case 7:
+ break;
+ case 8:
+ break;
+ case 9:
+ break;
+ case 10:
+ break;
+ case 11:
+ break;
+ case 12:
+ break;
+ case 13:
+ break;
+ case 14:
+ break;
+ case 15:
+ motorDisable();
+ g_adjust.menu(); //調整メニューに行く
+ break;
+ default:
+ break;
+ }
+ motorDisable();
}
diff --git a/pico_v2_STEP8_micromouse/mytypedef.h b/pico_v2_STEP8_micromouse/mytypedef.h
deleted file mode 100644
index f04be48..0000000
--- a/pico_v2_STEP8_micromouse/mytypedef.h
+++ /dev/null
@@ -1,32 +0,0 @@
-#ifndef MYTYPEDEF_H_
-#define MYTYPEDEF_H_
-
-typedef struct
-{
- short value;
- short p_value;
- short error;
- short ref;
- short th_wall;
- short th_control;
- bool is_wall;
- bool is_control;
-} t_sensor;
-
-typedef struct
-{
- double control;
- double error;
- double p_error;
- double diff;
- double sum;
- double sum_max;
- double kp;
- double kd;
- double ki;
- bool enable;
-} t_control;
-
-typedef enum { MOT_FORWARD, MOT_BACK } t_CW_CCW;
-
-#endif // MYTYPEDEF_H_
\ No newline at end of file
diff --git a/pico_v2_STEP8_micromouse/parameter.h b/pico_v2_STEP8_micromouse/parameter.h
index a2e9378..e8d39bb 100644
--- a/pico_v2_STEP8_micromouse/parameter.h
+++ b/pico_v2_STEP8_micromouse/parameter.h
@@ -1,41 +1,49 @@
+// Copyright 2023 RT Corporation
+//
+// Licensed under the Apache License, Version 2.0 (the "License");
+// you may not use this file except in compliance with the License.
+// You may obtain a copy of the License at
+//
+// http://www.apache.org/licenses/LICENSE-2.0
+//
+// Unless required by applicable law or agreed to in writing, software
+// distributed under the License is distributed on an "AS IS" BASIS,
+// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+// See the License for the specific language governing permissions and
+// limitations under the License.
+
#ifndef PARAMETER_H_
#define PARAMETER_H_
-#define TIRE_DIAMETER (24.7)
-#define TREAD_WIDTH (31.5)
-#define TREAD_CIRCUIT (TREAD_WIDTH * PI / 4)
-#define PULSE (TIRE_DIAMETER * PI / (35.0 / 10.0 * 20.0 * 8.0))
-#define MIN_HZ 40
-
-#define WAITLOOP_SLED 10
+#define TIRE_DIAMETER_INIT (24.7)
+#define TREAD_WIDTH_INIT (31.5)
-#define REF_SEN_R 394
-#define REF_SEN_L 554
+#define REF_SEN_R_INIT 394
+#define REF_SEN_L_INIT 554
-#define TH_SEN_R 150
-#define TH_SEN_L 146
-#define TH_SEN_FR 192
-#define TH_SEN_FL 202
+#define TH_SEN_R_INIT 150
+#define TH_SEN_L_INIT 146
+#define TH_SEN_FR_INIT 192
+#define TH_SEN_FL_INIT 202
-#define CONTROL_TH_SEN_R TH_SEN_R
-#define CONTROL_TH_SEN_L TH_SEN_L
+#define GOAL_X_INIT 3
+#define GOAL_Y_INIT 3
-#define CON_WALL_KP 0.12
-#define SEARCH_ACCEL 1.5
-#define TURN_ACCEL 0.3
+#define WAITLOOP_SLED 10
-#define SEARCH_SPEED 200
-#define MAX_SPEED 600
-#define MIN_SPEED (MIN_HZ * PULSE)
+#define CON_WALL_KP_INIT 0.12
+#define SEARCH_ACCEL_INIT 1.5
+#define TURN_ACCEL_INIT 0.3
-#define GOAL_X 3
-#define GOAL_Y 3
+#define SEARCH_SPEED_INIT 200
+#define MAX_SPEED_INIT 600
+#define MIN_SPEED 10
#define INC_FREQ 3000
#define DEC_FREQ 2000
#define BATT_MAX 4000
-#define BATT_MIN 3800
+#define BATT_MIN 3250
#define HALF_SECTION 45
#define SECTION 90
diff --git a/pico_v2_STEP8_micromouse/pico_v2_STEP8_micromouse.ino b/pico_v2_STEP8_micromouse/pico_v2_STEP8_micromouse.ino
index 91d1a39..a39b489 100644
--- a/pico_v2_STEP8_micromouse/pico_v2_STEP8_micromouse.ino
+++ b/pico_v2_STEP8_micromouse/pico_v2_STEP8_micromouse.ino
@@ -12,113 +12,49 @@
// See the License for the specific language governing permissions and
// limitations under the License.
-#include "FS.h"
+#include
+#include
+#include
+#include
+
#include "SPIFFS.h"
+#include "adjust.h"
#include "device.h"
+#include "fast.h"
#include "map_manager.h"
-#include "mytypedef.h"
+#include "misc.h"
#include "parameter.h"
-
-signed char g_mode;
-short g_battery_value;
-t_sensor g_sen_r, g_sen_l, g_sen_fr, g_sen_fl;
-t_control g_con_wall;
-
-volatile double g_accel;
-double g_max_speed, g_min_speed;
-volatile double g_speed;
-volatile bool g_motor_move;
-MapManager g_map_control;
+#include "run.h"
+#include "search.h"
+#include "sensor.h"
void setup()
{
// put your setup code here, to run once:
+ deviceInit();
+ flashBegin();
+ paramRead();
- initAll();
+ motorDisable();
+ buzzerEnable(INC_FREQ);
+ delay(80);
+ buzzerDisable();
- disableBuzzer();
- g_mode = 1;
+ g_misc.mode_select = 1;
}
void loop()
{
// put your main code here, to run repeatedly:
- setLED(g_mode);
- switch (getSW()) {
+ ledSet(g_misc.mode_select);
+ switch (switchGet()) {
case SW_RM:
- g_mode = incButton(g_mode, 15, 1);
+ g_misc.mode_select = g_misc.buttonInc(g_misc.mode_select, 15, 1);
break;
case SW_LM:
- okButton();
- execByMode(g_mode);
+ g_misc.buttonOk();
+ g_misc.modeExec(g_misc.mode_select);
break;
}
delay(1);
-}
-
-void execByMode(int mode)
-{
- enableMotor();
- delay(1000);
-
- switch (mode) {
- case 1:
- searchLefthand();
- break;
- case 2: //足立法
- g_map_control.positionInit();
- searchAdachi(g_map_control.getGoalX(), g_map_control.getGoalY());
- rotate(right, 2);
- g_map_control.nextDir(right);
- g_map_control.nextDir(right);
- goalAppeal();
- searchAdachi(0, 0);
- rotate(right, 2);
- g_map_control.nextDir(right);
- g_map_control.nextDir(right);
- mapWrite();
- break;
- case 3: //最短走行
- copyMap();
- g_map_control.positionInit();
- fastRun(g_map_control.getGoalX(), g_map_control.getGoalY());
- rotate(right, 2);
- g_map_control.nextDir(right);
- g_map_control.nextDir(right);
- goalAppeal();
- fastRun(0, 0);
- rotate(right, 2);
- g_map_control.nextDir(right);
- g_map_control.nextDir(right);
- break;
- case 4:
- break;
- case 5:
- break;
- case 6:
- break;
- case 7:
- break;
- case 8:
- break;
- case 9:
- break;
- case 10:
- break;
- case 11:
- break;
- case 12:
- break;
- case 13:
- break;
- case 14:
- break;
- case 15:
- disableMotor();
- adjustMenu(); //調整メニューに行く
- break;
- default:
- break;
- }
- disableMotor();
-}
+}
\ No newline at end of file
diff --git a/pico_v2_STEP8_micromouse/run.h b/pico_v2_STEP8_micromouse/run.h
new file mode 100644
index 0000000..f2857d2
--- /dev/null
+++ b/pico_v2_STEP8_micromouse/run.h
@@ -0,0 +1,78 @@
+// Copyright 2023 RT Corporation
+//
+// Licensed under the Apache License, Version 2.0 (the "License");
+// you may not use this file except in compliance with the License.
+// You may obtain a copy of the License at
+//
+// http://www.apache.org/licenses/LICENSE-2.0
+//
+// Unless required by applicable law or agreed to in writing, software
+// distributed under the License is distributed on an "AS IS" BASIS,
+// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+// See the License for the specific language governing permissions and
+// limitations under the License.
+
+#ifndef SRC_RUN_H_
+#define SRC_RUN_H_
+
+typedef struct
+{
+ double control;
+ double error;
+ double p_error;
+ double diff;
+ double sum;
+ double sum_max;
+ double kp;
+ double fkp;
+ double kd;
+ double ki;
+ bool enable;
+} t_control;
+
+typedef enum {
+ MOT_FORWARD = 1, //TMC5240の方向に合わせた数字
+ MOT_BACK = 2
+} t_CW_CCW;
+
+class RUN
+{
+private:
+public:
+ volatile double accel;
+ volatile double speed;
+ volatile double speed_target_r;
+ volatile double speed_target_l;
+ volatile double upper_speed_limit;
+ volatile double lower_speed_limit;
+ float search_accel;
+ short search_speed;
+ short max_speed;
+ float turn_accel;
+ t_control con_wall;
+
+ float tire_diameter;
+ float tread_width;
+ float pulse;
+
+ RUN();
+ void interrupt(void);
+ void counterClear(void);
+ void straight(int len, int init_speed, int max_sp, int finish_speed);
+ void accelerate(int len, int finish_speed);
+ void oneStep(int len, int init_speed);
+ void decelerate(int len, int init_speed);
+ void rotate(t_local_direction dir, int times);
+
+private:
+ int step_lr_len, step_lr;
+ void dirSet(t_CW_CCW dir_left, t_CW_CCW dir_right);
+ void speedSet(double l_speed, double r_speed);
+ void stepGet(void);
+ void stay(float l_speed);
+ void stop(void);
+};
+
+extern RUN g_run;
+
+#endif /* SRC_RUN_H_ */
\ No newline at end of file
diff --git a/pico_v2_STEP8_micromouse/run.ino b/pico_v2_STEP8_micromouse/run.ino
index ebdc1d2..f0cdc10 100644
--- a/pico_v2_STEP8_micromouse/run.ino
+++ b/pico_v2_STEP8_micromouse/run.ino
@@ -12,185 +12,275 @@
// See the License for the specific language governing permissions and
// limitations under the License.
-void straight(int len, int init_speed, int max_speed, int finish_speed)
+#include "parameter.h"
+#include "run.h"
+
+RUN g_run;
+
+RUN::RUN()
+{
+ speed = 0.0;
+ accel = 0.0;
+}
+
+//割り込み
+void controlInterrupt(void) { g_run.interrupt(); }
+
+void RUN::interrupt(void)
+{ //割り込み内からコール
+
+ speed += accel;
+
+ if (speed > upper_speed_limit) {
+ speed = upper_speed_limit;
+ }
+ if (speed < lower_speed_limit) {
+ speed = lower_speed_limit;
+ }
+
+ if (con_wall.enable == true) {
+ con_wall.p_error = con_wall.error;
+ if ((g_sensor.sen_r.is_control == true) && (g_sensor.sen_l.is_control == true)) {
+ con_wall.error = g_sensor.sen_r.error - g_sensor.sen_l.error;
+ } else {
+ con_wall.error = 2.0 * (g_sensor.sen_r.error - g_sensor.sen_l.error);
+ }
+ con_wall.diff = con_wall.error - con_wall.p_error;
+ con_wall.sum += con_wall.error;
+ if (con_wall.sum > con_wall.sum_max) {
+ con_wall.sum = con_wall.sum_max;
+ } else if (con_wall.sum < (-con_wall.sum_max)) {
+ con_wall.sum = -con_wall.sum_max;
+ }
+ con_wall.control = 0.001 * speed * con_wall.kp * con_wall.error;
+ speed_target_r = speed + con_wall.control;
+ speed_target_l = speed - con_wall.control;
+ } else {
+ speed_target_r = speed;
+ speed_target_l = speed;
+ }
+ if (speed_target_r < MIN_SPEED) speed_target_r = MIN_SPEED;
+ if (speed_target_l < MIN_SPEED) speed_target_l = MIN_SPEED;
+
+ speedSet(speed_target_l, speed_target_r);
+
+}
+
+void RUN::dirSet(t_CW_CCW dir_left, t_CW_CCW dir_right) { motorDirectionSet(dir_left, dir_right); }
+
+void RUN::counterClear(void)
+{
+ stepClearR();
+ stepClearL();
+}
+
+void RUN::speedSet(double l_speed, double r_speed)
+{
+ stepHzSetR(r_speed / pulse);
+ stepHzSetL(l_speed / pulse);
+}
+
+void RUN::stay(float l_speed)
+{
+ controlInterruptStop();
+ upper_speed_limit = lower_speed_limit = speed = (double)l_speed;
+ accel = 0.0;
+ counterClear();
+ speedSet(l_speed, l_speed);
+ controlInterruptStart();
+}
+
+void RUN::stepGet(void)
+{
+ step_lr = stepGetR() + stepGetL();
+ step_lr_len = (int)((float)step_lr / 2.0 * pulse);
+}
+
+void RUN::stop(void)
+{
+ motorMoveSet(0);
+ delay(300);
+}
+
+void RUN::straight(int len, int init_speed, int max_sp, int finish_speed)
{
int obj_step;
controlInterruptStop();
- g_max_speed = max_speed;
- g_accel = SEARCH_ACCEL;
+ upper_speed_limit = (double)max_sp;
+ accel = (double)search_accel;
if (init_speed < MIN_SPEED) {
- g_speed = MIN_SPEED;
- clearStepR();
- clearStepL();
+ speed = (double)MIN_SPEED;
} else {
- g_speed = init_speed;
+ speed = (double)init_speed;
}
if (finish_speed < MIN_SPEED) {
finish_speed = MIN_SPEED;
}
- if (init_speed < finish_speed) {
- g_min_speed = MIN_SPEED;
- } else {
- g_min_speed = finish_speed;
- }
- setRStepHz((unsigned short)(g_speed / PULSE));
- setLStepHz((unsigned short)(g_speed / PULSE));
+ lower_speed_limit = (double)finish_speed;
- g_con_wall.enable = true;
- obj_step = (int)((float)len * 2.0 / PULSE);
- moveDir(MOT_FORWARD, MOT_FORWARD); //left,right
+ con_wall.enable = true;
+ speedSet(speed, speed);
+ dirSet(MOT_FORWARD, MOT_FORWARD);
+ obj_step = (int)((float)len * 2.0 / pulse);
controlInterruptStart();
+ motorMoveSet(1);
- g_motor_move = 1;
- while ((len - (getStepR() + getStepL()) / 2.0 * PULSE) >
- (((g_speed * g_speed) - (finish_speed * finish_speed)) / (2.0 * 1000.0 * SEARCH_ACCEL))) {
- continue;
+ while (1) {
+ stepGet();
+ if (
+ (len - step_lr_len) <
+ (int)(((speed * speed) - (lower_speed_limit * lower_speed_limit)) / (2.0 * 1000.0 * accel))) {
+ break;
+ }
}
- g_accel = -1.0 * SEARCH_ACCEL;
- while ((getStepR() + getStepL()) < obj_step) {
- continue;
+ accel = -1.0 * search_accel;
+
+ while (1) {
+ stepGet();
+ if (step_lr > obj_step) {
+ break;
+ }
}
- if (finish_speed == SEARCH_SPEED) {
- controlInterruptStop();
- g_max_speed = g_min_speed = g_speed = finish_speed;
- g_accel = 0.0;
- clearStepR();
- clearStepL();
- controlInterruptStart();
+ if (finish_speed == MIN_SPEED) {
+ stop();
} else {
- g_motor_move = 0;
+ stay(finish_speed);
}
}
-void accelerate(int len, int finish_speed)
+void RUN::accelerate(int len, int finish_speed)
{
int obj_step;
controlInterruptStop();
- g_max_speed = finish_speed;
- g_accel = SEARCH_ACCEL;
- g_speed = g_min_speed = MIN_SPEED;
- setRStepHz((unsigned short)(g_speed / PULSE));
- setLStepHz((unsigned short)(g_speed / PULSE));
- clearStepR();
- clearStepL();
- g_con_wall.enable = true;
- obj_step = (int)((float)len * 2.0 / PULSE);
- moveDir(MOT_FORWARD, MOT_FORWARD);
+ accel = search_accel;
+ speed = lower_speed_limit = (double)MIN_SPEED;
+ upper_speed_limit = (double)finish_speed;
+ con_wall.enable = true;
+ dirSet(MOT_FORWARD, MOT_FORWARD);
+ speedSet(speed, speed);
+ counterClear();
+ obj_step = (int)((float)len * 2.0 / pulse);
controlInterruptStart();
- g_motor_move = 1;
+ motorMoveSet(1);
- while ((getStepR() + getStepL()) < obj_step) {
- continue;
+ while (1) {
+ stepGet();
+ if (step_lr > obj_step) {
+ break;
+ }
}
- controlInterruptStop();
- g_max_speed = g_min_speed = g_speed = finish_speed;
- g_accel = 0.0;
- clearStepR();
- clearStepL();
- controlInterruptStart();
+ stay(finish_speed);
}
-void oneStep(int len, int tar_speed)
+void RUN::oneStep(int len, int init_speed)
{
int obj_step;
+
controlInterruptStop();
- g_speed = g_min_speed = g_max_speed = tar_speed;
- g_accel = 0.0;
- setRStepHz((unsigned short)(g_speed / PULSE));
- setLStepHz((unsigned short)(g_speed / PULSE));
- g_con_wall.enable = true;
- obj_step = (int)((float)len * 2.0 / PULSE);
- moveDir(MOT_FORWARD, MOT_FORWARD);
+ accel = 0.0;
+ speed = lower_speed_limit = upper_speed_limit = (double)init_speed;
+ con_wall.enable = true;
+ dirSet(MOT_FORWARD, MOT_FORWARD);
+ speedSet(speed, speed);
+ obj_step = (int)((float)len * 2.0 / pulse);
controlInterruptStart();
- while ((getStepR() + getStepL()) < obj_step) {
- continue;
+ while (1) {
+ stepGet();
+ if (step_lr > obj_step) {
+ break;
+ }
}
- controlInterruptStop();
- g_max_speed = g_min_speed = g_speed = tar_speed;
- g_accel = 0.0;
- clearStepR();
- clearStepL();
- controlInterruptStart();
+
+ stay(init_speed);
}
-void decelerate(int len, int tar_speed)
+void RUN::decelerate(int len, int init_speed)
{
int obj_step;
+
controlInterruptStop();
- g_max_speed = tar_speed;
- g_accel = 0.0;
- g_speed = g_min_speed = tar_speed;
-
- setRStepHz((unsigned short)(g_speed / PULSE));
- setLStepHz((unsigned short)(g_speed / PULSE));
- g_con_wall.enable = true;
- obj_step = (int)((float)len * 2.0 / PULSE);
- moveDir(MOT_FORWARD, MOT_FORWARD);
+ accel = search_accel;
+ speed = upper_speed_limit = init_speed;
+ lower_speed_limit = MIN_SPEED;
+ con_wall.enable = true;
+ dirSet(MOT_FORWARD, MOT_FORWARD);
+ speedSet(speed, speed);
+ obj_step = (int)((float)len * 2.0 / pulse);
controlInterruptStart();
- while ((len - (getStepR() + getStepL()) / 2.0 * PULSE) >
- (((g_speed * g_speed) - (MIN_SPEED * MIN_SPEED)) / (2.0 * 1000.0 * SEARCH_ACCEL))) {
- continue;
+ while (1) {
+ stepGet();
+ if (
+ (int)(len - step_lr_len) <
+ (int)(((speed * speed) - (MIN_SPEED * MIN_SPEED)) / (2.0 * 1000.0 * accel))) {
+ break;
+ }
}
- g_accel = -1.0 * SEARCH_ACCEL;
- g_min_speed = MIN_SPEED;
- while ((getStepR() + getStepL()) < obj_step) {
- continue;
- }
+ accel = -1 * search_accel;
- g_motor_move = 0;
+ while (1) {
+ stepGet();
+ if (step_lr > obj_step) {
+ break;
+ }
+ }
- delay(300);
+ stop();
}
-void rotate(t_direction dir, int times)
+void RUN::rotate(t_local_direction dir, int times)
{
int obj_step;
+
controlInterruptStop();
- g_max_speed = SEARCH_SPEED;
- g_accel = TURN_ACCEL;
- g_speed = g_min_speed = MIN_SPEED;
- setRStepHz((unsigned short)(g_speed / PULSE));
- setLStepHz((unsigned short)(g_speed / PULSE));
- clearStepR();
- clearStepL();
- g_con_wall.enable = false;
- obj_step = (int)(TREAD_WIDTH * PI / 4.0 * (float)times * 2.0 / PULSE);
+ accel = turn_accel;
+ upper_speed_limit = search_speed;
+ speed = lower_speed_limit = MIN_SPEED;
+ con_wall.enable = false;
+ obj_step = (int)(tread_width * PI / 4.0 * (float)times * 2.0 / pulse);
switch (dir) {
case right:
- moveDir(MOT_FORWARD, MOT_BACK);
- g_motor_move = 1;
+ dirSet(MOT_FORWARD, MOT_BACK);
+ motorMoveSet(1);
break;
case left:
- moveDir(MOT_BACK, MOT_FORWARD);
- g_motor_move = 1;
+ dirSet(MOT_BACK, MOT_FORWARD);
+ motorMoveSet(1);
break;
default:
- g_motor_move = 0;
+ motorMoveSet(0);
break;
}
+ speedSet(MIN_SPEED, MIN_SPEED);
+ counterClear();
controlInterruptStart();
- while (((obj_step - (getStepR() + getStepL())) / 2.0 * PULSE) >
- (((g_speed * g_speed) - (MIN_SPEED * MIN_SPEED)) / (2.0 * 1000.0 * TURN_ACCEL))) {
- continue;
+ while (1) {
+ stepGet();
+ if (
+ (int)((tread_width * PI / 4.0 * times) - step_lr_len) <
+ (int)(((speed * speed) - (MIN_SPEED * MIN_SPEED)) / (2.0 * 1000.0 * accel))) {
+ break;
+ }
}
- g_accel = -1.0 * TURN_ACCEL;
- while ((getStepR() + getStepL()) < obj_step) {
- continue;
- }
+ accel = -1.0 * turn_accel;
- g_motor_move = 0;
- delay(300);
+ while (1) {
+ stepGet();
+ if (step_lr > obj_step) {
+ break;
+ }
+ }
+ stop();
}
diff --git a/pico_v2_STEP6_rotate/interrupt.ino b/pico_v2_STEP8_micromouse/search.h
similarity index 71%
rename from pico_v2_STEP6_rotate/interrupt.ino
rename to pico_v2_STEP8_micromouse/search.h
index 8d9e922..614b724 100644
--- a/pico_v2_STEP6_rotate/interrupt.ino
+++ b/pico_v2_STEP8_micromouse/search.h
@@ -11,17 +11,16 @@
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
+#ifndef SRC_SEARCH_H_
+#define SRC_SEARCH_H_
-void controlInterrupt(void)
-{
- g_speed += g_accel;
- if (g_speed > g_max_speed) {
- g_speed = g_max_speed;
- }
- if (g_speed < g_min_speed) {
- g_speed = g_min_speed;
- }
+class SEARCH {
+public:
+ void lefthand(void);
+ void adachi(char gx, char gy);
+private:
- g_step_hz_l = g_step_hz_r = (unsigned short)(g_speed / PULSE);
-}
\ No newline at end of file
+};
+extern SEARCH g_search;
+#endif /* SRC_SEARCH_H_ */
\ No newline at end of file
diff --git a/pico_v2_STEP8_micromouse/search.ino b/pico_v2_STEP8_micromouse/search.ino
index 4ba97ae..644ad55 100644
--- a/pico_v2_STEP8_micromouse/search.ino
+++ b/pico_v2_STEP8_micromouse/search.ino
@@ -12,83 +12,85 @@
// See the License for the specific language governing permissions and
// limitations under the License.
-void searchLefthand(void)
+#include "search.h"
+
+SEARCH g_search;
+
+void SEARCH::lefthand(void)
{
- accelerate(HALF_SECTION, SEARCH_SPEED);
+ g_run.accelerate(HALF_SECTION, g_run.search_speed);
while (1) {
- if (g_sen_l.is_wall == false) {
- decelerate(HALF_SECTION, SEARCH_SPEED);
- rotate(left, 1);
- accelerate(HALF_SECTION, SEARCH_SPEED);
- } else if ((g_sen_fl.is_wall == false) && (g_sen_fr.is_wall == false)) {
- straight(SECTION, SEARCH_SPEED, SEARCH_SPEED, SEARCH_SPEED);
- } else if (g_sen_r.is_wall == false) {
- decelerate(HALF_SECTION, SEARCH_SPEED);
- rotate(right, 1);
- accelerate(HALF_SECTION, SEARCH_SPEED);
+ if (g_sensor.sen_l.is_wall == false) {
+ g_run.decelerate(HALF_SECTION, g_run.search_speed);
+ g_run.rotate(left, 1);
+ g_run.accelerate(HALF_SECTION, g_run.search_speed);
+ } else if ((g_sensor.sen_fl.is_wall == false) && (g_sensor.sen_fr.is_wall == false)) {
+ g_run.straight(SECTION, g_run.search_speed, g_run.search_speed, g_run.search_speed);
+ } else if (g_sensor.sen_r.is_wall == false) {
+ g_run.decelerate(HALF_SECTION, g_run.search_speed);
+ g_run.rotate(right, 1);
+ g_run.accelerate(HALF_SECTION, g_run.search_speed);
} else {
- decelerate(HALF_SECTION, SEARCH_SPEED);
- rotate(right, 2);
- accelerate(HALF_SECTION, SEARCH_SPEED);
+ g_run.decelerate(HALF_SECTION, g_run.search_speed);
+ g_run.rotate(right, 2);
+ g_run.accelerate(HALF_SECTION, g_run.search_speed);
}
}
}
-void searchAdachi(char gx, char gy)
+void SEARCH::adachi(char gx, char gy)
{
- t_direction_glob glob_nextdir;
- t_direction temp_next_dir;
-
- temp_next_dir = g_map_control.getNextDir(gx, gy, &glob_nextdir);
+ t_global_direction glob_nextdir;
+ t_local_direction temp_next_dir;
- switch (temp_next_dir) {
+ switch (g_map.nextDirGet(gx, gy, &glob_nextdir)) {
case front:
break;
case right:
- rotate(right, 1);
+ g_run.rotate(right, 1);
break;
case left:
- rotate(left, 1);
+ g_run.rotate(left, 1);
break;
case rear:
- rotate(right, 2);
+ g_run.rotate(right, 2);
break;
}
- accelerate(HALF_SECTION, SEARCH_SPEED);
+ g_run.accelerate(HALF_SECTION, g_run.search_speed);
- g_map_control.setMyPosDir(glob_nextdir);
- g_map_control.axisUpdate();
+ g_map.mypos.dir = glob_nextdir;
+ g_map.axisUpdate();
- while ((g_map_control.getMyPosX() != gx) || (g_map_control.getMyPosY() != gy)) {
- g_map_control.setWall(g_sen_fr.is_wall, g_sen_r.is_wall, g_sen_l.is_wall);
+ while ((g_map.mypos.x != gx) || (g_map.mypos.y != gy)) {
+ g_map.wallSet(g_sensor.sen_fr.is_wall, g_sensor.sen_r.is_wall, g_sensor.sen_l.is_wall);
- switch (g_map_control.getNextDir(gx, gy, &glob_nextdir)) {
+ switch (g_map.nextDirGet(gx, gy, &glob_nextdir)) {
case front:
- oneStep(SECTION, SEARCH_SPEED);
+ g_run.oneStep(SECTION, g_run.search_speed);
break;
case right:
- decelerate(HALF_SECTION, SEARCH_SPEED);
- rotate(right, 1);
- accelerate(HALF_SECTION, SEARCH_SPEED);
+ g_run.decelerate(HALF_SECTION, g_run.search_speed);
+ g_run.rotate(right, 1);
+ g_run.accelerate(HALF_SECTION, g_run.search_speed);
break;
case left:
- decelerate(HALF_SECTION, SEARCH_SPEED);
- rotate(left, 1);
- accelerate(HALF_SECTION, SEARCH_SPEED);
+ g_run.decelerate(HALF_SECTION, g_run.search_speed);
+ g_run.rotate(left, 1);
+ g_run.accelerate(HALF_SECTION, g_run.search_speed);
break;
case rear:
- decelerate(HALF_SECTION, SEARCH_SPEED);
- rotate(right, 2);
- accelerate(HALF_SECTION, SEARCH_SPEED);
+ g_run.decelerate(HALF_SECTION, g_run.search_speed);
+ g_run.rotate(right, 2);
+ g_run.accelerate(HALF_SECTION, g_run.search_speed);
break;
}
- g_map_control.setMyPosDir(glob_nextdir); //方向を更新
- g_map_control.axisUpdate();
+ g_map.mypos.dir = glob_nextdir; //方向を更新
+ g_map.axisUpdate();
}
- g_map_control.setWall(g_sen_fr.is_wall, g_sen_r.is_wall, g_sen_l.is_wall);
- decelerate(HALF_SECTION, SEARCH_SPEED);
+ g_map.wallSet(g_sensor.sen_fr.is_wall, g_sensor.sen_r.is_wall, g_sensor.sen_l.is_wall);
+ g_run.decelerate(HALF_SECTION, g_run.search_speed);
}
\ No newline at end of file
diff --git a/pico_v2_STEP8_micromouse/sensor.h b/pico_v2_STEP8_micromouse/sensor.h
new file mode 100644
index 0000000..73faa60
--- /dev/null
+++ b/pico_v2_STEP8_micromouse/sensor.h
@@ -0,0 +1,42 @@
+// Copyright 2023 RT Corporation
+//
+// Licensed under the Apache License, Version 2.0 (the "License");
+// you may not use this file except in compliance with the License.
+// You may obtain a copy of the License at
+//
+// http://www.apache.org/licenses/LICENSE-2.0
+//
+// Unless required by applicable law or agreed to in writing, software
+// distributed under the License is distributed on an "AS IS" BASIS,
+// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+// See the License for the specific language governing permissions and
+// limitations under the License.
+
+#ifndef SRC_SENSOR_H_
+#define SRC_SENSOR_H_
+
+#include "run.h"
+
+typedef struct
+{
+ short value;
+ short p_value;
+ short error;
+ short ref;
+ short th_wall;
+ short th_control;
+ bool is_wall;
+ bool is_control;
+} t_sensor;
+
+
+class SENSOR{
+public:
+ volatile t_sensor sen_r, sen_l, sen_fr, sen_fl;
+ volatile short battery_value;
+ void interrupt(void);
+};
+
+extern SENSOR g_sensor;
+
+#endif /* SRC_SENSOR_H_ */
\ No newline at end of file
diff --git a/pico_v2_STEP8_micromouse/sensor.ino b/pico_v2_STEP8_micromouse/sensor.ino
new file mode 100644
index 0000000..f26d2c6
--- /dev/null
+++ b/pico_v2_STEP8_micromouse/sensor.ino
@@ -0,0 +1,99 @@
+// Copyright 2023 RT Corporation
+//
+// Licensed under the Apache License, Version 2.0 (the "License");
+// you may not use this file except in compliance with the License.
+// You may obtain a copy of the License at
+//
+// http://www.apache.org/licenses/LICENSE-2.0
+//
+// Unless required by applicable law or agreed to in writing, software
+// distributed under the License is distributed on an "AS IS" BASIS,
+// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+// See the License for the specific language governing permissions and
+// limitations under the License.
+
+#include "sensor.h"
+
+SENSOR g_sensor;
+
+void sensorInterrupt(void) {
+ g_sensor.interrupt();
+}
+
+void SENSOR::interrupt(void)
+{
+ static char cnt = 0;
+ static char bled_cnt = 0;
+ static int low_batt_cnt =0;
+
+ switch (cnt) {
+ case 0:
+ sen_r.p_value = sen_r.value;
+ sen_l.p_value = sen_l.value;
+ sensorGetS(&sen_r.value, &sen_l.value);
+ if (sen_r.value > sen_r.th_wall) {
+ sen_r.is_wall = true;
+ } else {
+ sen_r.is_wall = false;
+ }
+ if (sen_r.value > sen_r.th_control) {
+ sen_r.error = sen_r.value - sen_r.ref;
+ sen_r.is_control = true;
+ } else {
+ sen_r.error = 0;
+ sen_r.is_control = false;
+ }
+ if (sen_l.value > sen_l.th_wall) {
+ sen_l.is_wall = true;
+ } else {
+ sen_l.is_wall = false;
+ }
+ if (sen_l.value > sen_l.th_control) {
+ sen_l.error = sen_l.value - sen_l.ref;
+ sen_l.is_control = true;
+ } else {
+ sen_l.error = 0;
+ sen_l.is_control = false;
+ }
+ break;
+ case 1:
+ sen_fr.p_value = sen_fr.value;
+ sen_fl.p_value = sen_fl.value;
+ sensorGetF(&sen_fr.value, &sen_fl.value);
+ if (sen_fr.value > sen_fr.th_wall) {
+ sen_fr.is_wall = true;
+ } else {
+ sen_fr.is_wall = false;
+ }
+ if (sen_fl.value > sen_fl.th_wall) {
+ sen_fl.is_wall = true;
+ } else {
+ sen_fl.is_wall = false;
+ }
+
+ bled_cnt++;
+ if (bled_cnt > 10) {
+ bled_cnt = 0;
+ }
+ battery_value = batteryVoltGet();
+ if (((battery_value - BATT_MIN) * 10 / (BATT_MAX - BATT_MIN)) > bled_cnt) {
+ bledSet(1);
+ } else {
+ bledSet(2);
+ }
+ if(battery_value < BATT_MIN){
+ low_batt_cnt++;
+ if(low_batt_cnt>=100){
+ buzzerEnable(400);
+ }
+ }else{
+ low_batt_cnt=0;
+ }
+ break;
+ default:
+ Serial.printf("sensor state error\n\r");
+ break;
+ }
+ cnt++;
+ if (cnt >= 2) cnt = 0;
+}
\ No newline at end of file
diff --git a/pico_v2_STEP8_micromouse/webserver.ino b/pico_v2_STEP8_micromouse/webserver.ino
new file mode 100644
index 0000000..4407229
--- /dev/null
+++ b/pico_v2_STEP8_micromouse/webserver.ino
@@ -0,0 +1,326 @@
+// Copyright 2023 RT Corporation
+//
+// Licensed under the Apache License, Version 2.0 (the "License");
+// you may not use this file except in compliance with the License.
+// You may obtain a copy of the License at
+//
+// http://www.apache.org/licenses/LICENSE-2.0
+//
+// Unless required by applicable law or agreed to in writing, software
+// distributed under the License is distributed on an "AS IS" BASIS,
+// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+// See the License for the specific language governing permissions and
+// limitations under the License.
+
+#define AP_MODE
+
+AsyncWebServer server(80);
+
+#ifdef AP_MODE
+const char* ssid = "PICO2";
+const char* password = "12345678";
+#else
+const char* ssid = "使用しているルータのSSID";
+const char* password = "ルータのパスワード";
+#endif
+
+
+
+void webServerSetup(void) {
+
+#ifdef AP_MODE
+ WiFi.softAP(ssid, password);
+ IPAddress myIP = WiFi.softAPIP();
+ Serial.println(myIP);
+#else
+ WiFi.mode(WIFI_STA);
+ WiFi.begin(ssid, password);
+ if (WiFi.waitForConnectResult() != WL_CONNECTED) {
+ Serial.printf("WiFi Failed!\n");
+ return;
+ }
+ Serial.print("IP Address: ");
+ Serial.println(WiFi.localIP());
+#endif
+
+ server.on("/", HTTP_GET, [](AsyncWebServerRequest* request) {
+ String html = "";
+ html += "";
+ html += "";
+ html += "";
+ html += "";
+ html += "Pi:Co V2 WebServer";
+ html += "";
+ html += "";
+ html += "";
+ html += "Pi:Co V2_Parameter
";
+ html += "
";
+ html += "";
+ html += "";
+ html += String(g_sensor.battery_value);
+ html += " |
";
+ html += "
";
+ html += "
";
+
+ html += "Sensor Value
";
+ html += "";
+ html += " | Left | Right |
";
+ html += "SIDE VALUE | ";
+ html += String(g_sensor.sen_l.value);
+ html += " | ";
+ html += String(g_sensor.sen_r.value);
+ html += " |
";
+ html += "FRONT VALUE | ";
+ html += String(g_sensor.sen_fl.value);
+ html += " | ";
+ html += String(g_sensor.sen_fr.value);
+ html += " |
";
+ html += "
";
+ html += "
";
+ html += "
";
+
+ html += "Sensor Parameter
";
+
+ html += "";
+ html += "
";
+
+ html += "";
+
+ html += "
";
+ html += "
";
+
+ html += "";
+
+ html += "
";
+ html += "
";
+
+ html += "Tire Parameter
";
+ html += "";
+ html += "
";
+ html += "
";
+
+ html += "GOAL Parameter
";
+ html += "";
+ html += "
";
+ html += "
";
+
+ html += "Accel Parameter
";
+ html += "";
+ html += "
";
+ html += "
";
+
+ html += "Speed Parameter
";
+ html += "";
+ html += "
";
+ html += "
";
+
+
+ html += "";
+ html += "
";
+ html += "";
+ html += "";
+ html += "";
+ request->send(200, "text/html", html);
+ });
+
+ server.on("/voltage", HTTP_GET, [](AsyncWebServerRequest* request) {
+ request->send(200, "text/plain", String(g_sensor.battery_value) + "mV");
+ });
+
+ server.on("/left_value", HTTP_GET, [](AsyncWebServerRequest* request) {
+ request->send(200, "text/plain", String(g_sensor.sen_l.value));
+ });
+
+ server.on("/right_value", HTTP_GET, [](AsyncWebServerRequest* request) {
+ request->send(200, "text/plain", String(g_sensor.sen_r.value));
+ });
+
+ server.on("/left_front_value", HTTP_GET, [](AsyncWebServerRequest* request) {
+ request->send(200, "text/plain", String(g_sensor.sen_fl.value));
+ });
+
+ server.on("/right_front_value", HTTP_GET, [](AsyncWebServerRequest* request) {
+ request->send(200, "text/plain", String(g_sensor.sen_fr.value));
+ });
+
+
+ server.on("/get", HTTP_GET, [](AsyncWebServerRequest* request) {
+ String inputMessage;
+
+ inputMessage = request->getParam("tire_dia")->value();
+ g_run.tire_diameter = inputMessage.toFloat();
+ inputMessage = request->getParam("tread_width")->value();
+ g_run.tread_width = inputMessage.toFloat();
+
+ inputMessage = request->getParam("wall_kp")->value();
+ g_run.con_wall.kp = inputMessage.toFloat();
+
+ inputMessage = request->getParam("ref_left")->value();
+ g_sensor.sen_l.ref = inputMessage.toInt();
+ inputMessage = request->getParam("ref_right")->value();
+ g_sensor.sen_r.ref = inputMessage.toInt();
+
+ inputMessage = request->getParam("th_left")->value();
+ g_sensor.sen_l.th_wall = inputMessage.toInt();
+ inputMessage = request->getParam("th_right")->value();
+ g_sensor.sen_r.th_wall = inputMessage.toInt();
+
+ inputMessage = request->getParam("th_fl")->value();
+ g_sensor.sen_fl.th_wall = inputMessage.toInt();
+ inputMessage = request->getParam("th_fr")->value();
+ g_sensor.sen_fr.th_wall = inputMessage.toInt();
+
+ inputMessage = request->getParam("goal_x")->value();
+ g_map.goal_mx = inputMessage.toInt();
+ inputMessage = request->getParam("goal_y")->value();
+ g_map.goal_my = inputMessage.toInt();
+
+ inputMessage = request->getParam("search_acc")->value();
+ g_run.search_accel = inputMessage.toFloat();
+ inputMessage = request->getParam("turn_acc")->value();
+ g_run.turn_accel = inputMessage.toFloat();
+
+ inputMessage = request->getParam("search_spd")->value();
+ g_run.search_speed = inputMessage.toInt();
+ inputMessage = request->getParam("max_spd")->value();
+ g_run.max_speed = inputMessage.toInt();
+
+
+ Serial.println("saved");
+ paramWrite();
+ g_run.pulse = g_run.tire_diameter * PI / (35.0 / 10.0 * 20.0 *8.0);
+
+ buzzerEnable(INC_FREQ);
+ delay(30);
+ buzzerDisable();
+ request->redirect("/");
+ });
+
+ // ESP32_WebServer start
+ server.begin(); //APモードを起動
+ Serial.println("ESP32_WebServer start!");
+}
\ No newline at end of file
From 2dbd825602fb8f14201f839a00fcde0a8863804e Mon Sep 17 00:00:00 2001
From: masatake aoki
Date: Fri, 18 Apr 2025 14:31:25 +0900
Subject: [PATCH 2/5] change format
---
pico_v2_STEP8_micromouse/Flash.ino | 2 +-
pico_v2_STEP8_micromouse/run.ino | 1 -
pico_v2_STEP8_micromouse/search.h | 10 ++---
pico_v2_STEP8_micromouse/sensor.h | 10 ++---
pico_v2_STEP8_micromouse/sensor.ino | 18 ++++-----
pico_v2_STEP8_micromouse/webserver.ino | 51 +++++++++++++-------------
6 files changed, 45 insertions(+), 47 deletions(-)
diff --git a/pico_v2_STEP8_micromouse/Flash.ino b/pico_v2_STEP8_micromouse/Flash.ino
index 13f5c88..ed039f4 100644
--- a/pico_v2_STEP8_micromouse/Flash.ino
+++ b/pico_v2_STEP8_micromouse/Flash.ino
@@ -273,7 +273,7 @@ void paramRead(void)
flashInit();
break;
}
- g_run.pulse = g_run.tire_diameter * PI / (35.0 / 10.0 * 20.0 *8.0);
+ g_run.pulse = g_run.tire_diameter * PI / (35.0 / 10.0 * 20.0 * 8.0);
cmds[0] = {"\0"};
cmds[1] = {"\0"};
}
diff --git a/pico_v2_STEP8_micromouse/run.ino b/pico_v2_STEP8_micromouse/run.ino
index f0cdc10..bb0c90c 100644
--- a/pico_v2_STEP8_micromouse/run.ino
+++ b/pico_v2_STEP8_micromouse/run.ino
@@ -63,7 +63,6 @@ void RUN::interrupt(void)
if (speed_target_l < MIN_SPEED) speed_target_l = MIN_SPEED;
speedSet(speed_target_l, speed_target_r);
-
}
void RUN::dirSet(t_CW_CCW dir_left, t_CW_CCW dir_right) { motorDirectionSet(dir_left, dir_right); }
diff --git a/pico_v2_STEP8_micromouse/search.h b/pico_v2_STEP8_micromouse/search.h
index 614b724..8dc00a2 100644
--- a/pico_v2_STEP8_micromouse/search.h
+++ b/pico_v2_STEP8_micromouse/search.h
@@ -14,13 +14,13 @@
#ifndef SRC_SEARCH_H_
#define SRC_SEARCH_H_
-
-class SEARCH {
+class SEARCH
+{
public:
- void lefthand(void);
- void adachi(char gx, char gy);
-private:
+ void lefthand(void);
+ void adachi(char gx, char gy);
+private:
};
extern SEARCH g_search;
#endif /* SRC_SEARCH_H_ */
\ No newline at end of file
diff --git a/pico_v2_STEP8_micromouse/sensor.h b/pico_v2_STEP8_micromouse/sensor.h
index 73faa60..1bdc355 100644
--- a/pico_v2_STEP8_micromouse/sensor.h
+++ b/pico_v2_STEP8_micromouse/sensor.h
@@ -29,12 +29,12 @@ typedef struct
bool is_control;
} t_sensor;
-
-class SENSOR{
+class SENSOR
+{
public:
- volatile t_sensor sen_r, sen_l, sen_fr, sen_fl;
- volatile short battery_value;
- void interrupt(void);
+ volatile t_sensor sen_r, sen_l, sen_fr, sen_fl;
+ volatile short battery_value;
+ void interrupt(void);
};
extern SENSOR g_sensor;
diff --git a/pico_v2_STEP8_micromouse/sensor.ino b/pico_v2_STEP8_micromouse/sensor.ino
index f26d2c6..873241d 100644
--- a/pico_v2_STEP8_micromouse/sensor.ino
+++ b/pico_v2_STEP8_micromouse/sensor.ino
@@ -16,15 +16,13 @@
SENSOR g_sensor;
-void sensorInterrupt(void) {
- g_sensor.interrupt();
-}
+void sensorInterrupt(void) { g_sensor.interrupt(); }
-void SENSOR::interrupt(void)
+void SENSOR::interrupt(void)
{
static char cnt = 0;
static char bled_cnt = 0;
- static int low_batt_cnt =0;
+ static int low_batt_cnt = 0;
switch (cnt) {
case 0:
@@ -81,13 +79,13 @@ void SENSOR::interrupt(void)
} else {
bledSet(2);
}
- if(battery_value < BATT_MIN){
+ if (battery_value < BATT_MIN) {
low_batt_cnt++;
- if(low_batt_cnt>=100){
- buzzerEnable(400);
+ if (low_batt_cnt >= 100) {
+ buzzerEnable(400);
}
- }else{
- low_batt_cnt=0;
+ } else {
+ low_batt_cnt = 0;
}
break;
default:
diff --git a/pico_v2_STEP8_micromouse/webserver.ino b/pico_v2_STEP8_micromouse/webserver.ino
index 4407229..1cdc2b0 100644
--- a/pico_v2_STEP8_micromouse/webserver.ino
+++ b/pico_v2_STEP8_micromouse/webserver.ino
@@ -17,17 +17,15 @@
AsyncWebServer server(80);
#ifdef AP_MODE
-const char* ssid = "PICO2";
-const char* password = "12345678";
+const char * ssid = "PICO2";
+const char * password = "12345678";
#else
-const char* ssid = "使用しているルータのSSID";
-const char* password = "ルータのパスワード";
+const char * ssid = "使用しているルータのSSID";
+const char * password = "ルータのパスワード";
#endif
-
-
-void webServerSetup(void) {
-
+void webServerSetup(void)
+{
#ifdef AP_MODE
WiFi.softAP(ssid, password);
IPAddress myIP = WiFi.softAPIP();
@@ -43,7 +41,7 @@ void webServerSetup(void) {
Serial.println(WiFi.localIP());
#endif
- server.on("/", HTTP_GET, [](AsyncWebServerRequest* request) {
+ server.on("/", HTTP_GET, [](AsyncWebServerRequest * request) {
String html = "";
html += "";
html += "";
@@ -108,12 +106,14 @@ void webServerSetup(void) {
html += "> | ";
- html += "SIDE Threshold | | SIDE Threshold | | |
";
- html += "FRONT Threshold | | FRONT Threshold | | Tire Parameter";
html += "";
@@ -154,7 +156,8 @@ void webServerSetup(void) {
html += "Accel Parameter";
html += "";
- html += "Search accel | | Search accel | mm | ";
html += "Turn accel | Speed Parameter";
html += "";
- html += "Search speed | | Search speed | mm | ";
html += "max speed | ";
html += " ";
-
html += "";
html += " ";
html += "";
@@ -247,28 +250,27 @@ void webServerSetup(void) {
request->send(200, "text/html", html);
});
- server.on("/voltage", HTTP_GET, [](AsyncWebServerRequest* request) {
+ server.on("/voltage", HTTP_GET, [](AsyncWebServerRequest * request) {
request->send(200, "text/plain", String(g_sensor.battery_value) + "mV");
});
- server.on("/left_value", HTTP_GET, [](AsyncWebServerRequest* request) {
+ server.on("/left_value", HTTP_GET, [](AsyncWebServerRequest * request) {
request->send(200, "text/plain", String(g_sensor.sen_l.value));
});
- server.on("/right_value", HTTP_GET, [](AsyncWebServerRequest* request) {
+ server.on("/right_value", HTTP_GET, [](AsyncWebServerRequest * request) {
request->send(200, "text/plain", String(g_sensor.sen_r.value));
});
- server.on("/left_front_value", HTTP_GET, [](AsyncWebServerRequest* request) {
+ server.on("/left_front_value", HTTP_GET, [](AsyncWebServerRequest * request) {
request->send(200, "text/plain", String(g_sensor.sen_fl.value));
});
- server.on("/right_front_value", HTTP_GET, [](AsyncWebServerRequest* request) {
+ server.on("/right_front_value", HTTP_GET, [](AsyncWebServerRequest * request) {
request->send(200, "text/plain", String(g_sensor.sen_fr.value));
});
-
- server.on("/get", HTTP_GET, [](AsyncWebServerRequest* request) {
+ server.on("/get", HTTP_GET, [](AsyncWebServerRequest * request) {
String inputMessage;
inputMessage = request->getParam("tire_dia")->value();
@@ -309,10 +311,9 @@ void webServerSetup(void) {
inputMessage = request->getParam("max_spd")->value();
g_run.max_speed = inputMessage.toInt();
-
Serial.println("saved");
paramWrite();
- g_run.pulse = g_run.tire_diameter * PI / (35.0 / 10.0 * 20.0 *8.0);
+ g_run.pulse = g_run.tire_diameter * PI / (35.0 / 10.0 * 20.0 * 8.0);
buzzerEnable(INC_FREQ);
delay(30);
From 90573f94f933dad03a058e8c5b75f9d547b89e7b Mon Sep 17 00:00:00 2001
From: masatake aoki
Date: Fri, 18 Apr 2025 14:39:39 +0900
Subject: [PATCH 3/5] change format
---
pico_v2_STEP5_Straight/pico_v2_STEP5_Straight.ino | 5 ++---
pico_v2_STEP5_Straight/run.h | 6 +-----
pico_v2_STEP5_Straight/run.ino | 1 -
pico_v2_STEP6_rotate/pico_v2_STEP6_rotate.ino | 4 ++--
pico_v2_STEP6_rotate/run.h | 5 +----
.../pico_v2_STEP7_P_control.ino | 7 +++----
pico_v2_STEP7_P_control/run.h | 10 ++++------
pico_v2_STEP7_P_control/sensor.h | 10 +++++-----
pico_v2_STEP7_P_control/sensor.ino | 14 ++++----------
pico_v2_STEP8_micromouse/device.ino | 4 ++--
10 files changed, 24 insertions(+), 42 deletions(-)
diff --git a/pico_v2_STEP5_Straight/pico_v2_STEP5_Straight.ino b/pico_v2_STEP5_Straight/pico_v2_STEP5_Straight.ino
index 764ca61..d6060c8 100644
--- a/pico_v2_STEP5_Straight/pico_v2_STEP5_Straight.ino
+++ b/pico_v2_STEP5_Straight/pico_v2_STEP5_Straight.ino
@@ -44,7 +44,6 @@ volatile unsigned int g_step_r, g_step_l;
unsigned short g_step_hz_r = MIN_HZ;
unsigned short g_step_hz_l = MIN_HZ;
-
//割り込み
//目標値の更新周期1kHz
void IRAM_ATTR onTimer0(void)
@@ -94,8 +93,8 @@ void setup()
pinMode(LED2, OUTPUT);
pinMode(LED3, OUTPUT);
- pinMode(SW_L, INPUT_PULLUP);
- pinMode(SW_R, INPUT_PULLUP);
+ pinMode(SW_L, INPUT);
+ pinMode(SW_R, INPUT);
//motor disable
pinMode(MOTOR_EN, OUTPUT);
diff --git a/pico_v2_STEP5_Straight/run.h b/pico_v2_STEP5_Straight/run.h
index 922c1b2..8c4a0b3 100644
--- a/pico_v2_STEP5_Straight/run.h
+++ b/pico_v2_STEP5_Straight/run.h
@@ -15,10 +15,7 @@
#ifndef SRC_RUN_H_
#define SRC_RUN_H_
-typedef enum {
- MOT_FORWARD = 1,
- MOT_BACK = 2
-} t_CW_CCW;
+typedef enum { MOT_FORWARD = 1, MOT_BACK = 2 } t_CW_CCW;
class RUN
{
@@ -29,7 +26,6 @@ class RUN
volatile double max_speed;
volatile double min_speed;
-
RUN();
void interrupt(void);
void counterClear(void);
diff --git a/pico_v2_STEP5_Straight/run.ino b/pico_v2_STEP5_Straight/run.ino
index c28fd19..e21441b 100644
--- a/pico_v2_STEP5_Straight/run.ino
+++ b/pico_v2_STEP5_Straight/run.ino
@@ -37,7 +37,6 @@ void RUN::interrupt(void)
speedSet(speed, speed);
}
-
void RUN::dirSet(t_CW_CCW dir_left, t_CW_CCW dir_right)
{
if (dir_left == MOT_FORWARD) {
diff --git a/pico_v2_STEP6_rotate/pico_v2_STEP6_rotate.ino b/pico_v2_STEP6_rotate/pico_v2_STEP6_rotate.ino
index e6ce33c..ba8469d 100644
--- a/pico_v2_STEP6_rotate/pico_v2_STEP6_rotate.ino
+++ b/pico_v2_STEP6_rotate/pico_v2_STEP6_rotate.ino
@@ -94,8 +94,8 @@ void setup()
pinMode(LED2, OUTPUT);
pinMode(LED3, OUTPUT);
- pinMode(SW_L, INPUT_PULLUP);
- pinMode(SW_R, INPUT_PULLUP);
+ pinMode(SW_L, INPUT);
+ pinMode(SW_R, INPUT);
//motor disable
pinMode(MOTOR_EN, OUTPUT);
diff --git a/pico_v2_STEP6_rotate/run.h b/pico_v2_STEP6_rotate/run.h
index 6b28f76..416c26a 100644
--- a/pico_v2_STEP6_rotate/run.h
+++ b/pico_v2_STEP6_rotate/run.h
@@ -17,10 +17,7 @@
typedef enum { front, right, left, rear } t_local_direction;
-typedef enum {
- MOT_FORWARD = 1,
- MOT_BACK = 2
-} t_CW_CCW;
+typedef enum { MOT_FORWARD = 1, MOT_BACK = 2 } t_CW_CCW;
class RUN
{
diff --git a/pico_v2_STEP7_P_control/pico_v2_STEP7_P_control.ino b/pico_v2_STEP7_P_control/pico_v2_STEP7_P_control.ino
index 98af44c..444a96c 100644
--- a/pico_v2_STEP7_P_control/pico_v2_STEP7_P_control.ino
+++ b/pico_v2_STEP7_P_control/pico_v2_STEP7_P_control.ino
@@ -40,7 +40,7 @@
#define MIN_HZ 40
#define TIRE_DIAMETER (24.70)
-#define PULSE (TIRE_DIAMETER * PI / (35.0 / 10.0 * 20.0 *8.0))
+#define PULSE (TIRE_DIAMETER * PI / (35.0 / 10.0 * 20.0 * 8.0))
#define MIN_SPEED (MIN_HZ * PULSE)
//環境に合わせて変更する
@@ -126,8 +126,8 @@ void setup()
pinMode(LED2, OUTPUT);
pinMode(LED3, OUTPUT);
- pinMode(SW_L, INPUT_PULLUP);
- pinMode(SW_R, INPUT_PULLUP);
+ pinMode(SW_L, INPUT);
+ pinMode(SW_R, INPUT);
//motor disable
pinMode(MOTOR_EN, OUTPUT);
@@ -168,7 +168,6 @@ void setup()
timerAttachInterrupt(g_timer3, &isrL);
timerAlarm(g_timer3, 13333, true, 0); //13333 * 0.5us = 6666us(150Hz)
timerStart(g_timer3);
-
}
void loop()
diff --git a/pico_v2_STEP7_P_control/run.h b/pico_v2_STEP7_P_control/run.h
index 9acbd29..2c68f45 100644
--- a/pico_v2_STEP7_P_control/run.h
+++ b/pico_v2_STEP7_P_control/run.h
@@ -32,20 +32,19 @@ typedef struct
bool enable;
} t_control;
-
typedef enum {
MOT_FORWARD = 1, //TMC5240の方向に合わせた数字
MOT_BACK = 2
} t_CW_CCW;
-class RUN {
+class RUN
+{
private:
-
public:
volatile double accel;
volatile double speed;
volatile double speed_target_r;
- volatile double speed_target_l;
+ volatile double speed_target_l;
volatile double max_speed;
volatile double min_speed;
@@ -64,10 +63,9 @@ class RUN {
void rotate(t_local_direction dir, int times);
private:
- int step_lr_len,step_lr;
+ int step_lr_len, step_lr;
};
-
extern RUN g_run;
#endif /* SRC_RUN_H_ */
\ No newline at end of file
diff --git a/pico_v2_STEP7_P_control/sensor.h b/pico_v2_STEP7_P_control/sensor.h
index 1f7723e..1912ca7 100644
--- a/pico_v2_STEP7_P_control/sensor.h
+++ b/pico_v2_STEP7_P_control/sensor.h
@@ -28,13 +28,13 @@ typedef struct
bool is_control;
} t_sensor;
-
-class SENSOR{
+class SENSOR
+{
public:
SENSOR();
- volatile t_sensor sen_r, sen_l, sen_fr, sen_fl;
- volatile short battery_value;
- void interrupt(void);
+ volatile t_sensor sen_r, sen_l, sen_fr, sen_fl;
+ volatile short battery_value;
+ void interrupt(void);
};
extern SENSOR g_sensor;
diff --git a/pico_v2_STEP7_P_control/sensor.ino b/pico_v2_STEP7_P_control/sensor.ino
index 689e4d2..3083a01 100644
--- a/pico_v2_STEP7_P_control/sensor.ino
+++ b/pico_v2_STEP7_P_control/sensor.ino
@@ -12,13 +12,12 @@
// See the License for the specific language governing permissions and
// limitations under the License.
-
#include "sensor.h"
SENSOR g_sensor;
-
-SENSOR::SENSOR() { //コンストラクタ
+SENSOR::SENSOR()
+{ //コンストラクタ
sen_r.ref = REF_SEN_R;
sen_l.ref = REF_SEN_L;
@@ -31,16 +30,11 @@ SENSOR::SENSOR() { //コンストラクタ
sen_r.th_control = CONTH_SEN_R;
sen_l.th_control = CONTH_SEN_L;
-
-
-}
-
-void sensorInterrupt(void) {
- g_sensor.interrupt();
}
+void sensorInterrupt(void) { g_sensor.interrupt(); }
-void SENSOR::interrupt(void)
+void SENSOR::interrupt(void)
{
static char cnt = 0;
short temp_r, temp_l;
diff --git a/pico_v2_STEP8_micromouse/device.ino b/pico_v2_STEP8_micromouse/device.ino
index 9744ce7..be4e571 100644
--- a/pico_v2_STEP8_micromouse/device.ino
+++ b/pico_v2_STEP8_micromouse/device.ino
@@ -105,8 +105,8 @@ void deviceInit(void)
pinMode(BLED0, OUTPUT);
pinMode(BLED1, OUTPUT);
- pinMode(SW_L, INPUT_PULLUP);
- pinMode(SW_R, INPUT_PULLUP);
+ pinMode(SW_L, INPUT);
+ pinMode(SW_R, INPUT);
ledcAttach(BUZZER, 440, 10);
ledcWrite(BUZZER, 0);
From 8a78e311cbd2ede6ccc79eb2e01a286918c45a00 Mon Sep 17 00:00:00 2001
From: masatake aoki
Date: Fri, 18 Apr 2025 14:44:22 +0900
Subject: [PATCH 4/5] change format
---
pico_v2_STEP2_SWITCH/pico_v2_STEP2_SWITCH.ino | 2 +-
1 file changed, 1 insertion(+), 1 deletion(-)
diff --git a/pico_v2_STEP2_SWITCH/pico_v2_STEP2_SWITCH.ino b/pico_v2_STEP2_SWITCH/pico_v2_STEP2_SWITCH.ino
index fbec9ab..75a9a93 100644
--- a/pico_v2_STEP2_SWITCH/pico_v2_STEP2_SWITCH.ino
+++ b/pico_v2_STEP2_SWITCH/pico_v2_STEP2_SWITCH.ino
@@ -47,7 +47,7 @@ void loop()
}
if (digitalRead(SW_L) == 0) {
digitalWrite(LED2, (++g_state_l) & 0x01);
- digitalWrite(LED1, (g_state_l)&0x01);
+ digitalWrite(LED1, g_state_l & 0x01);
}
delay(30);
while (!(digitalRead(SW_L) && digitalRead(SW_R))) {
From 3861d1c413facfdd16c4321daa23c3e6bc15e905 Mon Sep 17 00:00:00 2001
From: YusukeKato
Date: Fri, 18 Apr 2025 15:08:36 +0900
Subject: [PATCH 5/5] =?UTF-8?q?CI=E3=81=AE=E3=82=B3=E3=83=B3=E3=83=91?=
=?UTF-8?q?=E3=82=A4=E3=83=AB=E3=83=81=E3=82=A7=E3=83=83=E3=82=AF=E3=81=AB?=
=?UTF-8?q?=E3=81=8A=E3=81=91=E3=82=8B=E4=BE=9D=E5=AD=98=E3=83=91=E3=83=83?=
=?UTF-8?q?=E3=82=B1=E3=83=BC=E3=82=B8=E3=82=92=E8=BF=BD=E5=8A=A0?=
MIME-Version: 1.0
Content-Type: text/plain; charset=UTF-8
Content-Transfer-Encoding: 8bit
---
.github/workflows/compile-sketches.yaml | 7 ++++++-
.github/workflows/lint.yaml | 2 +-
2 files changed, 7 insertions(+), 2 deletions(-)
diff --git a/.github/workflows/compile-sketches.yaml b/.github/workflows/compile-sketches.yaml
index 183b97c..0f1f449 100644
--- a/.github/workflows/compile-sketches.yaml
+++ b/.github/workflows/compile-sketches.yaml
@@ -28,7 +28,12 @@ jobs:
platforms: | # ESP32公式のpackage indexを使用する
- name: esp32:esp32
source-url: https://raw.githubusercontent.com/espressif/arduino-esp32/gh-pages/package_esp32_index.json
- version: 3.0.1
+ version: 3.1.1
+ libraries: | # 依存パッケージを指定
+ - name: AsyncTCP
+ source-url: https://github.com/ESP32Async/AsyncTCP.git
+ - name: ESPAsyncWebServer
+ source-url: https://github.com/ESP32Async/ESPAsyncWebServer.git
sketch-paths: |
- pico_v2_STEP1_LED
- pico_v2_STEP2_SWITCH
diff --git a/.github/workflows/lint.yaml b/.github/workflows/lint.yaml
index c6f9e09..13368ed 100644
--- a/.github/workflows/lint.yaml
+++ b/.github/workflows/lint.yaml
@@ -14,7 +14,7 @@ jobs:
runs-on: ubuntu-latest
steps:
- uses: actions/checkout@v4
- - uses: arduino/arduino-lint-action@v1
+ - uses: arduino/arduino-lint-action@v2
with:
recursive: true
compliance: specification
|
---|
|
---|
|
---|