Skip to content

Commit b15fc8e

Browse files
committed
update
1 parent cc50206 commit b15fc8e

37 files changed

+2453
-1381
lines changed

Diff for: README.md

+4-2
Original file line numberDiff line numberDiff line change
@@ -8,8 +8,10 @@
88
Pi:Co V2用のArduinoサンプルスケッチ集です。
99

1010
## 動作環境
11-
12-
- arduino-esp32 : v3.0.1
11+
- Arduino IDE v2.3.4
12+
- arduino-esp32 v3.1.1
13+
- Async TCP 3.3.6
14+
- ESP Async WebServer 3.7.2
1315

1416
## サンプルスケッチについて
1517

Diff for: pico_v2_STEP3_Buzzer/pico_v2_STEP3_Buzzer.ino

+5-5
Original file line numberDiff line numberDiff line change
@@ -31,7 +31,7 @@
3131

3232
char g_mode;
3333

34-
void setLED(char data)
34+
void ledSet(char data)
3535
{
3636
if (data & 0x01) {
3737
digitalWrite(LED0, HIGH);
@@ -55,7 +55,7 @@ void setLED(char data)
5555
}
5656
}
5757

58-
void execByMode(char mode)
58+
void modeExec(char mode)
5959
{
6060
switch (mode) {
6161
case 1:
@@ -94,7 +94,7 @@ void setup()
9494
ledcWrite(BUZZER, 0);
9595

9696
g_mode = 1;
97-
setLED(g_mode);
97+
ledSet(g_mode);
9898
}
9999

100100
void loop()
@@ -112,7 +112,7 @@ void loop()
112112
delay(30);
113113
ledcWrite(BUZZER, 0);
114114
}
115-
setLED(g_mode);
115+
ledSet(g_mode);
116116
}
117117
if (digitalRead(SW_L) == 0) {
118118
ledcWriteTone(BUZZER, INC_FREQ);
@@ -121,7 +121,7 @@ void loop()
121121
delay(80);
122122
ledcWrite(BUZZER, 0);
123123
delay(300);
124-
execByMode(g_mode);
124+
modeExec(g_mode);
125125
}
126126
while (!(digitalRead(SW_L) & digitalRead(SW_R))) {
127127
continue;

Diff for: pico_v2_STEP5_Straight/pico_v2_STEP5_Straight.ino

+9-12
Original file line numberDiff line numberDiff line change
@@ -12,6 +12,8 @@
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
1414

15+
#include "run.h"
16+
1517
#define LED0 42
1618
#define LED1 41
1719
#define LED2 15
@@ -37,16 +39,11 @@ hw_timer_t * g_timer3 = NULL;
3739

3840
portMUX_TYPE g_timer_mux = portMUX_INITIALIZER_UNLOCKED;
3941

42+
volatile bool g_motor_move = 0;
43+
volatile unsigned int g_step_r, g_step_l;
4044
unsigned short g_step_hz_r = MIN_HZ;
4145
unsigned short g_step_hz_l = MIN_HZ;
4246

43-
volatile unsigned int g_step_r, g_step_l;
44-
double g_max_speed;
45-
double g_min_speed;
46-
double g_accel = 0.0;
47-
volatile double g_speed = MIN_SPEED;
48-
49-
volatile bool g_motor_move = 0;
5047

5148
//割り込み
5249
//目標値の更新周期1kHz
@@ -97,8 +94,8 @@ void setup()
9794
pinMode(LED2, OUTPUT);
9895
pinMode(LED3, OUTPUT);
9996

100-
pinMode(SW_L, INPUT);
101-
pinMode(SW_R, INPUT);
97+
pinMode(SW_L, INPUT_PULLUP);
98+
pinMode(SW_R, INPUT_PULLUP);
10299

103100
//motor disable
104101
pinMode(MOTOR_EN, OUTPUT);
@@ -138,12 +135,12 @@ void loop()
138135
digitalWrite(MOTOR_EN, HIGH);
139136
delay(1000);
140137
digitalWrite(LED0, HIGH);
141-
accelerate(45, 200);
138+
g_run.accelerate(45, 200);
142139
digitalWrite(LED1, HIGH);
143140
digitalWrite(LED2, HIGH);
144-
oneStep(90, 200);
141+
g_run.oneStep(90, 200);
145142
digitalWrite(LED3, HIGH);
146-
decelerate(45, 200);
143+
g_run.decelerate(45, 200);
147144
digitalWrite(LED0, LOW);
148145
digitalWrite(LED1, LOW);
149146
digitalWrite(LED2, LOW);

Diff for: pico_v2_STEP5_Straight/run.h

+50
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,50 @@
1+
// Copyright 2023 RT Corporation
2+
//
3+
// Licensed under the Apache License, Version 2.0 (the "License");
4+
// you may not use this file except in compliance with the License.
5+
// You may obtain a copy of the License at
6+
//
7+
// http://www.apache.org/licenses/LICENSE-2.0
8+
//
9+
// Unless required by applicable law or agreed to in writing, software
10+
// distributed under the License is distributed on an "AS IS" BASIS,
11+
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
// See the License for the specific language governing permissions and
13+
// limitations under the License.
14+
15+
#ifndef SRC_RUN_H_
16+
#define SRC_RUN_H_
17+
18+
typedef enum {
19+
MOT_FORWARD = 1,
20+
MOT_BACK = 2
21+
} t_CW_CCW;
22+
23+
class RUN
24+
{
25+
private:
26+
public:
27+
volatile double accel;
28+
volatile double speed;
29+
volatile double max_speed;
30+
volatile double min_speed;
31+
32+
33+
RUN();
34+
void interrupt(void);
35+
void counterClear(void);
36+
void dirSet(t_CW_CCW dir_left, t_CW_CCW dir_right);
37+
void speedSet(double l_speed, double r_speed);
38+
void stepGet(void);
39+
void stop(void);
40+
void accelerate(int len, int finish_speed);
41+
void oneStep(int len, int init_speed);
42+
void decelerate(int len, int init_speed);
43+
44+
private:
45+
int step_lr_len, step_lr;
46+
};
47+
48+
extern RUN g_run;
49+
50+
#endif /* SRC_RUN_H_ */

Diff for: pico_v2_STEP5_Straight/run.ino

+104-36
Original file line numberDiff line numberDiff line change
@@ -12,64 +12,132 @@
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
1414

15-
void accelerate(int len, int tar_speed)
15+
RUN g_run;
16+
17+
RUN::RUN()
18+
{
19+
speed = 0.0;
20+
accel = 0.0;
21+
}
22+
23+
//割り込み
24+
void controlInterrupt(void) { g_run.interrupt(); }
25+
26+
void RUN::interrupt(void)
27+
{ //割り込み内からコール
28+
speed += accel;
29+
30+
if (speed > max_speed) {
31+
speed = max_speed;
32+
}
33+
if (speed < min_speed) {
34+
speed = min_speed;
35+
}
36+
37+
speedSet(speed, speed);
38+
}
39+
40+
41+
void RUN::dirSet(t_CW_CCW dir_left, t_CW_CCW dir_right)
42+
{
43+
if (dir_left == MOT_FORWARD) {
44+
digitalWrite(CW_L, LOW);
45+
} else {
46+
digitalWrite(CW_L, HIGH);
47+
}
48+
if (dir_right == MOT_FORWARD) {
49+
digitalWrite(CW_R, HIGH);
50+
} else {
51+
digitalWrite(CW_R, LOW);
52+
}
53+
}
54+
55+
void RUN::counterClear(void) { g_step_r = g_step_l = 0; }
56+
57+
void RUN::speedSet(double l_speed, double r_speed)
58+
{
59+
g_step_hz_l = (int)(l_speed / PULSE);
60+
g_step_hz_r = (int)(r_speed / PULSE);
61+
}
62+
63+
void RUN::stepGet(void)
64+
{
65+
step_lr = g_step_r + g_step_l;
66+
step_lr_len = (int)((float)step_lr / 2.0 * PULSE);
67+
}
68+
69+
void RUN::stop(void) { g_motor_move = 0; }
70+
71+
void RUN::accelerate(int len, int finish_speed)
1672
{
1773
int obj_step;
18-
g_max_speed = tar_speed;
19-
g_accel = 1.5;
20-
g_step_r = g_step_l = 0;
21-
g_speed = g_min_speed = MIN_SPEED;
22-
g_step_hz_r = g_step_hz_l = (unsigned short)(g_speed / PULSE);
2374

75+
accel = 1.5;
76+
speed = min_speed = MIN_SPEED;
77+
max_speed = finish_speed;
78+
counterClear();
79+
speedSet(speed, speed);
80+
dirSet(MOT_FORWARD, MOT_FORWARD);
2481
obj_step = (int)((float)len * 2.0 / PULSE);
25-
digitalWrite(CW_R, HIGH);
26-
digitalWrite(CW_L, LOW);
2782
g_motor_move = 1;
2883

29-
while ((g_step_r + g_step_l) < obj_step) {
30-
continue;
84+
while (1) {
85+
stepGet();
86+
if (step_lr > obj_step) {
87+
break;
88+
}
3189
}
3290
}
3391

34-
void oneStep(int len, int tar_speed)
92+
void RUN::oneStep(int len, int init_speed)
3593
{
3694
int obj_step;
37-
g_max_speed = tar_speed;
38-
g_accel = 0.0;
39-
g_step_r = g_step_l = 0;
40-
g_speed = g_min_speed = tar_speed;
41-
g_step_hz_r = g_step_hz_l = (unsigned short)(g_speed / PULSE);
95+
96+
accel = 0.0;
97+
max_speed = init_speed;
98+
speed = min_speed = init_speed;
99+
counterClear();
100+
speedSet(init_speed, init_speed);
101+
dirSet(MOT_FORWARD, MOT_FORWARD);
42102
obj_step = (int)((float)len * 2.0 / PULSE);
43-
digitalWrite(CW_R, HIGH);
44-
digitalWrite(CW_L, LOW);
45103

46-
while ((g_step_r + g_step_l) < obj_step) {
47-
continue;
104+
while (1) {
105+
stepGet();
106+
if (step_lr > obj_step) {
107+
break;
108+
}
48109
}
49110
}
50111

51-
void decelerate(int len, int tar_speed)
112+
void RUN::decelerate(int len, int init_speed)
52113
{
53114
int obj_step;
54-
g_max_speed = tar_speed;
55-
g_accel = 0.0;
56-
g_step_r = g_step_l = 0;
57-
g_speed = g_min_speed = tar_speed;
58-
g_step_hz_r = g_step_hz_l = (unsigned short)(g_speed / PULSE);
115+
116+
accel = 1.5;
117+
max_speed = init_speed;
118+
speed = min_speed = init_speed;
119+
counterClear();
120+
speedSet(init_speed, init_speed);
121+
dirSet(MOT_FORWARD, MOT_FORWARD);
59122
obj_step = (int)((float)len * 2.0 / PULSE);
60-
digitalWrite(CW_R, HIGH);
61-
digitalWrite(CW_L, LOW);
62123

63-
while ((len - (g_step_r + g_step_l) / 2.0 * PULSE) >
64-
(((g_speed * g_speed) - (MIN_SPEED * MIN_SPEED)) / (2.0 * 1000.0 * 1.5))) {
65-
continue;
124+
while (1) {
125+
stepGet();
126+
if (
127+
(len - step_lr_len) <
128+
(int)(((speed * speed) - (MIN_SPEED * MIN_SPEED)) / (2.0 * 1000.0 * accel))) {
129+
break;
130+
}
66131
}
67-
g_accel = -1.5;
68-
g_min_speed = MIN_SPEED;
132+
accel = -1.5;
133+
min_speed = MIN_SPEED;
69134

70-
while ((g_step_r + g_step_l) < obj_step) {
71-
continue;
135+
while (1) {
136+
stepGet();
137+
if (step_lr > obj_step) {
138+
break;
139+
}
72140
}
73141

74-
g_motor_move = 0;
142+
stop();
75143
}

0 commit comments

Comments
 (0)