roundly migrated.

This commit is contained in:
Dooho Yi 2021-02-17 17:55:10 +09:00
parent 3bf8314f2e
commit c1a471b6bb
3 changed files with 273 additions and 396 deletions

16
post.h
View file

@ -44,6 +44,7 @@ struct AddressBook {
//
list.push_back(Address(0xB4, 0xE6, 0x2D, 0x37, 0x3B, 0x90, "root/osc"));
list.push_back(Address(0xF4, 0xCF, 0xA2, 0xED, 0xB4, 0x28, "taak/157"));
list.push_back(Address(0xF4, 0xCF, 0xA2, 0xED, 0xB8, 0x1E, "roundly/202"));
//
}
//
@ -55,8 +56,8 @@ struct AddressBook {
//
list.setStorage(lst);
//
if (booktitle == "YELLOW") {
;
if (booktitle == "root") {
list.push_back(Address(0xB4, 0xE6, 0x2D, 0x37, 0x3B, 0x90, "root/osc"));
}
}
private:
@ -115,4 +116,15 @@ struct Hello {
h3 = 0;
h4 = 0;
}
//
String to_string() {
String str = "";
str += "( id=" + String(id);
str += ", h1=" + String(h1);
str += ", h2=" + String(h2);
str += ", h3=" + String(h3);
str += ", h4=" + String(h4);
str += " )";
return str;
}
};

View file

@ -1,47 +1,44 @@
; PlatformIO Project Configuration File
;
; Build options: build flags, source filter
; Upload options: custom upload port, speed and extra flags
; Library options: dependencies, extra library storages
; Advanced options: extra scripting
;
; Please visit documentation for the other options and examples
; https://docs.platformio.org/page/projectconf.html
; < NOTE >
; to enable verbose output add option -->
; $ platformio run --verbose
; to make this permanent for the proj. -->
; $ platformio settings set force_verbose Yes
; then confirm the change -->
; $ platformio settings get
; // pio v 4.0 'Build options'
; - build_type
; - build_flags
; - src_build_flags
; - build_unflags
; - src_filter
; - targets
[platformio]
default_envs = d1_mini_pro
[env]
framework = arduino
upload_speed = 921600
upload_port =
/dev/ttyUSB0
/dev/tty.SLAB_USBtoUART
upload_port = /dev/ttyUSB0
lib_deps =
SPI
Wire
64
1269
265
5825 ; Vector
721 ; TaskScheduler
[env:nodemcuv2]
platform = espressif8266
board = nodemcuv2
lib_deps =
${env.lib_deps}
ESP8266WiFi
upload_speed = 921600 ; 9600, 19200, 38400, 57600, 115200, 230400, 460800, 921600
[env:d1_mini_pro]
platform = espressif8266
board = d1_mini_pro
lib_deps =
${env.lib_deps}
ESP8266WiFi
upload_speed = 460800
[env:nanoatmega328_TEST]
platform = atmelavr
board = nanoatmega328
lib_deps =
265
upload_speed = 57600
upload_speed = 460800 ; 9600, 19200, 38400, 57600, 115200, 230400, 460800, 921600

View file

@ -1,43 +1,45 @@
//
// wirelessly connected cloud (Wireless Mesh Networking)
// MIDI-like
// spacial
// wirelessly connected cloud (based on ESP-NOW, a kind of LPWAN?)
//
//
// conversation on the ROOT @ SEMA, Seoul
// Conversation about the ROOT @ SEMA warehouses, Seoul
//
//
// 2020 10 14
// 2021 02 15
//
//==========<configurations>===========
//
// 'HAVE_CLIENT'
// --> i have a client. enable the client task.
//
// 'SERIAL_SWAP'
// --> UART pin swapped.
// you want this, when you want a bi-directional comm. to external client boards (e.g. teensy).
//
// 'DISABLE_AP'
// --> disabling AP is for teensy audio samplers.
// they need this to reduce noise from AP beacon signals.
// but, then they cannot build-up net. by themselves.
// we need who can do AP..
// ==> TODO! just prepare some 'dummy' postmans around. w/ AP activated.
//
// 'DISABLE_I2C_REQ'
// --> a quirk.. due to bi-directional I2C hardship.
// ideally, we want to make this sampler node also speak.
// but, I2C doesn't work. maybe middleware bug.. we later want to change to diff. proto.
// for example, UART or so.
// ==> BEWARE! yet, still we need to take off this.. for 'osc' node.
//
// 'SET_ROOT'
// 'SET_CONTAINSROOT'
// --> for the network stability
// declare 1 root node and branches(constricted to 'contains the root')
// to improve the stability of the net
// --> (questioning)...
//
//==========</configurations>==========
//==========<preset>===========
#define SET_CONTAINSROOT
//
// (1) standalone
#if 1
// (2) osc client (the ROOT)
#elif 0
#define SERIAL_SWAP
#define HAVE_CLIENT
// (3) sampler client
#elif 0
#define SERIAL_SWAP
#define HAVE_CLIENT
#define DISABLE_AP
//
#endif
//
//==========</preset>==========
//============<list of reserved keys>============
@ -56,112 +58,52 @@
//============</identity key>===========
//============<parameters>============
#define MESH_SSID "forest-all/around"
#define MESH_PASSWORD "cc*vvvv/kkk"
#define MESH_PORT 5555
#define MESH_CHANNEL 5
#define LONELY_TO_DIE (1000)
//
#define LED_PERIOD (11111)
#define LED_ONTIME (1)
#define LED_GAPTIME (222)
//
#define WIFI_CHANNEL 5
//
// 'MONITORING_SERIAL'
//
// --> sometimes, the 'Serial' is in use (for example, 'osc' node)
// then, use 'Serial1' - D4/GPIO2/TDX1 @ nodemcu (this is TX only.)
//
// --> otherwise, MONITORING_SERIAL == Serial.
//
#if defined(SERIAL_SWAP)
#define MONITORING_SERIAL (Serial1)
#else
#define MONITORING_SERIAL (Serial)
#endif
//
//============</parameters>===========
//
// LED status indication
// phase 0
// - LED => steady on
// - booted. and running. no connection. scanning.
// phase 1
// - LED => slow blinking (syncronized)
// - + connected.
//
#if defined(ARDUINO_ESP8266_NODEMCU) // nodemcuv2
#define LED_PIN 2
#elif defined(ARDUINO_ESP8266_WEMOS_D1MINIPRO) // d1_mini_pro
#define LED_PIN 2
#elif defined(ARDUINO_ESP8266_ESP12) // huzzah
#define LED_PIN 2
#elif defined(ARDUINO_FEATHER_ESP32) // featheresp32
//============<board-specifics>============
#if defined(ARDUINO_FEATHER_ESP32) // featheresp32
#define LED_PIN 13
#elif defined(ARDUINO_NodeMCU_32S) // nodemcu-32s
#define LED_PIN 2
#elif defined(ARDUINO_ESP32_DEV) // esp32doit-devkit-v1
#else
#define LED_PIN 2
#endif
#define LED_PERIOD (1111)
#define LED_ONTIME (1)
//============</board-specifics>===========
//arduino
#include <Arduino.h>
//i2c
#include <Wire.h>
//post & addresses
#include "../../post.h"
AddressBook members;
//painlessmesh
#include <painlessMesh.h>
painlessMesh mesh;
//espnow
#include <ESP8266WiFi.h>
#include <espnow.h>
//scheduler
//task
#include <TaskScheduler.h>
Scheduler runner;
//task #0 : connection indicator
bool onFlag = false;
bool isConnected = false;
//prototypes
void taskStatusBlink_steadyOn();
void taskStatusBlink_slowblink_insync();
void taskStatusBlink_steadyOff();
//the task
Task statusblinks(0, 1, &taskStatusBlink_steadyOn); // at start, steady on. default == disabled. ==> setup() will enable.
// when disconnected, and trying, steadyon.
void taskStatusBlink_steadyOn() {
onFlag = true;
}
// when connected, blink per 1s. sync-ed. (== default configuration)
void taskStatusBlink_slowblink_insync() {
// toggler
onFlag = !onFlag;
// on-time
statusblinks.delay(LED_ONTIME);
// re-enable & sync.
if (statusblinks.isLastIteration()) {
statusblinks.setIterations(2); //refill iteration counts
statusblinks.enableDelayed(LED_PERIOD - (mesh.getNodeTime() % (LED_PERIOD*1000))/1000); //re-enable with sync-ed delay
}
}
// when connected, steadyoff. (== alternative configuration)
void taskStatusBlink_steadyOff() {
onFlag = false;
}
//task #1 : happy or lonely
// --> automatic reset after some time of 'loneliness (disconnected from any node)'
void nothappyalone() {
static bool isConnected_prev = false;
static unsigned long lonely_time_start = 0;
// oh.. i m lost the signal(==connection)
if (isConnected_prev != isConnected && isConnected == false) {
lonely_time_start = millis();
Serial.println("oh.. i m lost!");
}
// .... how long we've been lonely?
if (isConnected == false) {
if (millis() - lonely_time_start > LONELY_TO_DIE) {
// okay. i m fed up. bye the world.
Serial.println("okay. i m fed up. bye the world.");
Serial.println();
#if defined(ESP8266)
ESP.reset();
#else
#error unknown esp.
#endif
}
}
//
isConnected_prev = isConnected;
}
// Task nothappyalone_task(1000, TASK_FOREVER, &nothappyalone, &runner, true); // by default, ENABLED.
Task nothappyalone_task(100, TASK_FOREVER, &nothappyalone); // by default, ENABLED.
//
//-*-*-*-*-*-*-*-*-*-*-*-*-
#include <AccelStepper.h>
#define STEP_MODE_CONSTANT_VEL (0xDE00 + 0x01)
#define STEP_MODE_ACCELERATING (0xDE00 + 0x02)
@ -199,14 +141,14 @@ void stepping() {
float velocity = steps / dur * 1000; // unit conv.: (steps/msec) --> (steps/sec)
float speed = fabs(velocity);
//
Serial.print("target_step --> "); Serial.println(target_step);
Serial.print("dur --> "); Serial.println(dur);
Serial.print("cur_step --> "); Serial.println(cur_step);
MONITORING_SERIAL.print("target_step --> "); MONITORING_SERIAL.println(target_step);
MONITORING_SERIAL.print("dur --> "); MONITORING_SERIAL.println(dur);
MONITORING_SERIAL.print("cur_step --> "); MONITORING_SERIAL.println(cur_step);
//
if (speed > STEPS_PER_SEC_MAX) {
Serial.println("oh.. it might be TOO FAST for me..");
MONITORING_SERIAL.println("oh.. it might be TOO FAST for me..");
} else {
Serial.println("okay. i m going.");
MONITORING_SERIAL.println("okay. i m going.");
}
//
@ -228,286 +170,212 @@ void rest() {
}
}
Task rest_task(1000, TASK_FOREVER, &rest);
//sendhello - with 4 int // up to 6 letters for each
void sendhello (int hey0 = 0, int hey1 = 0, int hey2 = 0, int hey3 = 0) {
char msg_cstr[32+1] = "{/././././././././././././././.}";
snprintf(msg_cstr, 32+1, "{%03dA%06d%06d%06d%06d__}", ID_KEY, hey0, hey1, hey2, hey3);
mesh.sendBroadcast(String(msg_cstr));
}
//
String letter_ps = "00";
//*-*-*-*-*-*-*-*-*-*-*-*-*
//
extern Task hello_task;
static int hello_delay = 0;
void hello() {
//
sendhello(
Hello hello = {
ID_KEY,
stepper.currentPosition(),
stepper.distanceToGo(),
stepper.distanceToGo(),
stepper.distanceToGo()
);
};
//
int ps_int = letter_ps.toInt();
if (ps_int > 0) {
hello_task.restartDelayed(ps_int * 100);
uint8_t frm_size = sizeof(Hello) + 2;
uint8_t frm[frm_size];
frm[0] = '{';
memcpy(frm + 1, (uint8_t *) &hello, sizeof(Hello));
frm[frm_size - 1] = '}';
//
//pseudo-broadcast using peer-list!
//
esp_now_send(AddressBook("root").list[0].mac, frm, frm_size);
//
MONITORING_SERIAL.write(frm, frm_size);
MONITORING_SERIAL.println(" ==(esp_now_send/\"root\")==> ");
//
if (hello_delay > 0) {
if (hello_delay < 100) hello_delay = 100;
hello_task.restartDelayed(hello_delay);
}
}
Task hello_task(0, TASK_ONCE, &hello);
// mesh callbacks
void receivedCallback(uint32_t from, String & msg) { // REQUIRED
Serial.print("got msg.: ");
Serial.println(msg);
//parse now.
String str_type = msg.substring(0, 1);
// [letter...] >>> START
if (str_type == "[") {
//parse letter string.
// letter frame ( '[' + 30 bytes + ']' )
// : [123456789012345678901234567890]
// 'MIDI' letter frame
// : [123456789012345678901234567890]
// : [KKKVVVG.......................]
// : KKK - Key
// .substring(1, 4);
// : VVV - Velocity (volume/amp.)
// .substring(4, 7);
// : G - Gate (note on/off)
// .substring(7, 8);
String str_key = msg.substring(1, 4);
String str_velocity = msg.substring(4, 7);
String str_gate = msg.substring(7, 8);
int key = str_key.toInt();
int velocity = str_velocity.toInt(); // 0 ~ 127
int gate = str_gate.toInt();
//task #0 : blink led
extern Task blink_task;
void blink() {
//
static int count = 0;
count++;
//
switch (count % 4) {
case 0:
digitalWrite(LED_PIN, LOW); // first ON
blink_task.delay(LED_ONTIME);
break;
case 1:
digitalWrite(LED_PIN, HIGH); // first OFF
blink_task.delay(LED_GAPTIME);
break;
case 2:
digitalWrite(LED_PIN, LOW); // second ON
blink_task.delay(LED_ONTIME);
break;
case 3:
digitalWrite(LED_PIN, HIGH); // second OFF
blink_task.delay(LED_PERIOD - 2* LED_ONTIME - LED_GAPTIME);
break;
}
}
Task blink_task(0, TASK_FOREVER, &blink, &runner, true); // -> ENABLED, at start-up.
// on 'Note'
void onNoteHandler(Note & n) {
//is it for me?
if (key == ID_KEY) {
// : [_______X......................]
// : X - Extension starter 'X'
// .substring(8, 9);
// Extension (X == 'X')
// : [_______X11111222223333344444PS]
// : 1 - data of 5 letters
// .substring(9, 14);
// : 2 - data of 5 letters
// .substring(14, 19);
// : 3 - data of 5 letters
// .substring(19, 24);
// : 4 - data of 5 letters
// .substring(24, 29);
// : PS - 2 letter
// .substring(29, 31);
String str_ext = msg.substring(8, 9);
if (n.pitch == ID_KEY) {
//
String str_x1 = msg.substring(9, 14);
String str_x2 = msg.substring(14, 19);
String str_x3 = msg.substring(19, 24);
String str_x4 = msg.substring(24, 29);
// p. s.
letter_ps = msg.substring(29, 31);
if (letter_ps.toInt() > 0) {
hello_task.restartDelayed(10);
}
if (str_ext == "X") {
int step_target_multiplier = str_x3.toInt(); // -99 ~ 999
step_target = str_x1.toInt() * step_target_multiplier; // -999 ~ 9999 * -99 ~ 999
step_duration = str_x2.toInt(); // -999 ~ 9999
}
step_target = n.x1 * n.x3;
step_duration = n.x2;
//
if (gate == 1) {
hello_delay = n.ps;
if (hello_delay != 0 && hello_task.isEnabled() == false) {
hello_task.restart();
}
//
if (n.onoff == 1) {
stepping_task.restartDelayed(10);
} else if (gate == 0) {
} else if (n.onoff == 0) {
rest_task.restartDelayed(10);
}
}
}
//END <<< [letter...]
//{hello...} >>> START
else if (str_type == "{") {
// hello frame ( '{' + 30 bytes + '}' )
// : {123456789012345678901234567890}
// hello frame
// : {123456789012345678901234567890}
// : {IIIA111111222222333333444444__}
// : III - ID_KEY
// .substring(1, 4);
// : 1 - data of 6 letters
// .substring(9, 14);
// : 2 - data of 6 letters
// .substring(14, 19);
// : 3 - data of 6 letters
// .substring(19, 24);
// : 4 - data of 6 letters
// .substring(24, 29);
// received a hello.
String str_id = msg.substring(1, 4);
int id = str_id.toInt();
//is it for me?
if (id == ID_KEY) {
//
String str_aa = msg.substring(4, 5);
//
String str_h1 = msg.substring(5, 11);
String str_h2 = msg.substring(11, 17);
String str_h3 = msg.substring(17, 23);
String str_h4 = msg.substring(23, 29);
//
if (str_aa == "A") {
}
}
}
//END <<< {hello...}
}
void changedConnectionCallback() {
Serial.println(mesh.getNodeList().size());
// check status -> modify status LED
if (mesh.getNodeList().size() > 0) {
// (still) connected.
onFlag = false; //reset flag stat.
statusblinks.set(LED_PERIOD, 2, &taskStatusBlink_slowblink_insync);
// statusblinks.set(0, 1, &taskStatusBlink_steadyOff);
statusblinks.enable();
Serial.println("connected!");
//
isConnected = true;
runner.addTask(nothappyalone_task);
nothappyalone_task.enable();
}
else {
// disconnected!!
statusblinks.set(0, 1, &taskStatusBlink_steadyOn);
statusblinks.enable();
//
isConnected = false;
}
// let I2C device know
/////
Serial.println("hi. client, we ve got a change in the net.");
}
void newConnectionCallback(uint32_t nodeId) {
Serial.println(mesh.getNodeList().size());
Serial.println("newConnectionCallback.");
changedConnectionCallback();
}
// on 'receive'
void onDataReceive(uint8_t * mac, uint8_t *incomingData, uint8_t len) {
#if defined(HAVE_CLIENT)
Serial.write(incomingData, len); // we share it w/ the client.
#endif
// on 'Note'
if (incomingData[0] == '[' && incomingData[len - 1] == ']' && len == (sizeof(Note) + 2)) {
//
Note note;
memcpy((uint8_t *) &note, incomingData + 1, sizeof(Note));
onNoteHandler(note);
MONITORING_SERIAL.println(note.to_string());
}
}
// on 'sent'
void onDataSent(uint8_t *mac_addr, uint8_t sendStatus) {
if (sendStatus != 0) MONITORING_SERIAL.println("Delivery failed!");
}
//
void setup() {
//led
pinMode(LED_PIN, OUTPUT);
//mesh
//serial
Serial.begin(115200);
delay(100);
//info
Serial.println();
Serial.println();
Serial.println("\"hi, i m your postman.\"");
Serial.println("-");
Serial.println("- * info >>>");
#if defined(ID_KEY)
Serial.println("- identity (key): " + String(ID_KEY));
#endif
Serial.println("- mac address: " + WiFi.macAddress());
Serial.println("- wifi channel: " + String(WIFI_CHANNEL));
Serial.println("-");
Serial.println("- * conf >>>");
#if defined(HAVE_CLIENT)
Serial.println("- ======== 'HAVE_CLIENT' ========");
#endif
#if defined(SERIAL_SWAP)
Serial.println("- ======== 'SERIAL_SWAP' ========");
#endif
#if defined(DISABLE_AP)
Serial.println("- ======== 'DISABLE_AP' ========");
#endif
Serial.println("-");
Serial.println("- * addresses >>>");
for (uint32_t i = 0; i < members.list.size(); i++) {
Serial.print("- #" + String(i) + " : ");
Serial.print(members.list[i].mac[0], HEX);
for (int j = 1; j < 6; j++) {
Serial.print(":");
Serial.print(members.list[i].mac[j], HEX);
}
Serial.print(" ==> " + members.list[i].name);
Serial.println();
}
Serial.println("-");
Serial.println("\".-.-.-. :)\"");
Serial.println();
//wifi
WiFiMode_t node_type = WIFI_AP_STA;
#if defined(DISABLE_AP)
system_phy_set_max_tpw(0);
node_type = WIFI_STA;
#endif
// mesh.setDebugMsgTypes(ERROR | DEBUG | CONNECTION);
mesh.setDebugMsgTypes( ERROR | STARTUP );
mesh.init(MESH_SSID, MESH_PASSWORD, &runner, MESH_PORT, node_type, MESH_CHANNEL);
WiFi.mode(node_type);
//
// void init(String ssid, String password, Scheduler *baseScheduler, uint16_t port = 5555, WiFiMode_t connectMode = WIFI_AP_STA, uint8_t channel = 1, uint8_t hidden = 0, uint8_t maxconn = MAX_CONN);
// void init(String ssid, String password, uint16_t port = 5555, WiFiMode_t connectMode = WIFI_AP_STA, uint8_t channel = 1, uint8_t hidden = 0, uint8_t maxconn = MAX_CONN);
//
#if defined(SET_ROOT)
mesh.setRoot(true);
#endif
#if defined(SET_CONTAINSROOT)
mesh.setContainsRoot(true);
#endif
//callbacks
mesh.onReceive(&receivedCallback);
mesh.onNewConnection(&newConnectionCallback);
mesh.onChangedConnections(&changedConnectionCallback);
Serial.println(mesh.getNodeList().size());
//tasks
runner.addTask(statusblinks);
statusblinks.enable();
//serial
Serial.begin(115200);
delay(100);
Serial.println("hi, postman ready.");
#if defined(DISABLE_AP)
Serial.println("!NOTE!: we are in the WIFI_STA mode!");
#endif
//understanding what is 'the nodeId' ==> last 4 bytes of 'softAPmacAddress'
// uint32_t nodeId = tcp::encodeNodeId(MAC);
Serial.print("nodeId (dec) : ");
Serial.println(mesh.getNodeId(), DEC);
Serial.print("nodeId (hex) : ");
Serial.println(mesh.getNodeId(), HEX);
uint8_t MAC[] = {0, 0, 0, 0, 0, 0};
if (WiFi.softAPmacAddress(MAC) == 0) {
Serial.println("init(): WiFi.softAPmacAddress(MAC) failed.");
//esp-now
if (esp_now_init() != 0) {
Serial.println("Error initializing ESP-NOW");
return;
}
esp_now_set_self_role(ESP_NOW_ROLE_COMBO);
esp_now_register_send_cb(onDataSent);
esp_now_register_recv_cb(onDataReceive);
for (uint32_t i = 0; i < members.list.size(); i++) {
esp_now_add_peer(members.list[i].mac, ESP_NOW_ROLE_COMBO, 1, NULL, 0); // <-- '1' : "Channel does not affect any function" ... *.-a
//
// int esp_now_add_peer(u8 *mac_addr, u8 role, u8 channel, u8 *key, u8 key_len)
// - https://www.espressif.com/sites/default/files/documentation/2c-esp8266_non_os_sdk_api_reference_en.pdf
//
// "Channel does not affect any function, but only stores the channel information
// for the application layer. The value is defined by the application layer. For
// example, 0 means that the channel is not defined; 1 ~ 14 mean valid
// channels; all the rest values can be assigned functions that are specified
// by the application layer."
// - https://www.espressif.com/sites/default/files/documentation/esp-now_user_guide_en.pdf
}
Serial.print("MAC : ");
Serial.print(MAC[0], HEX); Serial.print(", ");
Serial.print(MAC[1], HEX); Serial.print(", ");
Serial.print(MAC[2], HEX); Serial.print(", ");
Serial.print(MAC[3], HEX); Serial.print(", ");
Serial.print(MAC[4], HEX); Serial.print(", ");
Serial.println(MAC[5], HEX);
// for instance,
#if defined(SERIAL_SWAP)
Serial.println("- ======== 'SERIAL_SWAP' ========");
// a proper say goodbye.
Serial.println("\"bye, i will do 'swap' in 1 second. find me on alternative pins!\"");
Serial.println("\" hint: osc wiring ==> esp8266(serial.swap) <-> teensy(serial3)\"");
Serial.println("-");
Serial.println("\".-.-.-. :)\"");
delay(1000); // flush out unsent serial messages.
// a huzzah board
// nodeId (dec) : 3256120530
// nodeId (hex) : C21474D2
// MAC : BE, DD, C2, 14, 74, D2
// a esp8266 board (node mcu)
// nodeId (dec) : 758581767
// nodeId (hex) : 2D370A07
// MAC : B6, E6, 2D, 37, A, 7
//introduction
Serial.print("my ID Key --> ");
Serial.println(ID_KEY);
//i2c master
Wire.begin();
// moving...
Serial.swap(); // use RXD2/TXD2 pins, afterwards.
delay(100); // wait re-initialization of the 'Serial'
#endif
//random seed
randomSeed(analogRead(0));
//stepper
// pinMode(D1, OUTPUT);
// pinMode(D2, OUTPUT);
// pinMode(D3, OUTPUT);
// pinMode(D4, OUTPUT);
/// "
/// The fastest motor speed that can be reliably supported is about 4000 steps per
/// second at a clock frequency of 16 MHz on Arduino such as Uno etc.
/// " @ AccelStepper.h
// "The fastest motor speed that can be reliably supported is about 4000 steps per
// second at a clock frequency of 16 MHz on Arduino such as Uno etc."
// @ AccelStepper.h
stepper.setMaxSpeed(STEPS_PER_SEC_MAX); //steps per second (trade-off between speed vs. torque)
#if (STEP_MODE == STEP_MODE_ACCELERATING)
stepper.setAcceleration(ACCELERATION_MAX);
@ -522,9 +390,9 @@ void setup() {
}
void loop() {
//
runner.execute();
mesh.update();
digitalWrite(LED_PIN, !onFlag); // value == false is ON. so onFlag == true is ON. (pull-up)
//
//stepper
if (stepper.distanceToGo() != 0) {