From 176927ae73be5160ece4d2d2a599aa5eb8eefcde Mon Sep 17 00:00:00 2001 From: Victor Nakoryakov Date: Thu, 27 Jul 2017 16:49:48 +0300 Subject: [PATCH] feat(stdlib): implement bunch of nodes - xod/core/count - xod/core/pulse-on-* - xod/units - xod/common-hardware/gp2y0a* - xod/common-hardware/dht11-thermometer - xod/common-hardware/button --- .../src/core/styles/components/Inspector.scss | 2 + .../lib/xod/common-hardware/button/patch.xodp | 122 +++++++++ .../dht11-thermometer/arduino.cpp | 142 ++++++++++ .../dht11-thermometer/patch.xodp | 56 ++++ .../gp2y0a-linearize/patch.xodp | 249 ++++++++++++++++++ .../gp2y0a02-range-meter/patch.xodp | 106 ++++++++ .../gp2y0a21-range-meter/patch.xodp | 106 ++++++++ .../gp2y0a41-range-meter/patch.xodp | 107 ++++++++ .../lib/xod/common-hardware/servo/patch.xodp | 4 +- workspace/lib/xod/core/count/any.cpp | 19 ++ workspace/lib/xod/core/count/patch.xodp | 55 ++++ .../lib/xod/core/debounce-boolean/any.cpp | 20 ++ .../lib/xod/core/debounce-boolean/patch.xodp | 45 ++++ workspace/lib/xod/core/fade/any.cpp | 38 +++ workspace/lib/xod/core/fade/patch.xodp | 58 ++++ .../lib/xod/core/pulse-on-change/any.cpp | 16 ++ .../lib/xod/core/pulse-on-change/patch.xodp | 29 ++ .../lib/xod/core/pulse-on-false/patch.xodp | 53 ++++ workspace/lib/xod/core/pulse-on-true/any.cpp | 15 ++ workspace/lib/xod/core/pulse-on-true/any.js | 14 + .../lib/xod/core/pulse-on-true/patch.xodp | 29 ++ workspace/lib/xod/units/c-to-f/patch.xodp | 58 ++++ workspace/lib/xod/units/m-to-cm/patch.xodp | 56 ++++ workspace/lib/xod/units/m-to-ft/patch.xodp | 56 ++++ workspace/lib/xod/units/m-to-in/patch.xodp | 56 ++++ workspace/lib/xod/units/m-to-mm/patch.xodp | 56 ++++ workspace/lib/xod/units/project.xod | 3 + 27 files changed, 1568 insertions(+), 2 deletions(-) create mode 100644 workspace/lib/xod/common-hardware/button/patch.xodp create mode 100644 workspace/lib/xod/common-hardware/dht11-thermometer/arduino.cpp create mode 100644 workspace/lib/xod/common-hardware/dht11-thermometer/patch.xodp create mode 100644 workspace/lib/xod/common-hardware/gp2y0a-linearize/patch.xodp create mode 100644 workspace/lib/xod/common-hardware/gp2y0a02-range-meter/patch.xodp create mode 100644 workspace/lib/xod/common-hardware/gp2y0a21-range-meter/patch.xodp create mode 100644 workspace/lib/xod/common-hardware/gp2y0a41-range-meter/patch.xodp create mode 100644 workspace/lib/xod/core/count/any.cpp create mode 100644 workspace/lib/xod/core/count/patch.xodp create mode 100644 workspace/lib/xod/core/debounce-boolean/any.cpp create mode 100644 workspace/lib/xod/core/debounce-boolean/patch.xodp create mode 100644 workspace/lib/xod/core/fade/any.cpp create mode 100644 workspace/lib/xod/core/fade/patch.xodp create mode 100644 workspace/lib/xod/core/pulse-on-change/any.cpp create mode 100644 workspace/lib/xod/core/pulse-on-change/patch.xodp create mode 100644 workspace/lib/xod/core/pulse-on-false/patch.xodp create mode 100644 workspace/lib/xod/core/pulse-on-true/any.cpp create mode 100644 workspace/lib/xod/core/pulse-on-true/any.js create mode 100644 workspace/lib/xod/core/pulse-on-true/patch.xodp create mode 100644 workspace/lib/xod/units/c-to-f/patch.xodp create mode 100644 workspace/lib/xod/units/m-to-cm/patch.xodp create mode 100644 workspace/lib/xod/units/m-to-ft/patch.xodp create mode 100644 workspace/lib/xod/units/m-to-in/patch.xodp create mode 100644 workspace/lib/xod/units/m-to-mm/patch.xodp create mode 100644 workspace/lib/xod/units/project.xod diff --git a/packages/xod-client/src/core/styles/components/Inspector.scss b/packages/xod-client/src/core/styles/components/Inspector.scss index 1e0fc01e..71a5d489 100644 --- a/packages/xod-client/src/core/styles/components/Inspector.scss +++ b/packages/xod-client/src/core/styles/components/Inspector.scss @@ -176,6 +176,8 @@ } .inspectorTextInput { + font-family: $font-family-condensed; width: 100%; + height: 8em; } } diff --git a/workspace/lib/xod/common-hardware/button/patch.xodp b/workspace/lib/xod/common-hardware/button/patch.xodp new file mode 100644 index 00000000..42bcf0ab --- /dev/null +++ b/workspace/lib/xod/common-hardware/button/patch.xodp @@ -0,0 +1,122 @@ +{ + "description": "Reads a generic button or another mechanical switch. It is expected that the button is normally high, i.e. it is pulled up with a resistor. The node provides signal debounce with 20 ms settle delay.", + "links": [ + { + "id": "B1fDfkF8W", + "input": { + "nodeId": "BkHBM1FLb", + "pinKey": "ry3zLA_Bv1Z" + }, + "output": { + "nodeId": "rkl8GkKUb", + "pinKey": "Sk7EARu8-" + } + }, + { + "id": "S1xwfyYUW", + "input": { + "nodeId": "rkl8GkKUb", + "pinKey": "S101C0OU-" + }, + "output": { + "nodeId": "BypVzytU-", + "pinKey": "B1gI0urv1W" + } + }, + { + "id": "r1bHGkF8W", + "input": { + "nodeId": "BypVzytU-", + "pinKey": "SyLCdSwJZ" + }, + "output": { + "nodeId": "ByG3ZyKLW", + "pinKey": "__out__" + } + }, + { + "id": "rJ2BG1tLW", + "input": { + "nodeId": "BJ--G1tI-", + "pinKey": "__in__" + }, + "output": { + "nodeId": "BkHBM1FLb", + "pinKey": "r1if8ROSDJ-" + } + }, + { + "id": "ryxSz1YIW", + "input": { + "nodeId": "BypVzytU-", + "pinKey": "B1ZUA_Hv1W" + }, + "output": { + "nodeId": "ByNiWkt8Z", + "pinKey": "__out__" + } + } + ], + "nodes": [ + { + "description": "Last read value. Equals to `true` while the button is pressed (hold down) and `false` while it is released.", + "id": "BJ--G1tI-", + "label": "PRS", + "position": { + "x": 138, + "y": 432 + }, + "type": "xod/patch-nodes/output-boolean" + }, + { + "id": "BkHBM1FLb", + "position": { + "x": 138, + "y": 328 + }, + "type": "xod/core/not" + }, + { + "boundValues": { + "__out__": "CONTINUOUSLY" + }, + "description": "Triggers update, i.e. reading value again.", + "id": "ByG3ZyKLW", + "label": "UPD", + "position": { + "x": 266, + "y": 16 + }, + "type": "xod/patch-nodes/input-pulse" + }, + { + "description": "Board port number the button is connected to.", + "id": "ByNiWkt8Z", + "label": "PORT", + "position": { + "x": 10, + "y": 16 + }, + "type": "xod/patch-nodes/input-number" + }, + { + "id": "BypVzytU-", + "position": { + "x": 138, + "y": 120 + }, + "type": "xod/core/digital-input" + }, + { + "boundValues": { + "SkqxAC_LW": 0.02 + }, + "id": "rkl8GkKUb", + "position": { + "x": 138, + "y": 224 + }, + "type": "xod/core/debounce-boolean" + } + ] +} \ No newline at end of file diff --git a/workspace/lib/xod/common-hardware/dht11-thermometer/arduino.cpp b/workspace/lib/xod/common-hardware/dht11-thermometer/arduino.cpp new file mode 100644 index 00000000..3cec27bd --- /dev/null +++ b/workspace/lib/xod/common-hardware/dht11-thermometer/arduino.cpp @@ -0,0 +1,142 @@ + +struct State { + bool reading; +}; + +{{ GENERATED_CODE }} + +enum DhtStatus +{ + DHT_OK = 0, + DHT_START_FAILED_1 = 1, + DHT_START_FAILED_2 = 2, + DHT_READ_TIMEOUT = 3, + DHT_CHECKSUM_FAILURE = 4, +}; + +bool readByte(uint8_t port, uint8_t* out) { + // Restrict waiting to prevent hanging + unsigned long numloops = 0; + unsigned long maxloops = microsecondsToClockCycles(100) / 16; + + // Collect 8 bits from datastream, return them interpreted + // as a byte. I.e. if 0000.0101 is sent, return decimal 5. + + uint8_t result = 0; + for (uint8_t i = 8; i--; ) { + // We enter this during the first start bit (low for 50uS) of the byte + // Wait until pin goes high + numloops = 0; + while (digitalRead(port) == LOW) + if (++numloops == maxloops) + return false; + + // Dataline will now stay high for 27 or 70 uS, depending on + // whether a 0 or a 1 is being sent, respectively. Take to + // a middle of that period to read the value + delayMicroseconds(45); + + if (digitalRead(port) == HIGH) + result |= 1 << i; // set subsequent bit + + // Wait until pin goes low again, which signals the START + // of the NEXT bit's transmission. + numloops = 0; + while (digitalRead(port) == HIGH) + if (++numloops == maxloops) + return false; + } + + *out = result; + return true; +} + +DhtStatus readValues(uint8_t port, Number* outTemp, Number* outRH) { + bool res; + uint8_t data[5]; + + // Stop reading request + digitalWrite(port, HIGH); + + // DHT datasheet says host should keep line high 20-40us, then watch for + // sensor taking line low. That low should last 80us. Acknowledges "start + // read and report" command. + delayMicroseconds(40); + + // Change Arduino pin to an input, to watch for the 80us low explained a + // moment ago. + pinMode(port, INPUT); + delayMicroseconds(40); + + res = digitalRead(port); + + if (res) + return DHT_START_FAILED_1; + + delayMicroseconds(80); + res = digitalRead(port); + + if (!res) + return DHT_START_FAILED_2; + + // After 80us low, the line should be taken high for 80us by the sensor. + // The low following that high is the start of the first bit of the forty + // to come. The method readByte() expects to be called with the system + // already into this low. + delayMicroseconds(80); + + // now ready for data reception... pick up the 5 bytes coming from + // the sensor + for (uint8_t i = 0; i < 5; i++) + if (!readByte(port, data + i)) + return DHT_READ_TIMEOUT; + + // Restore pin to output duties + pinMode(port, OUTPUT); + digitalWrite(port, HIGH); + + // See if data received consistent with checksum received + uint8_t checkSum = data[0] + data[1] + data[2] + data[3]; + if (data[4] != checkSum) + return DHT_CHECKSUM_FAILURE; + + // Decode the data (compose integer byte with fraction byte) + // For Relative Humidity also scale range from 0..100 to 0..1 + *outTemp = Number(data[2]) + Number(data[3]) / 100.0; + *outRH = (Number(data[0]) + Number(data[1]) / 100.0) / 100.0; + + return DHT_OK; +} + +void enterIdleState(uint8_t port) { + // Restore pin to output duties + pinMode(port, OUTPUT); + digitalWrite(port, HIGH); +} + +void evaluate(Context ctx) { + State* state = getState(ctx); + uint8_t port = (uint8_t)getValue(ctx); + + if (state->reading) { + Number temp; + Number rh; + auto status = readValues(port, &temp, &rh); + if (status == DHT_OK) { + emitValue(ctx, temp); + emitValue(ctx, rh); + } + + enterIdleState(port); + state->reading = false; + } else if (isInputDirty(ctx)) { + // initiate request for data + pinMode(port, OUTPUT); + digitalWrite(port, LOW); + // for request we should keep the line low for 18+ ms + setTimeout(ctx, 18); + state->reading = true; + } else { + enterIdleState(port); + } +} diff --git a/workspace/lib/xod/common-hardware/dht11-thermometer/patch.xodp b/workspace/lib/xod/common-hardware/dht11-thermometer/patch.xodp new file mode 100644 index 00000000..402c27f0 --- /dev/null +++ b/workspace/lib/xod/common-hardware/dht11-thermometer/patch.xodp @@ -0,0 +1,56 @@ +{ + "description": "Reads temperature and humidity from a DHT11 sensor.", + "nodes": [ + { + "description": "Last read temperature in °C.", + "id": "BJ244qwLZ", + "label": "Tc", + "position": { + "x": 10, + "y": 224 + }, + "type": "xod/patch-nodes/output-number" + }, + { + "id": "BJ3PEqDLb", + "position": { + "x": 10, + "y": 120 + }, + "type": "xod/patch-nodes/not-implemented-in-xod" + }, + { + "description": "Relative humidity in ragne [0.0, 1.0]", + "id": "HkgBE9D8Z", + "label": "RH", + "position": { + "x": 138, + "y": 224 + }, + "type": "xod/patch-nodes/output-number" + }, + { + "description": "Board port number the thermometer is connected to.", + "id": "SkUQV5wIb", + "label": "PORT", + "position": { + "x": 10, + "y": 16 + }, + "type": "xod/patch-nodes/input-number" + }, + { + "boundValues": { + "__out__": "CONTINUOUSLY" + }, + "description": "Triggers an update, i.e. reading values again.", + "id": "ryeE45PLZ", + "label": "UPD", + "position": { + "x": 138, + "y": 16 + }, + "type": "xod/patch-nodes/input-pulse" + } + ] +} \ No newline at end of file diff --git a/workspace/lib/xod/common-hardware/gp2y0a-linearize/patch.xodp b/workspace/lib/xod/common-hardware/gp2y0a-linearize/patch.xodp new file mode 100644 index 00000000..f954e0b3 --- /dev/null +++ b/workspace/lib/xod/common-hardware/gp2y0a-linearize/patch.xodp @@ -0,0 +1,249 @@ +{ + "description": "Transforms raw analog values of a Sharp infrared range meter to distance units.", + "links": [ + { + "id": "BJKeYrD8W", + "input": { + "nodeId": "HJA0wrDU-", + "pinKey": "ry1z8CuBDy-" + }, + "output": { + "nodeId": "BJrkFSDL-", + "pinKey": "__out__" + } + }, + { + "id": "BkReuHPUb", + "input": { + "nodeId": "HJ8g_rP8W", + "pinKey": "BytUCdHD1-" + }, + "output": { + "nodeId": "HJA0wrDU-", + "pinKey": "H12bIR_SPyZ" + } + }, + { + "id": "BkmwOHDU-", + "input": { + "nodeId": "Hk1vOrPIZ", + "pinKey": "BypX80uSD1Z" + }, + "output": { + "nodeId": "HJ8g_rP8W", + "pinKey": "BkqLCOSw1W" + } + }, + { + "id": "By9gFrv8-", + "input": { + "nodeId": "HJA0wrDU-", + "pinKey": "HJCWLAdSwyW" + }, + "output": { + "nodeId": "HJd1YBDL-", + "pinKey": "__out__" + } + }, + { + "id": "ByjrKrD8W", + "input": { + "nodeId": "Hk1vOrPIZ", + "pinKey": "rkJ4URuHDJ-" + }, + "output": { + "nodeId": "HJSHFHwI-", + "pinKey": "__out__" + } + }, + { + "id": "SJL1uSD8Z", + "input": { + "nodeId": "HJA0wrDU-", + "pinKey": "BJlzICOSv1-" + }, + "output": { + "nodeId": "BymKDSw8W", + "pinKey": "BkQzLCurwJZ" + } + }, + { + "id": "Sk2ltBP8Z", + "input": { + "nodeId": "HJA0wrDU-", + "pinKey": "rJbGU0_Hv1Z" + }, + "output": { + "nodeId": "BkqJFHDLW", + "pinKey": "__out__" + } + }, + { + "id": "SyRgKHDIW", + "input": { + "nodeId": "HJA0wrDU-", + "pinKey": "rkpbU0OrwyZ" + }, + "output": { + "nodeId": "B1p1KBvIW", + "pinKey": "__out__" + } + }, + { + "id": "Sy_YvSPLZ", + "input": { + "nodeId": "BymKDSw8W", + "pinKey": "B1GfLR_SPk-" + }, + "output": { + "nodeId": "SyTBDSwIZ", + "pinKey": "__out__" + } + }, + { + "id": "Synd0wwI-", + "input": { + "nodeId": "Hyl3dSw8-", + "pinKey": "__in__" + }, + "output": { + "nodeId": "rJE5_BwLb", + "pinKey": "BkqLCOSw1W" + } + }, + { + "id": "Syo5dBwLW", + "input": { + "nodeId": "rJE5_BwLb", + "pinKey": "SkdIRuBD1b" + }, + "output": { + "nodeId": "Hk1vOrPIZ", + "pinKey": "HyRmUCdBDkZ" + } + } + ], + "nodes": [ + { + "id": "B1p1KBvIW", + "label": "Xmax", + "position": { + "x": 522, + "y": 16 + }, + "type": "xod/patch-nodes/input-number" + }, + { + "id": "BJrkFSDL-", + "label": "Ymin", + "position": { + "x": 138, + "y": 16 + }, + "type": "xod/patch-nodes/input-number" + }, + { + "id": "BkqJFHDLW", + "label": "Xmin", + "position": { + "x": 394, + "y": 16 + }, + "type": "xod/patch-nodes/input-number" + }, + { + "boundValues": { + "SJ4zUC_BD1-": 5 + }, + "description": "Converts to voltage: 0V..5V", + "id": "BymKDSw8W", + "label": "×5", + "position": { + "x": 10, + "y": 120 + }, + "type": "xod/core/multiply" + }, + { + "boundValues": { + "SkdIRuBD1b": 1 + }, + "description": "Convert 1/(L+SHFT) → L+SHFT", + "id": "HJ8g_rP8W", + "label": "1/Y", + "position": { + "x": 266, + "y": 328 + }, + "type": "xod/core/divide" + }, + { + "id": "HJA0wrDU-", + "position": { + "x": 138, + "y": 224 + }, + "type": "xod/core/map-range" + }, + { + "id": "HJSHFHwI-", + "label": "SHFT", + "position": { + "x": 522, + "y": 328 + }, + "type": "xod/patch-nodes/input-number" + }, + { + "id": "HJd1YBDL-", + "label": "Ymax", + "position": { + "x": 266, + "y": 16 + }, + "type": "xod/patch-nodes/input-number" + }, + { + "boundValues": { + "rkJ4URuHDJ-": 0 + }, + "id": "Hk1vOrPIZ", + "position": { + "x": 394, + "y": 432 + }, + "type": "xod/core/subtract" + }, + { + "id": "Hyl3dSw8-", + "label": "Dm", + "position": { + "x": 394, + "y": 640 + }, + "type": "xod/patch-nodes/output-number" + }, + { + "id": "SyTBDSwIZ", + "label": "A", + "position": { + "x": 10, + "y": 16 + }, + "type": "xod/patch-nodes/input-number" + }, + { + "boundValues": { + "BytUCdHD1-": 100 + }, + "description": "Convert centimeters to meters", + "id": "rJE5_BwLb", + "label": "/100", + "position": { + "x": 394, + "y": 536 + }, + "type": "xod/core/divide" + } + ] +} \ No newline at end of file diff --git a/workspace/lib/xod/common-hardware/gp2y0a02-range-meter/patch.xodp b/workspace/lib/xod/common-hardware/gp2y0a02-range-meter/patch.xodp new file mode 100644 index 00000000..ac0bbfcf --- /dev/null +++ b/workspace/lib/xod/common-hardware/gp2y0a02-range-meter/patch.xodp @@ -0,0 +1,106 @@ +{ + "description": "Reads Sharp infrared range meter GP2Y0A02YK0F (the one with 20…150 cm range).", + "links": [ + { + "id": "H1rhQ5_UZ", + "input": { + "nodeId": "rJf275_U-", + "pinKey": "SyKd0E2x-" + }, + "output": { + "nodeId": "B1rqmq_8Z", + "pinKey": "__out__" + } + }, + { + "id": "HJ_2X5_I-", + "input": { + "nodeId": "SycjXcO8Z", + "pinKey": "SyTBDSwIZ" + }, + "output": { + "nodeId": "rJf275_U-", + "pinKey": "SyBtREhlW" + } + }, + { + "id": "SJ82mquUZ", + "input": { + "nodeId": "rJf275_U-", + "pinKey": "BJuORNheZ" + }, + "output": { + "nodeId": "ByaY75_Ib", + "pinKey": "__out__" + } + }, + { + "id": "rJc675uIZ", + "input": { + "nodeId": "H1JpXq_I-", + "pinKey": "__in__" + }, + "output": { + "nodeId": "SycjXcO8Z", + "pinKey": "Hyl3dSw8-" + } + } + ], + "nodes": [ + { + "boundValues": { + "__out__": "CONTINUOUSLY" + }, + "description": "Triggers an update, i.e. reading values again.", + "id": "B1rqmq_8Z", + "label": "UPD", + "position": { + "x": 138, + "y": 16 + }, + "type": "xod/patch-nodes/input-pulse" + }, + { + "description": "Board port number the sensor is connected to.", + "id": "ByaY75_Ib", + "label": "PORT", + "position": { + "x": 10, + "y": 16 + }, + "type": "xod/patch-nodes/input-number" + }, + { + "description": "Measured distance in meters. Trustworhy only for distances in [0.3, 1.5] meters range.", + "id": "H1JpXq_I-", + "label": "Dm", + "position": { + "x": 266, + "y": 328 + }, + "type": "xod/patch-nodes/output-number" + }, + { + "boundValues": { + "B1p1KBvIW": 0.033, + "BJrkFSDL-": 0.925, + "BkqJFHDLW": 0.014, + "HJd1YBDL-": 2 + }, + "id": "SycjXcO8Z", + "position": { + "x": 138, + "y": 224 + }, + "type": "@/gp2y0a-linearize" + }, + { + "id": "rJf275_U-", + "position": { + "x": 138, + "y": 120 + }, + "type": "xod/core/analog-input" + } + ] +} \ No newline at end of file diff --git a/workspace/lib/xod/common-hardware/gp2y0a21-range-meter/patch.xodp b/workspace/lib/xod/common-hardware/gp2y0a21-range-meter/patch.xodp new file mode 100644 index 00000000..d5a5731c --- /dev/null +++ b/workspace/lib/xod/common-hardware/gp2y0a21-range-meter/patch.xodp @@ -0,0 +1,106 @@ +{ + "description": "Reads Sharp infrared range meter GP2Y0A21YK0F (the one with 10…80 cm range).", + "links": [ + { + "id": "H1rhQ5_UZ", + "input": { + "nodeId": "rJf275_U-", + "pinKey": "SyKd0E2x-" + }, + "output": { + "nodeId": "B1rqmq_8Z", + "pinKey": "__out__" + } + }, + { + "id": "HJ_2X5_I-", + "input": { + "nodeId": "SycjXcO8Z", + "pinKey": "SyTBDSwIZ" + }, + "output": { + "nodeId": "rJf275_U-", + "pinKey": "SyBtREhlW" + } + }, + { + "id": "SJ82mquUZ", + "input": { + "nodeId": "rJf275_U-", + "pinKey": "BJuORNheZ" + }, + "output": { + "nodeId": "ByaY75_Ib", + "pinKey": "__out__" + } + }, + { + "id": "rJc675uIZ", + "input": { + "nodeId": "H1JpXq_I-", + "pinKey": "__in__" + }, + "output": { + "nodeId": "SycjXcO8Z", + "pinKey": "Hyl3dSw8-" + } + } + ], + "nodes": [ + { + "boundValues": { + "__out__": "CONTINUOUSLY" + }, + "description": "Triggers an update, i.e. reading values again.", + "id": "B1rqmq_8Z", + "label": "UPD", + "position": { + "x": 138, + "y": 16 + }, + "type": "xod/patch-nodes/input-pulse" + }, + { + "description": "Board port number the sensor is connected to.", + "id": "ByaY75_Ib", + "label": "PORT", + "position": { + "x": 10, + "y": 16 + }, + "type": "xod/patch-nodes/input-number" + }, + { + "description": "Measured distance in meters. Trustworhy only for distances in [0.1, 0.8] meters range.", + "id": "H1JpXq_I-", + "label": "Dm", + "position": { + "x": 266, + "y": 328 + }, + "type": "xod/patch-nodes/output-number" + }, + { + "boundValues": { + "B1p1KBvIW": 0.1, + "BJrkFSDL-": 0.75, + "BkqJFHDLW": 0.025, + "HJd1YBDL-": 2.325 + }, + "id": "SycjXcO8Z", + "position": { + "x": 138, + "y": 224 + }, + "type": "@/gp2y0a-linearize" + }, + { + "id": "rJf275_U-", + "position": { + "x": 138, + "y": 120 + }, + "type": "xod/core/analog-input" + } + ] +} \ No newline at end of file diff --git a/workspace/lib/xod/common-hardware/gp2y0a41-range-meter/patch.xodp b/workspace/lib/xod/common-hardware/gp2y0a41-range-meter/patch.xodp new file mode 100644 index 00000000..1ab57f70 --- /dev/null +++ b/workspace/lib/xod/common-hardware/gp2y0a41-range-meter/patch.xodp @@ -0,0 +1,107 @@ +{ + "description": "Reads Sharp infrared range meter GP2Y0A41SK0F (the one with 4…30 cm range).", + "links": [ + { + "id": "B1cJqHvL-", + "input": { + "nodeId": "ryby9rDLZ", + "pinKey": "BJuORNheZ" + }, + "output": { + "nodeId": "SkDkcrvI-", + "pinKey": "__out__" + } + }, + { + "id": "Bkb-5rvIW", + "input": { + "nodeId": "S10ecHDUW", + "pinKey": "__in__" + }, + "output": { + "nodeId": "Bk5lqHvIZ", + "pinKey": "Hyl3dSw8-" + } + }, + { + "id": "By1e9rPI-", + "input": { + "nodeId": "ryby9rDLZ", + "pinKey": "SyKd0E2x-" + }, + "output": { + "nodeId": "H1ny9SPLW", + "pinKey": "__out__" + } + }, + { + "id": "ByFW5Bv8-", + "input": { + "nodeId": "Bk5lqHvIZ", + "pinKey": "SyTBDSwIZ" + }, + "output": { + "nodeId": "ryby9rDLZ", + "pinKey": "SyBtREhlW" + } + } + ], + "nodes": [ + { + "boundValues": { + "B1p1KBvIW": 0.107, + "BJrkFSDL-": 0.3, + "BkqJFHDLW": 0.025, + "HJSHFHwI-": 0.42, + "HJd1YBDL-": 1.4 + }, + "id": "Bk5lqHvIZ", + "position": { + "x": 138, + "y": 224 + }, + "type": "@/gp2y0a-linearize" + }, + { + "boundValues": { + "__out__": "CONTINUOUSLY" + }, + "description": "Triggers an update, i.e. reading values again.", + "id": "H1ny9SPLW", + "label": "UPD", + "position": { + "x": 138, + "y": 16 + }, + "type": "xod/patch-nodes/input-pulse" + }, + { + "description": "Measured distance in meters. Trustworhy only for distances in [0.04, 0.30] meters range.", + "id": "S10ecHDUW", + "label": "Dm", + "position": { + "x": 266, + "y": 328 + }, + "type": "xod/patch-nodes/output-number" + }, + { + "description": "Board port number the sensor is connected to.", + "id": "SkDkcrvI-", + "label": "PORT", + "position": { + "x": 10, + "y": 16 + }, + "type": "xod/patch-nodes/input-number" + }, + { + "id": "ryby9rDLZ", + "position": { + "x": 138, + "y": 120 + }, + "type": "xod/core/analog-input" + } + ] +} \ No newline at end of file diff --git a/workspace/lib/xod/common-hardware/servo/patch.xodp b/workspace/lib/xod/common-hardware/servo/patch.xodp index 63411282..51e3e977 100644 --- a/workspace/lib/xod/common-hardware/servo/patch.xodp +++ b/workspace/lib/xod/common-hardware/servo/patch.xodp @@ -10,7 +10,7 @@ "type": "xod/patch-nodes/not-implemented-in-xod" }, { - "description": "Board port with servo.", + "description": "Board port number the servo is connected to.", "id": "S1vGmu6Gb", "label": "PORT", "position": { @@ -20,7 +20,7 @@ "type": "xod/patch-nodes/input-number" }, { - "description": "Desired servo angle in degrees (0 … 180)", + "description": "Desired servo angle or value in unit range [0.0, 1.0]. For standard servo 0.0 would be mapped to 0° and 1.0 would be 180°.", "id": "r1sfQ_6fb", "label": "VAL", "position": { diff --git a/workspace/lib/xod/core/count/any.cpp b/workspace/lib/xod/core/count/any.cpp new file mode 100644 index 00000000..bfe70c42 --- /dev/null +++ b/workspace/lib/xod/core/count/any.cpp @@ -0,0 +1,19 @@ + +struct State { + int32_t count = 0; +}; + +{{ GENERATED_CODE }} + +void evaluate(Context ctx) { + State* state = getState(ctx); + + if (isInputDirty(ctx)) { + state->count = 0; + } else if (isInputDirty(ctx)) { + auto step = (int32_t)getValue(ctx); + state->count += step; + } + + emitValue(ctx, state->count); +} diff --git a/workspace/lib/xod/core/count/patch.xodp b/workspace/lib/xod/core/count/patch.xodp new file mode 100644 index 00000000..70f1999c --- /dev/null +++ b/workspace/lib/xod/core/count/patch.xodp @@ -0,0 +1,55 @@ +{ + "description": "Stores a number which gets incremented on each `INC` pulse.", + "nodes": [ + { + "id": "H1MAWAu8-", + "position": { + "x": 10, + "y": 120 + }, + "type": "xod/patch-nodes/not-implemented-in-xod" + }, + { + "description": "Triggers a single increment.", + "id": "HJAq-A_8-", + "label": "INC", + "position": { + "x": 138, + "y": 16 + }, + "type": "xod/patch-nodes/input-pulse" + }, + { + "boundValues": { + "__out__": 1 + }, + "description": "Value to add on each increment. Use a negative value (e.g. -1) to make decrements.", + "id": "HJvqZ0dLZ", + "label": "STEP", + "position": { + "x": 10, + "y": 16 + }, + "type": "xod/patch-nodes/input-number" + }, + { + "description": "Resets the accumulated value to zero.", + "id": "SkUjZA_L-", + "label": "RST", + "position": { + "x": 266, + "y": 16 + }, + "type": "xod/patch-nodes/input-pulse" + }, + { + "description": "The accumulated value.", + "id": "r1yhZRd8W", + "position": { + "x": 10, + "y": 224 + }, + "type": "xod/patch-nodes/output-number" + } + ] +} \ No newline at end of file diff --git a/workspace/lib/xod/core/debounce-boolean/any.cpp b/workspace/lib/xod/core/debounce-boolean/any.cpp new file mode 100644 index 00000000..f394e1e1 --- /dev/null +++ b/workspace/lib/xod/core/debounce-boolean/any.cpp @@ -0,0 +1,20 @@ +struct State { + bool state = false; +}; + +{{ GENERATED_CODE }} + +void evaluate(Context ctx) { + State* state = getState(ctx); + bool x = getValue(ctx); + + if (x != state->state) { + state->state = x; + TimeMs dt = getValue(ctx) * 1000; + setTimeout(ctx, dt); + } else if (!isInputDirty(ctx) && !isInputDirty(ctx)) { + // TODO: implement XOD core function isTimedOut(ctx) to know for + // sure that we’re here because of time elapsed + emitValue(ctx, x); + } +} diff --git a/workspace/lib/xod/core/debounce-boolean/patch.xodp b/workspace/lib/xod/core/debounce-boolean/patch.xodp new file mode 100644 index 00000000..5ef05716 --- /dev/null +++ b/workspace/lib/xod/core/debounce-boolean/patch.xodp @@ -0,0 +1,45 @@ +{ + "description": "Debounces a boolean value. The `OUT` value would change only after a period of at least `Ts` seconds while which the input state `ST` has not changed. The node is useful to fight signal bouncing of mechanical switches.", + "nodes": [ + { + "id": "H12EACuUW", + "position": { + "x": 10, + "y": 120 + }, + "type": "xod/patch-nodes/not-implemented-in-xod" + }, + { + "description": "Input bouncing boolean state.", + "id": "S101C0OU-", + "label": "ST", + "position": { + "x": 10, + "y": 16 + }, + "type": "xod/patch-nodes/input-boolean" + }, + { + "description": "Debounced value.", + "id": "Sk7EARu8-", + "position": { + "x": 10, + "y": 224 + }, + "type": "xod/patch-nodes/output-boolean" + }, + { + "boundValues": { + "__out__": 0.03 + }, + "description": "Debounce time in seconds.", + "id": "SkqxAC_LW", + "label": "Ts", + "position": { + "x": 138, + "y": 16 + }, + "type": "xod/patch-nodes/input-number" + } + ] +} \ No newline at end of file diff --git a/workspace/lib/xod/core/fade/any.cpp b/workspace/lib/xod/core/fade/any.cpp new file mode 100644 index 00000000..bf262c8c --- /dev/null +++ b/workspace/lib/xod/core/fade/any.cpp @@ -0,0 +1,38 @@ +struct State { + Number position; + TimeMs lastUpdateTime; +}; + +{{ GENERATED_CODE }} + +void evaluate(Context ctx) { + State* state = getState(ctx); + if (!isInputDirty(ctx)) { + return; + } + + TimeMs now = transactionTime(); + Number target = getValue(ctx); + Number position = state->position; + + if (target == position) { + // Already done. Store timestamp anyway so that an animation to a new + // value would not jump at the first update + state->lastUpdateTime = now; + return; + } + + Number rate = getValue(ctx); + TimeMs dtMs = now - state->lastUpdateTime; + Number step = (Number)dtMs / 1000. * rate; + + if (target > position) { + position = min(target, position + step); + } else { + position = max(target, position - step); + } + + emitValue(ctx, position); + state->position = position; + state->lastUpdateTime = now; +} diff --git a/workspace/lib/xod/core/fade/patch.xodp b/workspace/lib/xod/core/fade/patch.xodp new file mode 100644 index 00000000..ce981108 --- /dev/null +++ b/workspace/lib/xod/core/fade/patch.xodp @@ -0,0 +1,58 @@ +{ + "description": "Lineary animates an internal value toward target value `TARG` with a rate `RATE`. Use the node to smoothen LED switching, motor starting, or servo angular position update.", + "nodes": [ + { + "description": "The current animation value.", + "id": "BJ0M5JKUW", + "position": { + "x": 138, + "y": 224 + }, + "type": "xod/patch-nodes/output-number" + }, + { + "boundValues": { + "__out__": 1 + }, + "description": "Speed rate in units per second.", + "id": "BkweckF8-", + "label": "RATE", + "position": { + "x": 138, + "y": 16 + }, + "type": "xod/patch-nodes/input-number" + }, + { + "boundValues": { + "__out__": "CONTINUOUSLY" + }, + "description": "Triggers an update (i.e. recalculation) of `OUT` value. Keep the value set to `Continuously` to achieve the most smooth animation possible.", + "id": "HJblc1YUZ", + "label": "UPD", + "position": { + "x": 266, + "y": 16 + }, + "type": "xod/patch-nodes/input-pulse" + }, + { + "description": "The target value to strive for.", + "id": "HyYJqJFLZ", + "label": "TARG", + "position": { + "x": 10, + "y": 16 + }, + "type": "xod/patch-nodes/input-number" + }, + { + "id": "Sk7m5kYIb", + "position": { + "x": 138, + "y": 120 + }, + "type": "xod/patch-nodes/not-implemented-in-xod" + } + ] +} \ No newline at end of file diff --git a/workspace/lib/xod/core/pulse-on-change/any.cpp b/workspace/lib/xod/core/pulse-on-change/any.cpp new file mode 100644 index 00000000..5a659431 --- /dev/null +++ b/workspace/lib/xod/core/pulse-on-change/any.cpp @@ -0,0 +1,16 @@ + +struct State { + Number sample = NAN; +}; + +{{ GENERATED_CODE }} + +void evaluate(Context ctx) { + State* state = getState(ctx); + auto newValue = getValue(ctx); + + if (newValue != state->sample) + emitValue(ctx, 1); + + state->sample = newValue; +} diff --git a/workspace/lib/xod/core/pulse-on-change/patch.xodp b/workspace/lib/xod/core/pulse-on-change/patch.xodp new file mode 100644 index 00000000..8b9c0bcc --- /dev/null +++ b/workspace/lib/xod/core/pulse-on-change/patch.xodp @@ -0,0 +1,29 @@ +{ + "description": "Emits a pulse every time input value changes.", + "nodes": [ + { + "id": "Bk-DbROUZ", + "position": { + "x": 10, + "y": 120 + }, + "type": "xod/patch-nodes/not-implemented-in-xod" + }, + { + "id": "BkjI-COLb", + "position": { + "x": 10, + "y": 16 + }, + "type": "xod/patch-nodes/input-number" + }, + { + "id": "ByAIWR_UZ", + "position": { + "x": 10, + "y": 224 + }, + "type": "xod/patch-nodes/output-pulse" + } + ] +} \ No newline at end of file diff --git a/workspace/lib/xod/core/pulse-on-false/patch.xodp b/workspace/lib/xod/core/pulse-on-false/patch.xodp new file mode 100644 index 00000000..40f85b7b --- /dev/null +++ b/workspace/lib/xod/core/pulse-on-false/patch.xodp @@ -0,0 +1,53 @@ +{ + "description": "Emits a pulse on a rising edge, i.e. when `true` changes to `false`", + "links": [ + { + "id": "HJXReAuIZ", + "input": { + "nodeId": "r1R2gRu8Z", + "pinKey": "ry3zLA_Bv1Z" + }, + "output": { + "nodeId": "H1v3lCu8-", + "pinKey": "__out__" + } + }, + { + "id": "SyV0eAuLZ", + "input": { + "nodeId": "BJxRgAO8-", + "pinKey": "__in__" + }, + "output": { + "nodeId": "r1R2gRu8Z", + "pinKey": "r1if8ROSDJ-" + } + } + ], + "nodes": [ + { + "id": "BJxRgAO8-", + "position": { + "x": 10, + "y": 224 + }, + "type": "xod/patch-nodes/output-pulse" + }, + { + "id": "H1v3lCu8-", + "position": { + "x": 10, + "y": 16 + }, + "type": "xod/patch-nodes/input-boolean" + }, + { + "id": "r1R2gRu8Z", + "position": { + "x": 10, + "y": 120 + }, + "type": "xod/core/not" + } + ] +} \ No newline at end of file diff --git a/workspace/lib/xod/core/pulse-on-true/any.cpp b/workspace/lib/xod/core/pulse-on-true/any.cpp new file mode 100644 index 00000000..a527111b --- /dev/null +++ b/workspace/lib/xod/core/pulse-on-true/any.cpp @@ -0,0 +1,15 @@ +struct State { + bool state = false; +}; + +{{ GENERATED_CODE }} + +void evaluate(Context ctx) { + State* state = getState(ctx); + auto newValue = getValue(ctx); + + if (newValue == true && state->state == false) + emitValue(ctx, 1); + + state->state = newValue; +} diff --git a/workspace/lib/xod/core/pulse-on-true/any.js b/workspace/lib/xod/core/pulse-on-true/any.js new file mode 100644 index 00000000..fc2d3421 --- /dev/null +++ b/workspace/lib/xod/core/pulse-on-true/any.js @@ -0,0 +1,14 @@ +module.exports.setup = function(e) { + e.context.state = false; +}; + +module.exports.evaluate = function(e) { + var state = e.context.state; + var newValue = e.inputs.IN; + + e.context.state = newValue; + + if (!(newValue === true && state === false)) return {}; + + return { OUT: PULSE }; +}; diff --git a/workspace/lib/xod/core/pulse-on-true/patch.xodp b/workspace/lib/xod/core/pulse-on-true/patch.xodp new file mode 100644 index 00000000..e94d7836 --- /dev/null +++ b/workspace/lib/xod/core/pulse-on-true/patch.xodp @@ -0,0 +1,29 @@ +{ + "description": "Emits a pulse on a rising edge, i.e. when false changes to true", + "nodes": [ + { + "id": "__in__", + "position": { + "x": 0, + "y": 0 + }, + "type": "xod/patch-nodes/input-boolean" + }, + { + "id": "__out__", + "position": { + "x": 0, + "y": 300 + }, + "type": "xod/patch-nodes/output-pulse" + }, + { + "id": "noNativeImpl", + "position": { + "x": 138, + "y": 120 + }, + "type": "xod/patch-nodes/not-implemented-in-xod" + } + ] +} \ No newline at end of file diff --git a/workspace/lib/xod/units/c-to-f/patch.xodp b/workspace/lib/xod/units/c-to-f/patch.xodp new file mode 100644 index 00000000..654f0ce2 --- /dev/null +++ b/workspace/lib/xod/units/c-to-f/patch.xodp @@ -0,0 +1,58 @@ +{ + "description": "Maps temperature from °C to °F", + "links": [ + { + "id": "SkvyETuIZ", + "input": { + "nodeId": "H1kiQaO8W", + "pinKey": "__in__" + }, + "output": { + "nodeId": "r1VkETdU-", + "pinKey": "H12bIR_SPyZ" + } + }, + { + "id": "rkUJE6uIZ", + "input": { + "nodeId": "r1VkETdU-", + "pinKey": "BJlzICOSv1-" + }, + "output": { + "nodeId": "Skd9Qa_8W", + "pinKey": "__out__" + } + } + ], + "nodes": [ + { + "id": "H1kiQaO8W", + "position": { + "x": 10, + "y": 224 + }, + "type": "xod/patch-nodes/output-number" + }, + { + "id": "Skd9Qa_8W", + "position": { + "x": 10, + "y": 16 + }, + "type": "xod/patch-nodes/input-number" + }, + { + "boundValues": { + "HJCWLAdSwyW": 100, + "rJbGU0_Hv1Z": 32, + "rkpbU0OrwyZ": 212 + }, + "id": "r1VkETdU-", + "position": { + "x": 10, + "y": 120 + }, + "type": "xod/core/map-range" + } + ] +} \ No newline at end of file diff --git a/workspace/lib/xod/units/m-to-cm/patch.xodp b/workspace/lib/xod/units/m-to-cm/patch.xodp new file mode 100644 index 00000000..f9e4c06b --- /dev/null +++ b/workspace/lib/xod/units/m-to-cm/patch.xodp @@ -0,0 +1,56 @@ +{ + "description": "Maps meters to centimeters", + "links": [ + { + "id": "HkqvcYd8b", + "input": { + "nodeId": "Sy8IcKdIZ", + "pinKey": "__in__" + }, + "output": { + "nodeId": "ByA89t_LW", + "pinKey": "BkQzLCurwJZ" + } + }, + { + "id": "r1XPctOLZ", + "input": { + "nodeId": "ByA89t_LW", + "pinKey": "B1GfLR_SPk-" + }, + "output": { + "nodeId": "SkbLqKdUW", + "pinKey": "__out__" + } + } + ], + "nodes": [ + { + "boundValues": { + "SJ4zUC_BD1-": 100 + }, + "id": "ByA89t_LW", + "position": { + "x": 10, + "y": 120 + }, + "type": "xod/core/multiply" + }, + { + "id": "SkbLqKdUW", + "position": { + "x": 10, + "y": 16 + }, + "type": "xod/patch-nodes/input-number" + }, + { + "id": "Sy8IcKdIZ", + "position": { + "x": 10, + "y": 224 + }, + "type": "xod/patch-nodes/output-number" + } + ] +} \ No newline at end of file diff --git a/workspace/lib/xod/units/m-to-ft/patch.xodp b/workspace/lib/xod/units/m-to-ft/patch.xodp new file mode 100644 index 00000000..5214f84f --- /dev/null +++ b/workspace/lib/xod/units/m-to-ft/patch.xodp @@ -0,0 +1,56 @@ +{ + "description": "Maps meters to feets", + "links": [ + { + "id": "HkqvcYd8b", + "input": { + "nodeId": "Sy8IcKdIZ", + "pinKey": "__in__" + }, + "output": { + "nodeId": "ByA89t_LW", + "pinKey": "BkQzLCurwJZ" + } + }, + { + "id": "r1XPctOLZ", + "input": { + "nodeId": "ByA89t_LW", + "pinKey": "B1GfLR_SPk-" + }, + "output": { + "nodeId": "SkbLqKdUW", + "pinKey": "__out__" + } + } + ], + "nodes": [ + { + "boundValues": { + "SJ4zUC_BD1-": 3.28084 + }, + "id": "ByA89t_LW", + "position": { + "x": 10, + "y": 120 + }, + "type": "xod/core/multiply" + }, + { + "id": "SkbLqKdUW", + "position": { + "x": 10, + "y": 16 + }, + "type": "xod/patch-nodes/input-number" + }, + { + "id": "Sy8IcKdIZ", + "position": { + "x": 10, + "y": 224 + }, + "type": "xod/patch-nodes/output-number" + } + ] +} \ No newline at end of file diff --git a/workspace/lib/xod/units/m-to-in/patch.xodp b/workspace/lib/xod/units/m-to-in/patch.xodp new file mode 100644 index 00000000..5ee11856 --- /dev/null +++ b/workspace/lib/xod/units/m-to-in/patch.xodp @@ -0,0 +1,56 @@ +{ + "description": "Maps meters to inches", + "links": [ + { + "id": "HkqvcYd8b", + "input": { + "nodeId": "Sy8IcKdIZ", + "pinKey": "__in__" + }, + "output": { + "nodeId": "ByA89t_LW", + "pinKey": "BkQzLCurwJZ" + } + }, + { + "id": "r1XPctOLZ", + "input": { + "nodeId": "ByA89t_LW", + "pinKey": "B1GfLR_SPk-" + }, + "output": { + "nodeId": "SkbLqKdUW", + "pinKey": "__out__" + } + } + ], + "nodes": [ + { + "boundValues": { + "SJ4zUC_BD1-": 39.3701 + }, + "id": "ByA89t_LW", + "position": { + "x": 10, + "y": 120 + }, + "type": "xod/core/multiply" + }, + { + "id": "SkbLqKdUW", + "position": { + "x": 10, + "y": 16 + }, + "type": "xod/patch-nodes/input-number" + }, + { + "id": "Sy8IcKdIZ", + "position": { + "x": 10, + "y": 224 + }, + "type": "xod/patch-nodes/output-number" + } + ] +} \ No newline at end of file diff --git a/workspace/lib/xod/units/m-to-mm/patch.xodp b/workspace/lib/xod/units/m-to-mm/patch.xodp new file mode 100644 index 00000000..3d394700 --- /dev/null +++ b/workspace/lib/xod/units/m-to-mm/patch.xodp @@ -0,0 +1,56 @@ +{ + "description": "Maps meters to millimeters", + "links": [ + { + "id": "HkqvcYd8b", + "input": { + "nodeId": "Sy8IcKdIZ", + "pinKey": "__in__" + }, + "output": { + "nodeId": "ByA89t_LW", + "pinKey": "BkQzLCurwJZ" + } + }, + { + "id": "r1XPctOLZ", + "input": { + "nodeId": "ByA89t_LW", + "pinKey": "B1GfLR_SPk-" + }, + "output": { + "nodeId": "SkbLqKdUW", + "pinKey": "__out__" + } + } + ], + "nodes": [ + { + "boundValues": { + "SJ4zUC_BD1-": 1000 + }, + "id": "ByA89t_LW", + "position": { + "x": 10, + "y": 120 + }, + "type": "xod/core/multiply" + }, + { + "id": "SkbLqKdUW", + "position": { + "x": 10, + "y": 16 + }, + "type": "xod/patch-nodes/input-number" + }, + { + "id": "Sy8IcKdIZ", + "position": { + "x": 10, + "y": 224 + }, + "type": "xod/patch-nodes/output-number" + } + ] +} \ No newline at end of file diff --git a/workspace/lib/xod/units/project.xod b/workspace/lib/xod/units/project.xod new file mode 100644 index 00000000..c8fcf98a --- /dev/null +++ b/workspace/lib/xod/units/project.xod @@ -0,0 +1,3 @@ +{ + "name": "units" +} \ No newline at end of file