pull.. old proj. li_li_li_li_li_li as a starting point.
This commit is contained in:
parent
14a39eda33
commit
acbbf6aa69
16 changed files with 1206 additions and 485 deletions
45
.gitignore
vendored
45
.gitignore
vendored
|
|
@ -1 +1,44 @@
|
||||||
.pio
|
# Prerequisites
|
||||||
|
*.d
|
||||||
|
|
||||||
|
# Compiled Object files
|
||||||
|
*.slo
|
||||||
|
*.lo
|
||||||
|
*.o
|
||||||
|
*.obj
|
||||||
|
|
||||||
|
# Precompiled Headers
|
||||||
|
*.gch
|
||||||
|
*.pch
|
||||||
|
|
||||||
|
# Compiled Dynamic libraries
|
||||||
|
*.so
|
||||||
|
*.dylib
|
||||||
|
*.dll
|
||||||
|
|
||||||
|
# Fortran module files
|
||||||
|
*.mod
|
||||||
|
*.smod
|
||||||
|
|
||||||
|
# Compiled Static libraries
|
||||||
|
*.lai
|
||||||
|
*.la
|
||||||
|
*.a
|
||||||
|
*.lib
|
||||||
|
|
||||||
|
# Executables
|
||||||
|
*.exe
|
||||||
|
*.out
|
||||||
|
*.app
|
||||||
|
|
||||||
|
# esp-idf / CMake
|
||||||
|
# build/*
|
||||||
|
|
||||||
|
# platformio
|
||||||
|
.DS_Store
|
||||||
|
*/.DS_Store
|
||||||
|
.travis.yml
|
||||||
|
.pio/
|
||||||
|
.pio/*
|
||||||
|
members/*/.pio/
|
||||||
|
members/*/.pio/*
|
||||||
|
|
|
||||||
67
.travis.yml
67
.travis.yml
|
|
@ -1,67 +0,0 @@
|
||||||
# Continuous Integration (CI) is the practice, in software
|
|
||||||
# engineering, of merging all developer working copies with a shared mainline
|
|
||||||
# several times a day < https://docs.platformio.org/page/ci/index.html >
|
|
||||||
#
|
|
||||||
# Documentation:
|
|
||||||
#
|
|
||||||
# * Travis CI Embedded Builds with PlatformIO
|
|
||||||
# < https://docs.travis-ci.com/user/integration/platformio/ >
|
|
||||||
#
|
|
||||||
# * PlatformIO integration with Travis CI
|
|
||||||
# < https://docs.platformio.org/page/ci/travis.html >
|
|
||||||
#
|
|
||||||
# * User Guide for `platformio ci` command
|
|
||||||
# < https://docs.platformio.org/page/userguide/cmd_ci.html >
|
|
||||||
#
|
|
||||||
#
|
|
||||||
# Please choose one of the following templates (proposed below) and uncomment
|
|
||||||
# it (remove "# " before each line) or use own configuration according to the
|
|
||||||
# Travis CI documentation (see above).
|
|
||||||
#
|
|
||||||
|
|
||||||
|
|
||||||
#
|
|
||||||
# Template #1: General project. Test it using existing `platformio.ini`.
|
|
||||||
#
|
|
||||||
|
|
||||||
# language: python
|
|
||||||
# python:
|
|
||||||
# - "2.7"
|
|
||||||
#
|
|
||||||
# sudo: false
|
|
||||||
# cache:
|
|
||||||
# directories:
|
|
||||||
# - "~/.platformio"
|
|
||||||
#
|
|
||||||
# install:
|
|
||||||
# - pip install -U platformio
|
|
||||||
# - platformio update
|
|
||||||
#
|
|
||||||
# script:
|
|
||||||
# - platformio run
|
|
||||||
|
|
||||||
|
|
||||||
#
|
|
||||||
# Template #2: The project is intended to be used as a library with examples.
|
|
||||||
#
|
|
||||||
|
|
||||||
# language: python
|
|
||||||
# python:
|
|
||||||
# - "2.7"
|
|
||||||
#
|
|
||||||
# sudo: false
|
|
||||||
# cache:
|
|
||||||
# directories:
|
|
||||||
# - "~/.platformio"
|
|
||||||
#
|
|
||||||
# env:
|
|
||||||
# - PLATFORMIO_CI_SRC=path/to/test/file.c
|
|
||||||
# - PLATFORMIO_CI_SRC=examples/file.ino
|
|
||||||
# - PLATFORMIO_CI_SRC=path/to/test/directory
|
|
||||||
#
|
|
||||||
# install:
|
|
||||||
# - pip install -U platformio
|
|
||||||
# - platformio update
|
|
||||||
#
|
|
||||||
# script:
|
|
||||||
# - platformio ci --lib="." --board=ID_1 --board=ID_2 --board=ID_N
|
|
||||||
2
LICENSE
2
LICENSE
|
|
@ -21,4 +21,4 @@ OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE,
|
||||||
ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR
|
ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR
|
||||||
OTHER DEALINGS IN THE SOFTWARE.
|
OTHER DEALINGS IN THE SOFTWARE.
|
||||||
|
|
||||||
For more information, please refer to <https://unlicense.org>
|
For more information, please refer to <http://unlicense.org>
|
||||||
|
|
|
||||||
105
README.md
105
README.md
|
|
@ -1,99 +1,20 @@
|
||||||
# crickets - wireless mesh sound device
|
# li_li_li_li_li_li for cosmo40 performance
|
||||||
|
|
||||||
## esp8266 or esp32 based WMN
|
## platformio
|
||||||
|
|
||||||
## (optional) teensy35/36 or arduino nano.. by i2c comm.
|
## small IoT objects in the wireless mesh network
|
||||||
|
|
||||||
### some cricket use only espX.. + motor or relay etc..
|
### forked from the repository 'darker-than-the-navel-mesh'
|
||||||
|
|
||||||
espX 단계에서는.. json으로 대화를 한다.
|
## members
|
||||||
어차피 painlessmesh 도 그렇고. 문자열기반이므로, 이부분 어렵지 않음.
|
|
||||||
나중에 어떤 espX 한대가 중계기가 되는 경우 브라우져의 js 에 연결도 스무쓰해서 좋다.
|
|
||||||
|
|
||||||
그런데, teensy 가 있는 경우에는..
|
- 6 (six) speakers (behaviours: 'voice', 'fall', 'animal', etc..)
|
||||||
즉, sampler 인 경우에는.. 뭔가 컨트롤이 오고 갈 필요가 있는데..
|
- 1 or more (one) gas-tank
|
||||||
이 컨트롤은 지금까지.. i2c를 써왔었는데.
|
|
||||||
i2c는 커멘드의 구조를 매번 잡아야하고 이런저런 것들이 불편하다.
|
|
||||||
좀더 유연한 통신을 원하는 것 같기도 하다. 양방향시리얼통신이라던가.. (uart)
|
|
||||||
|
|
||||||
또한, 지금 UI를 짜는 경우에.. 즉 브라우져 말고.. 디스플레이중심장치말고. 좀더 연주중심장치를 인터페이스 그니까, 오르가넬레 / pd 연결하는 경우에
|
- ?? 1 (one) trunk
|
||||||
osc 가 가장 유력한데
|
- ?? 1 (one) drum
|
||||||
그런경우에 어떤 espX 는 osc를 보내주면 좋겠다.. 라는 바램이 있긴하다.
|
- ?? 1 (one) reel-deck
|
||||||
serialize가 된다면 어떤 메세지던 상관없다 매쉬입장에서는..
|
- ?? 1 (one) float <=== Adafruit Huzzah : append '-e huzzah'
|
||||||
그렇다면, 애초에.. json을 하지 말고. osc를 주고 받게 할 수도 있지 않을까? espX 단부터..
|
|
||||||
브라우져도 osc.js 가 있기때문에 인터페이스할수있고..
|
|
||||||
이렇게 되면 teensy도 CNMAT OSC 가 있고.. espX 도 같은 라이브러리가 서포트 하는 걸로 보이는데..
|
|
||||||
|
|
||||||
다만, OSCBundle을 serialize 할 수 있는 수단. 그리고, 성능적인 오버헤드가 어느정도인지.. 그런질문이 남는다.
|
- 1 conductor <=== Adafruit Huzzah : append '-e huzzah'
|
||||||
|
- (optional) a monitor
|
||||||
OSCBundle은 SLIP으로 encoding 하게 되어있는데..그렇게 하면 몬가 좋은게 있겠나? ..
|
|
||||||
암튼 근데 그게.. serial 통신 기반으로 하게 되어있어서.. espX <-> teensy 사이에는 쓸수있겠지만.. espX mesh 안에서는 string 메세지로 통신하니까. 쓰기가 애매하다. 별도로 print 하는 방법으로 하면 좋겠지만.. printout을 할수 있게 되어있는지 잘 모르겠음. 불확실.
|
|
||||||
|
|
||||||
teensy 또는 espX <-> pc 사이에는 쓸수가 있고, 썼을때, 유용하다. osc 니까.
|
|
||||||
|
|
||||||
문제는 mesh 이후인데.. mesh가 웹서비스를 할경우에.. osc.js로 할수가 있겠지만.. 음..
|
|
||||||
|
|
||||||
한가지 어서 정하는게 좋을거 같은데....
|
|
||||||
|
|
||||||
mesh들 끼리 통신은 string 이다.
|
|
||||||
osc를 string으로 표현하면 딱 좋아.
|
|
||||||
osc를 slip으로 encoding 한다고 하는 것은 packet을 만든다는 건데..
|
|
||||||
사실 그럴필요도 없지 않나 싶다.
|
|
||||||
그냥 다 전개된 string으로 만드는 방법만 있다면, 모든 것이 osc 가 될수가 있는데.
|
|
||||||
그런 방법이 있으면 좋겠지만.....
|
|
||||||
|
|
||||||
그냥 지금 가능한 방법으로만 한다면..
|
|
||||||
json이 serialize가 되니까.. osc를 json으로 바꿔서 serialize해서 보내고 받고 하는 것이 한가지 방법.
|
|
||||||
|
|
||||||
osc 는 되게 쌈빡한 메세지인데.. 이걸 json으로 만들면.. 되게 지저분해진다. overhead가 많아. 간단하게 적으면 되는 건데.. 그냥 프린트하는 방법이 없을까? cnmat osc 에서.... 한번 조사해보자.
|
|
||||||
|
|
||||||
----
|
|
||||||
|
|
||||||
StringStream 이란걸 구해다가 중간에 변환기 처럼 사용해서, 테스트를 해봤는데... 변환은 되지만, mesh에 전송했을때 안가는 문제가 있었는데, 원인은 다음과 같다.
|
|
||||||
|
|
||||||
https://gitlab.com/painlessMesh/painlessMesh/issues/140
|
|
||||||
|
|
||||||
painlessmesh 에서.. 그냥 binary data를 보내는 걸 허용을 안하기때문에.. osc 메세지를 바로 보낼수가 없다.
|
|
||||||
base64 인코딩을 해야한다는데.. 그렇게 되면, integrity가 깨진다고나 할까.. (숫자들만 base64 를 할건지.. 전체다 할건지.. 암튼 지저분해지잖아.)
|
|
||||||
어차피 내부적으로 json을 이미 쓰고 있다는 걸까? .. 그런가보다..
|
|
||||||
그럼 그냥 json으로 번역하도록 하는게 맞는 걸까?..
|
|
||||||
그럼 이걸.. generally 할 수 있어야 할텐데..
|
|
||||||
osc --> json json --> osc 자동..
|
|
||||||
그런걸 만들 수 있을까?
|
|
||||||
OSCBundle 이란게 있다면. 이거를 확장해서 ArduinoJson 으로 print 하게 만들수도 있을까..
|
|
||||||
아.. 쩝. 지저분하거나, 혹은 어렵네..
|
|
||||||
가능하긴 한데.. 어려움.. 흠. 그래서 좀 귀찮음..
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
----
|
|
||||||
|
|
||||||
그렇다면..
|
|
||||||
아예.. 모든것을 json으로 바꿀순 없을까?
|
|
||||||
예를들어서 pd만 특별하게 예외로 한다던가 하고...
|
|
||||||
|
|
||||||
https://github.com/residuum/PuRestJson/wiki/%5Bjson-decode%5D-And-%5Bjson-encode%5D:-JSON-Data-in-Pd
|
|
||||||
|
|
||||||
이런게 있는데.. 흥미롭긴하지만.. symbol 로 json string을 받아야하는데 comport로 받으니까 (ArduinoJson) 그렇게 안됨.. serial 통신이니까. slip encoding이라도 안하면.. event도 아니고.. packet이면 차라리 편한데...
|
|
||||||
|
|
||||||
----
|
|
||||||
|
|
||||||
결국 중간에 json <--> osc 변환을 하는게 가장 현명한 방법인데.. 이걸 generally 구현하려면, 좀 짜증날거 같고..
|
|
||||||
그냥 약식으로 해야 할거 같네.. 어차피.. 이게 .. json이든 머든.. 형식이 free하다고 해도 마냥 free하게 쓸수있는 것도 아님.
|
|
||||||
|
|
||||||
----
|
|
||||||
|
|
||||||
또는....... ESP-MESH 를 사용해서 전체적으로 다시 만드는 수가 있음. 즉, painlessmesh 를 버리는 거지.
|
|
||||||
ESP-MESH 에서는 binary 를 보낼수가 있음.
|
|
||||||
즉, OSCBundle 을 StringStream으로 담아서.. 보내고 받고 할 수 있음.
|
|
||||||
|
|
||||||
그러면.. 되나?
|
|
||||||
그러면.. 모든 곳에서 OSC 메세지를 사용할수가 있게 되나?
|
|
||||||
|
|
||||||
----
|
|
||||||
|
|
||||||
근데. 솔직히.. 그거는 좀.. 너무 큰 일이다. 지금도 시간 많이 썼는데.. 더 이상은 위험하게 하고 싶지 않고, 재미없어질듯.
|
|
||||||
|
|
||||||
하지만, 다음에 꼭 해보자...
|
|
||||||
|
|
||||||
장기적으로 보나.. 필요한 방향..
|
|
||||||
|
|
|
||||||
95
include/common.h
Normal file
95
include/common.h
Normal file
|
|
@ -0,0 +1,95 @@
|
||||||
|
#pragma once
|
||||||
|
|
||||||
|
//
|
||||||
|
// [ room protocol (message format) ]
|
||||||
|
//
|
||||||
|
// DDDDD ==> 5 decimal-digits.
|
||||||
|
// IIIWW ==> id (3 decimal-digits) * 100 + word (2 decimal-digits)
|
||||||
|
// id ==> 100~ : objects
|
||||||
|
// id ==> 200~ : agents (controller)
|
||||||
|
// id ==> 900~ : groups
|
||||||
|
// words ==> 1 ~ 99 ==> see 'words.h' for the details
|
||||||
|
|
||||||
|
// member identity
|
||||||
|
// objects
|
||||||
|
// speakers
|
||||||
|
#define ID_SPEAK_A (10600)
|
||||||
|
// (special agent)
|
||||||
|
#define ID_MONITOR (20100)
|
||||||
|
#define ID_CONDUCTOR (20200)
|
||||||
|
// (groups)
|
||||||
|
#define ID_EVERYONE (90100)
|
||||||
|
#define ID_SPEAKERS (90200)
|
||||||
|
// (choice)
|
||||||
|
#define IDENTITY ID_CONDUCTOR
|
||||||
|
|
||||||
|
|
||||||
|
//
|
||||||
|
#define LONELY_TO_DIE (30000)
|
||||||
|
|
||||||
|
//
|
||||||
|
#include <Arduino.h>
|
||||||
|
|
||||||
|
//
|
||||||
|
#include <painlessMesh.h>
|
||||||
|
extern painlessMesh mesh;
|
||||||
|
|
||||||
|
// firmata connectivity
|
||||||
|
#define FIRMATA_ON (0xF13A0001)
|
||||||
|
#define FIRMATA_OFF (0xF13A0002)
|
||||||
|
#define FIRMATA_USE FIRMATA_OFF
|
||||||
|
#if (IDENTITY == ID_KEYBED)
|
||||||
|
#undef FIRMATA_USE
|
||||||
|
#define FIRMATA_USE FIRMATA_ON
|
||||||
|
#endif
|
||||||
|
|
||||||
|
//NOTE: disabling AP beacon for speaker accompanied devices!
|
||||||
|
#define NODE_TYPE_AP_STA (0x40DE0001)
|
||||||
|
#define NODE_TYPE_STA_ONLY (0x40DE0002)
|
||||||
|
//by-default : STA_ONLY
|
||||||
|
#define NODE_TYPE NODE_TYPE_STA_ONLY
|
||||||
|
//guys w/o speakers : AP_STA
|
||||||
|
#if (IDENTITY == ID_GAS || IDENTITY == ID_DRUM || IDENTITY == ID_REEL || IDENTITY == ID_FLOAT || IDENTITY == ID_CONDUCTOR || IDENTITY == ID_MONITOR)
|
||||||
|
#undef NODE_TYPE
|
||||||
|
#define NODE_TYPE NODE_TYPE_AP_STA
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// board
|
||||||
|
#define BOARD_NODEMCU_ESP12E (0xBD00 + 1)
|
||||||
|
#define BOARD_NODEMCU_ESP12N (0xBD00 + 2)
|
||||||
|
#define BOARD_NODEMCU_ESP32 (0xBD00 + 3)
|
||||||
|
//(choice)
|
||||||
|
#define BOARD_SELECT BOARD_NODEMCU_ESP12E
|
||||||
|
|
||||||
|
// mesh
|
||||||
|
#define MESH_SSID "cricket-crackers"
|
||||||
|
#define MESH_PASSWORD "11*1111/111"
|
||||||
|
#define MESH_PORT 5555
|
||||||
|
#define MESH_CHANNEL 5
|
||||||
|
// #define MESH_ANCHOR
|
||||||
|
|
||||||
|
//
|
||||||
|
// LED status indication
|
||||||
|
// operation modes
|
||||||
|
// 0 - booted. and running. no connection. scanning.
|
||||||
|
// 1 - + connected.
|
||||||
|
// notifying patterns
|
||||||
|
// 0 - steady on
|
||||||
|
// 1 - slow blinking (syncronized)
|
||||||
|
//
|
||||||
|
#if (BOARD_SELECT == BOARD_NODEMCU_ESP12E)
|
||||||
|
#define LED_PIN 2 // nodemcuv2
|
||||||
|
#elif (BOARD_SELECT == BOARD_NODEMCU_ESP32)
|
||||||
|
#define LED_PIN 13 // featheresp32
|
||||||
|
#endif
|
||||||
|
#define LED_PERIOD (1111)
|
||||||
|
#define LED_ONTIME (1)
|
||||||
|
|
||||||
|
// event handlers fo connection-related events
|
||||||
|
extern void gotMessageCallback(uint32_t from, String & msg); // REQUIRED
|
||||||
|
extern void gotChangedConnectionCallback();
|
||||||
|
|
||||||
|
// the system scheduler
|
||||||
|
extern Scheduler runner;
|
||||||
|
|
||||||
|
#include "words.h"
|
||||||
26
include/words.h
Normal file
26
include/words.h
Normal file
|
|
@ -0,0 +1,26 @@
|
||||||
|
#define MSG_LENGTH_MAX 256
|
||||||
|
|
||||||
|
#define SPEAK_A_HELLO (ID_SPEAK_A + 1)
|
||||||
|
#define SPEAK_A_SLEEPING (ID_SPEAK_A + 2)
|
||||||
|
#define SPEAK_A_TIC (ID_SPEAK_A + 3)
|
||||||
|
#define SPEAK_A_TAC (ID_SPEAK_A + 4)
|
||||||
|
#define SPEAK_A_TOE (ID_SPEAK_A + 5)
|
||||||
|
#define SPEAK_A_PLAYMODE (ID_SPEAK_A + 6) // + XX : 0: Individual random, 1: Directional Propagation
|
||||||
|
#define SPEAK_A_PARA_SPEED (ID_SPEAK_A + 7) // + XX : speed of rhythm
|
||||||
|
#define SPEAK_A_PARA_SNDSET (ID_SPEAK_A + 8) // + XX : sound set select
|
||||||
|
|
||||||
|
//for group (all speakers)
|
||||||
|
#define SPEAKERS_HELLO (ID_SPEAKERS + 1)
|
||||||
|
#define SPEAKERS_SLEEPING (ID_SPEAKERS + 2)
|
||||||
|
#define SPEAKERS_TIC (ID_SPEAKERS + 3)
|
||||||
|
#define SPEAKERS_TAC (ID_SPEAKERS + 4)
|
||||||
|
#define SPEAKERS_TOE (ID_SPEAKERS + 5)
|
||||||
|
#define SPEAKERS_PLAYMODE (ID_SPEAKERS + 6) // + XX : 0: Individual random, 1: Directional Propagation
|
||||||
|
#define SPEAKERS_PARA_SPEED (ID_SPEAKERS + 7) // + XX : speed of rhythm
|
||||||
|
#define SPEAKERS_PARA_SNDSET (ID_SPEAKERS + 8) // + XX : sound set select
|
||||||
|
|
||||||
|
//common constants for all speakers
|
||||||
|
#define SPEAKERS_PLAYMODE_INDEP (ID_SPEAKERS + 50)
|
||||||
|
#define SPEAKERS_PLAYMODE_PROPA (ID_SPEAKERS + 51)
|
||||||
|
// #define SPEAKERS_LEADING (ID_SPEAKERS + 80)
|
||||||
|
// #define SPEAKERS_FOLLOWING (ID_SPEAKERS + 81)
|
||||||
|
|
@ -1,25 +0,0 @@
|
||||||
#ifndef _STRING_STREAM_H_
|
|
||||||
#define _STRING_STREAM_H_
|
|
||||||
|
|
||||||
#include <Stream.h>
|
|
||||||
|
|
||||||
class StringStream : public Stream
|
|
||||||
{
|
|
||||||
public:
|
|
||||||
StringStream(String &s) : string(s), position(0) { }
|
|
||||||
|
|
||||||
// Stream methods
|
|
||||||
virtual int available() { return string.length() - position; }
|
|
||||||
virtual int read() { return position < string.length() ? string[position++] : -1; }
|
|
||||||
virtual int peek() { return position < string.length() ? string[position] : -1; }
|
|
||||||
virtual void flush() { };
|
|
||||||
// Print methods
|
|
||||||
virtual size_t write(uint8_t c) { string += (char)c; return 1;};
|
|
||||||
|
|
||||||
private:
|
|
||||||
String &string;
|
|
||||||
unsigned int length;
|
|
||||||
unsigned int position;
|
|
||||||
};
|
|
||||||
|
|
||||||
#endif // _STRING_STREAM_H_
|
|
||||||
377
members/conductor.cpp
Normal file
377
members/conductor.cpp
Normal file
|
|
@ -0,0 +1,377 @@
|
||||||
|
// tasks
|
||||||
|
extern Task loop_msg_reel_task;
|
||||||
|
extern Task loop_msg_float_task;
|
||||||
|
extern Task loop_msg_gas_task;
|
||||||
|
extern Task loop_msg_drum_task;
|
||||||
|
|
||||||
|
// room protocol
|
||||||
|
static char msg_cstr[MSG_LENGTH_MAX] = {0, };
|
||||||
|
void gotChangedConnectionCallback() { // REQUIRED
|
||||||
|
}
|
||||||
|
void gotMessageCallback(uint32_t from, String & msg) { // REQUIRED
|
||||||
|
Serial.println(msg);
|
||||||
|
int message = msg.substring(1, 6).toInt();
|
||||||
|
|
||||||
|
// town_onoff
|
||||||
|
static unsigned long timestamp = millis(); // init timestamp!
|
||||||
|
static bool town_onoff = false;
|
||||||
|
//
|
||||||
|
if (message == SPEAK_A_HELLO || message == SPEAK_B_HELLO || message == SPEAK_C_HELLO || message == SPEAK_D_HELLO || message == SPEAK_E_HELLO || message == SPEAK_F_HELLO) {
|
||||||
|
//
|
||||||
|
timestamp = millis(); // update timestamp!
|
||||||
|
// Serial.println("town-folks alive!");
|
||||||
|
//
|
||||||
|
if (town_onoff == false) {
|
||||||
|
town_onoff = true;
|
||||||
|
loop_msg_reel_task.restartDelayed(100);
|
||||||
|
loop_msg_float_task.restartDelayed(100);
|
||||||
|
loop_msg_gas_task.restartDelayed(100);
|
||||||
|
loop_msg_drum_task.restartDelayed(100);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
// if there's NO SPEAK_X_HELLO for 1 min. turn off objects.
|
||||||
|
if (millis() - timestamp > 1000*20) {
|
||||||
|
town_onoff = false;
|
||||||
|
loop_msg_reel_task.disable();
|
||||||
|
loop_msg_float_task.disable();
|
||||||
|
loop_msg_gas_task.disable();
|
||||||
|
loop_msg_drum_task.disable();
|
||||||
|
//
|
||||||
|
// Serial.println("town-folks sleep!");
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
//msg_reel task
|
||||||
|
void loop_msg_reel() {
|
||||||
|
//
|
||||||
|
static String msg = "";
|
||||||
|
sprintf(msg_cstr, "[%05d]", REEL_TURN);
|
||||||
|
msg = String(msg_cstr);
|
||||||
|
mesh.sendBroadcast(msg);
|
||||||
|
Serial.println("TX : " + msg);
|
||||||
|
//
|
||||||
|
loop_msg_reel_task.restartDelayed(random(1000*60*1.5, 1000*60*2));
|
||||||
|
}
|
||||||
|
Task loop_msg_reel_task(0, TASK_ONCE, &loop_msg_reel);
|
||||||
|
|
||||||
|
//msg_float task
|
||||||
|
void loop_msg_float() {
|
||||||
|
//
|
||||||
|
static String msg = "";
|
||||||
|
sprintf(msg_cstr, "[%05d]", FLOAT_FLY);
|
||||||
|
msg = String(msg_cstr);
|
||||||
|
mesh.sendBroadcast(msg);
|
||||||
|
Serial.println("TX : " + msg);
|
||||||
|
//
|
||||||
|
loop_msg_float_task.restartDelayed(random(1000*60*2, 1000*60*2.5));
|
||||||
|
}
|
||||||
|
Task loop_msg_float_task(0, TASK_ONCE, &loop_msg_float);
|
||||||
|
|
||||||
|
//msg_gas task
|
||||||
|
void loop_msg_gas() {
|
||||||
|
//
|
||||||
|
static String msg = "";
|
||||||
|
sprintf(msg_cstr, "[%05d]", GAS_RING_RING_RING);
|
||||||
|
msg = String(msg_cstr);
|
||||||
|
mesh.sendBroadcast(msg);
|
||||||
|
Serial.println("TX : " + msg);
|
||||||
|
//
|
||||||
|
loop_msg_gas_task.restartDelayed(random(800, 3000));
|
||||||
|
}
|
||||||
|
Task loop_msg_gas_task(0, TASK_ONCE, &loop_msg_gas);
|
||||||
|
|
||||||
|
//msg_drum task
|
||||||
|
void loop_msg_drum() {
|
||||||
|
//
|
||||||
|
static String msg = "";
|
||||||
|
sprintf(msg_cstr, "[%05d]", DRUM_SCRATCH);
|
||||||
|
msg = String(msg_cstr);
|
||||||
|
mesh.sendBroadcast(msg);
|
||||||
|
Serial.println("TX : " + msg);
|
||||||
|
//
|
||||||
|
loop_msg_drum_task.restartDelayed(random(800, 3000));
|
||||||
|
}
|
||||||
|
Task loop_msg_drum_task(0, TASK_ONCE, &loop_msg_drum);
|
||||||
|
|
||||||
|
// sound theme
|
||||||
|
#define N_THEMES 14
|
||||||
|
int theme = 0;
|
||||||
|
|
||||||
|
// vspeed
|
||||||
|
int vspeed = 0;
|
||||||
|
|
||||||
|
// soundset
|
||||||
|
int soundset = 0;
|
||||||
|
|
||||||
|
//speakers soundset changer
|
||||||
|
// // speakers mode changer
|
||||||
|
// // //speakers tic task
|
||||||
|
// // speakers speed changer
|
||||||
|
|
||||||
|
extern Task speaker_a_tick_task;
|
||||||
|
void speaker_a_tick() {
|
||||||
|
//
|
||||||
|
int base_speed = 1000 + (vspeed * 10);
|
||||||
|
int random_portion = base_speed * 0.1;
|
||||||
|
//
|
||||||
|
static String msg = "";
|
||||||
|
sprintf(msg_cstr, "[%05d]", SPEAK_A_TIC);
|
||||||
|
msg = String(msg_cstr);
|
||||||
|
mesh.sendBroadcast(msg);
|
||||||
|
Serial.println("TX : " + msg);
|
||||||
|
//
|
||||||
|
speaker_a_tick_task.restartDelayed(base_speed + random(random_portion));
|
||||||
|
}
|
||||||
|
Task speaker_a_tick_task(0, TASK_ONCE, &speaker_a_tick);
|
||||||
|
|
||||||
|
extern Task playloop_task;
|
||||||
|
void playloop() {
|
||||||
|
static String msg = "";
|
||||||
|
|
||||||
|
//
|
||||||
|
Serial.print("current THEME => ");
|
||||||
|
Serial.println(theme);
|
||||||
|
|
||||||
|
//
|
||||||
|
if (theme == 0) {
|
||||||
|
//
|
||||||
|
// directional propagation + soundset 01~10 + vspeed 20
|
||||||
|
//
|
||||||
|
sprintf(msg_cstr, "[%05d:%02d]", SPEAKERS_PLAYMODE, SPEAKERS_PLAYMODE_PROPA);
|
||||||
|
msg = String(msg_cstr);
|
||||||
|
mesh.sendBroadcast(msg);
|
||||||
|
Serial.println("TX : SPEAKERS_PLAYMODE == SPEAKERS_PLAYMODE_PROPA");
|
||||||
|
speaker_a_tick_task.restartDelayed(10);
|
||||||
|
//
|
||||||
|
soundset = 1; // soundset ==> 1 ~ 99
|
||||||
|
sprintf(msg_cstr, "[%05d:%02d]", SPEAKERS_PARA_SNDSET, soundset); // soundset ==> give starting sound #..
|
||||||
|
msg = String(msg_cstr);
|
||||||
|
mesh.sendBroadcast(msg);
|
||||||
|
Serial.print("TX : SPEAKERS_PARA_SNDSET == ");
|
||||||
|
Serial.println(soundset);
|
||||||
|
Serial.println(msg);
|
||||||
|
//
|
||||||
|
vspeed = 0; // vspeed ==> 0 ~ 999
|
||||||
|
sprintf(msg_cstr, "[%05d:%03d]", SPEAKERS_PARA_SPEED, vspeed);
|
||||||
|
msg = String(msg_cstr);
|
||||||
|
mesh.sendBroadcast(msg);
|
||||||
|
Serial.print("TX : SPEAKERS_PARA_SPEED == ");
|
||||||
|
Serial.println(vspeed);
|
||||||
|
Serial.println(msg);
|
||||||
|
//
|
||||||
|
playloop_task.restartDelayed(30000);
|
||||||
|
//
|
||||||
|
} else if (theme == 1) {
|
||||||
|
//
|
||||||
|
vspeed = 75; // vspeed ==> 0 ~ 999
|
||||||
|
sprintf(msg_cstr, "[%05d:%03d]", SPEAKERS_PARA_SPEED, vspeed);
|
||||||
|
msg = String(msg_cstr);
|
||||||
|
mesh.sendBroadcast(msg);
|
||||||
|
Serial.print("TX : SPEAKERS_PARA_SPEED == ");
|
||||||
|
Serial.println(vspeed);
|
||||||
|
Serial.println(msg);
|
||||||
|
//
|
||||||
|
playloop_task.restartDelayed(30000);
|
||||||
|
//
|
||||||
|
} else if (theme == 2) {
|
||||||
|
//
|
||||||
|
vspeed = 0; // vspeed ==> 0 ~ 999
|
||||||
|
sprintf(msg_cstr, "[%05d:%03d]", SPEAKERS_PARA_SPEED, vspeed);
|
||||||
|
msg = String(msg_cstr);
|
||||||
|
mesh.sendBroadcast(msg);
|
||||||
|
Serial.print("TX : SPEAKERS_PARA_SPEED == ");
|
||||||
|
Serial.println(vspeed);
|
||||||
|
Serial.println(msg);
|
||||||
|
//
|
||||||
|
playloop_task.restartDelayed(40000);
|
||||||
|
//
|
||||||
|
} else if (theme == 3) {
|
||||||
|
//
|
||||||
|
vspeed = 500; // vspeed ==> 0 ~ 999
|
||||||
|
sprintf(msg_cstr, "[%05d:%03d]", SPEAKERS_PARA_SPEED, vspeed);
|
||||||
|
msg = String(msg_cstr);
|
||||||
|
mesh.sendBroadcast(msg);
|
||||||
|
Serial.print("TX : SPEAKERS_PARA_SPEED == ");
|
||||||
|
Serial.println(vspeed);
|
||||||
|
Serial.println(msg);
|
||||||
|
//
|
||||||
|
playloop_task.restartDelayed(30000);
|
||||||
|
//
|
||||||
|
} else if (theme == 4) {
|
||||||
|
//
|
||||||
|
// indep_random + soundset 01~10
|
||||||
|
//
|
||||||
|
sprintf(msg_cstr, "[%05d:%02d]", SPEAKERS_PLAYMODE, SPEAKERS_PLAYMODE_INDEP);
|
||||||
|
msg = String(msg_cstr);
|
||||||
|
mesh.sendBroadcast(msg);
|
||||||
|
Serial.println("TX : SPEAKERS_PLAYMODE == SPEAKERS_PLAYMODE_INDEP");
|
||||||
|
speaker_a_tick_task.disable();
|
||||||
|
//
|
||||||
|
vspeed = 0; // vspeed ==> 0 ~ 999
|
||||||
|
sprintf(msg_cstr, "[%05d:%03d]", SPEAKERS_PARA_SPEED, vspeed);
|
||||||
|
msg = String(msg_cstr);
|
||||||
|
mesh.sendBroadcast(msg);
|
||||||
|
Serial.print("TX : SPEAKERS_PARA_SPEED == ");
|
||||||
|
Serial.println(vspeed);
|
||||||
|
Serial.println(msg);
|
||||||
|
//
|
||||||
|
playloop_task.restartDelayed(30000);
|
||||||
|
//
|
||||||
|
} else if (theme == 5) {
|
||||||
|
//
|
||||||
|
vspeed = 150; // vspeed ==> 0 ~ 999
|
||||||
|
sprintf(msg_cstr, "[%05d:%03d]", SPEAKERS_PARA_SPEED, vspeed);
|
||||||
|
msg = String(msg_cstr);
|
||||||
|
mesh.sendBroadcast(msg);
|
||||||
|
Serial.print("TX : SPEAKERS_PARA_SPEED == ");
|
||||||
|
Serial.println(vspeed);
|
||||||
|
Serial.println(msg);
|
||||||
|
//
|
||||||
|
playloop_task.restartDelayed(30000);
|
||||||
|
//
|
||||||
|
} else if (theme == 6) {
|
||||||
|
//
|
||||||
|
vspeed = 200; // vspeed ==> 0 ~ 999
|
||||||
|
sprintf(msg_cstr, "[%05d:%03d]", SPEAKERS_PARA_SPEED, vspeed);
|
||||||
|
msg = String(msg_cstr);
|
||||||
|
mesh.sendBroadcast(msg);
|
||||||
|
Serial.print("TX : SPEAKERS_PARA_SPEED == ");
|
||||||
|
Serial.println(vspeed);
|
||||||
|
Serial.println(msg);
|
||||||
|
//
|
||||||
|
playloop_task.restartDelayed(10000);
|
||||||
|
//
|
||||||
|
} else if (theme == 7) {
|
||||||
|
//
|
||||||
|
vspeed = 0; // vspeed ==> 0 ~ 999
|
||||||
|
sprintf(msg_cstr, "[%05d:%03d]", SPEAKERS_PARA_SPEED, vspeed);
|
||||||
|
msg = String(msg_cstr);
|
||||||
|
mesh.sendBroadcast(msg);
|
||||||
|
Serial.print("TX : SPEAKERS_PARA_SPEED == ");
|
||||||
|
Serial.println(vspeed);
|
||||||
|
Serial.println(msg);
|
||||||
|
//
|
||||||
|
playloop_task.restartDelayed(40000);
|
||||||
|
//
|
||||||
|
} else if (theme == 8) {
|
||||||
|
//
|
||||||
|
// directional propagation + soundset 01~10 + vspeed 20
|
||||||
|
//
|
||||||
|
sprintf(msg_cstr, "[%05d:%02d]", SPEAKERS_PLAYMODE, SPEAKERS_PLAYMODE_PROPA);
|
||||||
|
msg = String(msg_cstr);
|
||||||
|
mesh.sendBroadcast(msg);
|
||||||
|
Serial.println("TX : SPEAKERS_PLAYMODE == SPEAKERS_PLAYMODE_PROPA");
|
||||||
|
speaker_a_tick_task.restartDelayed(10);
|
||||||
|
//
|
||||||
|
soundset = 11; // soundset ==> 1 ~ 99
|
||||||
|
sprintf(msg_cstr, "[%05d:%02d]", SPEAKERS_PARA_SNDSET, soundset); // soundset ==> give starting sound #..
|
||||||
|
msg = String(msg_cstr);
|
||||||
|
mesh.sendBroadcast(msg);
|
||||||
|
Serial.print("TX : SPEAKERS_PARA_SNDSET == ");
|
||||||
|
Serial.println(soundset);
|
||||||
|
Serial.println(msg);
|
||||||
|
//
|
||||||
|
vspeed = 0; // vspeed ==> 0 ~ 999
|
||||||
|
sprintf(msg_cstr, "[%05d:%03d]", SPEAKERS_PARA_SPEED, vspeed);
|
||||||
|
msg = String(msg_cstr);
|
||||||
|
mesh.sendBroadcast(msg);
|
||||||
|
Serial.print("TX : SPEAKERS_PARA_SPEED == ");
|
||||||
|
Serial.println(vspeed);
|
||||||
|
Serial.println(msg);
|
||||||
|
//
|
||||||
|
playloop_task.restartDelayed(30000);
|
||||||
|
//
|
||||||
|
} else if (theme == 9) {
|
||||||
|
//
|
||||||
|
vspeed = 300; // vspeed ==> 0 ~ 999
|
||||||
|
sprintf(msg_cstr, "[%05d:%03d]", SPEAKERS_PARA_SPEED, vspeed);
|
||||||
|
msg = String(msg_cstr);
|
||||||
|
mesh.sendBroadcast(msg);
|
||||||
|
Serial.print("TX : SPEAKERS_PARA_SPEED == ");
|
||||||
|
Serial.println(vspeed);
|
||||||
|
Serial.println(msg);
|
||||||
|
//
|
||||||
|
playloop_task.restartDelayed(20000);
|
||||||
|
//
|
||||||
|
} else if (theme == 10) {
|
||||||
|
//
|
||||||
|
vspeed = 0; // vspeed ==> 0 ~ 999
|
||||||
|
sprintf(msg_cstr, "[%05d:%03d]", SPEAKERS_PARA_SPEED, vspeed);
|
||||||
|
msg = String(msg_cstr);
|
||||||
|
mesh.sendBroadcast(msg);
|
||||||
|
Serial.print("TX : SPEAKERS_PARA_SPEED == ");
|
||||||
|
Serial.println(vspeed);
|
||||||
|
Serial.println(msg);
|
||||||
|
//
|
||||||
|
playloop_task.restartDelayed(30000);
|
||||||
|
//
|
||||||
|
} else if (theme == 11) {
|
||||||
|
//
|
||||||
|
vspeed = 200; // vspeed ==> 0 ~ 999
|
||||||
|
sprintf(msg_cstr, "[%05d:%03d]", SPEAKERS_PARA_SPEED, vspeed);
|
||||||
|
msg = String(msg_cstr);
|
||||||
|
mesh.sendBroadcast(msg);
|
||||||
|
Serial.print("TX : SPEAKERS_PARA_SPEED == ");
|
||||||
|
Serial.println(vspeed);
|
||||||
|
Serial.println(msg);
|
||||||
|
//
|
||||||
|
playloop_task.restartDelayed(20000);
|
||||||
|
//
|
||||||
|
} else if (theme == 12) {
|
||||||
|
//
|
||||||
|
// indep_random + soundset 01~10
|
||||||
|
//
|
||||||
|
sprintf(msg_cstr, "[%05d:%02d]", SPEAKERS_PLAYMODE, SPEAKERS_PLAYMODE_INDEP);
|
||||||
|
msg = String(msg_cstr);
|
||||||
|
mesh.sendBroadcast(msg);
|
||||||
|
Serial.println("TX : SPEAKERS_PLAYMODE == SPEAKERS_PLAYMODE_INDEP");
|
||||||
|
speaker_a_tick_task.disable();
|
||||||
|
//
|
||||||
|
vspeed = 0; // vspeed ==> 0 ~ 999
|
||||||
|
sprintf(msg_cstr, "[%05d:%03d]", SPEAKERS_PARA_SPEED, vspeed);
|
||||||
|
msg = String(msg_cstr);
|
||||||
|
mesh.sendBroadcast(msg);
|
||||||
|
Serial.print("TX : SPEAKERS_PARA_SPEED == ");
|
||||||
|
Serial.println(vspeed);
|
||||||
|
Serial.println(msg);
|
||||||
|
//
|
||||||
|
playloop_task.restartDelayed(40000);
|
||||||
|
//
|
||||||
|
} else if (theme == 13) {
|
||||||
|
//
|
||||||
|
vspeed = 300; // vspeed ==> 0 ~ 999
|
||||||
|
sprintf(msg_cstr, "[%05d:%03d]", SPEAKERS_PARA_SPEED, vspeed);
|
||||||
|
msg = String(msg_cstr);
|
||||||
|
mesh.sendBroadcast(msg);
|
||||||
|
Serial.print("TX : SPEAKERS_PARA_SPEED == ");
|
||||||
|
Serial.println(vspeed);
|
||||||
|
Serial.println(msg);
|
||||||
|
//
|
||||||
|
playloop_task.restartDelayed(20000);
|
||||||
|
//
|
||||||
|
}
|
||||||
|
|
||||||
|
// theme : 0 ~ (N_THEMES - 1)
|
||||||
|
theme++;
|
||||||
|
if (theme >= N_THEMES) {
|
||||||
|
theme = 0;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
Task playloop_task(0, TASK_ONCE, &playloop);
|
||||||
|
|
||||||
|
//
|
||||||
|
void setup_member() {
|
||||||
|
|
||||||
|
//
|
||||||
|
runner.addTask(loop_msg_reel_task);
|
||||||
|
runner.addTask(loop_msg_float_task);
|
||||||
|
runner.addTask(loop_msg_gas_task);
|
||||||
|
runner.addTask(loop_msg_drum_task);
|
||||||
|
|
||||||
|
//
|
||||||
|
runner.addTask(speaker_a_tick_task);
|
||||||
|
|
||||||
|
//
|
||||||
|
runner.addTask(playloop_task);
|
||||||
|
playloop_task.restartDelayed(100);
|
||||||
|
}
|
||||||
126
members/speaker_a.cpp
Normal file
126
members/speaker_a.cpp
Normal file
|
|
@ -0,0 +1,126 @@
|
||||||
|
// i2c
|
||||||
|
#include <Wire.h>
|
||||||
|
#include "speakers/i2c_protocol.h"
|
||||||
|
|
||||||
|
// tasks
|
||||||
|
extern Task sing_task;
|
||||||
|
extern Task indep_random_task;
|
||||||
|
extern Task direc_propa_task;
|
||||||
|
|
||||||
|
// soundset
|
||||||
|
int soundset = 1; // starting # of the set. (10 files will be selected.)
|
||||||
|
|
||||||
|
// playmode
|
||||||
|
int playmode = SPEAKERS_PLAYMODE_INDEP;
|
||||||
|
|
||||||
|
// vspeed
|
||||||
|
int vspeed = 0;
|
||||||
|
|
||||||
|
// room protocol
|
||||||
|
static char msg_cstr[MSG_LENGTH_MAX] = {0, };
|
||||||
|
void gotChangedConnectionCallback() { // REQUIRED
|
||||||
|
}
|
||||||
|
void gotMessageCallback(uint32_t from, String & msg) { // REQUIRED
|
||||||
|
Serial.println(msg);
|
||||||
|
int message = msg.substring(1, 6).toInt();
|
||||||
|
// this speaker event
|
||||||
|
if (playmode == SPEAKERS_PLAYMODE_PROPA) {
|
||||||
|
if (message == SPEAK_A_TIC) {
|
||||||
|
Serial.println("SPEAK_A_TIC");
|
||||||
|
int r = 100 + random(vspeed * 10);
|
||||||
|
sing_task.restartDelayed(r);
|
||||||
|
direc_propa_task.restartDelayed(r);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
// speakers group : SPEAKERS_PLAYMODE
|
||||||
|
if (message == SPEAKERS_PLAYMODE) {
|
||||||
|
int para = msg.substring(7, 9).toInt(); // get +XX parameter..
|
||||||
|
// only allow valid inputs
|
||||||
|
if (para == SPEAKERS_PLAYMODE_INDEP) {
|
||||||
|
playmode = para;
|
||||||
|
indep_random_task.restartDelayed(100);
|
||||||
|
}
|
||||||
|
else if (para == SPEAKERS_PLAYMODE_PROPA) {
|
||||||
|
playmode = para;
|
||||||
|
indep_random_task.disable();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
// speakers group : SPEAKERS_PARA_SNDSET
|
||||||
|
if (message == SPEAKERS_PARA_SNDSET) {
|
||||||
|
int para = msg.substring(7, 9).toInt(); // get +XX parameter..
|
||||||
|
// only allow valid inputs
|
||||||
|
if (para >= 1 && para < 100) { // 1 ~ 99
|
||||||
|
soundset = para;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
// speakers group : SPEAKERS_PARA_SPEED
|
||||||
|
if (message == SPEAKERS_PARA_SPEED) {
|
||||||
|
int para = msg.substring(7, 10).toInt(); // get +XXX parameter..
|
||||||
|
// only allow valid inputs
|
||||||
|
if (para >= 0 && para < 1000) { // 0 ~ 999
|
||||||
|
vspeed = para;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
// saying hello
|
||||||
|
void greeting() {
|
||||||
|
static String msg = "";
|
||||||
|
sprintf(msg_cstr, "[%05d]", SPEAK_A_HELLO);
|
||||||
|
msg = String(msg_cstr);
|
||||||
|
mesh.sendBroadcast(msg);
|
||||||
|
Serial.println("TX : " + msg);
|
||||||
|
}
|
||||||
|
Task saying_greeting(10000, TASK_FOREVER, &greeting);
|
||||||
|
|
||||||
|
//playmode #1 : independent random playmode
|
||||||
|
void indep_random() {
|
||||||
|
int base_speed = 1000 + (vspeed * 10);
|
||||||
|
int random_portion = base_speed * 0.1;
|
||||||
|
//
|
||||||
|
sing_task.restartDelayed(100);
|
||||||
|
indep_random_task.restartDelayed(base_speed + random(random_portion)); //re-schedule myself.
|
||||||
|
}
|
||||||
|
Task indep_random_task(0, TASK_ONCE, &indep_random);
|
||||||
|
|
||||||
|
//playmode #2 : directional propagation playmode
|
||||||
|
void direc_propa() {
|
||||||
|
static String msg = "";
|
||||||
|
sprintf(msg_cstr, "[%05d]", SPEAK_B_TIC);
|
||||||
|
msg = String(msg_cstr);
|
||||||
|
mesh.sendBroadcast(msg);
|
||||||
|
Serial.println("TX : SPEAK_B_TIC");
|
||||||
|
}
|
||||||
|
Task direc_propa_task(0, TASK_ONCE, &direc_propa);
|
||||||
|
|
||||||
|
// sing!
|
||||||
|
void sing() {
|
||||||
|
//
|
||||||
|
static int song_select = 1;
|
||||||
|
//
|
||||||
|
song_select = random(soundset, (soundset + 10)); // every sound set has 10 sounds. x ~ x+9
|
||||||
|
// "P#SSS@AAAA" - P: P (play), SSS: song #, A: amp. (x 1000)
|
||||||
|
// "SXXXXXXXXX" - S: S (stop)
|
||||||
|
sprintf(cmdstr, "P#%03d@%04d", song_select, 800); // play song #1, with amplitude
|
||||||
|
Wire.beginTransmission(I2C_ADDR);
|
||||||
|
Wire.write(cmdstr, CMD_LENGTH);
|
||||||
|
Wire.endTransmission();
|
||||||
|
}
|
||||||
|
Task sing_task(0, TASK_ONCE, &sing);
|
||||||
|
|
||||||
|
//setup_member
|
||||||
|
void setup_member() {
|
||||||
|
//i2c master
|
||||||
|
Wire.begin();
|
||||||
|
|
||||||
|
//tasks
|
||||||
|
runner.addTask(saying_greeting);
|
||||||
|
saying_greeting.enable();
|
||||||
|
//
|
||||||
|
runner.addTask(sing_task);
|
||||||
|
//
|
||||||
|
runner.addTask(indep_random_task);
|
||||||
|
runner.addTask(direc_propa_task);
|
||||||
|
//
|
||||||
|
indep_random_task.restartDelayed(100);
|
||||||
|
}
|
||||||
12
members/speakers/i2c_protocol.h
Normal file
12
members/speakers/i2c_protocol.h
Normal file
|
|
@ -0,0 +1,12 @@
|
||||||
|
#pragma once
|
||||||
|
|
||||||
|
//i2c address
|
||||||
|
#define I2C_ADDR 3
|
||||||
|
|
||||||
|
//i2c protocol
|
||||||
|
#define CMD_LENGTH 10
|
||||||
|
#define CMD_BUFF_LEN (CMD_LENGTH + 1)
|
||||||
|
char cmdstr[CMD_BUFF_LEN] = "P#SSS@AAAA";
|
||||||
|
|
||||||
|
// "P#SSS@AAAA" - P: P (play), SSS: song #, A: amp. (x 1000)
|
||||||
|
// "SXXXXXXXXX" - S: S (stop)
|
||||||
7
members/speakers/monitor.sh
Normal file
7
members/speakers/monitor.sh
Normal file
|
|
@ -0,0 +1,7 @@
|
||||||
|
#!/bin/bash
|
||||||
|
|
||||||
|
#NOTE: u might want to wait a bit before running this script..
|
||||||
|
# 'right after' upload system reports that the port is not ready yet!
|
||||||
|
# so, we don't support here.. 'upload-n-monitor.sh' option.
|
||||||
|
|
||||||
|
pio device monitor -p /dev/cu.usbmodem32231601 -b 9600
|
||||||
28
members/speakers/platformio.ini
Normal file
28
members/speakers/platformio.ini
Normal file
|
|
@ -0,0 +1,28 @@
|
||||||
|
; 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
|
||||||
|
|
||||||
|
[platformio]
|
||||||
|
env_default = teensy35
|
||||||
|
|
||||||
|
[common]
|
||||||
|
lib_deps =
|
||||||
|
721@3.0.2 ; TaskScheduler
|
||||||
|
|
||||||
|
[env:teensy35]
|
||||||
|
platform = teensy@3.6.0
|
||||||
|
board = teensy35
|
||||||
|
framework = arduino
|
||||||
|
lib_deps = ${common.lib_deps}
|
||||||
|
|
||||||
|
[env:teensy36]
|
||||||
|
platform = teensy@3.6.0
|
||||||
|
board = teensy36
|
||||||
|
framework = arduino
|
||||||
|
lib_deps = ${common.lib_deps}
|
||||||
206
members/speakers/src/main.cpp
Normal file
206
members/speakers/src/main.cpp
Normal file
|
|
@ -0,0 +1,206 @@
|
||||||
|
//HACK: let auto-poweroff speakers stay turned ON! - (creative muvo mini)
|
||||||
|
#define IDLE_FREQ 22000
|
||||||
|
#define IDLE_AMP 0 // --> creative muvo 2 doesn't need this. they just stay on!
|
||||||
|
|
||||||
|
//teensy audio
|
||||||
|
#include <Audio.h>
|
||||||
|
#include <Wire.h>
|
||||||
|
#include <SPI.h>
|
||||||
|
#include <SD.h>
|
||||||
|
#include <SerialFlash.h>
|
||||||
|
|
||||||
|
//teensy 3.5 with SD card
|
||||||
|
#define SDCARD_CS_PIN BUILTIN_SDCARD
|
||||||
|
#define SDCARD_MOSI_PIN 11 // not actually used
|
||||||
|
#define SDCARD_SCK_PIN 13 // not actually used
|
||||||
|
|
||||||
|
// GUItool: begin automatically generated code
|
||||||
|
AudioPlaySdWav playSdWav1; //xy=224,265
|
||||||
|
AudioSynthWaveformSine sine1; //xy=236,361
|
||||||
|
AudioMixer4 mixer2; //xy=497,328
|
||||||
|
AudioMixer4 mixer1; //xy=499,245
|
||||||
|
AudioAmplifier amp1; //xy=633,245
|
||||||
|
AudioAmplifier amp2; //xy=634,328
|
||||||
|
AudioOutputAnalogStereo dacs1; //xy=788,284
|
||||||
|
AudioConnection patchCord1(playSdWav1, 0, mixer1, 0);
|
||||||
|
AudioConnection patchCord2(playSdWav1, 1, mixer2, 0);
|
||||||
|
AudioConnection patchCord3(sine1, 0, mixer1, 1);
|
||||||
|
AudioConnection patchCord4(sine1, 0, mixer2, 1);
|
||||||
|
AudioConnection patchCord5(mixer2, amp2);
|
||||||
|
AudioConnection patchCord6(mixer1, amp1);
|
||||||
|
AudioConnection patchCord7(amp1, 0, dacs1, 0);
|
||||||
|
AudioConnection patchCord8(amp2, 0, dacs1, 1);
|
||||||
|
// GUItool: end automatically generated code
|
||||||
|
|
||||||
|
//task
|
||||||
|
#include <TaskScheduler.h>
|
||||||
|
Scheduler runner;
|
||||||
|
//song #
|
||||||
|
int song_now = 0; //0~99
|
||||||
|
//
|
||||||
|
void sound_player_start()
|
||||||
|
{
|
||||||
|
//filename buffer - 8.3 naming convension! 8+1+3+1 = 13
|
||||||
|
char filename[13] = "NN.WAV";
|
||||||
|
//search for the sound file
|
||||||
|
int limit = (song_now % 100); // 0~99
|
||||||
|
filename[0] = '0' + (limit / 10); // [N]N.WAV
|
||||||
|
filename[1] = '0' + (limit % 10); // N[N].WAV
|
||||||
|
//TEST
|
||||||
|
Serial.println(filename);
|
||||||
|
//start the player!
|
||||||
|
//NOTE: block out 're-triggering'
|
||||||
|
if (playSdWav1.isPlaying() == false) {
|
||||||
|
playSdWav1.play(filename);
|
||||||
|
}
|
||||||
|
//mark the indicator : HIGH: ON
|
||||||
|
// digitalWrite(13, HIGH);
|
||||||
|
//to wait a bit for updating isPlaying()
|
||||||
|
delay(10);
|
||||||
|
}
|
||||||
|
void sound_player_stop() {
|
||||||
|
//stop the player.
|
||||||
|
if (playSdWav1.isPlaying() == true) {
|
||||||
|
playSdWav1.stop();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
void sound_player_check() {
|
||||||
|
if (playSdWav1.isPlaying() == false) {
|
||||||
|
//mark the indicator : LOW: OFF
|
||||||
|
digitalWrite(13, LOW);
|
||||||
|
//let speaker leave turned ON!
|
||||||
|
sine1.amplitude(IDLE_AMP);
|
||||||
|
}
|
||||||
|
else {
|
||||||
|
//let speaker leave turned ON!
|
||||||
|
sine1.amplitude(0);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
//
|
||||||
|
Task sound_player_start_task(0, TASK_ONCE, sound_player_start);
|
||||||
|
Task sound_player_stop_task(0, TASK_ONCE, sound_player_stop);
|
||||||
|
Task sound_player_check_task(0, TASK_FOREVER, sound_player_check, &runner, true);
|
||||||
|
|
||||||
|
//i2c
|
||||||
|
#include <Wire.h>
|
||||||
|
#include "../i2c_protocol.h"
|
||||||
|
void receiveEvent(int numBytes) {
|
||||||
|
//numBytes : how many bytes received(==available)
|
||||||
|
|
||||||
|
// Serial.println("[i2c] on receive!");
|
||||||
|
int nb = Wire.readBytes(cmdstr, CMD_LENGTH);
|
||||||
|
Serial.print("[i2c] cmdstr : ");
|
||||||
|
Serial.println(cmdstr);
|
||||||
|
|
||||||
|
if (CMD_LENGTH == nb) { // receive cmdstr.
|
||||||
|
|
||||||
|
//convert to String
|
||||||
|
String msg = String(cmdstr);
|
||||||
|
|
||||||
|
//parse command string.
|
||||||
|
char first = msg.charAt(0);
|
||||||
|
if (first == 'P') {
|
||||||
|
//
|
||||||
|
// "P#SSS@AAAA" - P: P (play), SSS: song #, A: amp. (x 1000)
|
||||||
|
//
|
||||||
|
String str_song = msg.substring(2,5); // 234
|
||||||
|
String str_gain = msg.substring(6,10); // 6789
|
||||||
|
song_now = str_song.toInt();
|
||||||
|
float amp_gain = str_gain.toFloat() * 0.001;
|
||||||
|
//
|
||||||
|
amp1.gain(amp_gain);
|
||||||
|
amp2.gain(amp_gain);
|
||||||
|
sound_player_start_task.restart();
|
||||||
|
//
|
||||||
|
} else {
|
||||||
|
//
|
||||||
|
// "SXXXXXXXXX" - S: S (stop)
|
||||||
|
//
|
||||||
|
sound_player_stop_task.restart();
|
||||||
|
amp1.gain(1.0);
|
||||||
|
amp2.gain(1.0);
|
||||||
|
//
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
// SD TEST
|
||||||
|
void printDirectory(File dir, int numTabs) {
|
||||||
|
while(true) {
|
||||||
|
|
||||||
|
File entry = dir.openNextFile();
|
||||||
|
if (!entry) {
|
||||||
|
// no more files
|
||||||
|
//Serial.println("**nomorefiles**");
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
for (uint8_t i=0; i<numTabs; i++) {
|
||||||
|
Serial.print('\t');
|
||||||
|
}
|
||||||
|
Serial.print(entry.name());
|
||||||
|
if (entry.isDirectory()) {
|
||||||
|
Serial.println("/");
|
||||||
|
printDirectory(entry, numTabs+1);
|
||||||
|
} else {
|
||||||
|
// files have sizes, directories do not
|
||||||
|
Serial.print("\t\t");
|
||||||
|
Serial.println(entry.size(), DEC);
|
||||||
|
}
|
||||||
|
entry.close();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
//
|
||||||
|
File root;
|
||||||
|
void setup() {
|
||||||
|
|
||||||
|
//serial monitor
|
||||||
|
Serial.begin(9600);
|
||||||
|
delay(50);
|
||||||
|
|
||||||
|
//i2c
|
||||||
|
Wire.begin(I2C_ADDR);
|
||||||
|
Wire.onReceive(receiveEvent);
|
||||||
|
//Wire.onRequest(requestEvent);
|
||||||
|
|
||||||
|
//SD - AudioPlaySdWav @ teensy audio library needs SD.begin() first. don't forget/ignore!
|
||||||
|
//+ let's additionally check contents of SD.
|
||||||
|
if (!SD.begin(BUILTIN_SDCARD)) {
|
||||||
|
Serial.println("[sd] initialization failed!");
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
Serial.println("[sd] initialization done.");
|
||||||
|
root = SD.open("/");
|
||||||
|
printDirectory(root, 0);
|
||||||
|
|
||||||
|
//audio
|
||||||
|
AudioMemory(20);
|
||||||
|
mixer1.gain(0,1.0);
|
||||||
|
mixer1.gain(1,1.0);
|
||||||
|
mixer1.gain(2,0);
|
||||||
|
mixer1.gain(3,0);
|
||||||
|
mixer2.gain(0,1.0);
|
||||||
|
mixer2.gain(1,1.0);
|
||||||
|
mixer2.gain(2,0);
|
||||||
|
mixer2.gain(3,0);
|
||||||
|
amp1.gain(1.0);
|
||||||
|
amp2.gain(1.0);
|
||||||
|
|
||||||
|
//let auto-poweroff speakers stay turned ON!
|
||||||
|
sine1.frequency(IDLE_FREQ);
|
||||||
|
|
||||||
|
//led
|
||||||
|
pinMode(13, OUTPUT);
|
||||||
|
digitalWrite(13, LOW); // LOW: OFF
|
||||||
|
|
||||||
|
//player task
|
||||||
|
runner.addTask(sound_player_start_task);
|
||||||
|
runner.addTask(sound_player_stop_task);
|
||||||
|
|
||||||
|
//
|
||||||
|
Serial.println("[setup] done.");
|
||||||
|
}
|
||||||
|
|
||||||
|
void loop() {
|
||||||
|
runner.execute();
|
||||||
|
}
|
||||||
3
members/speakers/upload.sh
Executable file
3
members/speakers/upload.sh
Executable file
|
|
@ -0,0 +1,3 @@
|
||||||
|
#!/bin/bash
|
||||||
|
|
||||||
|
pio run -t upload
|
||||||
|
|
@ -1,4 +1,4 @@
|
||||||
;PlatformIO Project Configuration File
|
; PlatformIO Project Configuration File
|
||||||
;
|
;
|
||||||
; Build options: build flags, source filter
|
; Build options: build flags, source filter
|
||||||
; Upload options: custom upload port, speed and extra flags
|
; Upload options: custom upload port, speed and extra flags
|
||||||
|
|
@ -8,19 +8,68 @@
|
||||||
; Please visit documentation for the other options and examples
|
; Please visit documentation for the other options and examples
|
||||||
; https://docs.platformio.org/page/projectconf.html
|
; https://docs.platformio.org/page/projectconf.html
|
||||||
|
|
||||||
[env:teensy35]
|
[platformio]
|
||||||
platform = teensy
|
default_envs = nodemcuv2
|
||||||
board = teensy35
|
; src_dir = src_gps_serial_monitor_oled
|
||||||
|
|
||||||
|
[common]
|
||||||
framework = arduino
|
framework = arduino
|
||||||
|
lib_deps =
|
||||||
|
SPI
|
||||||
|
Wire
|
||||||
|
64 ; ArduinoJson
|
||||||
|
; 64@5.13.4 ; ArduinoJson
|
||||||
|
1269 ; Painless Mesh
|
||||||
|
; 1269@1.3.0 ; Painless Mesh
|
||||||
|
135@1.2.9 ; Adafruit SSD1306
|
||||||
|
13 ; Adafruit GFX Library
|
||||||
|
22 ; Adafruit HX8357 Library
|
||||||
|
377 ; Adafruit STMPE610
|
||||||
|
307 ; Firmata
|
||||||
|
|
||||||
|
; we had very similar issue like --> https://gitlab.com/painlessMesh/painlessMesh/issues/159
|
||||||
|
; but according to the discussion.. this should not happen again.. since that should be fixed @ 1.2.7 and i was using 1.2.8. no?
|
||||||
|
; so.. somehow commented other version requirements.. (dependent libs.)
|
||||||
|
; now.. it seems.. works fine..?
|
||||||
|
; but no clear mind. what was it? and why now ok?
|
||||||
|
|
||||||
[env:nodemcuv2]
|
[env:nodemcuv2]
|
||||||
platform = espressif8266
|
platform = espressif8266
|
||||||
board = nodemcuv2
|
board = nodemcuv2
|
||||||
framework = arduino
|
framework = ${common.framework}
|
||||||
|
lib_deps =
|
||||||
|
ESP8266WiFi
|
||||||
|
Servo(esp8266)
|
||||||
|
; 305@1.2.0 ; ESPAsyncTCP
|
||||||
|
${common.lib_deps}
|
||||||
upload_speed = 921600
|
upload_speed = 921600
|
||||||
|
|
||||||
[env:huzzah]
|
[env:huzzah]
|
||||||
platform = espressif8266
|
platform = espressif8266
|
||||||
board = huzzah
|
board = huzzah
|
||||||
framework = arduino
|
framework = ${common.framework}
|
||||||
|
lib_deps =
|
||||||
|
ESP8266WiFi
|
||||||
|
Servo(esp8266)
|
||||||
|
; 305@1.2.0 ; ESPAsyncTCP
|
||||||
|
${common.lib_deps}
|
||||||
upload_speed = 921600
|
upload_speed = 921600
|
||||||
|
|
||||||
|
[env:featheresp32]
|
||||||
|
build_unflags = -std=gnu++11
|
||||||
|
build_flags = -std=gnu++14 ; AsyncTCP wants this.
|
||||||
|
platform = espressif32
|
||||||
|
board = featheresp32
|
||||||
|
framework = ${common.framework}
|
||||||
|
lib_deps =
|
||||||
|
1826@1.0.3 ; AsyncTCP
|
||||||
|
${common.lib_deps}
|
||||||
|
upload_speed = 921600
|
||||||
|
|
||||||
|
|
||||||
|
; < NOTE >
|
||||||
|
; to enable verbose output type in the terminal -->
|
||||||
|
; $ platformio settings set force_verbose Yes
|
||||||
|
|
||||||
|
; then confirm the change -->
|
||||||
|
; $ platformio settings get
|
||||||
|
|
|
||||||
506
src/main.cpp
506
src/main.cpp
|
|
@ -1,304 +1,224 @@
|
||||||
// ArduinoJson - arduinojson.org
|
|
||||||
// Copyright Benoit Blanchon 2014-2019
|
|
||||||
// MIT License
|
|
||||||
//
|
//
|
||||||
// This example shows how to generate a JSON document with ArduinoJson.
|
// Exhibition @ exhibition-space
|
||||||
|
// <one and twelve one-hundred-eighth seconds at the prince's room>
|
||||||
|
//
|
||||||
|
// Feb. 11 @ 2019
|
||||||
//
|
//
|
||||||
// https://arduinojson.org/v6/example/generator/
|
|
||||||
|
|
||||||
#include <Arduino.h>
|
// the common sense
|
||||||
#include <ArduinoJson.h>
|
#include "common.h"
|
||||||
|
|
||||||
|
#if (IDENTITY == ID_SPEAK_A)
|
||||||
|
#include "../members/speaker_a.cpp"
|
||||||
|
//
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// painless mesh
|
||||||
|
painlessMesh mesh;
|
||||||
|
|
||||||
|
// firmata
|
||||||
|
#if (FIRMATA_USE == FIRMATA_ON)
|
||||||
|
#include <Firmata.h>
|
||||||
|
#endif
|
||||||
|
|
||||||
|
//scheduler
|
||||||
|
Scheduler runner;
|
||||||
|
|
||||||
|
//task #0 : connection indicator
|
||||||
|
bool onFlag = false;
|
||||||
|
bool isConnected = false;
|
||||||
|
//prototypes
|
||||||
|
void taskStatusBlink_steadyOn();
|
||||||
|
void taskStatusBlink_slowblink_insync();
|
||||||
|
void taskStatusBlink_fastblink();
|
||||||
|
void taskStatusBlink_steadyOff();
|
||||||
|
//the task
|
||||||
|
Task statusblinks(0, 1, &taskStatusBlink_steadyOn); // at start, steady on. default == disabled. ==> setup() will enable.
|
||||||
|
// when disconnected, steadyon.
|
||||||
|
void taskStatusBlink_steadyOn() {
|
||||||
|
onFlag = true;
|
||||||
|
}
|
||||||
|
// blink per 1s. sync-ed.
|
||||||
|
void taskStatusBlink_slowblink_insync() {
|
||||||
|
// toggler
|
||||||
|
if (onFlag) {
|
||||||
|
onFlag = false;
|
||||||
|
}
|
||||||
|
else {
|
||||||
|
onFlag = true;
|
||||||
|
}
|
||||||
|
// 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
|
||||||
|
}
|
||||||
|
}
|
||||||
|
void taskStatusBlink_fastblink() {
|
||||||
|
}
|
||||||
|
// when connected, steadyoff. (?)
|
||||||
|
void taskStatusBlink_steadyOff() {
|
||||||
|
onFlag = false;
|
||||||
|
}
|
||||||
|
|
||||||
|
// 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 (BOARD_SELECT == BOARD_NODEMCU_ESP12E)
|
||||||
|
ESP.reset();
|
||||||
|
#elif (BOARD_SELECT == BOARD_NODEMCU_ESP32)
|
||||||
|
ESP.restart(); // esp32 doesn't support 'reset()' yet... (restart() is framework-supported, reset() is more forced hardware-reset-action)
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
}
|
||||||
|
//
|
||||||
|
isConnected_prev = isConnected;
|
||||||
|
}
|
||||||
|
Task nothappyalone_task(1000, TASK_FOREVER, ¬happyalone, &runner, true); // by default, ENABLED.
|
||||||
|
|
||||||
|
// mesh callbacks
|
||||||
|
void receivedCallback(uint32_t from, String & msg) { // REQUIRED
|
||||||
|
// let the member device know.
|
||||||
|
gotMessageCallback(from, msg);
|
||||||
|
}
|
||||||
|
void changedConnectionCallback() {
|
||||||
|
// 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;
|
||||||
|
}
|
||||||
|
else {
|
||||||
|
// disconnected!!
|
||||||
|
statusblinks.set(0, 1, &taskStatusBlink_steadyOn);
|
||||||
|
statusblinks.enable();
|
||||||
|
//
|
||||||
|
isConnected = false;
|
||||||
|
}
|
||||||
|
// let the member device know.
|
||||||
|
gotChangedConnectionCallback();
|
||||||
|
}
|
||||||
|
void newConnectionCallback(uint32_t nodeId) {
|
||||||
|
changedConnectionCallback();
|
||||||
|
}
|
||||||
|
|
||||||
|
void setup_member();
|
||||||
void setup() {
|
void setup() {
|
||||||
// Initialize Serial port
|
//led
|
||||||
Serial.begin(9600);
|
pinMode(LED_PIN, OUTPUT);
|
||||||
// while (!Serial) continue;
|
|
||||||
|
|
||||||
|
//mesh
|
||||||
|
WiFiMode_t node_type = WIFI_AP_STA;
|
||||||
|
#if (NODE_TYPE == NODE_TYPE_STA_ONLY)
|
||||||
|
system_phy_set_max_tpw(0);
|
||||||
|
node_type = WIFI_STA;
|
||||||
|
#endif
|
||||||
|
#if (FIRMATA_USE == FIRMATA_ON)
|
||||||
|
mesh.setDebugMsgTypes( ERROR );
|
||||||
|
#elif (FIRMATA_USE == FIRMATA_OFF)
|
||||||
|
// mesh.setDebugMsgTypes(ERROR | DEBUG | CONNECTION);
|
||||||
|
mesh.setDebugMsgTypes( ERROR | STARTUP );
|
||||||
|
#endif
|
||||||
|
mesh.init(MESH_SSID, MESH_PASSWORD, &runner, MESH_PORT, node_type, MESH_CHANNEL);
|
||||||
|
|
||||||
|
//
|
||||||
|
// 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);
|
||||||
|
//
|
||||||
|
|
||||||
|
#ifdef MESH_ANCHOR
|
||||||
|
mesh.setContainsRoot(true);
|
||||||
|
#endif
|
||||||
|
//callbacks
|
||||||
|
mesh.onReceive(&receivedCallback);
|
||||||
|
mesh.onNewConnection(&newConnectionCallback);
|
||||||
|
mesh.onChangedConnections(&changedConnectionCallback);
|
||||||
|
|
||||||
|
//tasks
|
||||||
|
runner.addTask(statusblinks);
|
||||||
|
statusblinks.enable();
|
||||||
|
|
||||||
|
#if (FIRMATA_USE == FIRMATA_ON)
|
||||||
|
Firmata.setFirmwareVersion(0,1);
|
||||||
|
Firmata.attach(ANALOG_MESSAGE, analogWriteCallback);
|
||||||
|
Firmata.begin(57600);
|
||||||
|
#elif (FIRMATA_USE == FIRMATA_OFF)
|
||||||
|
//serial
|
||||||
|
Serial.begin(9600);
|
||||||
|
delay(100);
|
||||||
|
Serial.println("setup done.");
|
||||||
|
Serial.print("IDENTITY: ");
|
||||||
|
Serial.println(IDENTITY);
|
||||||
|
#if (NODE_TYPE == NODE_TYPE_STA_ONLY)
|
||||||
|
Serial.println("INFO: we are in the WIFI_STA mode!");
|
||||||
|
#endif
|
||||||
|
#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.");
|
||||||
|
}
|
||||||
|
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,
|
||||||
|
|
||||||
|
// 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
|
||||||
|
|
||||||
|
//setup_member
|
||||||
|
setup_member();
|
||||||
}
|
}
|
||||||
|
|
||||||
void loop() {
|
void loop() {
|
||||||
// not used in this example
|
runner.execute();
|
||||||
StaticJsonDocument<200> doc;
|
mesh.update();
|
||||||
doc["sensor"] = "gps";
|
#if (BOARD_SELECT == BOARD_NODEMCU_ESP32)
|
||||||
doc["time"] = 1351824120;
|
digitalWrite(LED_PIN, onFlag); // value == true is ON.
|
||||||
JsonArray data = doc.createNestedArray("data");
|
#else
|
||||||
data.add(48.756080);
|
digitalWrite(LED_PIN, !onFlag); // value == false is ON. so onFlag == true is ON. (pull-up)
|
||||||
data.add(2.302038);
|
#endif
|
||||||
serializeJson(doc, Serial);
|
|
||||||
Serial.println();
|
|
||||||
// serializeJsonPretty(doc, Serial);
|
|
||||||
|
|
||||||
delay(1000);
|
#if (FIRMATA_USE == FIRMATA_ON)
|
||||||
|
while (Firmata.available()) {
|
||||||
|
Firmata.processInput();
|
||||||
|
}
|
||||||
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
// See also
|
|
||||||
// --------
|
|
||||||
//
|
|
||||||
// https://arduinojson.org/ contains the documentation for all the functions
|
|
||||||
// used above. It also includes an FAQ that will help you solve any
|
|
||||||
// serialization problem.
|
|
||||||
//
|
|
||||||
// The book "Mastering ArduinoJson" contains a tutorial on serialization.
|
|
||||||
// It begins with a simple example, like the one above, and then adds more
|
|
||||||
// features like serializing directly to a file or an HTTP request.
|
|
||||||
// Learn more at https://arduinojson.org/book/
|
|
||||||
// Use the coupon code TWENTY for a 20% discount ❤❤❤❤❤
|
|
||||||
|
|
||||||
// //************************************************************
|
|
||||||
// // this is a simple example that uses the easyMesh library
|
|
||||||
// //
|
|
||||||
// // 1. blinks led once for every node on the mesh
|
|
||||||
// // 2. blink cycle repeats every BLINK_PERIOD
|
|
||||||
// // 3. sends a silly message to every node on the mesh at a random time between 1 and 5 seconds
|
|
||||||
// // 4. prints anything it receives to Serial.print
|
|
||||||
// //
|
|
||||||
// //
|
|
||||||
// //************************************************************
|
|
||||||
// #include <Arduino.h>
|
|
||||||
// #include <painlessMesh.h>
|
|
||||||
//
|
|
||||||
// #include <OSCBundle.h>
|
|
||||||
// #include <OSCBoards.h>
|
|
||||||
// #include "StringStream.h"
|
|
||||||
//
|
|
||||||
// // some gpio pin that is connected to an LED...
|
|
||||||
// // on my rig, this is 5, change to the right number of your LED.
|
|
||||||
// #define LED 2 // GPIO number of connected LED, ON ESP-12 IS GPIO2
|
|
||||||
//
|
|
||||||
// #define BLINK_PERIOD 3000 // milliseconds until cycle repeat
|
|
||||||
// #define BLINK_DURATION 100 // milliseconds LED is on for
|
|
||||||
//
|
|
||||||
// #define MESH_SSID "whateverYouLike"
|
|
||||||
// #define MESH_PASSWORD "somethingSneaky"
|
|
||||||
// #define MESH_PORT 5555
|
|
||||||
//
|
|
||||||
// // Prototypes
|
|
||||||
// void sendMessage();
|
|
||||||
// void receivedCallback(uint32_t from, String & msg);
|
|
||||||
// void newConnectionCallback(uint32_t nodeId);
|
|
||||||
// void changedConnectionCallback();
|
|
||||||
// void nodeTimeAdjustedCallback(int32_t offset);
|
|
||||||
// void delayReceivedCallback(uint32_t from, int32_t delay);
|
|
||||||
//
|
|
||||||
// Scheduler userScheduler; // to control your personal task
|
|
||||||
// painlessMesh mesh;
|
|
||||||
//
|
|
||||||
// bool calc_delay = false;
|
|
||||||
// SimpleList<uint32_t> nodes;
|
|
||||||
//
|
|
||||||
// void sendMessage(); // Prototype
|
|
||||||
// Task taskSendMessage( TASK_SECOND * 1, TASK_FOREVER, &sendMessage ); // start with a one second interval
|
|
||||||
//
|
|
||||||
// // Task to blink the number of nodes
|
|
||||||
// Task blinkNoNodes;
|
|
||||||
// bool onFlag = false;
|
|
||||||
//
|
|
||||||
// void setup() {
|
|
||||||
// Serial.begin(115200);
|
|
||||||
//
|
|
||||||
// pinMode(LED, OUTPUT);
|
|
||||||
//
|
|
||||||
// mesh.setDebugMsgTypes(ERROR | DEBUG); // set before init() so that you can see error messages
|
|
||||||
// // mesh.setDebugMsgTypes(ERROR | MESH_STATUS | CONNECTION | SYNC | COMMUNICATION | GENERAL | MSG_TYPES | REMOTE); // set before init() so that you can see error messages
|
|
||||||
//
|
|
||||||
// mesh.init(MESH_SSID, MESH_PASSWORD, &userScheduler, MESH_PORT);
|
|
||||||
// mesh.onReceive(&receivedCallback);
|
|
||||||
// mesh.onNewConnection(&newConnectionCallback);
|
|
||||||
// mesh.onChangedConnections(&changedConnectionCallback);
|
|
||||||
// mesh.onNodeTimeAdjusted(&nodeTimeAdjustedCallback);
|
|
||||||
// mesh.onNodeDelayReceived(&delayReceivedCallback);
|
|
||||||
//
|
|
||||||
// userScheduler.addTask( taskSendMessage );
|
|
||||||
// taskSendMessage.enable();
|
|
||||||
//
|
|
||||||
// blinkNoNodes.set(BLINK_PERIOD, (mesh.getNodeList().size() + 1) * 2, []() {
|
|
||||||
// // If on, switch off, else switch on
|
|
||||||
// if (onFlag)
|
|
||||||
// onFlag = false;
|
|
||||||
// else
|
|
||||||
// onFlag = true;
|
|
||||||
// blinkNoNodes.delay(BLINK_DURATION);
|
|
||||||
//
|
|
||||||
// if (blinkNoNodes.isLastIteration()) {
|
|
||||||
// // Finished blinking. Reset task for next run
|
|
||||||
// // blink number of nodes (including this node) times
|
|
||||||
// blinkNoNodes.setIterations((mesh.getNodeList().size() + 1) * 2);
|
|
||||||
// // Calculate delay based on current mesh time and BLINK_PERIOD
|
|
||||||
// // This results in blinks between nodes being synced
|
|
||||||
// blinkNoNodes.enableDelayed(BLINK_PERIOD -
|
|
||||||
// (mesh.getNodeTime() % (BLINK_PERIOD*1000))/1000);
|
|
||||||
// }
|
|
||||||
// });
|
|
||||||
// userScheduler.addTask(blinkNoNodes);
|
|
||||||
// blinkNoNodes.enable();
|
|
||||||
//
|
|
||||||
// randomSeed(analogRead(A0));
|
|
||||||
// }
|
|
||||||
//
|
|
||||||
// void loop() {
|
|
||||||
// mesh.update();
|
|
||||||
// digitalWrite(LED, !onFlag);
|
|
||||||
// }
|
|
||||||
//
|
|
||||||
// OSCErrorCode error;
|
|
||||||
// void oscRecvNodeId(OSCMessage &msg) {
|
|
||||||
// Serial.print("/nodeid --> ");
|
|
||||||
// Serial.println(msg.getInt(0));
|
|
||||||
// }
|
|
||||||
//
|
|
||||||
// void oscRecvMyFreeMemory(OSCMessage &msg) {
|
|
||||||
// Serial.print("/myFreeMemory --> ");
|
|
||||||
// Serial.println(msg.getInt(0));
|
|
||||||
// }
|
|
||||||
//
|
|
||||||
//
|
|
||||||
// void sendMessage() {
|
|
||||||
// //
|
|
||||||
// OSCBundle bndl;
|
|
||||||
// String oscmsg;
|
|
||||||
// StringStream sstream(oscmsg);
|
|
||||||
// bndl.add("/nodeid").add(mesh.getNodeId());
|
|
||||||
// bndl.add("/myFreeMemory").add(ESP.getFreeHeap());
|
|
||||||
// bndl.send(sstream);
|
|
||||||
// //
|
|
||||||
// mesh.sendBroadcast(oscmsg);
|
|
||||||
//
|
|
||||||
// //
|
|
||||||
// int size = sstream.available();
|
|
||||||
// //
|
|
||||||
// OSCBundle bndl2;
|
|
||||||
// if (size > 0) {
|
|
||||||
// while (size--) {
|
|
||||||
// bndl2.fill(sstream.read());
|
|
||||||
// }
|
|
||||||
// if (!bndl2.hasError()) {
|
|
||||||
// Serial.println("bndl2.dispatch...");
|
|
||||||
// bndl2.dispatch("/nodeid", oscRecvNodeId);
|
|
||||||
// bndl2.dispatch("/myFreeMemory", oscRecvMyFreeMemory);
|
|
||||||
// } else {
|
|
||||||
// error = bndl2.getError();
|
|
||||||
// Serial.print("error: ");
|
|
||||||
// Serial.println(error);
|
|
||||||
// }
|
|
||||||
// }
|
|
||||||
//
|
|
||||||
//
|
|
||||||
// if (calc_delay) {
|
|
||||||
// SimpleList<uint32_t>::iterator node = nodes.begin();
|
|
||||||
// while (node != nodes.end()) {
|
|
||||||
// mesh.startDelayMeas(*node);
|
|
||||||
// node++;
|
|
||||||
// }
|
|
||||||
// calc_delay = false;
|
|
||||||
// }
|
|
||||||
//
|
|
||||||
// Serial.print("Sending message: ");
|
|
||||||
// Serial.println(oscmsg);
|
|
||||||
//
|
|
||||||
// taskSendMessage.setInterval( random(TASK_SECOND * 1, TASK_SECOND * 5)); // between 1 and 5 seconds
|
|
||||||
// }
|
|
||||||
//
|
|
||||||
// void receivedCallback(uint32_t from, String & msg) {
|
|
||||||
// Serial.printf("startHere: Received from %u msg=", from);
|
|
||||||
// Serial.println(msg);
|
|
||||||
// //
|
|
||||||
// OSCBundle bndl;
|
|
||||||
// String oscmsg;
|
|
||||||
// StringStream sstream(oscmsg);
|
|
||||||
// oscmsg = msg;
|
|
||||||
// int size = sstream.available();
|
|
||||||
// //
|
|
||||||
// if (size > 0) {
|
|
||||||
// while (size--) {
|
|
||||||
// bndl.fill(sstream.read());
|
|
||||||
// }
|
|
||||||
// if (!bndl.hasError()) {
|
|
||||||
// Serial.println("bndl.dispatch...");
|
|
||||||
// bndl.dispatch("/nodeid", oscRecvNodeId);
|
|
||||||
// bndl.dispatch("/myFreeMemory", oscRecvMyFreeMemory);
|
|
||||||
// } else {
|
|
||||||
// error = bndl.getError();
|
|
||||||
// Serial.print("error: ");
|
|
||||||
// Serial.println(error);
|
|
||||||
// }
|
|
||||||
// }
|
|
||||||
// }
|
|
||||||
//
|
|
||||||
// void newConnectionCallback(uint32_t nodeId) {
|
|
||||||
// // Reset blink task
|
|
||||||
// onFlag = false;
|
|
||||||
// blinkNoNodes.setIterations((mesh.getNodeList().size() + 1) * 2);
|
|
||||||
// blinkNoNodes.enableDelayed(BLINK_PERIOD - (mesh.getNodeTime() % (BLINK_PERIOD*1000))/1000);
|
|
||||||
//
|
|
||||||
// Serial.printf("--> startHere: New Connection, nodeId = %u\n", nodeId);
|
|
||||||
// Serial.printf("--> startHere: New Connection, %s\n", mesh.subConnectionJson(true).c_str());
|
|
||||||
// }
|
|
||||||
//
|
|
||||||
// void changedConnectionCallback() {
|
|
||||||
// Serial.printf("Changed connections\n");
|
|
||||||
// // Reset blink task
|
|
||||||
// onFlag = false;
|
|
||||||
// blinkNoNodes.setIterations((mesh.getNodeList().size() + 1) * 2);
|
|
||||||
// blinkNoNodes.enableDelayed(BLINK_PERIOD - (mesh.getNodeTime() % (BLINK_PERIOD*1000))/1000);
|
|
||||||
//
|
|
||||||
// nodes = mesh.getNodeList();
|
|
||||||
//
|
|
||||||
// Serial.printf("Num nodes: %d\n", nodes.size());
|
|
||||||
// Serial.printf("Connection list:");
|
|
||||||
//
|
|
||||||
// SimpleList<uint32_t>::iterator node = nodes.begin();
|
|
||||||
// while (node != nodes.end()) {
|
|
||||||
// Serial.printf(" %u", *node);
|
|
||||||
// node++;
|
|
||||||
// }
|
|
||||||
// Serial.println();
|
|
||||||
// calc_delay = true;
|
|
||||||
// }
|
|
||||||
//
|
|
||||||
// void nodeTimeAdjustedCallback(int32_t offset) {
|
|
||||||
// Serial.printf("Adjusted time %u. Offset = %d\n", mesh.getNodeTime(), offset);
|
|
||||||
// }
|
|
||||||
//
|
|
||||||
// void delayReceivedCallback(uint32_t from, int32_t delay) {
|
|
||||||
// Serial.printf("Delay to node %u is %d us\n", from, delay);
|
|
||||||
// }
|
|
||||||
//
|
|
||||||
// // #include <Arduino.h>
|
|
||||||
// //
|
|
||||||
// // #include <OSCBundle.h>
|
|
||||||
// // #include <OSCBoards.h>
|
|
||||||
// //
|
|
||||||
// // #include "StringStream.h"
|
|
||||||
// //
|
|
||||||
// // void setup() {
|
|
||||||
// // Serial.begin(9600);
|
|
||||||
// // }
|
|
||||||
// //
|
|
||||||
// // void loop(){
|
|
||||||
// // OSCBundle bndl;
|
|
||||||
// // int size;
|
|
||||||
// // //receive a bundle
|
|
||||||
// //
|
|
||||||
// // while(!SLIPSerial.endofPacket())
|
|
||||||
// // if( (size = SLIPSerial.available()) > 0)
|
|
||||||
// // {
|
|
||||||
// // while(size--)
|
|
||||||
// // bndl.fill(SLIPSerial.read());
|
|
||||||
// // }
|
|
||||||
// //
|
|
||||||
// // // if(!bndl.hasError())
|
|
||||||
// // // {
|
|
||||||
// // static int32_t sequencenumber=0;
|
|
||||||
// // // we can sneak an addition onto the end of the bundle
|
|
||||||
// // // bndl.add("/micros").add((int32_t)micros()); // (int32_t) is the type of OSC Integers
|
|
||||||
// // bndl.add("/sequencenumber").add(sequencenumber++);
|
|
||||||
// // bndl.add("/digital/5").add(digitalRead(5)==HIGH);
|
|
||||||
// // // bndl.add("/lsb").add((sequencenumber &1)==1);
|
|
||||||
// // String sstr;
|
|
||||||
// // StringStream ss(sstr);
|
|
||||||
// // bndl.send(ss);
|
|
||||||
// // Serial.println(sstr);
|
|
||||||
// // // }
|
|
||||||
// //
|
|
||||||
// // delay(1000);
|
|
||||||
// // }
|
|
||||||
|
|
|
||||||
Loading…
Reference in a new issue