Skip to content

update #10

New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Open
wants to merge 5 commits into
base: main
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension


Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
7 changes: 6 additions & 1 deletion .github/workflows/compile-sketches.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
2 changes: 1 addition & 1 deletion .github/workflows/lint.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
6 changes: 4 additions & 2 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -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

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

Expand Down
2 changes: 1 addition & 1 deletion pico_v2_STEP2_SWITCH/pico_v2_STEP2_SWITCH.ino
Original file line number Diff line number Diff line change
Expand Up @@ -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))) {
Expand Down
10 changes: 5 additions & 5 deletions pico_v2_STEP3_Buzzer/pico_v2_STEP3_Buzzer.ino
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,7 @@

char g_mode;

void setLED(char data)
void ledSet(char data)
{
if (data & 0x01) {
digitalWrite(LED0, HIGH);
Expand All @@ -55,7 +55,7 @@ void setLED(char data)
}
}

void execByMode(char mode)
void modeExec(char mode)
{
switch (mode) {
case 1:
Expand Down Expand Up @@ -94,7 +94,7 @@ void setup()
ledcWrite(BUZZER, 0);

g_mode = 1;
setLED(g_mode);
ledSet(g_mode);
}

void loop()
Expand All @@ -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);
Expand All @@ -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;
Expand Down
18 changes: 7 additions & 11 deletions pico_v2_STEP5_Straight/pico_v2_STEP5_Straight.ino
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand All @@ -37,17 +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
void IRAM_ATTR onTimer0(void)
Expand Down Expand Up @@ -138,12 +134,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);
Expand Down
46 changes: 46 additions & 0 deletions pico_v2_STEP5_Straight/run.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,46 @@
// 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_ */
139 changes: 103 additions & 36 deletions pico_v2_STEP5_Straight/run.ino
Original file line number Diff line number Diff line change
Expand Up @@ -12,64 +12,131 @@
// 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();
}
Loading
Loading