mirror of
https://github.com/dalathegreat/Battery-Emulator.git
synced 2025-10-05 19:42:08 +02:00
Sync with latest master
This commit is contained in:
parent
df67067099
commit
ad4cbcc703
7 changed files with 4880 additions and 0 deletions
BIN
Images/ExampleLEAFBatteryCable.png
Normal file
BIN
Images/ExampleLEAFBatteryCable.png
Normal file
Binary file not shown.
After Width: | Height: | Size: 951 KiB |
Binary file not shown.
Before Width: | Height: | Size: 895 KiB After Width: | Height: | Size: 916 KiB |
|
@ -28,6 +28,9 @@ Here's how to connect the high voltage lines
|
|||
Here's how to wire up battery low voltage wiring
|
||||

|
||||
|
||||
For more examples showing wiring, see the Example#####.jpg pictures in the 'Images' folder
|
||||
https://github.com/dalathegreat/BYD-Battery-Emulator-For-Gen24/tree/main/Images
|
||||
|
||||
## How to compile the software 💻
|
||||
1. Download the Arduino IDE: https://www.arduino.cc/en/software
|
||||
2. When the Arduino IDE has been started;
|
||||
|
|
3474
Software/Adafruit_NeoPixel.cpp
Normal file
3474
Software/Adafruit_NeoPixel.cpp
Normal file
File diff suppressed because it is too large
Load diff
412
Software/Adafruit_NeoPixel.h
Normal file
412
Software/Adafruit_NeoPixel.h
Normal file
|
@ -0,0 +1,412 @@
|
|||
/*!
|
||||
* @file Adafruit_NeoPixel.h
|
||||
*
|
||||
* This is part of Adafruit's NeoPixel library for the Arduino platform,
|
||||
* allowing a broad range of microcontroller boards (most AVR boards,
|
||||
* many ARM devices, ESP8266 and ESP32, among others) to control Adafruit
|
||||
* NeoPixels, FLORA RGB Smart Pixels and compatible devices -- WS2811,
|
||||
* WS2812, WS2812B, SK6812, etc.
|
||||
*
|
||||
* Adafruit invests time and resources providing this open source code,
|
||||
* please support Adafruit and open-source hardware by purchasing products
|
||||
* from Adafruit!
|
||||
*
|
||||
* Written by Phil "Paint Your Dragon" Burgess for Adafruit Industries,
|
||||
* with contributions by PJRC, Michael Miller and other members of the
|
||||
* open source community.
|
||||
*
|
||||
* This file is part of the Adafruit_NeoPixel library.
|
||||
*
|
||||
* Adafruit_NeoPixel is free software: you can redistribute it and/or
|
||||
* modify it under the terms of the GNU Lesser General Public License as
|
||||
* published by the Free Software Foundation, either version 3 of the
|
||||
* License, or (at your option) any later version.
|
||||
*
|
||||
* Adafruit_NeoPixel is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU Lesser General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU Lesser General Public
|
||||
* License along with NeoPixel. If not, see
|
||||
* <http://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
|
||||
#ifndef ADAFRUIT_NEOPIXEL_H
|
||||
#define ADAFRUIT_NEOPIXEL_H
|
||||
|
||||
#ifdef ARDUINO
|
||||
#if (ARDUINO >= 100)
|
||||
#include <Arduino.h>
|
||||
#else
|
||||
#include <WProgram.h>
|
||||
#include <pins_arduino.h>
|
||||
#endif
|
||||
|
||||
#ifdef USE_TINYUSB // For Serial when selecting TinyUSB
|
||||
#include <Adafruit_TinyUSB.h>
|
||||
#endif
|
||||
|
||||
#endif
|
||||
|
||||
#ifdef TARGET_LPC1768
|
||||
#include <Arduino.h>
|
||||
#endif
|
||||
|
||||
#if defined(ARDUINO_ARCH_RP2040)
|
||||
#include <stdlib.h>
|
||||
#include "hardware/pio.h"
|
||||
#include "hardware/clocks.h"
|
||||
#include "rp2040_pio.h"
|
||||
#endif
|
||||
|
||||
// The order of primary colors in the NeoPixel data stream can vary among
|
||||
// device types, manufacturers and even different revisions of the same
|
||||
// item. The third parameter to the Adafruit_NeoPixel constructor encodes
|
||||
// the per-pixel byte offsets of the red, green and blue primaries (plus
|
||||
// white, if present) in the data stream -- the following #defines provide
|
||||
// an easier-to-use named version for each permutation. e.g. NEO_GRB
|
||||
// indicates a NeoPixel-compatible device expecting three bytes per pixel,
|
||||
// with the first byte transmitted containing the green value, second
|
||||
// containing red and third containing blue. The in-memory representation
|
||||
// of a chain of NeoPixels is the same as the data-stream order; no
|
||||
// re-ordering of bytes is required when issuing data to the chain.
|
||||
// Most of these values won't exist in real-world devices, but it's done
|
||||
// this way so we're ready for it (also, if using the WS2811 driver IC,
|
||||
// one might have their pixels set up in any weird permutation).
|
||||
|
||||
// Bits 5,4 of this value are the offset (0-3) from the first byte of a
|
||||
// pixel to the location of the red color byte. Bits 3,2 are the green
|
||||
// offset and 1,0 are the blue offset. If it is an RGBW-type device
|
||||
// (supporting a white primary in addition to R,G,B), bits 7,6 are the
|
||||
// offset to the white byte...otherwise, bits 7,6 are set to the same value
|
||||
// as 5,4 (red) to indicate an RGB (not RGBW) device.
|
||||
// i.e. binary representation:
|
||||
// 0bWWRRGGBB for RGBW devices
|
||||
// 0bRRRRGGBB for RGB
|
||||
|
||||
// RGB NeoPixel permutations; white and red offsets are always same
|
||||
// Offset: W R G B
|
||||
#define NEO_RGB ((0 << 6) | (0 << 4) | (1 << 2) | (2)) ///< Transmit as R,G,B
|
||||
#define NEO_RBG ((0 << 6) | (0 << 4) | (2 << 2) | (1)) ///< Transmit as R,B,G
|
||||
#define NEO_GRB ((1 << 6) | (1 << 4) | (0 << 2) | (2)) ///< Transmit as G,R,B
|
||||
#define NEO_GBR ((2 << 6) | (2 << 4) | (0 << 2) | (1)) ///< Transmit as G,B,R
|
||||
#define NEO_BRG ((1 << 6) | (1 << 4) | (2 << 2) | (0)) ///< Transmit as B,R,G
|
||||
#define NEO_BGR ((2 << 6) | (2 << 4) | (1 << 2) | (0)) ///< Transmit as B,G,R
|
||||
|
||||
// RGBW NeoPixel permutations; all 4 offsets are distinct
|
||||
// Offset: W R G B
|
||||
#define NEO_WRGB ((0 << 6) | (1 << 4) | (2 << 2) | (3)) ///< Transmit as W,R,G,B
|
||||
#define NEO_WRBG ((0 << 6) | (1 << 4) | (3 << 2) | (2)) ///< Transmit as W,R,B,G
|
||||
#define NEO_WGRB ((0 << 6) | (2 << 4) | (1 << 2) | (3)) ///< Transmit as W,G,R,B
|
||||
#define NEO_WGBR ((0 << 6) | (3 << 4) | (1 << 2) | (2)) ///< Transmit as W,G,B,R
|
||||
#define NEO_WBRG ((0 << 6) | (2 << 4) | (3 << 2) | (1)) ///< Transmit as W,B,R,G
|
||||
#define NEO_WBGR ((0 << 6) | (3 << 4) | (2 << 2) | (1)) ///< Transmit as W,B,G,R
|
||||
|
||||
#define NEO_RWGB ((1 << 6) | (0 << 4) | (2 << 2) | (3)) ///< Transmit as R,W,G,B
|
||||
#define NEO_RWBG ((1 << 6) | (0 << 4) | (3 << 2) | (2)) ///< Transmit as R,W,B,G
|
||||
#define NEO_RGWB ((2 << 6) | (0 << 4) | (1 << 2) | (3)) ///< Transmit as R,G,W,B
|
||||
#define NEO_RGBW ((3 << 6) | (0 << 4) | (1 << 2) | (2)) ///< Transmit as R,G,B,W
|
||||
#define NEO_RBWG ((2 << 6) | (0 << 4) | (3 << 2) | (1)) ///< Transmit as R,B,W,G
|
||||
#define NEO_RBGW ((3 << 6) | (0 << 4) | (2 << 2) | (1)) ///< Transmit as R,B,G,W
|
||||
|
||||
#define NEO_GWRB ((1 << 6) | (2 << 4) | (0 << 2) | (3)) ///< Transmit as G,W,R,B
|
||||
#define NEO_GWBR ((1 << 6) | (3 << 4) | (0 << 2) | (2)) ///< Transmit as G,W,B,R
|
||||
#define NEO_GRWB ((2 << 6) | (1 << 4) | (0 << 2) | (3)) ///< Transmit as G,R,W,B
|
||||
#define NEO_GRBW ((3 << 6) | (1 << 4) | (0 << 2) | (2)) ///< Transmit as G,R,B,W
|
||||
#define NEO_GBWR ((2 << 6) | (3 << 4) | (0 << 2) | (1)) ///< Transmit as G,B,W,R
|
||||
#define NEO_GBRW ((3 << 6) | (2 << 4) | (0 << 2) | (1)) ///< Transmit as G,B,R,W
|
||||
|
||||
#define NEO_BWRG ((1 << 6) | (2 << 4) | (3 << 2) | (0)) ///< Transmit as B,W,R,G
|
||||
#define NEO_BWGR ((1 << 6) | (3 << 4) | (2 << 2) | (0)) ///< Transmit as B,W,G,R
|
||||
#define NEO_BRWG ((2 << 6) | (1 << 4) | (3 << 2) | (0)) ///< Transmit as B,R,W,G
|
||||
#define NEO_BRGW ((3 << 6) | (1 << 4) | (2 << 2) | (0)) ///< Transmit as B,R,G,W
|
||||
#define NEO_BGWR ((2 << 6) | (3 << 4) | (1 << 2) | (0)) ///< Transmit as B,G,W,R
|
||||
#define NEO_BGRW ((3 << 6) | (2 << 4) | (1 << 2) | (0)) ///< Transmit as B,G,R,W
|
||||
|
||||
// Add NEO_KHZ400 to the color order value to indicate a 400 KHz device.
|
||||
// All but the earliest v1 NeoPixels expect an 800 KHz data stream, this is
|
||||
// the default if unspecified. Because flash space is very limited on ATtiny
|
||||
// devices (e.g. Trinket, Gemma), v1 NeoPixels aren't handled by default on
|
||||
// those chips, though it can be enabled by removing the ifndef/endif below,
|
||||
// but code will be bigger. Conversely, can disable the NEO_KHZ400 line on
|
||||
// other MCUs to remove v1 support and save a little space.
|
||||
|
||||
#define NEO_KHZ800 0x0000 ///< 800 KHz data transmission
|
||||
#ifndef __AVR_ATtiny85__
|
||||
#define NEO_KHZ400 0x0100 ///< 400 KHz data transmission
|
||||
#endif
|
||||
|
||||
// If 400 KHz support is enabled, the third parameter to the constructor
|
||||
// requires a 16-bit value (in order to select 400 vs 800 KHz speed).
|
||||
// If only 800 KHz is enabled (as is default on ATtiny), an 8-bit value
|
||||
// is sufficient to encode pixel color order, saving some space.
|
||||
|
||||
#ifdef NEO_KHZ400
|
||||
typedef uint16_t neoPixelType; ///< 3rd arg to Adafruit_NeoPixel constructor
|
||||
#else
|
||||
typedef uint8_t neoPixelType; ///< 3rd arg to Adafruit_NeoPixel constructor
|
||||
#endif
|
||||
|
||||
// These two tables are declared outside the Adafruit_NeoPixel class
|
||||
// because some boards may require oldschool compilers that don't
|
||||
// handle the C++11 constexpr keyword.
|
||||
|
||||
/* A PROGMEM (flash mem) table containing 8-bit unsigned sine wave (0-255).
|
||||
Copy & paste this snippet into a Python REPL to regenerate:
|
||||
import math
|
||||
for x in range(256):
|
||||
print("{:3},".format(int((math.sin(x/128.0*math.pi)+1.0)*127.5+0.5))),
|
||||
if x&15 == 15: print
|
||||
*/
|
||||
static const uint8_t PROGMEM _NeoPixelSineTable[256] = {
|
||||
128, 131, 134, 137, 140, 143, 146, 149, 152, 155, 158, 162, 165, 167, 170,
|
||||
173, 176, 179, 182, 185, 188, 190, 193, 196, 198, 201, 203, 206, 208, 211,
|
||||
213, 215, 218, 220, 222, 224, 226, 228, 230, 232, 234, 235, 237, 238, 240,
|
||||
241, 243, 244, 245, 246, 248, 249, 250, 250, 251, 252, 253, 253, 254, 254,
|
||||
254, 255, 255, 255, 255, 255, 255, 255, 254, 254, 254, 253, 253, 252, 251,
|
||||
250, 250, 249, 248, 246, 245, 244, 243, 241, 240, 238, 237, 235, 234, 232,
|
||||
230, 228, 226, 224, 222, 220, 218, 215, 213, 211, 208, 206, 203, 201, 198,
|
||||
196, 193, 190, 188, 185, 182, 179, 176, 173, 170, 167, 165, 162, 158, 155,
|
||||
152, 149, 146, 143, 140, 137, 134, 131, 128, 124, 121, 118, 115, 112, 109,
|
||||
106, 103, 100, 97, 93, 90, 88, 85, 82, 79, 76, 73, 70, 67, 65,
|
||||
62, 59, 57, 54, 52, 49, 47, 44, 42, 40, 37, 35, 33, 31, 29,
|
||||
27, 25, 23, 21, 20, 18, 17, 15, 14, 12, 11, 10, 9, 7, 6,
|
||||
5, 5, 4, 3, 2, 2, 1, 1, 1, 0, 0, 0, 0, 0, 0,
|
||||
0, 1, 1, 1, 2, 2, 3, 4, 5, 5, 6, 7, 9, 10, 11,
|
||||
12, 14, 15, 17, 18, 20, 21, 23, 25, 27, 29, 31, 33, 35, 37,
|
||||
40, 42, 44, 47, 49, 52, 54, 57, 59, 62, 65, 67, 70, 73, 76,
|
||||
79, 82, 85, 88, 90, 93, 97, 100, 103, 106, 109, 112, 115, 118, 121,
|
||||
124};
|
||||
|
||||
/* Similar to above, but for an 8-bit gamma-correction table.
|
||||
Copy & paste this snippet into a Python REPL to regenerate:
|
||||
import math
|
||||
gamma=2.6
|
||||
for x in range(256):
|
||||
print("{:3},".format(int(math.pow((x)/255.0,gamma)*255.0+0.5))),
|
||||
if x&15 == 15: print
|
||||
*/
|
||||
static const uint8_t PROGMEM _NeoPixelGammaTable[256] = {
|
||||
0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
|
||||
0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1, 1, 1, 1,
|
||||
1, 1, 1, 1, 1, 1, 2, 2, 2, 2, 2, 2, 2, 2, 3,
|
||||
3, 3, 3, 3, 3, 4, 4, 4, 4, 5, 5, 5, 5, 5, 6,
|
||||
6, 6, 6, 7, 7, 7, 8, 8, 8, 9, 9, 9, 10, 10, 10,
|
||||
11, 11, 11, 12, 12, 13, 13, 13, 14, 14, 15, 15, 16, 16, 17,
|
||||
17, 18, 18, 19, 19, 20, 20, 21, 21, 22, 22, 23, 24, 24, 25,
|
||||
25, 26, 27, 27, 28, 29, 29, 30, 31, 31, 32, 33, 34, 34, 35,
|
||||
36, 37, 38, 38, 39, 40, 41, 42, 42, 43, 44, 45, 46, 47, 48,
|
||||
49, 50, 51, 52, 53, 54, 55, 56, 57, 58, 59, 60, 61, 62, 63,
|
||||
64, 65, 66, 68, 69, 70, 71, 72, 73, 75, 76, 77, 78, 80, 81,
|
||||
82, 84, 85, 86, 88, 89, 90, 92, 93, 94, 96, 97, 99, 100, 102,
|
||||
103, 105, 106, 108, 109, 111, 112, 114, 115, 117, 119, 120, 122, 124, 125,
|
||||
127, 129, 130, 132, 134, 136, 137, 139, 141, 143, 145, 146, 148, 150, 152,
|
||||
154, 156, 158, 160, 162, 164, 166, 168, 170, 172, 174, 176, 178, 180, 182,
|
||||
184, 186, 188, 191, 193, 195, 197, 199, 202, 204, 206, 209, 211, 213, 215,
|
||||
218, 220, 223, 225, 227, 230, 232, 235, 237, 240, 242, 245, 247, 250, 252,
|
||||
255};
|
||||
|
||||
/*!
|
||||
@brief Class that stores state and functions for interacting with
|
||||
Adafruit NeoPixels and compatible devices.
|
||||
*/
|
||||
class Adafruit_NeoPixel {
|
||||
|
||||
public:
|
||||
// Constructor: number of LEDs, pin number, LED type
|
||||
Adafruit_NeoPixel(uint16_t n, int16_t pin = 6,
|
||||
neoPixelType type = NEO_GRB + NEO_KHZ800);
|
||||
Adafruit_NeoPixel(void);
|
||||
~Adafruit_NeoPixel();
|
||||
|
||||
void begin(void);
|
||||
void show(void);
|
||||
void setPin(int16_t p);
|
||||
void setPixelColor(uint16_t n, uint8_t r, uint8_t g, uint8_t b);
|
||||
void setPixelColor(uint16_t n, uint8_t r, uint8_t g, uint8_t b, uint8_t w);
|
||||
void setPixelColor(uint16_t n, uint32_t c);
|
||||
void fill(uint32_t c = 0, uint16_t first = 0, uint16_t count = 0);
|
||||
void setBrightness(uint8_t);
|
||||
void clear(void);
|
||||
void updateLength(uint16_t n);
|
||||
void updateType(neoPixelType t);
|
||||
/*!
|
||||
@brief Check whether a call to show() will start sending data
|
||||
immediately or will 'block' for a required interval. NeoPixels
|
||||
require a short quiet time (about 300 microseconds) after the
|
||||
last bit is received before the data 'latches' and new data can
|
||||
start being received. Usually one's sketch is implicitly using
|
||||
this time to generate a new frame of animation...but if it
|
||||
finishes very quickly, this function could be used to see if
|
||||
there's some idle time available for some low-priority
|
||||
concurrent task.
|
||||
@return 1 or true if show() will start sending immediately, 0 or false
|
||||
if show() would block (meaning some idle time is available).
|
||||
*/
|
||||
bool canShow(void) {
|
||||
// It's normal and possible for endTime to exceed micros() if the
|
||||
// 32-bit clock counter has rolled over (about every 70 minutes).
|
||||
// Since both are uint32_t, a negative delta correctly maps back to
|
||||
// positive space, and it would seem like the subtraction below would
|
||||
// suffice. But a problem arises if code invokes show() very
|
||||
// infrequently...the micros() counter may roll over MULTIPLE times in
|
||||
// that interval, the delta calculation is no longer correct and the
|
||||
// next update may stall for a very long time. The check below resets
|
||||
// the latch counter if a rollover has occurred. This can cause an
|
||||
// extra delay of up to 300 microseconds in the rare case where a
|
||||
// show() call happens precisely around the rollover, but that's
|
||||
// neither likely nor especially harmful, vs. other code that might
|
||||
// stall for 30+ minutes, or having to document and frequently remind
|
||||
// and/or provide tech support explaining an unintuitive need for
|
||||
// show() calls at least once an hour.
|
||||
uint32_t now = micros();
|
||||
if (endTime > now) {
|
||||
endTime = now;
|
||||
}
|
||||
return (now - endTime) >= 300L;
|
||||
}
|
||||
/*!
|
||||
@brief Get a pointer directly to the NeoPixel data buffer in RAM.
|
||||
Pixel data is stored in a device-native format (a la the NEO_*
|
||||
constants) and is not translated here. Applications that access
|
||||
this buffer will need to be aware of the specific data format
|
||||
and handle colors appropriately.
|
||||
@return Pointer to NeoPixel buffer (uint8_t* array).
|
||||
@note This is for high-performance applications where calling
|
||||
setPixelColor() on every single pixel would be too slow (e.g.
|
||||
POV or light-painting projects). There is no bounds checking
|
||||
on the array, creating tremendous potential for mayhem if one
|
||||
writes past the ends of the buffer. Great power, great
|
||||
responsibility and all that.
|
||||
*/
|
||||
uint8_t *getPixels(void) const { return pixels; };
|
||||
uint8_t getBrightness(void) const;
|
||||
/*!
|
||||
@brief Retrieve the pin number used for NeoPixel data output.
|
||||
@return Arduino pin number (-1 if not set).
|
||||
*/
|
||||
int16_t getPin(void) const { return pin; };
|
||||
/*!
|
||||
@brief Return the number of pixels in an Adafruit_NeoPixel strip object.
|
||||
@return Pixel count (0 if not set).
|
||||
*/
|
||||
uint16_t numPixels(void) const { return numLEDs; }
|
||||
uint32_t getPixelColor(uint16_t n) const;
|
||||
/*!
|
||||
@brief An 8-bit integer sine wave function, not directly compatible
|
||||
with standard trigonometric units like radians or degrees.
|
||||
@param x Input angle, 0-255; 256 would loop back to zero, completing
|
||||
the circle (equivalent to 360 degrees or 2 pi radians).
|
||||
One can therefore use an unsigned 8-bit variable and simply
|
||||
add or subtract, allowing it to overflow/underflow and it
|
||||
still does the expected contiguous thing.
|
||||
@return Sine result, 0 to 255, or -128 to +127 if type-converted to
|
||||
a signed int8_t, but you'll most likely want unsigned as this
|
||||
output is often used for pixel brightness in animation effects.
|
||||
*/
|
||||
static uint8_t sine8(uint8_t x) {
|
||||
return pgm_read_byte(&_NeoPixelSineTable[x]); // 0-255 in, 0-255 out
|
||||
}
|
||||
/*!
|
||||
@brief An 8-bit gamma-correction function for basic pixel brightness
|
||||
adjustment. Makes color transitions appear more perceptially
|
||||
correct.
|
||||
@param x Input brightness, 0 (minimum or off/black) to 255 (maximum).
|
||||
@return Gamma-adjusted brightness, can then be passed to one of the
|
||||
setPixelColor() functions. This uses a fixed gamma correction
|
||||
exponent of 2.6, which seems reasonably okay for average
|
||||
NeoPixels in average tasks. If you need finer control you'll
|
||||
need to provide your own gamma-correction function instead.
|
||||
*/
|
||||
static uint8_t gamma8(uint8_t x) {
|
||||
return pgm_read_byte(&_NeoPixelGammaTable[x]); // 0-255 in, 0-255 out
|
||||
}
|
||||
/*!
|
||||
@brief Convert separate red, green and blue values into a single
|
||||
"packed" 32-bit RGB color.
|
||||
@param r Red brightness, 0 to 255.
|
||||
@param g Green brightness, 0 to 255.
|
||||
@param b Blue brightness, 0 to 255.
|
||||
@return 32-bit packed RGB value, which can then be assigned to a
|
||||
variable for later use or passed to the setPixelColor()
|
||||
function. Packed RGB format is predictable, regardless of
|
||||
LED strand color order.
|
||||
*/
|
||||
static uint32_t Color(uint8_t r, uint8_t g, uint8_t b) {
|
||||
return ((uint32_t)r << 16) | ((uint32_t)g << 8) | b;
|
||||
}
|
||||
/*!
|
||||
@brief Convert separate red, green, blue and white values into a
|
||||
single "packed" 32-bit WRGB color.
|
||||
@param r Red brightness, 0 to 255.
|
||||
@param g Green brightness, 0 to 255.
|
||||
@param b Blue brightness, 0 to 255.
|
||||
@param w White brightness, 0 to 255.
|
||||
@return 32-bit packed WRGB value, which can then be assigned to a
|
||||
variable for later use or passed to the setPixelColor()
|
||||
function. Packed WRGB format is predictable, regardless of
|
||||
LED strand color order.
|
||||
*/
|
||||
static uint32_t Color(uint8_t r, uint8_t g, uint8_t b, uint8_t w) {
|
||||
return ((uint32_t)w << 24) | ((uint32_t)r << 16) | ((uint32_t)g << 8) | b;
|
||||
}
|
||||
static uint32_t ColorHSV(uint16_t hue, uint8_t sat = 255, uint8_t val = 255);
|
||||
/*!
|
||||
@brief A gamma-correction function for 32-bit packed RGB or WRGB
|
||||
colors. Makes color transitions appear more perceptially
|
||||
correct.
|
||||
@param x 32-bit packed RGB or WRGB color.
|
||||
@return Gamma-adjusted packed color, can then be passed in one of the
|
||||
setPixelColor() functions. Like gamma8(), this uses a fixed
|
||||
gamma correction exponent of 2.6, which seems reasonably okay
|
||||
for average NeoPixels in average tasks. If you need finer
|
||||
control you'll need to provide your own gamma-correction
|
||||
function instead.
|
||||
*/
|
||||
static uint32_t gamma32(uint32_t x);
|
||||
|
||||
void rainbow(uint16_t first_hue = 0, int8_t reps = 1,
|
||||
uint8_t saturation = 255, uint8_t brightness = 255,
|
||||
bool gammify = true);
|
||||
|
||||
static neoPixelType str2order(const char *v);
|
||||
|
||||
private:
|
||||
#if defined(ARDUINO_ARCH_RP2040)
|
||||
void rp2040Init(uint8_t pin, bool is800KHz);
|
||||
void rp2040Show(uint8_t pin, uint8_t *pixels, uint32_t numBytes, bool is800KHz);
|
||||
#endif
|
||||
|
||||
protected:
|
||||
#ifdef NEO_KHZ400 // If 400 KHz NeoPixel support enabled...
|
||||
bool is800KHz; ///< true if 800 KHz pixels
|
||||
#endif
|
||||
bool begun; ///< true if begin() previously called
|
||||
uint16_t numLEDs; ///< Number of RGB LEDs in strip
|
||||
uint16_t numBytes; ///< Size of 'pixels' buffer below
|
||||
int16_t pin; ///< Output pin number (-1 if not yet set)
|
||||
uint8_t brightness; ///< Strip brightness 0-255 (stored as +1)
|
||||
uint8_t *pixels; ///< Holds LED color values (3 or 4 bytes each)
|
||||
uint8_t rOffset; ///< Red index within each 3- or 4-byte pixel
|
||||
uint8_t gOffset; ///< Index of green byte
|
||||
uint8_t bOffset; ///< Index of blue byte
|
||||
uint8_t wOffset; ///< Index of white (==rOffset if no white)
|
||||
uint32_t endTime; ///< Latch timing reference
|
||||
#ifdef __AVR__
|
||||
volatile uint8_t *port; ///< Output PORT register
|
||||
uint8_t pinMask; ///< Output PORT bitmask
|
||||
#endif
|
||||
#if defined(ARDUINO_ARCH_STM32) || defined(ARDUINO_ARCH_ARDUINO_CORE_STM32)
|
||||
GPIO_TypeDef *gpioPort; ///< Output GPIO PORT
|
||||
uint32_t gpioPin; ///< Output GPIO PIN
|
||||
#endif
|
||||
#if defined(ARDUINO_ARCH_RP2040)
|
||||
PIO pio = pio0;
|
||||
int sm = 0;
|
||||
bool init = true;
|
||||
#endif
|
||||
};
|
||||
|
||||
#endif // ADAFRUIT_NEOPIXEL_H
|
813
Software/Software.ino
Normal file
813
Software/Software.ino
Normal file
|
@ -0,0 +1,813 @@
|
|||
#include <Arduino.h>
|
||||
#include "HardwareSerial.h"
|
||||
#include "config.h"
|
||||
#include "logging.h"
|
||||
#include "mbServerFCs.h"
|
||||
#include "ModbusServerRTU.h"
|
||||
#include "ESP32CAN.h"
|
||||
#include "CAN_config.h"
|
||||
#include "Adafruit_NeoPixel.h"
|
||||
|
||||
/* User definable settings */
|
||||
#define BATTERY_WH_MAX 30000 //Battery size in Wh (Maximum value Fronius accepts is 60000 [60kWh])
|
||||
#define MAXPERCENTAGE 800 //80.0% , Max percentage the battery will charge to (App will show 100% once this value is reached)
|
||||
#define MINPERCENTAGE 200 //20.0% , Min percentage the battery will discharge to (App will show 0% once this value is reached)
|
||||
//#define INTERLOCK_REQUIRED //Uncomment this line to skip requiring both high voltage connectors to be seated on the LEAF battery
|
||||
byte printValues = 1; //Should modbus values be printed to serial output?
|
||||
|
||||
/* Do not change code below unless you are sure what you are doing */
|
||||
//CAN parameters
|
||||
CAN_device_t CAN_cfg; // CAN Config
|
||||
unsigned long previousMillis10 = 0; // will store last time a 10ms CAN Message was send
|
||||
unsigned long previousMillis100 = 0; // will store last time a 100ms CAN Message was send
|
||||
const int interval10 = 10; // interval (ms) at which send CAN Messages
|
||||
const int interval100 = 100; // interval (ms) at which send CAN Messages
|
||||
const int rx_queue_size = 10; // Receive Queue size
|
||||
uint8_t CANstillAlive = 12; //counter for checking if CAN is still alive
|
||||
uint8_t errorCode = 0; //stores if we have an error code active from battery control logic
|
||||
uint8_t mprun10r = 0; //counter 0-20 for 0x1F2 message
|
||||
byte mprun10 = 0; //counter 0-3
|
||||
byte mprun100 = 0; //counter 0-3
|
||||
|
||||
CAN_frame_t LEAF_1F2 = {.FIR = {.B = {.DLC = 8,.FF = CAN_frame_std,}},.MsgID = 0x1F2,.data = {0x10, 0x64, 0x00, 0xB0, 0x00, 0x1E, 0x00, 0x8F}};
|
||||
CAN_frame_t LEAF_50B = {.FIR = {.B = {.DLC = 7,.FF = CAN_frame_std,}},.MsgID = 0x50B,.data = {0x00, 0x00, 0x06, 0xC0, 0x00, 0x00, 0x00}};
|
||||
CAN_frame_t LEAF_50C = {.FIR = {.B = {.DLC = 6,.FF = CAN_frame_std,}},.MsgID = 0x50C,.data = {0x00, 0x00, 0x00, 0x00, 0x00, 0x00}};
|
||||
CAN_frame_t LEAF_1D4 = {.FIR = {.B = {.DLC = 8,.FF = CAN_frame_std,}},.MsgID = 0x1D4,.data = {0x6E, 0x6E, 0x00, 0x04, 0x07, 0x46, 0xE0, 0x44}};
|
||||
|
||||
//Nissan LEAF battery parameters from CAN
|
||||
#define ZE0_BATTERY 0
|
||||
#define AZE0_BATTERY 1
|
||||
#define ZE1_BATTERY 2
|
||||
uint8_t LEAF_Battery_Type = ZE0_BATTERY;
|
||||
#define WH_PER_GID 77 //One GID is this amount of Watt hours
|
||||
#define LB_MAX_SOC 1000 //LEAF BMS never goes over this value. We use this info to rescale SOC% sent to Fronius
|
||||
#define LB_MIN_SOC 0 //LEAF BMS never goes below this value. We use this info to rescale SOC% sent to Fronius
|
||||
uint16_t LB_Discharge_Power_Limit = 0; //Limit in kW
|
||||
uint16_t LB_Charge_Power_Limit = 0; //Limit in kW
|
||||
int16_t LB_MAX_POWER_FOR_CHARGER = 0; //Limit in kW
|
||||
int16_t LB_SOC = 500; //0 - 100.0 % (0-1000)
|
||||
uint16_t LB_TEMP = 0; //Temporary value used in status checks
|
||||
uint16_t LB_Wh_Remaining = 0; //Amount of energy in battery, in Wh
|
||||
uint16_t LB_GIDS = 0;
|
||||
uint16_t LB_MAX = 0;
|
||||
uint16_t LB_Max_GIDS = 273; //Startup in 24kWh mode
|
||||
uint16_t LB_StateOfHealth = 99; //State of health %
|
||||
uint16_t LB_Total_Voltage = 370; //Battery voltage (0-450V)
|
||||
int16_t LB_Current = 0; //Current in A going in/out of battery
|
||||
int16_t LB_Power = 0; //Watts going in/out of battery
|
||||
int16_t LB_HistData_Temperature_MAX = 6; //-40 to 86*C
|
||||
int16_t LB_HistData_Temperature_MIN = 5; //-40 to 86*C
|
||||
uint8_t LB_Relay_Cut_Request = 0; //LB_FAIL
|
||||
uint8_t LB_Failsafe_Status = 0; //LB_STATUS = 000b = normal start Request
|
||||
//001b = Main Relay OFF Request
|
||||
//010b = Charging Mode Stop Request
|
||||
//011b = Main Relay OFF Request
|
||||
//100b = Caution Lamp Request
|
||||
//101b = Caution Lamp Request & Main Relay OFF Request
|
||||
//110b = Caution Lamp Request & Charging Mode Stop Request
|
||||
//111b = Caution Lamp Request & Main Relay OFF Request
|
||||
byte LB_Interlock = 1; //Contains info on if HV leads are seated (Note, to use this both HV connectors need to be inserted)
|
||||
byte LB_Full_CHARGE_flag = 0; //LB_FCHGEND , Goes to 1 if battery is fully charged
|
||||
byte LB_MainRelayOn_flag = 0; //No-Permission=0, Main Relay On Permission=1
|
||||
byte LB_Capacity_Empty = 0; //LB_EMPTY, , Goes to 1 if battery is empty
|
||||
|
||||
// global Modbus memory registers
|
||||
const int intervalModbusTask = 4800; //Interval at which to refresh modbus registers
|
||||
unsigned long previousMillisModbus = 0; //will store last time a modbus register refresh
|
||||
// ModbusRTU Server
|
||||
#define MB_RTU_NUM_VALUES 30000
|
||||
//#define MB_RTU_DIVICE_ID 21
|
||||
uint16_t mbPV[MB_RTU_NUM_VALUES]; // process variable memory: produced by sensors, etc., cyclic read by PLC via modbus TCP
|
||||
|
||||
#define STANDBY 0
|
||||
#define INACTIVE 1
|
||||
#define DARKSTART 2
|
||||
#define ACTIVE 3
|
||||
#define FAULT 4
|
||||
#define UPDATING 5
|
||||
uint16_t capacity_Wh_startup = BATTERY_WH_MAX;
|
||||
uint16_t max_power = 40960; //41kW
|
||||
uint16_t max_voltage = 4040; //(404.4V), if higher charging is not possible (goes into forced discharge)
|
||||
uint16_t min_voltage = 3100; //Min Voltage (310.0V), if lower Gen24 disables battery
|
||||
uint16_t battery_voltage = 3700;
|
||||
uint16_t SOC = 5000; //SOC 0-100.00% //Updates later on from CAN
|
||||
uint16_t StateOfHealth = 9900; //SOH 0-100.00% //Updates later on from CAN
|
||||
uint16_t capacity_Wh = BATTERY_WH_MAX; //Updates later on from CAN
|
||||
uint16_t remaining_capacity_Wh = BATTERY_WH_MAX; //Updates later on from CAN
|
||||
uint16_t max_target_discharge_power = 0; //0W (0W > restricts to no discharge) //Updates later on from CAN
|
||||
uint16_t max_target_charge_power = 4312; //4.3kW (during charge), both 307&308 can be set (>0) at the same time //Updates later on from CAN
|
||||
uint16_t temperature_max = 50; //Todo, read from LEAF pack, uint not ok
|
||||
uint16_t temperature_min = 60; //Todo, read from LEAF pack, uint not ok
|
||||
uint16_t bms_char_dis_status; //0 idle, 1 discharging, 2, charging
|
||||
uint16_t bms_status = ACTIVE; //ACTIVE - [0..5]<>[STANDBY,INACTIVE,DARKSTART,ACTIVE,FAULT,UPDATING]
|
||||
uint16_t stat_batt_power = 0; //power going in/out of battery
|
||||
|
||||
// Create a ModbusRTU server instance listening on Serial2 with 2000ms timeout
|
||||
ModbusServerRTU MBserver(Serial2, 2000);
|
||||
|
||||
// LED control
|
||||
Adafruit_NeoPixel pixels(1, WS2812_PIN, NEO_GRB + NEO_KHZ800);
|
||||
unsigned long previousMillis10ms = 0;
|
||||
static int green = 0;
|
||||
static bool rampUp = true;
|
||||
const int maxBrightness = 255;
|
||||
|
||||
// Setup() - initialization happens here
|
||||
void setup()
|
||||
{
|
||||
//CAN pins
|
||||
pinMode(CAN_SE_PIN, OUTPUT);
|
||||
digitalWrite(CAN_SE_PIN, LOW);
|
||||
CAN_cfg.speed = CAN_SPEED_500KBPS;
|
||||
CAN_cfg.tx_pin_id = GPIO_NUM_27;
|
||||
CAN_cfg.rx_pin_id = GPIO_NUM_26;
|
||||
CAN_cfg.rx_queue = xQueueCreate(rx_queue_size, sizeof(CAN_frame_t));
|
||||
// Init CAN Module
|
||||
ESP32Can.CANInit();
|
||||
Serial.println(CAN_cfg.speed);
|
||||
|
||||
// Init Serial monitor
|
||||
Serial.begin(9600);
|
||||
while (!Serial)
|
||||
{
|
||||
}
|
||||
Serial.println("__ OK __");
|
||||
|
||||
//Set up Modbus RTU Server
|
||||
Serial.println("Set ModbusRtu PIN");
|
||||
pinMode(RS485_EN_PIN, OUTPUT);
|
||||
digitalWrite(RS485_EN_PIN, HIGH);
|
||||
|
||||
pinMode(RS485_SE_PIN, OUTPUT);
|
||||
digitalWrite(RS485_SE_PIN, HIGH);
|
||||
|
||||
pinMode(PIN_5V_EN, OUTPUT);
|
||||
digitalWrite(PIN_5V_EN, HIGH);
|
||||
|
||||
// Init Static data to the RTU Modbus
|
||||
handle_static_data_modbus();
|
||||
|
||||
// Init Serial2 connected to the RTU Modbus
|
||||
RTUutils::prepareHardwareSerial(Serial2);
|
||||
Serial2.begin(9600, SERIAL_8N1, RS485_RX_PIN, RS485_TX_PIN);
|
||||
|
||||
// Register served function code worker for server
|
||||
MBserver.registerWorker(MBTCP_ID, READ_HOLD_REGISTER, &FC03);
|
||||
MBserver.registerWorker(MBTCP_ID, WRITE_HOLD_REGISTER, &FC06);
|
||||
MBserver.registerWorker(MBTCP_ID, WRITE_MULT_REGISTERS, &FC16);
|
||||
MBserver.registerWorker(MBTCP_ID, R_W_MULT_REGISTERS, &FC23);
|
||||
|
||||
// Start ModbusRTU background task
|
||||
MBserver.begin(Serial2);
|
||||
|
||||
// Init LED control
|
||||
pixels.begin();
|
||||
}
|
||||
|
||||
// perform main program functions
|
||||
void loop()
|
||||
{
|
||||
handle_can_leaf_battery(); //runs as fast as possible
|
||||
|
||||
if (millis() - previousMillis10ms >= interval10) //every 10ms
|
||||
{
|
||||
previousMillis10ms = millis();
|
||||
handle_LED_state(); //Set the LED color according to state
|
||||
}
|
||||
|
||||
if (millis() - previousMillisModbus >= intervalModbusTask) //every 5s
|
||||
{
|
||||
previousMillisModbus = millis();
|
||||
update_values_leaf_battery(); //Map the values to the correct registers
|
||||
handle_update_data_modbusp201(); //Updata for ModbusRTU Server for GEN24
|
||||
handle_update_data_modbusp301(); //Updata for ModbusRTU Server for GEN24
|
||||
}
|
||||
}
|
||||
|
||||
void update_values_leaf_battery()
|
||||
{ //This function maps all the values fetched via CAN to the correct parameters used for modbus
|
||||
bms_status = ACTIVE; //Startout in active mode
|
||||
|
||||
StateOfHealth = (LB_StateOfHealth * 100); //Increase range from 99% -> 99.00%
|
||||
|
||||
//Calculate the SOC% value to send to Fronius
|
||||
LB_SOC = LB_MIN_SOC + (LB_MAX_SOC - LB_MIN_SOC) * (LB_SOC - MINPERCENTAGE) / (MAXPERCENTAGE - MINPERCENTAGE);
|
||||
if (LB_SOC < 0)
|
||||
{ //We are in the real SOC% range of 0-20%, always set SOC sent to Fronius as 0%
|
||||
LB_SOC = 0;
|
||||
}
|
||||
if (LB_SOC > 1000)
|
||||
{ //We are in the real SOC% range of 80-100%, always set SOC sent to Fronius as 100%
|
||||
LB_SOC = 1000;
|
||||
}
|
||||
SOC = (LB_SOC * 10); //increase LB_SOC range from 0-100.0 -> 100.00
|
||||
|
||||
battery_voltage = (LB_Total_Voltage*10); //One more decimal needed
|
||||
|
||||
capacity_Wh = (LB_Max_GIDS * WH_PER_GID);
|
||||
|
||||
remaining_capacity_Wh = LB_Wh_Remaining;
|
||||
|
||||
/* Define power able to be discharged from battery */
|
||||
if(LB_Discharge_Power_Limit > 30) //if >30kW can be pulled from battery
|
||||
{
|
||||
max_target_discharge_power = 30000; //cap value so we don't go over the Fronius limits
|
||||
}
|
||||
else
|
||||
{
|
||||
max_target_discharge_power = (LB_Discharge_Power_Limit * 1000); //kW to W
|
||||
}
|
||||
if(SOC == 0) //Scaled SOC% value is 0.00%, we should not discharge battery further
|
||||
{
|
||||
max_target_discharge_power = 0;
|
||||
}
|
||||
|
||||
/* Define power able to be put into the battery */
|
||||
if(LB_Charge_Power_Limit > 30) //if >30kW can be put into the battery
|
||||
{
|
||||
max_target_charge_power = 30000; //cap value so we don't go over the Fronius limits
|
||||
}
|
||||
if(LB_Charge_Power_Limit < 0) //LB_MAX_POWER_FOR_CHARGER can actually go to -10kW
|
||||
{
|
||||
max_target_charge_power = 0; //cap calue so we dont do under the Fronius limits
|
||||
}
|
||||
else
|
||||
{
|
||||
max_target_charge_power = (LB_Charge_Power_Limit * 1000); //kW to W
|
||||
}
|
||||
if(SOC == 10000) //Scaled SOC% value is 100.00%
|
||||
{
|
||||
max_target_charge_power = 0; //No need to charge further, set max power to 0
|
||||
}
|
||||
|
||||
/*Extra safeguards*/
|
||||
if(LB_GIDS < 10) //800Wh left in battery
|
||||
{ //Battery is running abnormally low, some discharge logic might have failed. Zero it all out.
|
||||
SOC = 0;
|
||||
max_target_discharge_power = 0;
|
||||
}
|
||||
|
||||
if(LB_Full_CHARGE_flag)
|
||||
{ //Battery reports that it is fully charged stop all further charging incase it hasn't already
|
||||
max_target_charge_power = 0;
|
||||
}
|
||||
|
||||
if(LB_Relay_Cut_Request)
|
||||
{ //LB_FAIL, BMS requesting shutdown and contactors to be opened
|
||||
Serial.println("Battery requesting immediate shutdown and contactors to be opened!");
|
||||
//Note, this is sometimes triggered during the night while idle, and the BMS recovers after a while. Removed latching from this scenario
|
||||
errorCode = 1;
|
||||
max_target_discharge_power = 0;
|
||||
max_target_charge_power = 0;
|
||||
}
|
||||
|
||||
if(LB_Failsafe_Status > 0) // 0 is normal, start charging/discharging
|
||||
{
|
||||
switch(LB_Failsafe_Status)
|
||||
{
|
||||
case(1):
|
||||
//Normal Stop Request
|
||||
//This means that battery is fully discharged and it's OK to stop the session. For stationary storage we don't disconnect contactors, so we do nothing here.
|
||||
break;
|
||||
case(2):
|
||||
//Charging Mode Stop Request
|
||||
//This means that battery is fully charged and it's OK to stop the session. For stationary storage we don't disconnect contactors, so we do nothing here.
|
||||
break;
|
||||
case(3):
|
||||
//Charging Mode Stop Request & Normal Stop Request
|
||||
//Normal stop request. For stationary storage we don't disconnect contactors, so we ignore this.
|
||||
break;
|
||||
case(4):
|
||||
//Caution Lamp Request
|
||||
Serial.println("Battery raised caution indicator. Inspect battery status!");
|
||||
break;
|
||||
case(5):
|
||||
//Caution Lamp Request & Normal Stop Request
|
||||
bms_status = FAULT;
|
||||
errorCode = 2;
|
||||
Serial.println("Battery raised caution indicator AND requested discharge stop. Inspect battery status!");
|
||||
break;
|
||||
case(6):
|
||||
//Caution Lamp Request & Charging Mode Stop Request
|
||||
bms_status = FAULT;
|
||||
errorCode = 3;
|
||||
Serial.println("Battery raised caution indicator AND requested charge stop. Inspect battery status!");
|
||||
break;
|
||||
case(7):
|
||||
//Caution Lamp Request & Charging Mode Stop Request & Normal Stop Request
|
||||
bms_status = FAULT;
|
||||
errorCode = 4;
|
||||
Serial.println("Battery raised caution indicator AND requested charge/discharge stop. Inspect battery status!");
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
if(LB_StateOfHealth < 25)
|
||||
{ //Battery is extremely degraded, not fit for secondlifestorage. Zero it all out.
|
||||
if(LB_StateOfHealth != 0)
|
||||
{ //Extra check to see that we actually have a SOH Value available
|
||||
Serial.println("State of health critically low. Battery internal resistance too high to continue. Recycle battery.");
|
||||
bms_status = FAULT;
|
||||
errorCode = 5;
|
||||
max_target_discharge_power = 0;
|
||||
max_target_charge_power = 0;
|
||||
}
|
||||
}
|
||||
|
||||
#ifdef INTERLOCK_REQUIRED
|
||||
if(!LB_Interlock)
|
||||
{
|
||||
Serial.println("Battery interlock loop broken. Check that high voltage connectors are seated. Battery will be disabled!");
|
||||
bms_status = FAULT;
|
||||
errorCode = 6;
|
||||
SOC = 0;
|
||||
max_target_discharge_power = 0;
|
||||
max_target_charge_power = 0;
|
||||
}
|
||||
#endif
|
||||
|
||||
/* Check if the BMS is still sending CAN messages. If we go 60s without messages we raise an error*/
|
||||
if(!CANstillAlive)
|
||||
{
|
||||
bms_status = FAULT;
|
||||
errorCode = 7;
|
||||
Serial.println("No CAN communication detected for 60s. Shutting down battery control.");
|
||||
}
|
||||
else
|
||||
{
|
||||
CANstillAlive--;
|
||||
}
|
||||
|
||||
LB_Power = LB_Total_Voltage * LB_Current;//P = U * I
|
||||
stat_batt_power = convert2unsignedint16(LB_Power); //add sign if needed
|
||||
|
||||
temperature_min = convert2unsignedint16((LB_HistData_Temperature_MIN * 10)); //add sign if needed and increase range
|
||||
temperature_max = convert2unsignedint16((LB_HistData_Temperature_MAX * 10));
|
||||
|
||||
if(printValues)
|
||||
{ //values heading towards the modbus registers
|
||||
if(errorCode > 0)
|
||||
{
|
||||
Serial.print("ERROR CODE ACTIVE IN SYSTEM. NUMBER: ");
|
||||
Serial.println(errorCode);
|
||||
}
|
||||
Serial.print("BMS Status (3=OK): ");
|
||||
Serial.println(bms_status);
|
||||
switch (bms_char_dis_status)
|
||||
{
|
||||
case 0:
|
||||
Serial.println("Battery Idle");
|
||||
break;
|
||||
case 1:
|
||||
Serial.println("Battery Discharging");
|
||||
break;
|
||||
case 2:
|
||||
Serial.println("Battery Charging");
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
}
|
||||
Serial.print("Power: ");
|
||||
Serial.println(LB_Power);
|
||||
Serial.print("Max discharge power: ");
|
||||
Serial.println(max_target_discharge_power);
|
||||
Serial.print("Max charge power: ");
|
||||
Serial.println(max_target_charge_power);
|
||||
Serial.print("SOH%: ");
|
||||
Serial.println(StateOfHealth);
|
||||
Serial.print("SOC% to Fronius: ");
|
||||
Serial.println(SOC);
|
||||
Serial.print("Temperature Min: ");
|
||||
Serial.println(temperature_min);
|
||||
Serial.print("Temperature Max: ");
|
||||
Serial.println(temperature_max);
|
||||
Serial.print("GIDS: ");
|
||||
Serial.println(LB_GIDS);
|
||||
Serial.print("LEAF battery gen: ");
|
||||
Serial.println(LEAF_Battery_Type);
|
||||
}
|
||||
}
|
||||
|
||||
void handle_static_data_modbus() {
|
||||
// Store the data into the array
|
||||
static uint16_t si_data[] = { 21321, 1 };
|
||||
static uint16_t byd_data[] = { 16985, 17408, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 };
|
||||
static uint16_t battery_data[] = { 16985, 17440, 16993, 29812, 25970, 31021, 17007, 30752, 20594, 25965, 26997, 27936, 18518, 0, 0, 0 };
|
||||
static uint16_t volt_data[] = { 13614, 12288, 0, 0, 0, 0, 0, 0, 13102, 12598, 0, 0, 0, 0, 0, 0 };
|
||||
static uint16_t serial_data[] = { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 };
|
||||
static uint16_t static_data[] = { 1, 0 };
|
||||
static uint16_t* data_array_pointers[] = { si_data, byd_data, battery_data, volt_data, serial_data, static_data };
|
||||
static uint16_t data_sizes[] = { sizeof(si_data), sizeof(byd_data), sizeof(battery_data), sizeof(volt_data), sizeof(serial_data), sizeof(static_data) };
|
||||
static uint16_t i = 100;
|
||||
for (uint8_t arr_idx = 0; arr_idx < sizeof(data_array_pointers) / sizeof(uint16_t*); arr_idx++) {
|
||||
uint16_t data_size = data_sizes[arr_idx];
|
||||
memcpy(&mbPV[i], data_array_pointers[arr_idx], data_size);
|
||||
i += data_size / sizeof(uint16_t);
|
||||
}
|
||||
}
|
||||
|
||||
void handle_update_data_modbusp201() {
|
||||
// Store the data into the array
|
||||
static uint16_t system_data[13];
|
||||
system_data[0] = 0; // Id.: p201 Value.: 0 Scaled value.: 0 Comment.: Always 0
|
||||
system_data[1] = 0; // Id.: p202 Value.: 0 Scaled value.: 0 Comment.: Always 0
|
||||
system_data[2] = (capacity_Wh_startup); // Id.: p203 Value.: 32000 Scaled value.: 32kWh Comment.: Capacity rated, maximum value is 60000 (60kWh)
|
||||
system_data[3] = (max_power); // Id.: p204 Value.: 32000 Scaled value.: 32kWh Comment.: Nominal capacity
|
||||
system_data[4] = (max_power); // Id.: p205 Value.: 14500 Scaled value.: 30,42kW Comment.: Max Charge/Discharge Power=10.24kW (lowest value of 204 and 205 will be enforced by Gen24)
|
||||
system_data[5] = (max_voltage); // Id.: p206 Value.: 3667 Scaled value.: 362,7VDC Comment.: Max Voltage, if higher charging is not possible (goes into forced discharge)
|
||||
system_data[6] = (min_voltage); // Id.: p207 Value.: 2776 Scaled value.: 277,6VDC Comment.: Min Voltage, if lower Gen24 disables battery
|
||||
system_data[7] = 53248; // Id.: p208 Value.: 53248 Scaled value.: 53248 Comment.: Always 53248 for this BYD, Peak Charge power?
|
||||
system_data[8] = 10; // Id.: p209 Value.: 10 Scaled value.: 10 Comment.: Always 10
|
||||
system_data[9] = 53248; // Id.: p210 Value.: 53248 Scaled value.: 53248 Comment.: Always 53248 for this BYD, Peak Discharge power?
|
||||
system_data[10] = 10; // Id.: p211 Value.: 10 Scaled value.: 10 Comment.: Always 10
|
||||
system_data[11] = 0; // Id.: p212 Value.: 0 Scaled value.: 0 Comment.: Always 0
|
||||
system_data[12] = 0; // Id.: p213 Value.: 0 Scaled value.: 0 Comment.: Always 0
|
||||
static uint16_t i = 200;
|
||||
memcpy(&mbPV[i], system_data, sizeof(system_data));
|
||||
}
|
||||
|
||||
void handle_update_data_modbusp301() {
|
||||
// Store the data into the array
|
||||
static uint16_t battery_data[24];
|
||||
if (LB_Current > 0) { //Positive value = Charging on LEAF
|
||||
bms_char_dis_status = 2; //Charging
|
||||
} else if (LB_Current < 0) { //Negative value = Discharging on LEAF
|
||||
bms_char_dis_status = 1; //Discharging
|
||||
} else { //LB_Current == 0
|
||||
bms_char_dis_status = 0; //idle
|
||||
}
|
||||
|
||||
if (bms_status == ACTIVE) {
|
||||
battery_data[8] = battery_voltage; // Id.: p309 Value.: 3161 Scaled value.: 316,1VDC Comment.: Batt Voltage outer (0 if status !=3, maybe a contactor closes when active): 173.4V
|
||||
} else {
|
||||
battery_data[8] = 0;
|
||||
}
|
||||
battery_data[0] = bms_status; // Id.: p301 Value.: 3 Scaled value.: 3 Comment.: status(*): ACTIVE - [0..5]<>[STANDBY,INACTIVE,DARKSTART,ACTIVE,FAULT,UPDATING]
|
||||
battery_data[1] = 0; // Id.: p302 Value.: 0 Scaled value.: 0 Comment.: always 0
|
||||
battery_data[2] = 128 + bms_char_dis_status; // Id.: p303 Value.: 130 Scaled value.: 130 Comment.: mode(*): normal
|
||||
battery_data[3] = SOC; // Id.: p304 Value.: 1700 Scaled value.: 50% Comment.: SOC: (50% would equal 5000)
|
||||
battery_data[4] = capacity_Wh; // Id.: p305 Value.: 32000 Scaled value.: 32kWh Comment.: tot cap:
|
||||
battery_data[5] = remaining_capacity_Wh; // Id.: p306 Value.: 13260 Scaled value.: 13,26kWh Comment.: remaining cap: 7.68kWh
|
||||
battery_data[6] = max_target_discharge_power; // Id.: p307 Value.: 25604 Scaled value.: 25,604kW Comment.: max/target discharge power: 0W (0W > restricts to no discharge)
|
||||
battery_data[7] = max_target_charge_power; // Id.: p308 Value.: 25604 Scaled value.: 25,604kW Comment.: max/target charge power: 4.3kW (during charge), both 307&308 can be set (>0) at the same time
|
||||
//Battery_data[8] set previously in function // Id.: p309 Value.: 3161 Scaled value.: 316,1VDC Comment.: Batt Voltage outer (0 if status !=3, maybe a contactor closes when active): 173.4V
|
||||
battery_data[9] = 2000; // Id.: p310 Value.: 64121 Scaled value.: 6412,1W Comment.: Current Power to API: if>32768... -(65535-61760)=3775W
|
||||
battery_data[10] = battery_voltage; // Id.: p311 Value.: 3161 Scaled value.: 316,1VDC Comment.: Batt Voltage inner: 173.2V (LEAF voltage is in whole volts, need to add a decimal)
|
||||
battery_data[11] = 2000; // Id.: p312 Value.: 64121 Scaled value.: 6412,1W Comment.: p310
|
||||
battery_data[12] = temperature_min; // Id.: p313 Value.: 75 Scaled value.: 7,5 Comment.: temp min: 7 degrees (if below 0....65535-t)
|
||||
battery_data[13] = temperature_max; // Id.: p314 Value.: 95 Scaled value.: 9,5 Comment.: temp max: 9 degrees (if below 0....65535-t)
|
||||
battery_data[14] = 0; // Id.: p315 Value.: 0 Scaled value.: 0 Comment.: always 0
|
||||
battery_data[15] = 0; // Id.: p316 Value.: 0 Scaled value.: 0 Comment.: always 0
|
||||
battery_data[16] = 16; // Id.: p317 Value.: 0 Scaled value.: 0 Comment.: counter charge hi
|
||||
battery_data[17] = 22741; // Id.: p318 Value.: 0 Scaled value.: 0 Comment.: counter charge lo....65536*101+9912 = 6629048 Wh?
|
||||
battery_data[18] = 0; // Id.: p319 Value.: 0 Scaled value.: 0 Comment.: always 0
|
||||
battery_data[19] = 0; // Id.: p320 Value.: 0 Scaled value.: 0 Comment.: always 0
|
||||
battery_data[20] = 13; // Id.: p321 Value.: 0 Scaled value.: 0 Comment.: counter discharge hi
|
||||
battery_data[21] = 52064; // Id.: p322 Value.: 0 Scaled value.: 0 Comment.: counter discharge lo....65536*92+7448 = 6036760 Wh?
|
||||
battery_data[22] = 230; // Id.: p323 Value.: 0 Scaled value.: 0 Comment.: device temperature (23 degrees)
|
||||
battery_data[23] = StateOfHealth; // Id.: p324 Value.: 9900 Scaled value.: 99% Comment.: SOH
|
||||
static uint16_t i = 300;
|
||||
memcpy(&mbPV[i], battery_data, sizeof(battery_data));
|
||||
}
|
||||
|
||||
void handle_can_leaf_battery()
|
||||
{
|
||||
CAN_frame_t rx_frame;
|
||||
unsigned long currentMillis = millis();
|
||||
|
||||
// Receive next CAN frame from queue
|
||||
if (xQueueReceive(CAN_cfg.rx_queue, &rx_frame, 3 * portTICK_PERIOD_MS) == pdTRUE)
|
||||
{
|
||||
if (rx_frame.FIR.B.FF == CAN_frame_std)
|
||||
{
|
||||
//printf("New standard frame");
|
||||
switch (rx_frame.MsgID)
|
||||
{
|
||||
case 0x1DB:
|
||||
LB_Current = (rx_frame.data.u8[0] << 3) | (rx_frame.data.u8[1] & 0xe0) >> 5;
|
||||
if (LB_Current & 0x0400)
|
||||
{
|
||||
// negative so extend the sign bit
|
||||
LB_Current |= 0xf800;
|
||||
}
|
||||
|
||||
LB_Total_Voltage = ((rx_frame.data.u8[2] << 2) | (rx_frame.data.u8[3] & 0xc0) >> 6) / 2;
|
||||
|
||||
//Collect various data from the BMS
|
||||
LB_Relay_Cut_Request = ((rx_frame.data.u8[1] & 0x18) >> 3);
|
||||
LB_Failsafe_Status = (rx_frame.data.u8[1] & 0x07);
|
||||
LB_MainRelayOn_flag = (byte) ((rx_frame.data.u8[3] & 0x20) >> 5);
|
||||
LB_Full_CHARGE_flag = (byte) ((rx_frame.data.u8[3] & 0x10) >> 4);
|
||||
LB_Interlock = (byte) ((rx_frame.data.u8[3] & 0x08) >> 3);
|
||||
break;
|
||||
case 0x1DC:
|
||||
LB_Discharge_Power_Limit = ((rx_frame.data.u8[0] << 2 | rx_frame.data.u8[1] >> 6) / 4.0);
|
||||
LB_Charge_Power_Limit = (((rx_frame.data.u8[1] & 0x3F) << 2 | rx_frame.data.u8[2] >> 4) / 4.0);
|
||||
LB_MAX_POWER_FOR_CHARGER = ((((rx_frame.data.u8[2] & 0x0F) << 6 | rx_frame.data.u8[3] >> 2) / 10.0) - 10);
|
||||
break;
|
||||
case 0x55B:
|
||||
LB_TEMP = (rx_frame.data.u8[0] << 2 | rx_frame.data.u8[1] >> 6);
|
||||
if (LB_TEMP != 0x3ff) //3FF is unavailable value
|
||||
{
|
||||
LB_SOC = LB_TEMP;
|
||||
}
|
||||
break;
|
||||
case 0x5BC:
|
||||
CANstillAlive = 12; //Indicate that we are still getting CAN messages from the BMS
|
||||
|
||||
LB_MAX = ((rx_frame.data.u8[5] & 0x10) >> 4);
|
||||
if (LB_MAX)
|
||||
{
|
||||
LB_Max_GIDS = (rx_frame.data.u8[0] << 2) | ((rx_frame.data.u8[1] & 0xC0) >> 6);
|
||||
//Max gids active, do nothing
|
||||
//Only the 30/40/62kWh packs have this mux
|
||||
}
|
||||
else
|
||||
{
|
||||
//Normal current GIDS value is transmitted
|
||||
LB_GIDS = (rx_frame.data.u8[0] << 2) | ((rx_frame.data.u8[1] & 0xC0) >> 6);
|
||||
LB_Wh_Remaining = (LB_GIDS * WH_PER_GID);
|
||||
}
|
||||
|
||||
LB_TEMP = (rx_frame.data.u8[4] >> 1);
|
||||
if (LB_TEMP != 0)
|
||||
{
|
||||
LB_StateOfHealth = LB_TEMP; //Collect state of health from battery
|
||||
}
|
||||
break;
|
||||
case 0x5C0: //This method only works for 2013-2017 AZE0 LEAF packs, the mux is different on other generations
|
||||
if(LEAF_Battery_Type == AZE0_BATTERY)
|
||||
{
|
||||
if ((rx_frame.data.u8[0]>>6) == 1)
|
||||
{ // Battery MAX temperature. Effectively has only 7-bit precision, as the bottom bit is always 0.
|
||||
LB_HistData_Temperature_MAX = ((rx_frame.data.u8[2] / 2) - 40);
|
||||
}
|
||||
if ((rx_frame.data.u8[0]>>6) == 3)
|
||||
{ // Battery MIN temperature. Effectively has only 7-bit precision, as the bottom bit is always 0.
|
||||
LB_HistData_Temperature_MIN = ((rx_frame.data.u8[2] / 2) - 40);
|
||||
}
|
||||
}
|
||||
if(LEAF_Battery_Type == ZE1_BATTERY)
|
||||
{ //note different mux location in first frame
|
||||
if ((rx_frame.data.u8[0] & 0x0F) == 1)
|
||||
{
|
||||
LB_HistData_Temperature_MAX = ((rx_frame.data.u8[2] / 2) - 40);
|
||||
}
|
||||
if ((rx_frame.data.u8[0] & 0x0F) == 3)
|
||||
{
|
||||
LB_HistData_Temperature_MIN = ((rx_frame.data.u8[2] / 2) - 40);
|
||||
}
|
||||
}
|
||||
break;
|
||||
case 0x59E:
|
||||
//AZE0 2013-2017 or ZE1 2018-2023 battery detected
|
||||
//Only detect as AZE0 if not already set as ZE1
|
||||
if(LEAF_Battery_Type != ZE1_BATTERY)
|
||||
{
|
||||
LEAF_Battery_Type = AZE0_BATTERY;
|
||||
}
|
||||
break;
|
||||
case 0x1ED:
|
||||
case 0x1C2:
|
||||
//ZE1 2018-2023 battery detected!
|
||||
LEAF_Battery_Type = ZE1_BATTERY;
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
//printf("New extended frame");
|
||||
}
|
||||
}
|
||||
// Send 100ms CAN Message
|
||||
if (currentMillis - previousMillis100 >= interval100)
|
||||
{
|
||||
previousMillis100 = currentMillis;
|
||||
|
||||
ESP32Can.CANWriteFrame(&LEAF_50B); //Always send 50B as a static message (Contains HCM_WakeUpSleepCommand == 11b == WakeUp, and CANMASK = 1)
|
||||
|
||||
mprun100++;
|
||||
if (mprun100 > 3)
|
||||
{
|
||||
mprun100 = 0;
|
||||
}
|
||||
|
||||
if (mprun100 == 0)
|
||||
{
|
||||
LEAF_50C.data.u8[3] = 0x00;
|
||||
LEAF_50C.data.u8[4] = 0x5D;
|
||||
LEAF_50C.data.u8[5] = 0xC8;
|
||||
}
|
||||
else if(mprun100 == 1)
|
||||
{
|
||||
LEAF_50C.data.u8[3] = 0x01;
|
||||
LEAF_50C.data.u8[4] = 0xB2;
|
||||
LEAF_50C.data.u8[5] = 0x31;
|
||||
}
|
||||
else if(mprun100 == 2)
|
||||
{
|
||||
LEAF_50C.data.u8[3] = 0x02;
|
||||
LEAF_50C.data.u8[4] = 0x5D;
|
||||
LEAF_50C.data.u8[5] = 0x63;
|
||||
}
|
||||
else if(mprun100 == 3)
|
||||
{
|
||||
LEAF_50C.data.u8[3] = 0x03;
|
||||
LEAF_50C.data.u8[4] = 0xB2;
|
||||
LEAF_50C.data.u8[5] = 0x9A;
|
||||
}
|
||||
ESP32Can.CANWriteFrame(&LEAF_50C);
|
||||
}
|
||||
//Send 10ms message
|
||||
if (currentMillis - previousMillis10 >= interval10)
|
||||
{
|
||||
previousMillis10 = currentMillis;
|
||||
|
||||
if(mprun10 == 0)
|
||||
{
|
||||
LEAF_1D4.data.u8[4] = 0x07;
|
||||
LEAF_1D4.data.u8[7] = 0x12;
|
||||
}
|
||||
else if(mprun10 == 1)
|
||||
{
|
||||
LEAF_1D4.data.u8[4] = 0x47;
|
||||
LEAF_1D4.data.u8[7] = 0xD5;
|
||||
}
|
||||
else if(mprun10 == 2)
|
||||
{
|
||||
LEAF_1D4.data.u8[4] = 0x87;
|
||||
LEAF_1D4.data.u8[7] = 0x19;
|
||||
}
|
||||
else if(mprun10 == 3)
|
||||
{
|
||||
LEAF_1D4.data.u8[4] = 0xC7;
|
||||
LEAF_1D4.data.u8[7] = 0xDE;
|
||||
}
|
||||
ESP32Can.CANWriteFrame(&LEAF_1D4);
|
||||
|
||||
mprun10++;
|
||||
if (mprun10 > 3)
|
||||
{
|
||||
mprun10 = 0;
|
||||
}
|
||||
|
||||
switch(mprun10r)
|
||||
{
|
||||
case(0):
|
||||
LEAF_1F2.data.u8[3] = 0xB0;
|
||||
LEAF_1F2.data.u8[6] = 0x00;
|
||||
LEAF_1F2.data.u8[7] = 0x8F;
|
||||
break;
|
||||
case(1):
|
||||
LEAF_1F2.data.u8[3] = 0xB0;
|
||||
LEAF_1F2.data.u8[6] = 0x01;
|
||||
LEAF_1F2.data.u8[7] = 0x80;
|
||||
break;
|
||||
case(2):
|
||||
LEAF_1F2.data.u8[3] = 0xB0;
|
||||
LEAF_1F2.data.u8[6] = 0x02;
|
||||
LEAF_1F2.data.u8[7] = 0x81;
|
||||
break;
|
||||
case(3):
|
||||
LEAF_1F2.data.u8[3] = 0xB0;
|
||||
LEAF_1F2.data.u8[6] = 0x03;
|
||||
LEAF_1F2.data.u8[7] = 0x82;
|
||||
break;
|
||||
case(4):
|
||||
LEAF_1F2.data.u8[3] = 0xB0;
|
||||
LEAF_1F2.data.u8[6] = 0x00;
|
||||
LEAF_1F2.data.u8[7] = 0x8F;
|
||||
break;
|
||||
case(5): // Set 2
|
||||
LEAF_1F2.data.u8[3] = 0xB4;
|
||||
LEAF_1F2.data.u8[6] = 0x01;
|
||||
LEAF_1F2.data.u8[7] = 0x84;
|
||||
break;
|
||||
case(6):
|
||||
LEAF_1F2.data.u8[3] = 0xB4;
|
||||
LEAF_1F2.data.u8[6] = 0x02;
|
||||
LEAF_1F2.data.u8[7] = 0x85;
|
||||
break;
|
||||
case(7):
|
||||
LEAF_1F2.data.u8[3] = 0xB4;
|
||||
LEAF_1F2.data.u8[6] = 0x03;
|
||||
LEAF_1F2.data.u8[7] = 0x86;
|
||||
break;
|
||||
case(8):
|
||||
LEAF_1F2.data.u8[3] = 0xB4;
|
||||
LEAF_1F2.data.u8[6] = 0x00;
|
||||
LEAF_1F2.data.u8[7] = 0x83;
|
||||
break;
|
||||
case(9):
|
||||
LEAF_1F2.data.u8[3] = 0xB4;
|
||||
LEAF_1F2.data.u8[6] = 0x01;
|
||||
LEAF_1F2.data.u8[7] = 0x84;
|
||||
break;
|
||||
case(10): // Set 3
|
||||
LEAF_1F2.data.u8[3] = 0xB0;
|
||||
LEAF_1F2.data.u8[6] = 0x02;
|
||||
LEAF_1F2.data.u8[7] = 0x81;
|
||||
break;
|
||||
case(11):
|
||||
LEAF_1F2.data.u8[3] = 0xB0;
|
||||
LEAF_1F2.data.u8[6] = 0x03;
|
||||
LEAF_1F2.data.u8[7] = 0x82;
|
||||
break;
|
||||
case(12):
|
||||
LEAF_1F2.data.u8[3] = 0xB0;
|
||||
LEAF_1F2.data.u8[6] = 0x00;
|
||||
LEAF_1F2.data.u8[7] = 0x8F;
|
||||
break;
|
||||
case(13):
|
||||
LEAF_1F2.data.u8[3] = 0xB0;
|
||||
LEAF_1F2.data.u8[6] = 0x01;
|
||||
LEAF_1F2.data.u8[7] = 0x80;
|
||||
break;
|
||||
case(14):
|
||||
LEAF_1F2.data.u8[3] = 0xB0;
|
||||
LEAF_1F2.data.u8[6] = 0x02;
|
||||
LEAF_1F2.data.u8[7] = 0x81;
|
||||
break;
|
||||
case(15): // Set 4
|
||||
LEAF_1F2.data.u8[3] = 0xB4;
|
||||
LEAF_1F2.data.u8[6] = 0x03;
|
||||
LEAF_1F2.data.u8[7] = 0x86;
|
||||
break;
|
||||
case(16):
|
||||
LEAF_1F2.data.u8[3] = 0xB4;
|
||||
LEAF_1F2.data.u8[6] = 0x00;
|
||||
LEAF_1F2.data.u8[7] = 0x83;
|
||||
break;
|
||||
case(17):
|
||||
LEAF_1F2.data.u8[3] = 0xB4;
|
||||
LEAF_1F2.data.u8[6] = 0x01;
|
||||
LEAF_1F2.data.u8[7] = 0x84;
|
||||
break;
|
||||
case(18):
|
||||
LEAF_1F2.data.u8[3] = 0xB4;
|
||||
LEAF_1F2.data.u8[6] = 0x02;
|
||||
LEAF_1F2.data.u8[7] = 0x85;
|
||||
break;
|
||||
case(19):
|
||||
LEAF_1F2.data.u8[3] = 0xB4;
|
||||
LEAF_1F2.data.u8[6] = 0x03;
|
||||
LEAF_1F2.data.u8[7] = 0x86;
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
}
|
||||
|
||||
ESP32Can.CANWriteFrame(&LEAF_1F2); //Contains (CHG_STA_RQ == 1 == Normal Charge)
|
||||
|
||||
mprun10r++;
|
||||
if(mprun10r > 19) // 0x1F2 patter repeats after 20 messages,
|
||||
{
|
||||
mprun10r = 0;
|
||||
}
|
||||
//Serial.println("CAN 10ms done");
|
||||
}
|
||||
}
|
||||
|
||||
uint16_t convert2unsignedint16(uint16_t signed_value)
|
||||
{
|
||||
if(signed_value < 0)
|
||||
{
|
||||
return(65535 + signed_value);
|
||||
}
|
||||
else
|
||||
{
|
||||
return signed_value;
|
||||
}
|
||||
}
|
||||
|
||||
void handle_LED_state()
|
||||
{
|
||||
// Determine how bright the green LED should be
|
||||
if (rampUp && green < maxBrightness)
|
||||
{
|
||||
green++;
|
||||
}
|
||||
else if (rampUp && green == maxBrightness)
|
||||
{
|
||||
rampUp = false;
|
||||
}
|
||||
else if (!rampUp && green > 0)
|
||||
{
|
||||
green--;
|
||||
} else if (!rampUp && green == 0)
|
||||
{
|
||||
rampUp = true;
|
||||
}
|
||||
pixels.setPixelColor(0, pixels.Color(0, green, 0)); // Set LED to green according to calculated value
|
||||
|
||||
if(bms_status == FAULT)
|
||||
{
|
||||
pixels.setPixelColor(0, pixels.Color(255, 0, 0)); // Red LED full brightness
|
||||
}
|
||||
|
||||
pixels.show(); // This sends the updated pixel color to the hardware.
|
||||
}
|
178
Software/esp.c
Normal file
178
Software/esp.c
Normal file
|
@ -0,0 +1,178 @@
|
|||
// Implements the RMT peripheral on Espressif SoCs
|
||||
// Copyright (c) 2020 Lucian Copeland for Adafruit Industries
|
||||
|
||||
/* Uses code from Espressif RGB LED Strip demo and drivers
|
||||
* Copyright 2015-2020 Espressif Systems (Shanghai) PTE LTD
|
||||
*
|
||||
* Licensed under the Apache License, Version 2.0 (the "License");
|
||||
* you may not use this file except in compliance with the License.
|
||||
* You may obtain a copy of the License at
|
||||
*
|
||||
* http://www.apache.org/licenses/LICENSE-2.0
|
||||
*
|
||||
* Unless required by applicable law or agreed to in writing, software
|
||||
* distributed under the License is distributed on an "AS IS" BASIS,
|
||||
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||
* See the License for the specific language governing permissions and
|
||||
* limitations under the License.
|
||||
*/
|
||||
|
||||
#if defined(ESP32)
|
||||
|
||||
#include <Arduino.h>
|
||||
#include "driver/rmt.h"
|
||||
|
||||
#if defined(ESP_IDF_VERSION)
|
||||
#if ESP_IDF_VERSION >= ESP_IDF_VERSION_VAL(4, 0, 0)
|
||||
#define HAS_ESP_IDF_4
|
||||
#endif
|
||||
#endif
|
||||
|
||||
// This code is adapted from the ESP-IDF v3.4 RMT "led_strip" example, altered
|
||||
// to work with the Arduino version of the ESP-IDF (3.2)
|
||||
|
||||
#define WS2812_T0H_NS (400)
|
||||
#define WS2812_T0L_NS (850)
|
||||
#define WS2812_T1H_NS (800)
|
||||
#define WS2812_T1L_NS (450)
|
||||
|
||||
#define WS2811_T0H_NS (500)
|
||||
#define WS2811_T0L_NS (2000)
|
||||
#define WS2811_T1H_NS (1200)
|
||||
#define WS2811_T1L_NS (1300)
|
||||
|
||||
static uint32_t t0h_ticks = 0;
|
||||
static uint32_t t1h_ticks = 0;
|
||||
static uint32_t t0l_ticks = 0;
|
||||
static uint32_t t1l_ticks = 0;
|
||||
|
||||
// Limit the number of RMT channels available for the Neopixels. Defaults to all
|
||||
// channels (8 on ESP32, 4 on ESP32-S2 and S3). Redefining this value will free
|
||||
// any channels with a higher number for other uses, such as IR send-and-recieve
|
||||
// libraries. Redefine as 1 to restrict Neopixels to only a single channel.
|
||||
#define ADAFRUIT_RMT_CHANNEL_MAX RMT_CHANNEL_MAX
|
||||
|
||||
#define RMT_LL_HW_BASE (&RMT)
|
||||
|
||||
bool rmt_reserved_channels[ADAFRUIT_RMT_CHANNEL_MAX];
|
||||
|
||||
static void IRAM_ATTR ws2812_rmt_adapter(const void *src, rmt_item32_t *dest, size_t src_size,
|
||||
size_t wanted_num, size_t *translated_size, size_t *item_num)
|
||||
{
|
||||
if (src == NULL || dest == NULL) {
|
||||
*translated_size = 0;
|
||||
*item_num = 0;
|
||||
return;
|
||||
}
|
||||
const rmt_item32_t bit0 = {{{ t0h_ticks, 1, t0l_ticks, 0 }}}; //Logical 0
|
||||
const rmt_item32_t bit1 = {{{ t1h_ticks, 1, t1l_ticks, 0 }}}; //Logical 1
|
||||
size_t size = 0;
|
||||
size_t num = 0;
|
||||
uint8_t *psrc = (uint8_t *)src;
|
||||
rmt_item32_t *pdest = dest;
|
||||
while (size < src_size && num < wanted_num) {
|
||||
for (int i = 0; i < 8; i++) {
|
||||
// MSB first
|
||||
if (*psrc & (1 << (7 - i))) {
|
||||
pdest->val = bit1.val;
|
||||
} else {
|
||||
pdest->val = bit0.val;
|
||||
}
|
||||
num++;
|
||||
pdest++;
|
||||
}
|
||||
size++;
|
||||
psrc++;
|
||||
}
|
||||
*translated_size = size;
|
||||
*item_num = num;
|
||||
}
|
||||
|
||||
void espShow(uint8_t pin, uint8_t *pixels, uint32_t numBytes, boolean is800KHz) {
|
||||
// Reserve channel
|
||||
rmt_channel_t channel = ADAFRUIT_RMT_CHANNEL_MAX;
|
||||
for (size_t i = 0; i < ADAFRUIT_RMT_CHANNEL_MAX; i++) {
|
||||
if (!rmt_reserved_channels[i]) {
|
||||
rmt_reserved_channels[i] = true;
|
||||
channel = i;
|
||||
break;
|
||||
}
|
||||
}
|
||||
if (channel == ADAFRUIT_RMT_CHANNEL_MAX) {
|
||||
// Ran out of channels!
|
||||
return;
|
||||
}
|
||||
|
||||
#if defined(HAS_ESP_IDF_4)
|
||||
rmt_config_t config = RMT_DEFAULT_CONFIG_TX(pin, channel);
|
||||
config.clk_div = 2;
|
||||
#else
|
||||
// Match default TX config from ESP-IDF version 3.4
|
||||
rmt_config_t config = {
|
||||
.rmt_mode = RMT_MODE_TX,
|
||||
.channel = channel,
|
||||
.gpio_num = pin,
|
||||
.clk_div = 2,
|
||||
.mem_block_num = 1,
|
||||
.tx_config = {
|
||||
.carrier_freq_hz = 38000,
|
||||
.carrier_level = RMT_CARRIER_LEVEL_HIGH,
|
||||
.idle_level = RMT_IDLE_LEVEL_LOW,
|
||||
.carrier_duty_percent = 33,
|
||||
.carrier_en = false,
|
||||
.loop_en = false,
|
||||
.idle_output_en = true,
|
||||
}
|
||||
};
|
||||
#endif
|
||||
rmt_config(&config);
|
||||
rmt_driver_install(config.channel, 0, 0);
|
||||
|
||||
// Convert NS timings to ticks
|
||||
uint32_t counter_clk_hz = 0;
|
||||
|
||||
#if defined(HAS_ESP_IDF_4)
|
||||
rmt_get_counter_clock(channel, &counter_clk_hz);
|
||||
#else
|
||||
// this emulates the rmt_get_counter_clock() function from ESP-IDF 3.4
|
||||
if (RMT_LL_HW_BASE->conf_ch[config.channel].conf1.ref_always_on == RMT_BASECLK_REF) {
|
||||
uint32_t div_cnt = RMT_LL_HW_BASE->conf_ch[config.channel].conf0.div_cnt;
|
||||
uint32_t div = div_cnt == 0 ? 256 : div_cnt;
|
||||
counter_clk_hz = REF_CLK_FREQ / (div);
|
||||
} else {
|
||||
uint32_t div_cnt = RMT_LL_HW_BASE->conf_ch[config.channel].conf0.div_cnt;
|
||||
uint32_t div = div_cnt == 0 ? 256 : div_cnt;
|
||||
counter_clk_hz = APB_CLK_FREQ / (div);
|
||||
}
|
||||
#endif
|
||||
|
||||
// NS to tick converter
|
||||
float ratio = (float)counter_clk_hz / 1e9;
|
||||
|
||||
if (is800KHz) {
|
||||
t0h_ticks = (uint32_t)(ratio * WS2812_T0H_NS);
|
||||
t0l_ticks = (uint32_t)(ratio * WS2812_T0L_NS);
|
||||
t1h_ticks = (uint32_t)(ratio * WS2812_T1H_NS);
|
||||
t1l_ticks = (uint32_t)(ratio * WS2812_T1L_NS);
|
||||
} else {
|
||||
t0h_ticks = (uint32_t)(ratio * WS2811_T0H_NS);
|
||||
t0l_ticks = (uint32_t)(ratio * WS2811_T0L_NS);
|
||||
t1h_ticks = (uint32_t)(ratio * WS2811_T1H_NS);
|
||||
t1l_ticks = (uint32_t)(ratio * WS2811_T1L_NS);
|
||||
}
|
||||
|
||||
// Initialize automatic timing translator
|
||||
rmt_translator_init(config.channel, ws2812_rmt_adapter);
|
||||
|
||||
// Write and wait to finish
|
||||
rmt_write_sample(config.channel, pixels, (size_t)numBytes, true);
|
||||
rmt_wait_tx_done(config.channel, pdMS_TO_TICKS(100));
|
||||
|
||||
// Free channel again
|
||||
rmt_driver_uninstall(config.channel);
|
||||
rmt_reserved_channels[channel] = false;
|
||||
|
||||
gpio_set_direction(pin, GPIO_MODE_OUTPUT);
|
||||
}
|
||||
|
||||
#endif
|
Loading…
Add table
Add a link
Reference in a new issue