Twizy Virtual BMS V1.0 RC2 (2017-06-10)
- Conversion to Arduino library - Added CAN RX callback bmsProcessCanMsg() - Added twizySetError() and error codes - Using ROM strings to save RAM - Configurable debug output level - Added example Template - Added example SimpleBMS - Added setCanFilter() - Added API documentation - Added hardware documentation - Added SEVCON configuration info Version: 0.2 (2017-06-06) - 3MW pulse cycle - Separate states for trickle charging - CAN TX retries - Added bmsTicker() callback Version: 0.1 (2017-06-04) - Initial release
2
.gitignore
vendored
Normal file
|
@ -0,0 +1,2 @@
|
||||||
|
assets
|
||||||
|
*.html
|
186
API.md
Normal file
|
@ -0,0 +1,186 @@
|
||||||
|
# API & Usage
|
||||||
|
|
||||||
|
Hint: begin with the "Template" example to get a standard usage template including all callbacks.
|
||||||
|
|
||||||
|
|
||||||
|
## Library inclusion
|
||||||
|
|
||||||
|
1. Create a TwizyVirtualBMS object (`twizy` is a good name for this)
|
||||||
|
2. Call `twizy.begin()` in your setup function
|
||||||
|
3. Call `twizy.looper()` in your main loop:
|
||||||
|
```c++
|
||||||
|
#include "TwizyVirtualBMS_config.h"
|
||||||
|
#include "TwizyVirtualBMS.h"
|
||||||
|
|
||||||
|
TwizyVirtualBMS twizy;
|
||||||
|
|
||||||
|
void setup() {
|
||||||
|
Serial.begin(115200);
|
||||||
|
twizy.begin();
|
||||||
|
}
|
||||||
|
|
||||||
|
void loop() {
|
||||||
|
twizy.looper();
|
||||||
|
}
|
||||||
|
```
|
||||||
|
|
||||||
|
|
||||||
|
## Twizy control functions
|
||||||
|
|
||||||
|
Note: all control functions validate their parameters. If you pass any value out of bounds, nothing will be changed, an error message will be generated on the serial port and the function will return `false`.
|
||||||
|
|
||||||
|
- `bool setChargeCurrent(int amps)` -- Set battery charge current level
|
||||||
|
- amps: 0 .. 35 A current level at battery
|
||||||
|
- will stop charge if set to 0 while charging
|
||||||
|
- Note: this has a 5 A resolution rounded downwards
|
||||||
|
- Note: 35 A will not be reached with current charger generation (max ~32 A)
|
||||||
|
|
||||||
|
| Current level | Power drawn from socket |
|
||||||
|
| ------------- | ----------------------- |
|
||||||
|
| 35 A | ~ 2.2 kW |
|
||||||
|
| 30 A | ~ 2.1 kW |
|
||||||
|
| 25 A | ~ 1.7 kW |
|
||||||
|
| 20 A | ~ 1.4 kW |
|
||||||
|
| 15 A | ~ 1.0 kW |
|
||||||
|
| 10 A | ~ 0.7 kW |
|
||||||
|
| 5 A | ~ 0.4 kW |
|
||||||
|
|
||||||
|
- `bool setCurrent(float amps)` -- Set momentary battery pack current level
|
||||||
|
- amps: -500 .. +500 (A, positive = charge, negative = discharge)
|
||||||
|
|
||||||
|
- `bool setSOC(float soc)` -- Set state of charge
|
||||||
|
- soc: 0.00 .. 100.00 (%)
|
||||||
|
- Note: the charger will not start charging at SOC=100%
|
||||||
|
|
||||||
|
- `bool setPowerLimits(unsigned int drive, unsigned int recup)` -- Set SEVCON power limits
|
||||||
|
- drive: 0 .. 30000 (W)
|
||||||
|
- recup: 0 .. 30000 (W)
|
||||||
|
- Note: both limits have a resolution of 500 W and will be rounded downwards
|
||||||
|
- Note: these limits do not apply if the SEVCON has been configured to ignore them (as done in some tuning configurations)
|
||||||
|
|
||||||
|
- `bool setSOH(int soh)` -- Set state of health
|
||||||
|
- soh: 0 .. 100 (%)
|
||||||
|
|
||||||
|
- `bool setCellVoltage(int cell, float volt)` -- Set battery cell voltage
|
||||||
|
- cell: 1 .. 14 (the original Twizy battery has 14 cells)
|
||||||
|
- volt: 1.0 .. 5.0
|
||||||
|
- Note: this does no implicit update on the overall pack voltage
|
||||||
|
|
||||||
|
- `bool setVoltage(float volt, bool deriveCells)` -- Set battery pack voltage
|
||||||
|
- volt: 19.3 … 69.6 (SEVCON G48 series voltage range)
|
||||||
|
- deriveCells: true = set all cell voltages to volt/14
|
||||||
|
|
||||||
|
- `bool setModuleTemperature(int module, int temp)` -- Set battery module temperature
|
||||||
|
- module: 1 .. 7 (the original Twizy battery is organized in 7 modules)
|
||||||
|
- temp: -40 .. 100 (°C)
|
||||||
|
- Note: this does no implicit update on the overall pack temperature
|
||||||
|
|
||||||
|
- `bool setTemperature(int tempMin, int tempMax, bool deriveModules)` -- Set battery pack temperature
|
||||||
|
- tempMin: -40 .. 100 (°C)
|
||||||
|
- tempMax: -40 .. 100 (°C)
|
||||||
|
- deriveModules: true = set all module temperatures to avg(min,max)
|
||||||
|
|
||||||
|
- `bool setError(unsigned long error)` -- Set error/warning indicators
|
||||||
|
- error: 0x000000 .. 0xFFFFFF (0 = no error) or use a bitwise ORed combination of…
|
||||||
|
|
||||||
|
| Code | Description |
|
||||||
|
| ----------------- | ------------------------------------- |
|
||||||
|
| `TWIZY_OK` | Clear all indicators |
|
||||||
|
| `TWIZY_SERV` | Set SERV indicator |
|
||||||
|
| `TWIZY_SERV_12V` | Set SERV + 12V battery indicator |
|
||||||
|
| `TWIZY_SERV_BATT` | Set SERV + 12V main battery indicator |
|
||||||
|
| `TWIZY_SERV_TEMP` | Set SERV + temperature indicator |
|
||||||
|
| `TWIZY_SERV_STOP` | Set SERV + STOP indicator + beep |
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
## User callback registration
|
||||||
|
|
||||||
|
To hook into the control flow you may register custom functions to be called by the VirtualBMS.
|
||||||
|
|
||||||
|
All callbacks are optional. See "Template" example for code templates and example attachment.
|
||||||
|
|
||||||
|
- `void attachEnterState(TwizyEnterStateCallback fn)`
|
||||||
|
- fn: `void fn(TwizyState currentState, TwizyState newState)`
|
||||||
|
- called on all state transitions after framework handling
|
||||||
|
- use this to apply custom settings on state changes
|
||||||
|
|
||||||
|
- `void attachCheckState(TwizyCheckStateCallback fn)`
|
||||||
|
- fn: `bool fn(TwizyState currentState, TwizyState newState)`
|
||||||
|
- called before transitions from `Init`, `Start…` and `Stop…` into `Ready`, `Driving`, `Charging` and `Trickle`
|
||||||
|
- if the callback returns false, the transition will be retried on the next 10 ms ticker run
|
||||||
|
- use this to check if the battery/BMS is ready for the state transition
|
||||||
|
|
||||||
|
- `void attachTicker(TwizyTickerCallback fn)`
|
||||||
|
- fn: `void fn(unsigned int clockCnt)`
|
||||||
|
- called by the 10 ms ticker *after* framework handling, i.e. after sending the Twizy CAN frames
|
||||||
|
- clockCnt: cyclic 10 ms interval counter range 0 … 2999
|
||||||
|
- use this to add custom CAN sends or do periodic checks, keep in mind this is not called when in state `Off`
|
||||||
|
|
||||||
|
- `void attachProcessCanMsg(TwizyProcessCanMsgCallback fn)`
|
||||||
|
- fn: `void fn(unsigned long rxId, byte rxLen, byte *rxBuf)`
|
||||||
|
- called on all received (filtered) CAN messages
|
||||||
|
- see `setCanFilter()` for setup of additional custom CAN ID filters
|
||||||
|
|
||||||
|
|
||||||
|
## State machine
|
||||||
|
|
||||||
|
The VirtualBMS will do state transitions automatically based on CAN input received from the Twizy.
|
||||||
|
|
||||||
|
__TwizyStates:__
|
||||||
|
- `Off`
|
||||||
|
- `Init`
|
||||||
|
- `Ready`
|
||||||
|
- `StartDrive`
|
||||||
|
- `Driving`
|
||||||
|
- `StopDrive`
|
||||||
|
- `StartCharge`
|
||||||
|
- `Charging`
|
||||||
|
- `StopCharge`
|
||||||
|
- `StartTrickle`
|
||||||
|
- `Trickle`
|
||||||
|
- `StopTrickle`
|
||||||
|
|
||||||
|
Normal startup procedure involves the wakeup phase `Init` followed by `Ready`. Depending on the mode of operation requested, this will be followed by one of the `Start…` states with operation mode established resulting in the according `…ing` state.
|
||||||
|
|
||||||
|
The shutdown procedure begins with a transition from the `…ing` state to the according `Stop…` state, followed by `Ready` and finally `Off`.
|
||||||
|
|
||||||
|
See [protocol documentation](extras/Protocol.ods) for details.
|
||||||
|
|
||||||
|
__API:__
|
||||||
|
- `TwizyState state()` -- Query current state
|
||||||
|
- `void enterState(TwizyState newState)` -- Force a state change
|
||||||
|
- **Note**: this is normally not necessary as the VirtualBMS does all state transitions automatically. Valid exceptions are:
|
||||||
|
- You may call `enterState(StopCharge)` to stop a running charge process. Note that `setChargeCurrent(0)` will do so as well.
|
||||||
|
- You may call `enterState(Off)` as an emergency measurement to cause the Twizy to stop. You should use `setError()` before and give the user enough time to react, as this may be dangerous depending on the driving situation.
|
||||||
|
|
||||||
|
__Callbacks:__
|
||||||
|
- Before entering states `Ready`, `Driving`, `Charging` and `Trickle` from any other state, the user callback `CheckState()` will be called.
|
||||||
|
- After any state transition, the user callback `EnterState` will be called.
|
||||||
|
|
||||||
|
|
||||||
|
## CAN interface access
|
||||||
|
|
||||||
|
To hook into the CAN receiver, use `attachProcessCanMsg()` (see above).
|
||||||
|
|
||||||
|
Standard filters will pass IDs `0x423`, `0x597` and `0x599`. Three free CAN filters can be used. The mask is fixed to match the whole ID, so you can filter at most three additional IDs at a time.
|
||||||
|
|
||||||
|
- `void setCanFilter(byte filterNum, unsigned int canId)` -- Set a free ID filter
|
||||||
|
- filterNum: 1 … 3
|
||||||
|
- canId: 11 bit CAN ID i.e. `0x196`
|
||||||
|
|
||||||
|
- `bool sendMsg(INT32U id, INT8U len, INT8U *buf)` -- Send a CAN message
|
||||||
|
- Note: will do three retries if TX buffers are full.
|
||||||
|
- Returns true if message has been sent, false on error.
|
||||||
|
- Retry and error counts are logged every 10 seconds if debug logging is enabled.
|
||||||
|
|
||||||
|
|
||||||
|
## Debug utils
|
||||||
|
|
||||||
|
- `void dumpId(FLASHSTRING *name, int len, byte *buf)` -- Dump a byte buffer in hex numbers
|
||||||
|
- name: must be a PROGMEM string, i.e. `dumpId(F("id123"), ...)`
|
||||||
|
|
||||||
|
- `void debugInfo()` -- Dump VirtualBMS status, include frame buffers if debug level >= 2
|
||||||
|
- this is automatically called every 10 seconds if debug level >= 1
|
||||||
|
|
||||||
|
|
31
HISTORY.md
Normal file
|
@ -0,0 +1,31 @@
|
||||||
|
# History
|
||||||
|
|
||||||
|
|
||||||
|
## Version: 1.0 (2017-06-10)
|
||||||
|
|
||||||
|
- Conversion to Arduino library
|
||||||
|
- Added CAN RX callback bmsProcessCanMsg()
|
||||||
|
- Added twizySetError() and error codes
|
||||||
|
- Using ROM strings to save RAM
|
||||||
|
- Configurable debug output level
|
||||||
|
- Added example Template
|
||||||
|
- Added example SimpleBMS
|
||||||
|
- Added setCanFilter()
|
||||||
|
- Added API documentation
|
||||||
|
- Added hardware documentation
|
||||||
|
- Added SEVCON configuration info
|
||||||
|
|
||||||
|
|
||||||
|
## Version: 0.2 (2017-06-06)
|
||||||
|
|
||||||
|
- 3MW pulse cycle
|
||||||
|
- Separate states for trickle charging
|
||||||
|
- CAN TX retries
|
||||||
|
- Added bmsTicker() callback
|
||||||
|
|
||||||
|
|
||||||
|
## Version: 0.1 (2017-06-04)
|
||||||
|
|
||||||
|
- Initial release
|
||||||
|
|
||||||
|
|
157
LICENSE.md
Normal file
|
@ -0,0 +1,157 @@
|
||||||
|
### GNU LESSER GENERAL PUBLIC LICENSE
|
||||||
|
|
||||||
|
Version 3, 29 June 2007
|
||||||
|
|
||||||
|
Copyright (C) 2007 Free Software Foundation, Inc.
|
||||||
|
<http://fsf.org/>
|
||||||
|
|
||||||
|
Everyone is permitted to copy and distribute verbatim copies of this
|
||||||
|
license document, but changing it is not allowed.
|
||||||
|
|
||||||
|
This version of the GNU Lesser General Public License incorporates the
|
||||||
|
terms and conditions of version 3 of the GNU General Public License,
|
||||||
|
supplemented by the additional permissions listed below.
|
||||||
|
|
||||||
|
#### 0. Additional Definitions.
|
||||||
|
|
||||||
|
As used herein, "this License" refers to version 3 of the GNU Lesser
|
||||||
|
General Public License, and the "GNU GPL" refers to version 3 of the
|
||||||
|
GNU General Public License.
|
||||||
|
|
||||||
|
"The Library" refers to a covered work governed by this License, other
|
||||||
|
than an Application or a Combined Work as defined below.
|
||||||
|
|
||||||
|
An "Application" is any work that makes use of an interface provided
|
||||||
|
by the Library, but which is not otherwise based on the Library.
|
||||||
|
Defining a subclass of a class defined by the Library is deemed a mode
|
||||||
|
of using an interface provided by the Library.
|
||||||
|
|
||||||
|
A "Combined Work" is a work produced by combining or linking an
|
||||||
|
Application with the Library. The particular version of the Library
|
||||||
|
with which the Combined Work was made is also called the "Linked
|
||||||
|
Version".
|
||||||
|
|
||||||
|
The "Minimal Corresponding Source" for a Combined Work means the
|
||||||
|
Corresponding Source for the Combined Work, excluding any source code
|
||||||
|
for portions of the Combined Work that, considered in isolation, are
|
||||||
|
based on the Application, and not on the Linked Version.
|
||||||
|
|
||||||
|
The "Corresponding Application Code" for a Combined Work means the
|
||||||
|
object code and/or source code for the Application, including any data
|
||||||
|
and utility programs needed for reproducing the Combined Work from the
|
||||||
|
Application, but excluding the System Libraries of the Combined Work.
|
||||||
|
|
||||||
|
#### 1. Exception to Section 3 of the GNU GPL.
|
||||||
|
|
||||||
|
You may convey a covered work under sections 3 and 4 of this License
|
||||||
|
without being bound by section 3 of the GNU GPL.
|
||||||
|
|
||||||
|
#### 2. Conveying Modified Versions.
|
||||||
|
|
||||||
|
If you modify a copy of the Library, and, in your modifications, a
|
||||||
|
facility refers to a function or data to be supplied by an Application
|
||||||
|
that uses the facility (other than as an argument passed when the
|
||||||
|
facility is invoked), then you may convey a copy of the modified
|
||||||
|
version:
|
||||||
|
|
||||||
|
- a) under this License, provided that you make a good faith effort
|
||||||
|
to ensure that, in the event an Application does not supply the
|
||||||
|
function or data, the facility still operates, and performs
|
||||||
|
whatever part of its purpose remains meaningful, or
|
||||||
|
- b) under the GNU GPL, with none of the additional permissions of
|
||||||
|
this License applicable to that copy.
|
||||||
|
|
||||||
|
#### 3. Object Code Incorporating Material from Library Header Files.
|
||||||
|
|
||||||
|
The object code form of an Application may incorporate material from a
|
||||||
|
header file that is part of the Library. You may convey such object
|
||||||
|
code under terms of your choice, provided that, if the incorporated
|
||||||
|
material is not limited to numerical parameters, data structure
|
||||||
|
layouts and accessors, or small macros, inline functions and templates
|
||||||
|
(ten or fewer lines in length), you do both of the following:
|
||||||
|
|
||||||
|
- a) Give prominent notice with each copy of the object code that
|
||||||
|
the Library is used in it and that the Library and its use are
|
||||||
|
covered by this License.
|
||||||
|
- b) Accompany the object code with a copy of the GNU GPL and this
|
||||||
|
license document.
|
||||||
|
|
||||||
|
#### 4. Combined Works.
|
||||||
|
|
||||||
|
You may convey a Combined Work under terms of your choice that, taken
|
||||||
|
together, effectively do not restrict modification of the portions of
|
||||||
|
the Library contained in the Combined Work and reverse engineering for
|
||||||
|
debugging such modifications, if you also do each of the following:
|
||||||
|
|
||||||
|
- a) Give prominent notice with each copy of the Combined Work that
|
||||||
|
the Library is used in it and that the Library and its use are
|
||||||
|
covered by this License.
|
||||||
|
- b) Accompany the Combined Work with a copy of the GNU GPL and this
|
||||||
|
license document.
|
||||||
|
- c) For a Combined Work that displays copyright notices during
|
||||||
|
execution, include the copyright notice for the Library among
|
||||||
|
these notices, as well as a reference directing the user to the
|
||||||
|
copies of the GNU GPL and this license document.
|
||||||
|
- d) Do one of the following:
|
||||||
|
- 0) Convey the Minimal Corresponding Source under the terms of
|
||||||
|
this License, and the Corresponding Application Code in a form
|
||||||
|
suitable for, and under terms that permit, the user to
|
||||||
|
recombine or relink the Application with a modified version of
|
||||||
|
the Linked Version to produce a modified Combined Work, in the
|
||||||
|
manner specified by section 6 of the GNU GPL for conveying
|
||||||
|
Corresponding Source.
|
||||||
|
- 1) Use a suitable shared library mechanism for linking with
|
||||||
|
the Library. A suitable mechanism is one that (a) uses at run
|
||||||
|
time a copy of the Library already present on the user's
|
||||||
|
computer system, and (b) will operate properly with a modified
|
||||||
|
version of the Library that is interface-compatible with the
|
||||||
|
Linked Version.
|
||||||
|
- e) Provide Installation Information, but only if you would
|
||||||
|
otherwise be required to provide such information under section 6
|
||||||
|
of the GNU GPL, and only to the extent that such information is
|
||||||
|
necessary to install and execute a modified version of the
|
||||||
|
Combined Work produced by recombining or relinking the Application
|
||||||
|
with a modified version of the Linked Version. (If you use option
|
||||||
|
4d0, the Installation Information must accompany the Minimal
|
||||||
|
Corresponding Source and Corresponding Application Code. If you
|
||||||
|
use option 4d1, you must provide the Installation Information in
|
||||||
|
the manner specified by section 6 of the GNU GPL for conveying
|
||||||
|
Corresponding Source.)
|
||||||
|
|
||||||
|
#### 5. Combined Libraries.
|
||||||
|
|
||||||
|
You may place library facilities that are a work based on the Library
|
||||||
|
side by side in a single library together with other library
|
||||||
|
facilities that are not Applications and are not covered by this
|
||||||
|
License, and convey such a combined library under terms of your
|
||||||
|
choice, if you do both of the following:
|
||||||
|
|
||||||
|
- a) Accompany the combined library with a copy of the same work
|
||||||
|
based on the Library, uncombined with any other library
|
||||||
|
facilities, conveyed under the terms of this License.
|
||||||
|
- b) Give prominent notice with the combined library that part of it
|
||||||
|
is a work based on the Library, and explaining where to find the
|
||||||
|
accompanying uncombined form of the same work.
|
||||||
|
|
||||||
|
#### 6. Revised Versions of the GNU Lesser General Public License.
|
||||||
|
|
||||||
|
The Free Software Foundation may publish revised and/or new versions
|
||||||
|
of the GNU Lesser General Public License from time to time. Such new
|
||||||
|
versions will be similar in spirit to the present version, but may
|
||||||
|
differ in detail to address new problems or concerns.
|
||||||
|
|
||||||
|
Each version is given a distinguishing version number. If the Library
|
||||||
|
as you received it specifies that a certain numbered version of the
|
||||||
|
GNU Lesser General Public License "or any later version" applies to
|
||||||
|
it, you have the option of following the terms and conditions either
|
||||||
|
of that published version or of any later version published by the
|
||||||
|
Free Software Foundation. If the Library as you received it does not
|
||||||
|
specify a version number of the GNU Lesser General Public License, you
|
||||||
|
may choose any version of the GNU Lesser General Public License ever
|
||||||
|
published by the Free Software Foundation.
|
||||||
|
|
||||||
|
If the Library as you received it specifies that a proxy can decide
|
||||||
|
whether future versions of the GNU Lesser General Public License shall
|
||||||
|
apply, that proxy's public statement of acceptance of any version is
|
||||||
|
permanent authorization for you to choose that version for the
|
||||||
|
Library.
|
81
README.md
Normal file
|
@ -0,0 +1,81 @@
|
||||||
|
# Twizy Virtual BMS
|
||||||
|
|
||||||
|
This is an Arduino library providing an emulation of the CAN communication protocol of the BMS (battery management system) on a Renault Twizy.
|
||||||
|
|
||||||
|
The library provides an API to control power limits and charge current, so a wide range of batteries can be used. Even lead-acid is an option.
|
||||||
|
|
||||||
|
In the most simple case this can be used without any customization. The provided "SimpleBMS" example shows how to derive a very basic battery monitoring by using the Arduino analog ports to monitor the battery pack voltage and temperature.
|
||||||
|
|
||||||
|
If you'd like to contribute a specific BMS adaptation, please fork and add your code in the examples folder.
|
||||||
|
|
||||||
|
|
||||||
|
## Installation
|
||||||
|
|
||||||
|
To download, click the DOWNLOADS button in the top right corner, download the ZIP file. Start the Arduino IDE, select menu Sketch → Include Library → Add .ZIP library, select the ZIP file and click OK. Try out the examples included.
|
||||||
|
|
||||||
|
You will also need these libraries:
|
||||||
|
- [MCP_CAN_lib by Cory Fowler](https://github.com/coryjfowler/MCP_CAN_lib)
|
||||||
|
- [TimerOne by Paul Stoffregen](https://github.com/PaulStoffregen/TimerOne)
|
||||||
|
|
||||||
|
To get the smallest possible ROM & RAM footprint, set `TWIZY_DEBUG_LEVEL` to 0 and `DEBUG_MODE` of the MCP_CAN library to 0. This reduces the core memory usage of the VirtualBMS library to (currently) 7782 bytes ROM and 403 bytes RAM.
|
||||||
|
|
||||||
|
|
||||||
|
## Hardware requirements
|
||||||
|
|
||||||
|
- **Battery**: you will need battery cells capable of producing enough voltage and current for the Twizy. You don't need to exactly match the original voltage and power range. The SEVCON G48 series can operate with input voltages from 19.3 to 69.6 V. The Twizy SEVCON is by default configured for a range of 39 to 65 V, but that can be modified (see [SEVCON configuration](extras/SEVCON-Configuration.md)). In standard configuration, the Twizy will draw up to ~330 A or 16 kW from the battery, and recuperate at up to ~70 A or 3.5 kW. If your battery cannot cope with this, you can either use the Virtual BMS to lower the limits or modify the SEVCON configuration.
|
||||||
|
|
||||||
|
Pascal is using Nissan Leaf cells, which offer a very good combination of capacity, availability and price. Blazej is using cheap 120 Ah lead acid batteries (price ~400 Euro for a complete set). Klaus will use chinese prismatic cells adding up to ~12 kWh.
|
||||||
|
|
||||||
|
**Note**: Klaus offers to organize a bulk order of high capacity prismatic cells priced at ~230 Euro/kWh. For details please contact him at <klauszinser@posteo.eu>.
|
||||||
|
|
||||||
|
- **BMS**: using a BMS is optional for lead acid batteries but _strongly recommended_ for lithium based batteries. You may pick any BMS, but you should focus on those that can be connected to the Arduino to query the battery state. Our recommendation is picking a good BMS capable of early balancing, monitoring the coulomb (Ah) consumption and calculating the real SOC.
|
||||||
|
|
||||||
|
**Note**: Pascal is developing a **fully integrated BMS solution** supporting various cell & chemistry configurations and containing the complete Twizy interface. The BMS should be available by the end of 2017. Pricing is expected to be around 350 Euro. Using this BMS will both simplify custom battery integration and reduce points of failure. You won't need an Arduino when using this BMS. For details please contact him at <pascal@ripp.li>.
|
||||||
|
|
||||||
|
- **Arduino**: to run the Twizy Virtual BMS you will need some Arduino and some MCP CAN interface. A wide range of hardware options is available. The code perfectly fits into an Arduino Nano leaving enough memory to implement quite complex custom logics. You should pick an MCP 2515 SPI CAN module with at least 16 MHz clock rate. IRQ connection is optional.
|
||||||
|
|
||||||
|
**Note**: Michael Balzer offers to customize the Virtual BMS for individual applications and BMS integration. For details please contact him at <dexter@dexters-web.de>.
|
||||||
|
|
||||||
|
- **Connection**: see the [part list](extras/Twizy-Battery-Part-List.md) for relais and connectors needed.
|
||||||
|
|
||||||
|
- **Battery case**: you can use the original Twizy battery case, available as a replacement part from Renault (see part list).
|
||||||
|
|
||||||
|
**Note**: Lutz Schäfer offers to build individual custom battery cases offering more space. For details please contact him at <aquillo@t-online.de>.
|
||||||
|
|
||||||
|
|
||||||
|
## Authors
|
||||||
|
|
||||||
|
This library has been created and is maintained by Michael Balzer (https://dexters-web.de/).
|
||||||
|
|
||||||
|
The CAN & hardware protocol decoding and reengineering has been done by a joint effort of (in reverse alphabetical order):
|
||||||
|
|
||||||
|
- Lutz Schäfer <aquillo@t-online.de> -- Hardware development
|
||||||
|
- Pascal Ripp <pascal@ripp.li> -- Hardware protocol decoding & implementation
|
||||||
|
- Bernd Eickhoff <b.eickhoff@gmx.de> -- CAN logging & testing
|
||||||
|
- Michael Balzer <dexter@dexters-web.de> -- CAN protocol decoding & implementation
|
||||||
|
|
||||||
|
Special thanks to Klaus Zinser <klauszinser@posteo.eu> for support and to Blazej Blaszczyk <blazej.blaszczyk@pascal-engineering.com> for prototype implementation and testing!
|
||||||
|
|
||||||
|
|
||||||
|
## Documentation
|
||||||
|
|
||||||
|
- [API reference](API.md)
|
||||||
|
- [History](HISTORY.md)
|
||||||
|
|
||||||
|
- [Twizy CAN object dictionary](https://docs.google.com/spreadsheets/d/1gOrG9rnGR9YuMGakAbl4s97a6irHF6UNFV1TS5Ll7MY)
|
||||||
|
- [Twizy BMS protocol](extras/Protocol.ods)
|
||||||
|
|
||||||
|
- [Battery connection scheme](extras/Twizy-BMS-wiring-scheme.pdf)
|
||||||
|
- [Battery connection part list](extras/Twizy-Battery-Part-List.md)
|
||||||
|
|
||||||
|
|
||||||
|
## License
|
||||||
|
|
||||||
|
This library is free software; you can redistribute it and/or modify it under the terms of the [GNU Lesser General Public License](https://www.gnu.org/licenses/lgpl.html) as published by the Free Software Foundation; either version 3 of the License, or (at your option) any later version.
|
||||||
|
|
||||||
|
This library 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 this library; if not, write to the Free Software Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110- 1301 USA
|
||||||
|
|
||||||
|
|
||||||
|
**Have fun!**
|
222
examples/SimpleBMS/SimpleBMS.ino
Normal file
|
@ -0,0 +1,222 @@
|
||||||
|
/**
|
||||||
|
* ==========================================================================
|
||||||
|
* Twizy Virtual BMS Example: SimpleBMS
|
||||||
|
* ==========================================================================
|
||||||
|
*
|
||||||
|
* - Derive SOC and power control from pack voltage measured using a
|
||||||
|
* simple voltage divider connected to an analog port.
|
||||||
|
* - Measure pack temperature using a simple temperature sensor (LM35D)
|
||||||
|
* and issue temperature and STOP warnings accordingly.
|
||||||
|
*
|
||||||
|
* Author: Michael Balzer <dexter@dexters-web.de>
|
||||||
|
*
|
||||||
|
* Libraries used:
|
||||||
|
* - TwizyVirtualBMS: https://github.com/dexterbg/Twizy-Virtual-BMS
|
||||||
|
* - MCP_CAN: https://github.com/coryjfowler/MCP_CAN_lib
|
||||||
|
* - TimerOne: https://github.com/PaulStoffregen/TimerOne
|
||||||
|
*
|
||||||
|
* Licenses:
|
||||||
|
* This is free software under GNU Lesser General Public License (LGPL)
|
||||||
|
* https://www.gnu.org/licenses/lgpl.html
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
|
||||||
|
#include "TwizyVirtualBMS_config.h"
|
||||||
|
#include "TwizyVirtualBMS.h"
|
||||||
|
|
||||||
|
TwizyVirtualBMS twizy;
|
||||||
|
|
||||||
|
|
||||||
|
// -----------------------------------------------------
|
||||||
|
// Configuration
|
||||||
|
//
|
||||||
|
|
||||||
|
// Maximum driving & recuperation power limits to use [W]:
|
||||||
|
#define MAX_DRIVE_POWER 18000
|
||||||
|
#define MAX_RECUP_POWER 8000
|
||||||
|
|
||||||
|
// Maximum charge current to use [A]:
|
||||||
|
#define MAX_CHARGE_CURRENT 35
|
||||||
|
|
||||||
|
// Voltage range 0…100% for driving:
|
||||||
|
#define VMIN_DRV 42.0
|
||||||
|
#define VMAX_DRV 52.0
|
||||||
|
|
||||||
|
// Voltage range 0…100% for charging:
|
||||||
|
#define VMIN_CHG 42.0
|
||||||
|
#define VMAX_CHG 57.6
|
||||||
|
|
||||||
|
// Voltage analog input:
|
||||||
|
// i.e. voltage divider scaling 60V → 4.5V
|
||||||
|
// (you may need to add some tolerance correction factor)
|
||||||
|
#define PORT_VOLT A0
|
||||||
|
#define SCALE_VOLT (60.0 / 4.5 * 5.0)
|
||||||
|
|
||||||
|
// SOC smoothing samples:
|
||||||
|
#define SMOOTH_SOC_DOWN 30 // slow adaption to lower voltage
|
||||||
|
#define SMOOTH_SOC_UP 5 // fast adaption to higher voltage
|
||||||
|
|
||||||
|
// Temperature analog input:
|
||||||
|
// i.e. LM35D: 2…100 °C → 0…1.0 V (10 mV/°C)
|
||||||
|
#define PORT_TEMP A1
|
||||||
|
#define BASE_TEMP 2.0
|
||||||
|
#define SCALE_TEMP (100.0 / 1.0 * 5.0)
|
||||||
|
|
||||||
|
// Temperature smoothing samples:
|
||||||
|
#define SMOOTH_TEMP 10
|
||||||
|
|
||||||
|
|
||||||
|
// -----------------------------------------------------
|
||||||
|
// Status
|
||||||
|
//
|
||||||
|
|
||||||
|
float temp = 20.0;
|
||||||
|
float soc = 90.0; // Note: needs to be below 100 to be able to start charging
|
||||||
|
|
||||||
|
|
||||||
|
// --------------------------------------------------------------------------
|
||||||
|
// Callback: handle state transition for BMS
|
||||||
|
// - called by twizyEnterState() after Twizy handling
|
||||||
|
// Note: avoid complex operations, this needs to be fast.
|
||||||
|
//
|
||||||
|
void bmsEnterState(TwizyState currentState, TwizyState newState) {
|
||||||
|
|
||||||
|
// The charger will not start charging at SOC=100%, so lower a too
|
||||||
|
// high SOC on wakeup to enable topping-off charges:
|
||||||
|
if (newState == Init) {
|
||||||
|
if (soc > 99) {
|
||||||
|
soc -= 1;
|
||||||
|
twizy.setSOC(soc);
|
||||||
|
twizy.setChargeCurrent(5);
|
||||||
|
Serial.print(F("bmsEnterState: soc lowered to "));
|
||||||
|
Serial.println(soc, 2);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
// --------------------------------------------------------------------------
|
||||||
|
// Callback: timer ticker
|
||||||
|
// - called every 10 ms by twizyTicker() after twizy handling
|
||||||
|
// - not called when Twizy is in state Off
|
||||||
|
// - clockCnt cyclic range: 0 .. 2999 = 30 seconds
|
||||||
|
// Note: avoid complex operations, this needs to be fast.
|
||||||
|
//
|
||||||
|
void bmsTicker(unsigned int clockCnt) {
|
||||||
|
|
||||||
|
if (clockCnt % 100 == 0) {
|
||||||
|
// per second:
|
||||||
|
Serial.println(F("\nbmsTicker:"));
|
||||||
|
|
||||||
|
float vpack, newsoc, newtemp;
|
||||||
|
|
||||||
|
// read pack voltage:
|
||||||
|
vpack = analogRead(PORT_VOLT) / 1024.0 * SCALE_VOLT;
|
||||||
|
|
||||||
|
Serial.print(F("- vpack=")); Serial.println(vpack, 2);
|
||||||
|
twizy.setVoltage(vpack, true);
|
||||||
|
|
||||||
|
// derive SOC change from voltage:
|
||||||
|
if (twizy.state() == Charging) {
|
||||||
|
newsoc = (vpack - VMIN_CHG) / (VMAX_CHG - VMIN_CHG) * 100.0;
|
||||||
|
}
|
||||||
|
else {
|
||||||
|
newsoc = (vpack - VMIN_DRV) / (VMAX_DRV - VMIN_DRV) * 100.0;
|
||||||
|
}
|
||||||
|
|
||||||
|
// smooth SOC:
|
||||||
|
if (newsoc < soc) {
|
||||||
|
// slow adaption to lower voltages:
|
||||||
|
soc = (soc * (SMOOTH_SOC_DOWN-1) + newsoc) / SMOOTH_SOC_DOWN;
|
||||||
|
}
|
||||||
|
else {
|
||||||
|
// fast adaption to higher voltages:
|
||||||
|
soc = (soc * (SMOOTH_SOC_UP-1) + newsoc) / SMOOTH_SOC_UP;
|
||||||
|
}
|
||||||
|
|
||||||
|
// sanitize...
|
||||||
|
soc = constrain(soc, 0.0, 100.0);
|
||||||
|
|
||||||
|
Serial.print(F("- soc=")); Serial.println(soc, 2);
|
||||||
|
twizy.setSOC(soc);
|
||||||
|
|
||||||
|
// derive power limits & charge current from SOC:
|
||||||
|
if (soc >= 90.0) {
|
||||||
|
// high SOC: scale down recuperation & charge power
|
||||||
|
int recpwr = (100-soc) / 10.0 * MAX_RECUP_POWER;
|
||||||
|
Serial.print(F("- recpwr=")); Serial.println(recpwr);
|
||||||
|
twizy.setPowerLimits(MAX_DRIVE_POWER, recpwr);
|
||||||
|
// charge automatically stops below 5.0 A, so keep min 5.0 until 100%:
|
||||||
|
float chgcurr = (round(soc*100) == 10000) ? 0.0 : 5.0 + (100-soc) / 10.0 * (MAX_CHARGE_CURRENT-5.0);
|
||||||
|
Serial.print(F("- chgcurr=")); Serial.println(chgcurr);
|
||||||
|
twizy.setChargeCurrent(chgcurr);
|
||||||
|
}
|
||||||
|
else if (soc <= 20.0) {
|
||||||
|
// low SOC: scale down drive power
|
||||||
|
int drvpwr = soc / 20.0 * MAX_DRIVE_POWER;
|
||||||
|
Serial.print(F("- drvpwr=")); Serial.println(drvpwr);
|
||||||
|
twizy.setPowerLimits(drvpwr, MAX_RECUP_POWER);
|
||||||
|
twizy.setChargeCurrent(MAX_CHARGE_CURRENT);
|
||||||
|
}
|
||||||
|
else {
|
||||||
|
// normal SOC: allow max power & current
|
||||||
|
twizy.setPowerLimits(MAX_DRIVE_POWER, MAX_RECUP_POWER);
|
||||||
|
twizy.setChargeCurrent(MAX_CHARGE_CURRENT);
|
||||||
|
}
|
||||||
|
|
||||||
|
// read battery temperature:
|
||||||
|
newtemp = BASE_TEMP + analogRead(PORT_TEMP) / 1024.0 * SCALE_TEMP;
|
||||||
|
|
||||||
|
// smooth:
|
||||||
|
temp = (temp * (SMOOTH_TEMP-1) + newtemp) / SMOOTH_TEMP;
|
||||||
|
|
||||||
|
Serial.print(F("- temp=")); Serial.println(temp);
|
||||||
|
twizy.setTemperature(temp, temp, true);
|
||||||
|
|
||||||
|
// set error status if battery too hot:
|
||||||
|
if (temp > 50) {
|
||||||
|
twizy.setError(TWIZY_SERV_TEMP|TWIZY_SERV_STOP);
|
||||||
|
}
|
||||||
|
else if (temp > 40) {
|
||||||
|
twizy.setError(TWIZY_SERV_TEMP);
|
||||||
|
}
|
||||||
|
else {
|
||||||
|
twizy.setError(TWIZY_OK);
|
||||||
|
}
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
// -----------------------------------------------------
|
||||||
|
// SETUP
|
||||||
|
//
|
||||||
|
|
||||||
|
void setup() {
|
||||||
|
|
||||||
|
Serial.begin(115200);
|
||||||
|
|
||||||
|
twizy.begin();
|
||||||
|
twizy.attachTicker(bmsTicker);
|
||||||
|
twizy.attachEnterState(bmsEnterState);
|
||||||
|
|
||||||
|
twizy.setPowerLimits(MAX_DRIVE_POWER, MAX_RECUP_POWER);
|
||||||
|
twizy.setChargeCurrent(MAX_CHARGE_CURRENT);
|
||||||
|
twizy.setSOH(100);
|
||||||
|
twizy.setSOC(soc);
|
||||||
|
twizy.setTemperature(temp, temp, true);
|
||||||
|
twizy.setVoltage(50.0, true);
|
||||||
|
twizy.setCurrent(0.0);
|
||||||
|
twizy.setError(TWIZY_OK);
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
// -----------------------------------------------------
|
||||||
|
// MAIN LOOP
|
||||||
|
//
|
||||||
|
|
||||||
|
void loop() {
|
||||||
|
twizy.looper();
|
||||||
|
}
|
35
examples/SimpleBMS/TwizyVirtualBMS_config.h
Normal file
|
@ -0,0 +1,35 @@
|
||||||
|
/**
|
||||||
|
* ==========================================================================
|
||||||
|
* Twizy Virtual BMS: Configuration
|
||||||
|
* ==========================================================================
|
||||||
|
*/
|
||||||
|
|
||||||
|
#ifndef _TwizyVirtualBMS_config_h
|
||||||
|
#define _TwizyVirtualBMS_config_h
|
||||||
|
|
||||||
|
// Serial debug output:
|
||||||
|
// Level 0 = none, only output init & error messages
|
||||||
|
// Level 1 = log state transitions & CAN statistics
|
||||||
|
// Level 2 = log CAN frame dumps (10 second interval)
|
||||||
|
#define TWIZY_DEBUG_LEVEL 1
|
||||||
|
|
||||||
|
// Set to 0 to disable CAN transmissions for testing:
|
||||||
|
#define TWIZY_CAN_SEND 1
|
||||||
|
|
||||||
|
// CAN send timing is normally 10 ms (10.000 us).
|
||||||
|
// You may need to lower this if your Arduino is too slow.
|
||||||
|
#define TWIZY_CAN_CLOCK_US 10000
|
||||||
|
|
||||||
|
// Set your MCP clock frequency here:
|
||||||
|
#define TWIZY_CAN_MCP_FREQ MCP_16MHZ
|
||||||
|
|
||||||
|
// Set your SPI CS pin number here:
|
||||||
|
#define TWIZY_CAN_CS_PIN 10
|
||||||
|
|
||||||
|
// If you've connected the CAN module's IRQ pin:
|
||||||
|
//#define TWIZY_CAN_IRQ_PIN 2
|
||||||
|
|
||||||
|
// Set your 3MW control pin here:
|
||||||
|
#define TWIZY_3MW_CONTROL_PIN 3
|
||||||
|
|
||||||
|
#endif // _TwizyVirtualBMS_config_h
|
157
examples/Template/Template.ino
Normal file
|
@ -0,0 +1,157 @@
|
||||||
|
/**
|
||||||
|
* ==========================================================================
|
||||||
|
* Twizy Virtual BMS Example: Template
|
||||||
|
* ==========================================================================
|
||||||
|
*
|
||||||
|
* - You can register some callbacks with the Virtual BMS, this
|
||||||
|
* template contains prototypes for all of them as well as the
|
||||||
|
* basic initialization and integration.
|
||||||
|
*
|
||||||
|
* Note: if you don't need a callback, you don't need to define and attach it.
|
||||||
|
*
|
||||||
|
* Author: Michael Balzer <dexter@dexters-web.de>
|
||||||
|
*
|
||||||
|
* Twizy CAN object dictionary:
|
||||||
|
* https://docs.google.com/spreadsheets/d/1gOrG9rnGR9YuMGakAbl4s97a6irHF6UNFV1TS5Ll7MY/edit#gid=0
|
||||||
|
* (Maintainer: Michael Balzer <dexter@dexters-web.de>)
|
||||||
|
*
|
||||||
|
* Twizy BMS CAN & hardware protocol decoding and reengineering has been done
|
||||||
|
* by a joint effort of (in reverse alphabetical order):
|
||||||
|
* - Lutz Schäfer <aquillo@t-online.de>
|
||||||
|
* - Pascal Ripp <pascal@ripp.li>
|
||||||
|
* - Bernd Eickhoff <b.eickhoff@gmx.de>
|
||||||
|
* - Michael Balzer <dexter@dexters-web.de>
|
||||||
|
*
|
||||||
|
* Libraries used:
|
||||||
|
* - MCP_CAN: https://github.com/coryjfowler/MCP_CAN_lib
|
||||||
|
* - TimerOne: https://github.com/PaulStoffregen/TimerOne
|
||||||
|
*
|
||||||
|
* Licenses:
|
||||||
|
* This is free software and information under the following licenses:
|
||||||
|
* - Source code: GNU Lesser General Public License (LGPL)
|
||||||
|
* https://www.gnu.org/licenses/lgpl.html
|
||||||
|
* - Documentation: GNU Free Documentation License (FDL)
|
||||||
|
* https://www.gnu.org/licenses/fdl.html
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
|
||||||
|
#include "TwizyVirtualBMS_config.h"
|
||||||
|
#include "TwizyVirtualBMS.h"
|
||||||
|
|
||||||
|
TwizyVirtualBMS twizy;
|
||||||
|
|
||||||
|
|
||||||
|
// --------------------------------------------------------------------------
|
||||||
|
// Callback: handle state transition for BMS
|
||||||
|
// - called by twizyEnterState() after Twizy handling
|
||||||
|
// Note: avoid complex operations, this needs to be fast.
|
||||||
|
//
|
||||||
|
void bmsEnterState(TwizyState currentState, TwizyState newState) {
|
||||||
|
|
||||||
|
//
|
||||||
|
// Add your code here
|
||||||
|
//
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
// --------------------------------------------------------------------------
|
||||||
|
// Callback: check if BMS allows state transition
|
||||||
|
// - return true when BMS is ready for newState
|
||||||
|
// - called by twizyTicker() every 10 ms before sending frames
|
||||||
|
// - called for newState: Ready, Charging, Driving
|
||||||
|
// Note: avoid complex operations, this needs to be fast.
|
||||||
|
//
|
||||||
|
bool bmsCheckState(TwizyState currentState, TwizyState newState) {
|
||||||
|
|
||||||
|
//
|
||||||
|
// Add your code here
|
||||||
|
//
|
||||||
|
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
// --------------------------------------------------------------------------
|
||||||
|
// Callback: process received CAN message
|
||||||
|
// - called on reception of a CAN frame that passed the filters
|
||||||
|
// (i.e. normally only IDs 0x423, 0x597 & 0x599)
|
||||||
|
// Note: avoid complex operations, this needs to be fast.
|
||||||
|
//
|
||||||
|
void bmsProcessCanMsg(unsigned long rxId, byte rxLen, byte *rxBuf) {
|
||||||
|
|
||||||
|
//
|
||||||
|
// Add your code here
|
||||||
|
//
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
// --------------------------------------------------------------------------
|
||||||
|
// Callback: timer ticker
|
||||||
|
// - called every 10 ms by twizyTicker() after twizy handling
|
||||||
|
// - not called when Twizy is in state Off
|
||||||
|
// - clockCnt cyclic range: 0 .. 2999 = 30 seconds
|
||||||
|
// Note: avoid complex operations, this needs to be fast.
|
||||||
|
//
|
||||||
|
void bmsTicker(unsigned int clockCnt) {
|
||||||
|
|
||||||
|
//
|
||||||
|
// Add your code here
|
||||||
|
//
|
||||||
|
|
||||||
|
if (clockCnt % 100 == 0) {
|
||||||
|
// per second…
|
||||||
|
}
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
// -----------------------------------------------------
|
||||||
|
// SETUP
|
||||||
|
//
|
||||||
|
|
||||||
|
void setup() {
|
||||||
|
|
||||||
|
Serial.begin(115200);
|
||||||
|
|
||||||
|
// Init TwizyVirtualBMS:
|
||||||
|
twizy.begin();
|
||||||
|
|
||||||
|
// Attach callbacks:
|
||||||
|
twizy.attachEnterState(bmsEnterState);
|
||||||
|
twizy.attachCheckState(bmsCheckState);
|
||||||
|
twizy.attachProcessCanMsg(bmsProcessCanMsg);
|
||||||
|
twizy.attachTicker(bmsTicker);
|
||||||
|
|
||||||
|
// Init data:
|
||||||
|
twizy.setPowerLimits(18000, 8000);
|
||||||
|
twizy.setChargeCurrent(35);
|
||||||
|
twizy.setSOH(100);
|
||||||
|
twizy.setSOC(90);
|
||||||
|
twizy.setTemperature(20, 20, true);
|
||||||
|
twizy.setVoltage(50.0, true);
|
||||||
|
twizy.setCurrent(0.0);
|
||||||
|
twizy.setError(TWIZY_OK);
|
||||||
|
|
||||||
|
//
|
||||||
|
// Add your code here
|
||||||
|
//
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
// -----------------------------------------------------
|
||||||
|
// MAIN LOOP
|
||||||
|
//
|
||||||
|
|
||||||
|
void loop() {
|
||||||
|
|
||||||
|
// TwizyVirtualBMS event handler:
|
||||||
|
twizy.looper();
|
||||||
|
|
||||||
|
//
|
||||||
|
// Add your code here
|
||||||
|
//
|
||||||
|
|
||||||
|
}
|
35
examples/Template/TwizyVirtualBMS_config.h
Normal file
|
@ -0,0 +1,35 @@
|
||||||
|
/**
|
||||||
|
* ==========================================================================
|
||||||
|
* Twizy Virtual BMS: Configuration
|
||||||
|
* ==========================================================================
|
||||||
|
*/
|
||||||
|
|
||||||
|
#ifndef _TwizyVirtualBMS_config_h
|
||||||
|
#define _TwizyVirtualBMS_config_h
|
||||||
|
|
||||||
|
// Serial debug output:
|
||||||
|
// Level 0 = none, only output init & error messages
|
||||||
|
// Level 1 = log state transitions & CAN statistics
|
||||||
|
// Level 2 = log CAN frame dumps (10 second interval)
|
||||||
|
#define TWIZY_DEBUG_LEVEL 1
|
||||||
|
|
||||||
|
// Set to 0 to disable CAN transmissions for testing:
|
||||||
|
#define TWIZY_CAN_SEND 1
|
||||||
|
|
||||||
|
// CAN send timing is normally 10 ms (10.000 us).
|
||||||
|
// You may need to lower this if your Arduino is too slow.
|
||||||
|
#define TWIZY_CAN_CLOCK_US 10000
|
||||||
|
|
||||||
|
// Set your MCP clock frequency here:
|
||||||
|
#define TWIZY_CAN_MCP_FREQ MCP_16MHZ
|
||||||
|
|
||||||
|
// Set your SPI CS pin number here:
|
||||||
|
#define TWIZY_CAN_CS_PIN 10
|
||||||
|
|
||||||
|
// If you've connected the CAN module's IRQ pin:
|
||||||
|
//#define TWIZY_CAN_IRQ_PIN 2
|
||||||
|
|
||||||
|
// Set your 3MW control pin here:
|
||||||
|
#define TWIZY_3MW_CONTROL_PIN 3
|
||||||
|
|
||||||
|
#endif // _TwizyVirtualBMS_config_h
|
BIN
extras/296740718R.jpg
Normal file
After Width: | Height: | Size: 194 KiB |
BIN
extras/CAN-Objektverzeichnis.ods
Normal file
BIN
extras/Leaf-Cells.jpg
Normal file
After Width: | Height: | Size: 179 KiB |
BIN
extras/Protocol.ods
Normal file
BIN
extras/Prototype-Blazej/20170604_163414.jpg
Normal file
After Width: | Height: | Size: 888 KiB |
BIN
extras/Prototype-Blazej/20170604_163556.jpg
Normal file
After Width: | Height: | Size: 924 KiB |
BIN
extras/Prototype-Blazej/DSC_9520.JPG
Normal file
After Width: | Height: | Size: 936 KiB |
BIN
extras/Prototype-Blazej/DSC_9521.JPG
Normal file
After Width: | Height: | Size: 909 KiB |
BIN
extras/Prototype-Blazej/DSC_9522.JPG
Normal file
After Width: | Height: | Size: 913 KiB |
BIN
extras/Prototype-Blazej/DSC_9523.JPG
Normal file
After Width: | Height: | Size: 912 KiB |
BIN
extras/Prototype-Blazej/DSC_9524.JPG
Normal file
After Width: | Height: | Size: 776 KiB |
BIN
extras/Prototype-Blazej/DSC_9525.JPG
Normal file
After Width: | Height: | Size: 835 KiB |
BIN
extras/Prototype-Blazej/DSC_9526.JPG
Normal file
After Width: | Height: | Size: 837 KiB |
BIN
extras/Prototype-Blazej/DSC_9527.JPG
Normal file
After Width: | Height: | Size: 843 KiB |
BIN
extras/Renault-Box-1.jpg
Normal file
After Width: | Height: | Size: 246 KiB |
BIN
extras/Renault-Box-2.jpg
Normal file
After Width: | Height: | Size: 264 KiB |
124
extras/SEVCON-Configuration.md
Normal file
|
@ -0,0 +1,124 @@
|
||||||
|
# SEVCON Configuration
|
||||||
|
|
||||||
|
You do not need to change the SEVCON configuration to use a custom battery if the custom battery delivers voltage and power matching the standard operating range and your SEVCON battery protection has not been disabled.
|
||||||
|
|
||||||
|
- The SEVCON G48 series can operate with input voltages from 19.3 to 69.6 V. The Twizy SEVCON is by default configured for a range of 39 to 65 V.
|
||||||
|
- In standard configuration, the Twizy will draw up to ~330 A or 16 kW from the battery, and recuperate at up to ~70 A or 3.5 kW.
|
||||||
|
|
||||||
|
If your battery cannot cope with these limits, you can either use the Virtual BMS to lower the limits or modify the SEVCON configuration.
|
||||||
|
|
||||||
|
If you need to set the limits regularly below the standards, consider tuning the Twizy down. Triggering the power limiter will result in a sudden power cutback followed by slowly raising power levels until the limit is reached again. This continues over and over leading to an inconvenient pumping effect.
|
||||||
|
|
||||||
|
**Note**: SEVCON write access has been limited by Renault on Twizys (SEVCONs) delivered after June 2016. The write protection only applies to power and driving profile tuning registers, most other parameters can still be changed, including voltage limits.
|
||||||
|
|
||||||
|
|
||||||
|
## Tools
|
||||||
|
|
||||||
|
You can configure the SEVCON using…
|
||||||
|
|
||||||
|
1. [Official SEVCON tools](http://www.sevcon.com/products/low-voltage-controllers/gen4/)
|
||||||
|
2. [OVMS](https://github.com/openvehicles/Open-Vehicle-Monitoring-System)
|
||||||
|
3. [Twizy-Cfg for Arduino](https://github.com/bgdexter/Twizy-Cfg)
|
||||||
|
4. Generic CANopen editor
|
||||||
|
|
||||||
|
The syntax for reading/writing the SEVCON registers slightly varies depending on the software used, but the registers and values are the same.
|
||||||
|
|
||||||
|
| Function | Twizy-Cfg | OVMS |
|
||||||
|
| --- | --- | --- |
|
||||||
|
| Enter pre-op mode | `p` | `cfg pre` |
|
||||||
|
| Enter op mode | `o` | `cfg op` |
|
||||||
|
| Read register | `r <id> <sub>` | `cfg read <id> <sub>` |
|
||||||
|
| Write register | `w <id> <sub> <val>` | `cfg write <id> <sub> <value>` |
|
||||||
|
|
||||||
|
The following command examples use the Twizy-Cfg syntax.
|
||||||
|
|
||||||
|
**Note**: negative values currently need to be read and written with value offset 65536 ("complementary"), i.e. -1 = 65535.
|
||||||
|
|
||||||
|
|
||||||
|
## Battery voltage limits
|
||||||
|
|
||||||
|
| Register | Description | Default | Scaling | …= |
|
||||||
|
| --- | --- | --- | --- | --- |
|
||||||
|
| `2c01 01` | Over voltage start cutback | 992 | 1/16 | 62 V |
|
||||||
|
| `2c01 02` | Over voltage limit | 1040 | 1/16 | 65 V |
|
||||||
|
| `2c02 01` | Under voltage start cutback | 656 | 1/16 | 41 V |
|
||||||
|
| `2c02 02` | Under voltage limit | 624 | 1/16 | 39 V |
|
||||||
|
| `2c03 00` | Protection delay | 80 | 1/10 | 8 s |
|
||||||
|
|
||||||
|
**Example**: to allow voltages down to 35 V, issue…
|
||||||
|
|
||||||
|
1. `w 2c02 01 592`
|
||||||
|
2. `w 2c02 02 560`
|
||||||
|
|
||||||
|
**Keep in mind** that the SEVCON derives current levels from allowed power levels (unless configured otherwise, see below). A lower voltage will result in higher currents, take care to lower the power limits as necessary using the `setPowerLimits()` API call when your voltage drops.
|
||||||
|
|
||||||
|
|
||||||
|
## Battery current & power limits
|
||||||
|
|
||||||
|
**Note**: these only apply to the driving state, the charger current can be controlled by `setChargeCurrent()` regardless of the SEVCON configuration.
|
||||||
|
|
||||||
|
| Register | Description | Default | Scaling | …= |
|
||||||
|
| --- | --- | --- | --- | --- |
|
||||||
|
| `2870 01` | Battery current limit source | 4 | see below | BMS |
|
||||||
|
| `2870 02` | Max discharge current | 500 | 1 | 500 A |
|
||||||
|
| `2870 03` | Max recharge current | 65536 | -1 | 200 A |
|
||||||
|
| `2870 04` | Profile 1 level | 0 | 1 | 0% |
|
||||||
|
| `2870 05` | Profile 2 level | 0 | 1 | 0% |
|
||||||
|
| `2870 06` | _Max discharge power (derived)_ | i.e. 4608 | 1/256 | 18 kW |
|
||||||
|
| `2870 06` | _Max recharge power (derived)_ | i.e. 64896 | -1/256 | 2.5 kW |
|
||||||
|
| `4623 01` | _Calculated recharge current limit (power/voltage)_ | 65493 | -1 | 43 A |
|
||||||
|
| `4623 02` | _Calculated discharge current limit (power/voltage)_ | 314 | 1 | 314 A |
|
||||||
|
| `4623 03` | Battery current cutback range | 15 | 1 | 15 A |
|
||||||
|
| `3813 30` | Battery current recovery speed | 100 | 100/256 | 39.0625 %/s |
|
||||||
|
| `3813 30` | Battery current cutback speed | 800 | 1 | 312.5 %/s |
|
||||||
|
|
||||||
|
**Battery current limit source**:
|
||||||
|
- `4`: BMS controls power limits through `setPowerLimits()`, current levels calculated from power levels
|
||||||
|
- `3`: Use max currents scaled down by profile level (`setPowerLimits()` disabled)
|
||||||
|
- `1`: Use max currents (`setPowerLimits()` disabled)
|
||||||
|
- `0`: Limiter off (`setPowerLimits()` disabled)
|
||||||
|
|
||||||
|
These registers need pre-operational mode to allow writes.
|
||||||
|
|
||||||
|
**Example**: to disable `setPowerLimits()` and set a fixed maximum of 250 A for discharge (driving) and 50 A for recharging (recuperation), issue…
|
||||||
|
|
||||||
|
1. `p`
|
||||||
|
2. `w 2870 01 1`
|
||||||
|
3. `w 2870 02 250`
|
||||||
|
4. `w 2870 03 65486`
|
||||||
|
5. `o`
|
||||||
|
|
||||||
|
|
||||||
|
## SOC based power cutbacks
|
||||||
|
|
||||||
|
| Register | Description | Default | Scaling | …= |
|
||||||
|
| --- | --- | --- | --- | --- |
|
||||||
|
| `3813 11` | Drive cutback map: SOC 1 | 0 | 1/50 | 0 % SOC |
|
||||||
|
| `3813 12` | … cutback 1 | 750 | 1/50 | 15 % power |
|
||||||
|
| `3813 13` | … SOC 2 | 750 | 1/50 | 15 % SOC |
|
||||||
|
| `3813 14` | … cutback 2 | 5000 | 1/50 | 100 % power |
|
||||||
|
| `3813 15` | Brake cutback map: SOC 1 | 0 | 1/50 | 0 % SOC |
|
||||||
|
| `3813 16` | … cutback 1 | 5000 | 1/50 | 100 % power |
|
||||||
|
| `3813 17` | … SOC 2 | 500 | 1/50 | 10 % SOC |
|
||||||
|
| `3813 18` | … cutback 2 | 5000 | 1/50 | 100 % power |
|
||||||
|
|
||||||
|
The SEVCON applies these linear cutbacks based on SOC additionally to the BMS power limits allowing for a smooth cutback slope. Default is to cutback drive power below 15% SOC, and leave brake power at BMS control.
|
||||||
|
|
||||||
|
These registers need pre-operational mode to allow writes.
|
||||||
|
|
||||||
|
**Example**: configure full brake power cutback from 90% to 100% SOC:
|
||||||
|
|
||||||
|
1. `p`
|
||||||
|
2. `w 3813 15 4500`
|
||||||
|
3. `w 3813 17 5000`
|
||||||
|
4. `w 3813 18 0`
|
||||||
|
5. `o`
|
||||||
|
|
||||||
|
|
||||||
|
## Other configuration options
|
||||||
|
|
||||||
|
Read the SEVCON Gen4 manual for some basic description. The full register set is documented in the SEVCON master dictionary, which is ©SEVCON. It's contained in the SEVCON DVT package.
|
||||||
|
|
||||||
|
Most registers of interest for normal tuning have been documented in the [OVMS Twizy SDO list](https://github.com/openvehicles/Open-Vehicle-Monitoring-System/raw/master/docs/Renault-Twizy/Twizy-SDO-List.ods).
|
||||||
|
|
||||||
|
**Have fun!**
|
BIN
extras/Twizy-BMS-wiring-scheme.pdf
Normal file
51
extras/Twizy-Battery-Part-List.md
Normal file
|
@ -0,0 +1,51 @@
|
||||||
|
# Twizy Battery Part List
|
||||||
|
|
||||||
|
For explosion drawings and OE part numbers, see…
|
||||||
|
|
||||||
|
1. [partsouq.com](https://partsouq.com/en/catalog/genuine/vehicle?c=Renault&ssd=%24HAxLcgIFBQEDBA5SXAdCUkZQXEd0e1pcB19WWkBRXFBTOQoWRnN5BAsCDXEVOjkCamFBSEtkVSECMBNNV0dyAw%24&vid=1409&cid=2043523126&q=)
|
||||||
|
2. [catcar.info](https://www.catcar.info/renault/?lang=en&l=c3Q9PTUwfHxzdHM9PXsiMTAiOiJNb2RlbCIsIjIwIjoiVHdpenkiLCIzMCI6Ik1BTUEiLCI0MCI6Ik1hbnVhbCIsIjUwIjoiMTkgQ29vbGluZyBzeXN0ZW0gLSBSZXNlcnZvaXJzIC0gRXhoYXVzdCBzeXN0ZW0gLSBFbmdpbmUgbW91bnRpbmcgXC8gVHJhY3Rpb24gYmF0dGVyeSJ9fHxub3Bycz09MTQwOXx8YnJhbmQ9PVJlbmF1bHR8fG5vcHI9PTE0MDl8fHR5cGU9PU1BTUF8fGNhdF9pZD09TXx8aW1nPT0wMTA0MDI2NHx8Z3JwX2lkPT0xOXx8c3ViR3JwX2lkPT0xOUd8fGNybnROb3ByPT0xNDA5fHxyZWZhY2Nlcz09TjE5OTAwMA%3D%3D)
|
||||||
|
|
||||||
|
|
||||||
|
## Connectors and relais
|
||||||
|
|
||||||
|
| # | Part | OE number | ~Price |
|
||||||
|
| --- | --- | --- | --- |
|
||||||
|
| 1x | Fusible Principal Fltg Ent Chr | 296539341R | 4.41 € |
|
||||||
|
| 1x | Fusible Chargeur Fltg Ent Chrj | 296539051R | 1.67 € |
|
||||||
|
| 1x | Fusible Apres Contact Fltg Ent | 296535672R | 1.30 € |
|
||||||
|
| 1x | Relais Principal Boitier Cnx P | 294B16331R | 56.63 € |
|
||||||
|
| 1x | Platine Fusible | 296713282R | 10.48 € |
|
||||||
|
| 1x | Platine Fusible | 296712452R | 7.96 € |
|
||||||
|
| 1x | Embase Connecteur Ba | 296746418R | 30.67 € |
|
||||||
|
| 1x | Embase Connecteur Batterie Tra | 296743399R | 52.22 € |
|
||||||
|
| 1x | Embase Connecteur | 296740718R | 86.30 € |
|
||||||
|
| 1x | Relais Precharge Boitier Cnx P | 294B20431R | 21.19 € |
|
||||||
|
| 1x | Relais Chargeur Fltg Ent Chrjr | 296156226R | 39.96 € |
|
||||||
|
|
||||||
|
Total: ~ 310 €
|
||||||
|
|
||||||
|
Parts may of course be replaced by functionally compatible ones, for example use a fork lift relais for the main power relais. Blazej Blaszczyk has built his prototype without using Renault parts. For details please contact him at <blazej.blaszczyk@pascal-engineering.com>.
|
||||||
|
|
||||||
|
- The `296740718R` signal connector is Yazaki part no. 7282-8854-30 [male](http://connectors-catalog.sys.yzk.co.jp/yazaki-web/servlet/SubServlet_e?forward=7282-8854-30&plist=detail&select=XX) [female](http://connectors-catalog.sys.yzk.co.jp/yazaki-web/servlet/SubServlet_e?forward=7283-8854-30&plist=detail&select=XX).
|
||||||
|
- The `296743399R` main power connector is DELPHI part no. [F473110](http://ecat.delphi.com/feature?search=F473110), with contact terminals (F176600)[ecat.delphi.com/feature?search=F176600].
|
||||||
|
- The `296746418R` charger power connector is DELPHI part no. [F873110](ecat.delphi.com/feature?search=F873110), with contact terminals [15516298](http://ecat.delphi.com/feature?search=15516298).
|
||||||
|
|
||||||
|
|
||||||
|
## Casing
|
||||||
|
|
||||||
|
| # | Part | OE number | ~Price |
|
||||||
|
| --- | --- | --- | --- |
|
||||||
|
| 1x | CARTER SUP BATTERI | 295F00162R | 129 € |
|
||||||
|
| 1x | CARTER INF BATTERI | 295F19016R | 216 € |
|
||||||
|
| 1x | JOINT ETC CARTER B | 295G32560R | 46 € |
|
||||||
|
|
||||||
|
Total: ~ 390 €
|
||||||
|
|
||||||
|
**Note**: Lutz Schäfer offers to build individual custom battery cases offering more space. For details please contact him at <aquillo@t-online.de>.
|
||||||
|
|
||||||
|
__Sizes__:
|
||||||
|
- Standard Renault Box: 724 x 368 x 208 mm
|
||||||
|
- Lutz-Box Box V1 (without car modification): 745 x 400 x 245 mm
|
||||||
|
- Lutz-Box V2 (car modification necessary): 745 x 480 x 245 mm
|
||||||
|
|
||||||
|
|
BIN
extras/Yazaki-7282-8854-30.jpg
Normal file
After Width: | Height: | Size: 198 KiB |
73
keywords.txt
Normal file
|
@ -0,0 +1,73 @@
|
||||||
|
###########################################
|
||||||
|
# Syntax Coloring Map
|
||||||
|
###########################################
|
||||||
|
|
||||||
|
###########################################
|
||||||
|
# Datatypes (KEYWORD1)
|
||||||
|
###########################################
|
||||||
|
|
||||||
|
TwizyState KEYWORD1
|
||||||
|
TwizyVirtualBMS KEYWORD1
|
||||||
|
twizy KEYWORD1
|
||||||
|
Twizy KEYWORD1
|
||||||
|
|
||||||
|
###########################################
|
||||||
|
# Methods and Functions (KEYWORD2)
|
||||||
|
###########################################
|
||||||
|
|
||||||
|
setup KEYWORD2
|
||||||
|
looper KEYWORD2
|
||||||
|
|
||||||
|
setPowerLimits KEYWORD2
|
||||||
|
setChargeCurrent KEYWORD2
|
||||||
|
setSOH KEYWORD2
|
||||||
|
setSOC KEYWORD2
|
||||||
|
setTemperature KEYWORD2
|
||||||
|
setVoltage KEYWORD2
|
||||||
|
setCurrent KEYWORD2
|
||||||
|
setError KEYWORD2
|
||||||
|
|
||||||
|
attachEnterState KEYWORD2
|
||||||
|
attachCheckState KEYWORD2
|
||||||
|
attachProcessCanMsg KEYWORD2
|
||||||
|
attachTicker KEYWORD2
|
||||||
|
|
||||||
|
sendMsg KEYWORD2
|
||||||
|
|
||||||
|
state KEYWORD2
|
||||||
|
enterState KEYWORD2
|
||||||
|
|
||||||
|
dumpId KEYWORD2
|
||||||
|
debugInfo KEYWORD2
|
||||||
|
|
||||||
|
######################################
|
||||||
|
# Constants (LITERAL1)
|
||||||
|
#######################################
|
||||||
|
|
||||||
|
TWIZY_DEBUG_LEVEL LITERAL1
|
||||||
|
TWIZY_CAN_SEND LITERAL1
|
||||||
|
TWIZY_CAN_CLOCK_US LITERAL1
|
||||||
|
TWIZY_CAN_MCP_FREQ LITERAL1
|
||||||
|
TWIZY_CAN_CS_PIN LITERAL1
|
||||||
|
TWIZY_CAN_IRQ_PIN LITERAL1
|
||||||
|
TWIZY_3MW_CONTROL_PIN LITERAL1
|
||||||
|
|
||||||
|
Off LITERAL1
|
||||||
|
Init LITERAL1
|
||||||
|
Ready LITERAL1
|
||||||
|
StartDrive LITERAL1
|
||||||
|
Driving LITERAL1
|
||||||
|
StopDrive LITERAL1
|
||||||
|
StartCharge LITERAL1
|
||||||
|
Charging LITERAL1
|
||||||
|
StopCharge LITERAL1
|
||||||
|
StartTrickle LITERAL1
|
||||||
|
Trickle LITERAL1
|
||||||
|
StopTrickle LITERAL1
|
||||||
|
|
||||||
|
TWIZY_OK LITERAL1
|
||||||
|
TWIZY_SERV LITERAL1
|
||||||
|
TWIZY_SERV_12V LITERAL1
|
||||||
|
TWIZY_SERV_BATT LITERAL1
|
||||||
|
TWIZY_SERV_TEMP LITERAL1
|
||||||
|
TWIZY_SERV_STOP LITERAL1
|
9
library.properties
Normal file
|
@ -0,0 +1,9 @@
|
||||||
|
name=Twizy Virtual BMS
|
||||||
|
version=1.0
|
||||||
|
author=Michael Balzer
|
||||||
|
maintainer=Michael Balzer <dexter@dexters-web.de>
|
||||||
|
sentence=Emulation of Renault Twizy BMS (battery management system)
|
||||||
|
paragraph=Interface between the Twizy and custom built / third party batteries
|
||||||
|
category=Other
|
||||||
|
url=https://github.com/dexterbg/Twizy-Virtual-BMS
|
||||||
|
architectures=*
|
4
src/TwizyVirtualBMS.cpp
Normal file
|
@ -0,0 +1,4 @@
|
||||||
|
// This file is intentionally left empty.
|
||||||
|
// To be able to configure code inclusions & exclusions from the sketch,
|
||||||
|
// (by customizing a sketch copy of "TwizyVirtualBMS_config.h")
|
||||||
|
// the whole library code is in the .h file.
|
968
src/TwizyVirtualBMS.h
Normal file
|
@ -0,0 +1,968 @@
|
||||||
|
/**
|
||||||
|
* ==========================================================================
|
||||||
|
* Twizy Virtual BMS
|
||||||
|
* ==========================================================================
|
||||||
|
*
|
||||||
|
* Emulation of Renault Twizy BMS (battery management system)
|
||||||
|
* Interface between the Twizy and custom built / third party batteries
|
||||||
|
*
|
||||||
|
* Author: Michael Balzer <dexter@dexters-web.de>
|
||||||
|
*
|
||||||
|
* Twizy CAN object dictionary:
|
||||||
|
* https://docs.google.com/spreadsheets/d/1gOrG9rnGR9YuMGakAbl4s97a6irHF6UNFV1TS5Ll7MY/edit#gid=0
|
||||||
|
* (Maintainer: Michael Balzer <dexter@dexters-web.de>)
|
||||||
|
*
|
||||||
|
* Twizy BMS CAN & hardware protocol decoding and reengineering has been done
|
||||||
|
* by a joint effort of (in reverse alphabetical order):
|
||||||
|
* - Lutz Schäfer <aquillo@t-online.de>
|
||||||
|
* - Pascal Ripp <pascal@ripp.li>
|
||||||
|
* - Bernd Eickhoff <b.eickhoff@gmx.de>
|
||||||
|
* - Michael Balzer <dexter@dexters-web.de>
|
||||||
|
*
|
||||||
|
* Libraries used:
|
||||||
|
* - MCP_CAN: https://github.com/coryjfowler/MCP_CAN_lib
|
||||||
|
* - TimerOne: https://github.com/PaulStoffregen/TimerOne
|
||||||
|
*
|
||||||
|
* Licenses:
|
||||||
|
* This is free software and information under the following licenses:
|
||||||
|
* - Source code: GNU Lesser General Public License (LGPL)
|
||||||
|
* https://www.gnu.org/licenses/lgpl.html
|
||||||
|
* - Documentation: GNU Free Documentation License (FDL)
|
||||||
|
* https://www.gnu.org/licenses/fdl.html
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
|
||||||
|
#ifndef _TwizyVirtualBMS_h
|
||||||
|
#define _TwizyVirtualBMS_h
|
||||||
|
|
||||||
|
#include <Arduino.h>
|
||||||
|
#include <avr/pgmspace.h>
|
||||||
|
|
||||||
|
#include <mcp_can.h>
|
||||||
|
#include <mcp_can_dfs.h>
|
||||||
|
#include <TimerOne.h>
|
||||||
|
|
||||||
|
#ifndef _TwizyVirtualBMS_config_h
|
||||||
|
#warning "Fallback to default TwizyVirtualBMS_config.h -- you should copy this into your sketch folder"
|
||||||
|
#include "TwizyVirtualBMS_config.h"
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#define TWIZY_VBMS_VERSION "V1.0 (2017-06-10)"
|
||||||
|
|
||||||
|
#ifndef TWIZY_TAG
|
||||||
|
#define TWIZY_TAG "twizy."
|
||||||
|
#endif
|
||||||
|
|
||||||
|
|
||||||
|
// ==========================================================================
|
||||||
|
// TYPES AND CONSTANTS
|
||||||
|
// ==========================================================================
|
||||||
|
|
||||||
|
|
||||||
|
// Twizy states:
|
||||||
|
enum TwizyState {
|
||||||
|
Off,
|
||||||
|
Init,
|
||||||
|
Ready,
|
||||||
|
StartDrive,
|
||||||
|
Driving,
|
||||||
|
StopDrive,
|
||||||
|
StartCharge,
|
||||||
|
Charging,
|
||||||
|
StopCharge,
|
||||||
|
StartTrickle,
|
||||||
|
Trickle,
|
||||||
|
StopTrickle
|
||||||
|
};
|
||||||
|
|
||||||
|
// Twizy state names:
|
||||||
|
#if TWIZY_DEBUG_LEVEL >= 1
|
||||||
|
const char PROGMEM twizyStateName[12][13] = {
|
||||||
|
"Off",
|
||||||
|
"Init",
|
||||||
|
"Ready",
|
||||||
|
"StartDrive",
|
||||||
|
"Driving",
|
||||||
|
"StopDrive",
|
||||||
|
"StartCharge",
|
||||||
|
"Charging",
|
||||||
|
"StopCharge",
|
||||||
|
"StartTrickle",
|
||||||
|
"Trickle",
|
||||||
|
"StopTrickle"
|
||||||
|
};
|
||||||
|
#endif
|
||||||
|
|
||||||
|
|
||||||
|
// Known error codes for twizySetError():
|
||||||
|
// Note: these can be used singularly or be ORed to set multiple indicators.
|
||||||
|
// i.e. do twizySetError(TWIZY_SERV_TEMP|TWIZY_SERV_STOP) to indicate
|
||||||
|
// a severely high temperature
|
||||||
|
#define TWIZY_OK 0x00000000 // clear all indicators
|
||||||
|
#define TWIZY_SERV 0x00eeee00 // set SERV indicator
|
||||||
|
#define TWIZY_SERV_12V 0x00eeee20 // set SERV + 12V battery indicator
|
||||||
|
#define TWIZY_SERV_BATT 0x00eeee40 // set SERV + main battery indicator
|
||||||
|
#define TWIZY_SERV_TEMP 0x00eeee80 // set SERV + temperature indicator
|
||||||
|
#define TWIZY_SERV_STOP 0x00eeff00 // set SERV + STOP indicator + beep
|
||||||
|
|
||||||
|
|
||||||
|
// User callbacks hooks:
|
||||||
|
typedef void (*TwizyEnterStateCallback)(TwizyState currentState, TwizyState newState);
|
||||||
|
typedef bool (*TwizyCheckStateCallback)(TwizyState currentState, TwizyState newState);
|
||||||
|
typedef void (*TwizyTickerCallback)(unsigned int clockCnt);
|
||||||
|
typedef void (*TwizyProcessCanMsgCallback)(unsigned long rxId, byte rxLen, byte *rxBuf);
|
||||||
|
|
||||||
|
|
||||||
|
// ==========================================================================
|
||||||
|
// LIBRARY CODE AREA
|
||||||
|
// ==========================================================================
|
||||||
|
|
||||||
|
// PROGMEM string helpers:
|
||||||
|
#define FLASHSTRING const __FlashStringHelper
|
||||||
|
#define FS(x) (__FlashStringHelper*)(x)
|
||||||
|
|
||||||
|
// Parameter boundary check with error output:
|
||||||
|
#define CHECKLIMIT(var, minval, maxval) \
|
||||||
|
if (var < minval || var > maxval) { \
|
||||||
|
Serial.print(TWIZY_TAG); \
|
||||||
|
Serial.print(__func__); \
|
||||||
|
Serial.print(F(": ERROR " #var "=")); \
|
||||||
|
Serial.print(var); \
|
||||||
|
Serial.println(F(" out of bounds [" #minval "," #maxval "]")); \
|
||||||
|
return false; \
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
// -----------------------------------------------------
|
||||||
|
// Interrupt handlers
|
||||||
|
//
|
||||||
|
|
||||||
|
volatile bool twizyCanMsgReceived = false;
|
||||||
|
|
||||||
|
#ifdef TWIZY_CAN_IRQ_PIN
|
||||||
|
void twizyCanISR() {
|
||||||
|
twizyCanMsgReceived = true;
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
volatile bool twizyClockTick = false;
|
||||||
|
|
||||||
|
void twizyClockISR() {
|
||||||
|
twizyClockTick = true;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
// -----------------------------------------------------
|
||||||
|
// TwizyVirtualBMS class definition
|
||||||
|
//
|
||||||
|
|
||||||
|
class TwizyVirtualBMS {
|
||||||
|
|
||||||
|
public:
|
||||||
|
|
||||||
|
// -----------------------------------------------------
|
||||||
|
// Public API
|
||||||
|
//
|
||||||
|
|
||||||
|
TwizyVirtualBMS();
|
||||||
|
|
||||||
|
void begin(); // to be called in setup()
|
||||||
|
void looper(); // to be called in loop()
|
||||||
|
|
||||||
|
// User callback registration:
|
||||||
|
void attachEnterState(TwizyEnterStateCallback fn);
|
||||||
|
void attachCheckState(TwizyCheckStateCallback fn);
|
||||||
|
void attachTicker(TwizyTickerCallback fn);
|
||||||
|
void attachProcessCanMsg(TwizyProcessCanMsgCallback fn);
|
||||||
|
|
||||||
|
// Model access:
|
||||||
|
bool setChargeCurrent(int amps);
|
||||||
|
bool setCurrent(float amps);
|
||||||
|
bool setSOC(float soc);
|
||||||
|
bool setPowerLimits(unsigned int drive, unsigned int recup);
|
||||||
|
bool setSOH(int soh);
|
||||||
|
bool setCellVoltage(int cell, float volt);
|
||||||
|
bool setVoltage(float volt, bool deriveCells);
|
||||||
|
bool setModuleTemperature(int module, int temp);
|
||||||
|
bool setTemperature(int tempMin, int tempMax, bool deriveModules);
|
||||||
|
bool setError(unsigned long error);
|
||||||
|
|
||||||
|
// State access:
|
||||||
|
TwizyState state() {
|
||||||
|
return twizyState;
|
||||||
|
}
|
||||||
|
void enterState(TwizyState newState);
|
||||||
|
|
||||||
|
// CAN interface access:
|
||||||
|
bool sendMsg(INT32U id, INT8U len, INT8U *buf);
|
||||||
|
void setCanFilter(byte filterNum, unsigned int canId);
|
||||||
|
|
||||||
|
// Debug utils:
|
||||||
|
void dumpId(FLASHSTRING *name, int len, byte *buf);
|
||||||
|
void debugInfo();
|
||||||
|
|
||||||
|
|
||||||
|
private:
|
||||||
|
|
||||||
|
// -----------------------------------------------------
|
||||||
|
// Twizy CAN model
|
||||||
|
//
|
||||||
|
|
||||||
|
// BMS (controlled by us):
|
||||||
|
byte id155[8] = { 0x07, 0x97, 0xCA, 0x54, 0x52, 0x30, 0x00, 0x6C };
|
||||||
|
byte id424[8] = { 0x11, 0x40, 0x10, 0x20, 0x39, 0x63, 0x00, 0x3A };
|
||||||
|
byte id425[8] = { 0x2A, 0x1F, 0x44, 0xFF, 0xFE, 0x42, 0x01, 0x20 };
|
||||||
|
byte id554[8] = { 0x3A, 0x3A, 0x3A, 0x3A, 0x3A, 0x3A, 0x3A, 0x00 };
|
||||||
|
byte id556[8] = { 0x30, 0x93, 0x09, 0x30, 0x93, 0x09, 0x30, 0x9A };
|
||||||
|
byte id557[8] = { 0x30, 0x93, 0x09, 0x30, 0x93, 0x09, 0x30, 0x90 };
|
||||||
|
byte id55E[8] = { 0x30, 0x93, 0x09, 0x30, 0x93, 0x09, 0x0C, 0xF9 };
|
||||||
|
byte id55F[8] = { 0xFF, 0xFF, 0x73, 0x00, 0x00, 0x21, 0xF2, 0x1F };
|
||||||
|
byte id628[3] = { 0x00, 0x00, 0x00 };
|
||||||
|
byte id659[4] = { 0xFF, 0xFF, 0xFF, 0xFF };
|
||||||
|
|
||||||
|
// CHARGER:
|
||||||
|
byte id423[8] = { 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 };
|
||||||
|
byte id597[8] = { 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 };
|
||||||
|
|
||||||
|
// DISPLAY:
|
||||||
|
byte id599[8] = { 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 };
|
||||||
|
|
||||||
|
|
||||||
|
// -----------------------------------------------------
|
||||||
|
// Twizy CAN interface
|
||||||
|
//
|
||||||
|
|
||||||
|
MCP_CAN twizyCAN;
|
||||||
|
|
||||||
|
unsigned int sendErrors = 0;
|
||||||
|
unsigned int sendRetries = 0;
|
||||||
|
|
||||||
|
// RX buffer:
|
||||||
|
unsigned long rxId;
|
||||||
|
byte rxLen;
|
||||||
|
byte rxBuf[8];
|
||||||
|
|
||||||
|
void receiveCanMsgs();
|
||||||
|
void process423();
|
||||||
|
void process597();
|
||||||
|
void process599();
|
||||||
|
|
||||||
|
|
||||||
|
// -----------------------------------------------------
|
||||||
|
// Twizy state machine
|
||||||
|
//
|
||||||
|
|
||||||
|
TwizyState twizyState = (TwizyState) -1;
|
||||||
|
|
||||||
|
// 3MW pulse tick counter:
|
||||||
|
byte counter3MW = 0;
|
||||||
|
|
||||||
|
|
||||||
|
// -----------------------------------------------------
|
||||||
|
// Twizy ticker:
|
||||||
|
//
|
||||||
|
|
||||||
|
unsigned int clockCnt = 0;
|
||||||
|
|
||||||
|
void ticker();
|
||||||
|
|
||||||
|
|
||||||
|
// -----------------------------------------------------
|
||||||
|
// User callbacks hooks
|
||||||
|
//
|
||||||
|
|
||||||
|
TwizyEnterStateCallback bmsEnterState = NULL;
|
||||||
|
TwizyCheckStateCallback bmsCheckState = NULL;
|
||||||
|
TwizyTickerCallback bmsTicker = NULL;
|
||||||
|
TwizyProcessCanMsgCallback bmsProcessCanMsg = NULL;
|
||||||
|
|
||||||
|
|
||||||
|
};
|
||||||
|
|
||||||
|
|
||||||
|
// -----------------------------------------------------
|
||||||
|
// API
|
||||||
|
//
|
||||||
|
|
||||||
|
TwizyVirtualBMS::TwizyVirtualBMS()
|
||||||
|
: twizyCAN(TWIZY_CAN_CS_PIN) {
|
||||||
|
}
|
||||||
|
|
||||||
|
void TwizyVirtualBMS::attachEnterState(TwizyEnterStateCallback fn) {
|
||||||
|
bmsEnterState = fn;
|
||||||
|
}
|
||||||
|
void TwizyVirtualBMS::attachCheckState(TwizyCheckStateCallback fn) {
|
||||||
|
bmsCheckState = fn;
|
||||||
|
}
|
||||||
|
void TwizyVirtualBMS::attachTicker(TwizyTickerCallback fn) {
|
||||||
|
bmsTicker = fn;
|
||||||
|
}
|
||||||
|
void TwizyVirtualBMS::attachProcessCanMsg(TwizyProcessCanMsgCallback fn) {
|
||||||
|
bmsProcessCanMsg = fn;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
// -----------------------------------------------------
|
||||||
|
// Twizy CAN model
|
||||||
|
//
|
||||||
|
|
||||||
|
|
||||||
|
// Set battery charge current level
|
||||||
|
// amps: 0 .. 35 [A] (5 A resolution, 35 not reached with current charger generation)
|
||||||
|
// Note: will enter state StopCharge if set to 0 during charge
|
||||||
|
bool TwizyVirtualBMS::setChargeCurrent(int amps) {
|
||||||
|
CHECKLIMIT(amps, 0, 35);
|
||||||
|
id155[0] = amps / 5;
|
||||||
|
if (twizyState == Charging && id155[0] == 0) {
|
||||||
|
enterState(StopCharge);
|
||||||
|
}
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
// Set battery pack current level
|
||||||
|
// amps: -500 .. +500 (positive = charge, negative = discharge)
|
||||||
|
bool TwizyVirtualBMS::setCurrent(float amps) {
|
||||||
|
CHECKLIMIT(amps, -500.0, 500.0);
|
||||||
|
unsigned int level = 2000 + (amps * 4);
|
||||||
|
id155[1] = (id155[1] & 0xf0) | ((level & 0x0f00) >> 8);
|
||||||
|
id155[2] = level & 0x00ff;
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
// Set battery pack SOC
|
||||||
|
// soc: 0.00 .. 100.00
|
||||||
|
// Note: the charger will not start charging at SOC=100%
|
||||||
|
bool TwizyVirtualBMS::setSOC(float soc) {
|
||||||
|
CHECKLIMIT(soc, 0.0, 100.0);
|
||||||
|
unsigned int level = soc * 400;
|
||||||
|
id155[4] = level >> 8;
|
||||||
|
id155[5] = level & 0x00ff;
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
// Set SEVCON power limits
|
||||||
|
// drive: 0 .. 30000 [W]
|
||||||
|
// recup: 0 .. 30000 [W]
|
||||||
|
// Note: both limits have a resolution of 500 W
|
||||||
|
bool TwizyVirtualBMS::setPowerLimits(unsigned int drive, unsigned int recup) {
|
||||||
|
CHECKLIMIT(drive, 0, 30000);
|
||||||
|
CHECKLIMIT(recup, 0, 30000);
|
||||||
|
id424[2] = recup / 500;
|
||||||
|
id424[3] = drive / 500;
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
// Set battery pack SOH
|
||||||
|
// soh: 0 .. 100
|
||||||
|
bool TwizyVirtualBMS::setSOH(int soh) {
|
||||||
|
CHECKLIMIT(soh, 0, 100);
|
||||||
|
id424[5] = soh;
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
// Set battery cell voltage level
|
||||||
|
// cell: 1 .. 14
|
||||||
|
// volt: 1.0 .. 5.0
|
||||||
|
bool TwizyVirtualBMS::setCellVoltage(int cell, float volt) {
|
||||||
|
CHECKLIMIT(cell, 1, 14);
|
||||||
|
CHECKLIMIT(volt, 1.0, 5.0);
|
||||||
|
|
||||||
|
// cell voltages are packed 12 bit values
|
||||||
|
// determine frame and position:
|
||||||
|
|
||||||
|
byte *frame;
|
||||||
|
|
||||||
|
if (cell <= 5) {
|
||||||
|
frame = id556;
|
||||||
|
cell -= 1;
|
||||||
|
}
|
||||||
|
else if (cell <= 10) {
|
||||||
|
frame = id557;
|
||||||
|
cell -= 6;
|
||||||
|
}
|
||||||
|
else {
|
||||||
|
frame = id55E;
|
||||||
|
cell -= 11;
|
||||||
|
}
|
||||||
|
|
||||||
|
int pos = cell * 1.5;
|
||||||
|
unsigned int level = volt * 200;
|
||||||
|
|
||||||
|
if (cell & 1) {
|
||||||
|
// odd cell number: pack right
|
||||||
|
frame[pos] = (frame[pos] & 0xf0) | (level >> 8);
|
||||||
|
frame[pos+1] = level & 0x00ff;
|
||||||
|
}
|
||||||
|
else {
|
||||||
|
// even cell number: pack left
|
||||||
|
frame[pos] = level >> 4;
|
||||||
|
frame[pos+1] = (frame[pos+1] & 0x0f) | ((level << 4) & 0xf0);
|
||||||
|
}
|
||||||
|
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
// Set battery pack voltage level
|
||||||
|
// volt: 19.3 … 69.6 (SEVCON G48 series voltage range)
|
||||||
|
// deriveCells: true = set all cell voltages to volt/14
|
||||||
|
bool TwizyVirtualBMS::setVoltage(float volt, bool deriveCells) {
|
||||||
|
CHECKLIMIT(volt, 19.3, 69.6);
|
||||||
|
|
||||||
|
unsigned long level;
|
||||||
|
|
||||||
|
// frame 55F: volt * 10, packed 2x:
|
||||||
|
level = volt * 10;
|
||||||
|
level |= level << 12;
|
||||||
|
id55F[5] = (level & 0x00ff0000) >> 16;
|
||||||
|
id55F[6] = (level & 0x0000ff00) >> 8;
|
||||||
|
id55F[7] = (level & 0x000000ff);
|
||||||
|
|
||||||
|
// frame 425: voltage scaling not 100% known yet, do approximation:
|
||||||
|
level = (volt - 13.051) * 6.981;
|
||||||
|
id425[6] = level >> 8;
|
||||||
|
id425[7] = level & 0x00ff;
|
||||||
|
level = 0xfc00 | (level << 1);
|
||||||
|
id425[4] = level >> 8;
|
||||||
|
id425[5] = level & 0x00ff;
|
||||||
|
|
||||||
|
if (deriveCells) {
|
||||||
|
float cellVolt = volt / 14.0;
|
||||||
|
for (int i=1; i<=14; i++) {
|
||||||
|
setCellVoltage(i, cellVolt);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
// Set battery module temperature
|
||||||
|
// module: 1 .. 7
|
||||||
|
// temp: -40 .. 100 [°C]
|
||||||
|
bool TwizyVirtualBMS::setModuleTemperature(int module, int temp) {
|
||||||
|
CHECKLIMIT(module, 1, 7);
|
||||||
|
CHECKLIMIT(temp, -40, 100);
|
||||||
|
id554[module-1] = 40 + temp;
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
// Set battery overall temperature
|
||||||
|
// tempMin: -40 .. 100 [°C]
|
||||||
|
// tempMax: -40 .. 100 [°C]
|
||||||
|
// deriveModules: true = set all cell temperatures to avg(min,max)
|
||||||
|
bool TwizyVirtualBMS::setTemperature(int tempMin, int tempMax, bool deriveModules) {
|
||||||
|
CHECKLIMIT(tempMin, -40, 100);
|
||||||
|
CHECKLIMIT(tempMax, -40, 100);
|
||||||
|
|
||||||
|
// set min/max temperatures:
|
||||||
|
id424[4] = 40 + tempMin;
|
||||||
|
id424[7] = 40 + tempMax;
|
||||||
|
|
||||||
|
// derive module temperatures:
|
||||||
|
if (deriveModules) {
|
||||||
|
int tempAvg = (tempMin + tempMax) / 2;
|
||||||
|
for (int i=0; i<7; i++) {
|
||||||
|
id554[i] = 40 + tempAvg;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
// Set battery error
|
||||||
|
// error: 0x000000 .. 0xFFFFFF (0 = no error)
|
||||||
|
bool TwizyVirtualBMS::setError(unsigned long error) {
|
||||||
|
CHECKLIMIT(error, 0x000000, 0xFFFFFF);
|
||||||
|
id628[0] = (error & 0xFF0000) >> 16;
|
||||||
|
id628[1] = (error & 0x00FF00) >> 8;
|
||||||
|
id628[2] = (error & 0x0000FF);
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
// -----------------------------------------------------
|
||||||
|
// Twizy CAN interface
|
||||||
|
//
|
||||||
|
|
||||||
|
|
||||||
|
// Set free CAN filters:
|
||||||
|
// filterNum: 1…3
|
||||||
|
// canId: 11 bit CAN ID i.e. 0x196
|
||||||
|
void TwizyVirtualBMS::setCanFilter(byte filterNum, unsigned int canId) {
|
||||||
|
CHECKLIMIT(filterNum, 1, 3);
|
||||||
|
twizyCAN.init_Filt(2+filterNum, 0, (unsigned long)canId << 16);
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
#define SAVEMSG(dst) for(int i = 0; i<rxLen; i++) { dst[i] = rxBuf[i]; }
|
||||||
|
|
||||||
|
// Read and process Twizy CAN messages:
|
||||||
|
void TwizyVirtualBMS::receiveCanMsgs() {
|
||||||
|
while (twizyCAN.readMsgBuf(&rxId, &rxLen, rxBuf) == CAN_OK) {
|
||||||
|
|
||||||
|
if (rxId == 0x423) {
|
||||||
|
SAVEMSG(id423);
|
||||||
|
process423();
|
||||||
|
}
|
||||||
|
else if (rxId == 0x597) {
|
||||||
|
SAVEMSG(id597);
|
||||||
|
process597();
|
||||||
|
}
|
||||||
|
else if (rxId == 0x599) {
|
||||||
|
SAVEMSG(id599);
|
||||||
|
process599();
|
||||||
|
}
|
||||||
|
|
||||||
|
// User space callback:
|
||||||
|
if (bmsProcessCanMsg) {
|
||||||
|
(*bmsProcessCanMsg)(rxId, rxLen, rxBuf);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
// Process CHARGER frame 423:
|
||||||
|
void TwizyVirtualBMS::process423() {
|
||||||
|
if (twizyState == Off && id423[0] != 0) {
|
||||||
|
enterState(Init);
|
||||||
|
}
|
||||||
|
else if (twizyState != Off && id423[0] == 0) {
|
||||||
|
enterState(Off);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
// Process CHARGER frame 597:
|
||||||
|
void TwizyVirtualBMS::process597() {
|
||||||
|
byte address = id597[1] & 0xE5;
|
||||||
|
byte chgmode = id597[3] & 0xF0;
|
||||||
|
|
||||||
|
if (address != 0xE4) {
|
||||||
|
return; // charger does not talk to us
|
||||||
|
}
|
||||||
|
|
||||||
|
if (chgmode == 0xC0) {
|
||||||
|
if (twizyState != Driving) {
|
||||||
|
enterState(StartDrive);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
else if (chgmode == 0xB0) {
|
||||||
|
if (twizyState != Charging) {
|
||||||
|
enterState(StartCharge);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
else if (chgmode == 0x90) {
|
||||||
|
if (twizyState != Trickle) {
|
||||||
|
enterState(StartTrickle);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
else if (chgmode == 0xD0) {
|
||||||
|
if (twizyState == Driving) {
|
||||||
|
enterState(StopDrive);
|
||||||
|
}
|
||||||
|
else if (twizyState == Charging) {
|
||||||
|
enterState(StopCharge);
|
||||||
|
}
|
||||||
|
else if (twizyState == Trickle) {
|
||||||
|
enterState(StopTrickle);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
// Process DISPLAY frame 599:
|
||||||
|
void TwizyVirtualBMS::process599() {
|
||||||
|
// copy odometer to BMS frame 55E
|
||||||
|
unsigned long odo = ((unsigned long)id599[0] << 24)
|
||||||
|
| ((unsigned long)id599[1] << 16)
|
||||||
|
| ((unsigned long)id599[2] << 8)
|
||||||
|
| (id599[3]);
|
||||||
|
odo /= 10;
|
||||||
|
id55E[6] = odo >> 8;
|
||||||
|
id55E[7] = odo & 0x00ff;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
// -----------------------------------------------------
|
||||||
|
// Send Twizy CAN messages:
|
||||||
|
//
|
||||||
|
|
||||||
|
bool TwizyVirtualBMS::sendMsg(INT32U id, INT8U len, INT8U *buf) {
|
||||||
|
|
||||||
|
#if TWIZY_CAN_SEND == 1
|
||||||
|
|
||||||
|
for (int tries=3; tries>0; tries--) {
|
||||||
|
if (twizyCAN.sendMsgBuf(id, 0, len, buf) != CAN_GETTXBFTIMEOUT) {
|
||||||
|
// CAN_OK = frame has been sent
|
||||||
|
// CAN_SENDMSGTIMEOUT = we made it into a send buffer
|
||||||
|
// → no need to repeat the send:
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
sendRetries++;
|
||||||
|
}
|
||||||
|
|
||||||
|
#endif //TWIZY_CAN_SEND
|
||||||
|
|
||||||
|
sendErrors++;
|
||||||
|
return false;
|
||||||
|
|
||||||
|
// Note: MCP_CAN.sendMsgBuf() is not optimized for throughput.
|
||||||
|
// Despite having three send buffers in the MCP, it will wait
|
||||||
|
// for the send to finish and return an error on timeout.
|
||||||
|
// The timeout is 50 MCP register reads via SPI.
|
||||||
|
// It could be worth replacing MCP_CAN.sendMsgBuf() to utilize
|
||||||
|
// asynchronous writes.
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
// -----------------------------------------------------
|
||||||
|
// Twizy ticker:
|
||||||
|
//
|
||||||
|
|
||||||
|
void TwizyVirtualBMS::ticker() {
|
||||||
|
|
||||||
|
if (twizyState == Off) {
|
||||||
|
clockCnt = 0;
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (++clockCnt == 3000)
|
||||||
|
clockCnt = 0;
|
||||||
|
|
||||||
|
bool ms100 = (clockCnt % 10 == 0);
|
||||||
|
bool ms1000 = (clockCnt % 100 == 0);
|
||||||
|
bool ms3000 = (clockCnt % 300 == 0);
|
||||||
|
bool ms10000 = (clockCnt % 1000 == 0);
|
||||||
|
|
||||||
|
|
||||||
|
//
|
||||||
|
// Send CAN messages
|
||||||
|
//
|
||||||
|
|
||||||
|
sendMsg(0x155, sizeof(id155), id155);
|
||||||
|
|
||||||
|
if (ms100) {
|
||||||
|
sendMsg(0x424, sizeof(id424), id424);
|
||||||
|
sendMsg(0x425, sizeof(id425), id425);
|
||||||
|
}
|
||||||
|
if (ms1000) {
|
||||||
|
sendMsg(0x554, sizeof(id554), id554);
|
||||||
|
}
|
||||||
|
if (ms100) {
|
||||||
|
sendMsg(0x556, sizeof(id556), id556);
|
||||||
|
}
|
||||||
|
if (ms1000) {
|
||||||
|
sendMsg(0x557, sizeof(id557), id557);
|
||||||
|
sendMsg(0x55E, sizeof(id55E), id55E);
|
||||||
|
sendMsg(0x55F, sizeof(id55F), id55F);
|
||||||
|
}
|
||||||
|
if (ms100) {
|
||||||
|
sendMsg(0x628, sizeof(id628), id628);
|
||||||
|
}
|
||||||
|
if (ms3000) {
|
||||||
|
sendMsg(0x659, sizeof(id659), id659);
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
//
|
||||||
|
// Create 3MW pulse cycle
|
||||||
|
// (high 150ms → low 150ms → high)
|
||||||
|
//
|
||||||
|
|
||||||
|
if (counter3MW > 0) {
|
||||||
|
--counter3MW;
|
||||||
|
// 3MW low after 150 ms:
|
||||||
|
if (counter3MW == 15) {
|
||||||
|
digitalWrite(TWIZY_3MW_CONTROL_PIN, 0);
|
||||||
|
}
|
||||||
|
// 3MW high after 300 ms (pulse finished):
|
||||||
|
else if (counter3MW == 0) {
|
||||||
|
digitalWrite(TWIZY_3MW_CONTROL_PIN, 1);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
//
|
||||||
|
// Check for state transition
|
||||||
|
//
|
||||||
|
|
||||||
|
switch (twizyState) {
|
||||||
|
|
||||||
|
// Transition to Ready?
|
||||||
|
case Init:
|
||||||
|
case StopDrive:
|
||||||
|
case StopCharge:
|
||||||
|
case StopTrickle:
|
||||||
|
if (!bmsCheckState || (*bmsCheckState)(twizyState, Ready)) {
|
||||||
|
enterState(Ready);
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
|
||||||
|
// Transition to Driving?
|
||||||
|
case StartDrive:
|
||||||
|
if (!bmsCheckState || (*bmsCheckState)(twizyState, Driving)) {
|
||||||
|
enterState(Driving);
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
|
||||||
|
// Transition to Charging?
|
||||||
|
case StartCharge:
|
||||||
|
if (!bmsCheckState || (*bmsCheckState)(twizyState, Charging)) {
|
||||||
|
enterState(Charging);
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
|
||||||
|
// Transition to Trickle?
|
||||||
|
case StartTrickle:
|
||||||
|
if (!bmsCheckState || (*bmsCheckState)(twizyState, Trickle)) {
|
||||||
|
enterState(Trickle);
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
//
|
||||||
|
// Debug info every 10 seconds
|
||||||
|
//
|
||||||
|
|
||||||
|
#if TWIZY_DEBUG_LEVEL >= 1
|
||||||
|
if (ms10000) {
|
||||||
|
debugInfo();
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
|
||||||
|
//
|
||||||
|
// Callback for BMS ticker code:
|
||||||
|
//
|
||||||
|
|
||||||
|
if (bmsTicker) {
|
||||||
|
(*bmsTicker)(clockCnt);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
// -----------------------------------------------------
|
||||||
|
// Twizy debug info:
|
||||||
|
//
|
||||||
|
|
||||||
|
void TwizyVirtualBMS::dumpId(FLASHSTRING *name, int len, byte *buf) {
|
||||||
|
Serial.print(F("- "));
|
||||||
|
Serial.print(name);
|
||||||
|
Serial.print(F(":"));
|
||||||
|
for (int i=0; i<len; i++) {
|
||||||
|
Serial.print(buf[i] < 0x10 ? F(" 0") : F(" "));
|
||||||
|
Serial.print(buf[i], HEX);
|
||||||
|
}
|
||||||
|
Serial.println();
|
||||||
|
}
|
||||||
|
|
||||||
|
void TwizyVirtualBMS::debugInfo() {
|
||||||
|
|
||||||
|
#if TWIZY_DEBUG_LEVEL >= 1
|
||||||
|
|
||||||
|
Serial.println(F("\n" TWIZY_TAG "debugInfo:"));
|
||||||
|
|
||||||
|
Serial.print(F("- twizyState="));
|
||||||
|
Serial.println(FS(twizyStateName[twizyState]));
|
||||||
|
|
||||||
|
Serial.print(F("- clockCnt="));
|
||||||
|
Serial.println(clockCnt);
|
||||||
|
|
||||||
|
if (sendRetries) {
|
||||||
|
Serial.print(F("- sendRetries="));
|
||||||
|
Serial.println(sendRetries);
|
||||||
|
sendRetries = 0;
|
||||||
|
}
|
||||||
|
if (sendErrors) {
|
||||||
|
Serial.print(F("- sendErrors="));
|
||||||
|
Serial.println(sendErrors);
|
||||||
|
sendErrors = 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if TWIZY_DEBUG_LEVEL >= 2
|
||||||
|
|
||||||
|
// CHARGER & DISPLAY:
|
||||||
|
dumpId(F("id423"), sizeof(id423), id423);
|
||||||
|
dumpId(F("id597"), sizeof(id597), id597);
|
||||||
|
dumpId(F("id599"), sizeof(id599), id599);
|
||||||
|
|
||||||
|
// BMS:
|
||||||
|
dumpId(F("id155"), sizeof(id155), id155);
|
||||||
|
dumpId(F("id424"), sizeof(id424), id424);
|
||||||
|
dumpId(F("id425"), sizeof(id425), id425);
|
||||||
|
dumpId(F("id554"), sizeof(id554), id554);
|
||||||
|
dumpId(F("id556"), sizeof(id556), id556);
|
||||||
|
dumpId(F("id557"), sizeof(id557), id557);
|
||||||
|
dumpId(F("id55E"), sizeof(id55E), id55E);
|
||||||
|
dumpId(F("id55F"), sizeof(id55F), id55F);
|
||||||
|
dumpId(F("id628"), sizeof(id628), id628);
|
||||||
|
dumpId(F("id659"), sizeof(id659), id659);
|
||||||
|
|
||||||
|
#endif
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
// -----------------------------------------------------
|
||||||
|
// Twizy state transitions:
|
||||||
|
//
|
||||||
|
|
||||||
|
void TwizyVirtualBMS::enterState(TwizyState newState) {
|
||||||
|
|
||||||
|
if (twizyState == newState) {
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
#if TWIZY_DEBUG_LEVEL >= 1
|
||||||
|
Serial.print(F(TWIZY_TAG "enterState: newState="));
|
||||||
|
Serial.println(FS(twizyStateName[newState]));
|
||||||
|
#endif
|
||||||
|
|
||||||
|
switch (newState) {
|
||||||
|
|
||||||
|
case Off:
|
||||||
|
case Init:
|
||||||
|
id424[0] = 0x00;
|
||||||
|
id425[0] = 0x1D;
|
||||||
|
digitalWrite(TWIZY_3MW_CONTROL_PIN, 0);
|
||||||
|
break;
|
||||||
|
|
||||||
|
case Ready:
|
||||||
|
// keep stop charge request if set:
|
||||||
|
if (id424[0] != 0x12) {
|
||||||
|
id424[0] = 0x11;
|
||||||
|
}
|
||||||
|
// restore minimum charge current level:
|
||||||
|
if (id155[0] == 0) {
|
||||||
|
id155[0] = 1;
|
||||||
|
}
|
||||||
|
id425[0] = 0x24;
|
||||||
|
// if just switched on...
|
||||||
|
if (twizyState == Init) {
|
||||||
|
// ...start 3MW pulse cycle:
|
||||||
|
digitalWrite(TWIZY_3MW_CONTROL_PIN, 1);
|
||||||
|
counter3MW = 30;
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
|
||||||
|
case Driving:
|
||||||
|
id425[0] = 0x2A;
|
||||||
|
break;
|
||||||
|
|
||||||
|
case Charging:
|
||||||
|
id425[0] = 0x0A;
|
||||||
|
break;
|
||||||
|
|
||||||
|
case StopCharge:
|
||||||
|
id424[0] = 0x12;
|
||||||
|
break;
|
||||||
|
|
||||||
|
case StartTrickle:
|
||||||
|
id425[0] = 0x2C;
|
||||||
|
break;
|
||||||
|
|
||||||
|
case Trickle:
|
||||||
|
id425[0] = 0x2A;
|
||||||
|
break;
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
// call BMS state transition:
|
||||||
|
if (bmsEnterState) {
|
||||||
|
(*bmsEnterState)(twizyState, newState);
|
||||||
|
}
|
||||||
|
|
||||||
|
// set new state:
|
||||||
|
twizyState = newState;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
// -----------------------------------------------------
|
||||||
|
// Twizy setup
|
||||||
|
//
|
||||||
|
|
||||||
|
void TwizyVirtualBMS::begin() {
|
||||||
|
|
||||||
|
Serial.println(F("Twizy Virtual BMS " TWIZY_VBMS_VERSION));
|
||||||
|
|
||||||
|
//
|
||||||
|
// Init Twizy CAN interface
|
||||||
|
//
|
||||||
|
|
||||||
|
while (twizyCAN.begin(MCP_STDEXT, CAN_500KBPS, TWIZY_CAN_MCP_FREQ) != CAN_OK) {
|
||||||
|
Serial.println(F(TWIZY_TAG "begin: waiting for CAN connection..."));
|
||||||
|
delay(500);
|
||||||
|
}
|
||||||
|
|
||||||
|
// Set filters:
|
||||||
|
|
||||||
|
twizyCAN.init_Mask(0, 0, 0x07FF0000);
|
||||||
|
twizyCAN.init_Filt(0, 0, 0x04230000); // CHARGER: 423
|
||||||
|
twizyCAN.init_Filt(1, 0, 0x05970000); // CHARGER: 597
|
||||||
|
|
||||||
|
twizyCAN.init_Mask(1, 0, 0x07FF0000);
|
||||||
|
twizyCAN.init_Filt(2, 0, 0x05990000); // DISPLAY: 599
|
||||||
|
twizyCAN.init_Filt(3, 0, 0x00000000);
|
||||||
|
twizyCAN.init_Filt(4, 0, 0x00000000);
|
||||||
|
twizyCAN.init_Filt(5, 0, 0x00000000);
|
||||||
|
|
||||||
|
#ifdef TWIZY_CAN_IRQ_PIN
|
||||||
|
pinMode(TWIZY_CAN_IRQ_PIN, INPUT);
|
||||||
|
attachInterrupt(digitalPinToInterrupt(TWIZY_CAN_IRQ_PIN), twizyCanISR, FALLING);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
twizyCAN.setMode(MCP_NORMAL);
|
||||||
|
|
||||||
|
|
||||||
|
//
|
||||||
|
// Init Twizy state machine & clock
|
||||||
|
//
|
||||||
|
|
||||||
|
pinMode(TWIZY_3MW_CONTROL_PIN, OUTPUT);
|
||||||
|
|
||||||
|
enterState(Off);
|
||||||
|
|
||||||
|
Timer1.initialize(TWIZY_CAN_CLOCK_US);
|
||||||
|
Timer1.attachInterrupt(twizyClockISR);
|
||||||
|
|
||||||
|
Serial.println(F(TWIZY_TAG "begin: done"));
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
// -----------------------------------------------------
|
||||||
|
// Twizy loop
|
||||||
|
//
|
||||||
|
|
||||||
|
void TwizyVirtualBMS::looper() {
|
||||||
|
//
|
||||||
|
// Receive Twizy CAN messages
|
||||||
|
//
|
||||||
|
|
||||||
|
#ifndef TWIZY_CAN_IRQ_PIN
|
||||||
|
// No IRQ, we need to poll:
|
||||||
|
twizyCanMsgReceived = twizyCAN.checkReceive();
|
||||||
|
#endif
|
||||||
|
|
||||||
|
if (twizyCanMsgReceived) {
|
||||||
|
twizyCanMsgReceived = false;
|
||||||
|
receiveCanMsgs();
|
||||||
|
}
|
||||||
|
|
||||||
|
//
|
||||||
|
// Twizy ticker (send CAN messages, check for state transitions)
|
||||||
|
//
|
||||||
|
|
||||||
|
if (twizyClockTick) {
|
||||||
|
twizyClockTick = false;
|
||||||
|
ticker();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
#endif // _TwizyVirtualBMS_h
|
35
src/TwizyVirtualBMS_config.h
Normal file
|
@ -0,0 +1,35 @@
|
||||||
|
/**
|
||||||
|
* ==========================================================================
|
||||||
|
* Twizy Virtual BMS: Configuration
|
||||||
|
* ==========================================================================
|
||||||
|
*/
|
||||||
|
|
||||||
|
#ifndef _TwizyVirtualBMS_config_h
|
||||||
|
#define _TwizyVirtualBMS_config_h
|
||||||
|
|
||||||
|
// Serial debug output:
|
||||||
|
// Level 0 = none, only output init & error messages
|
||||||
|
// Level 1 = log state transitions & CAN statistics
|
||||||
|
// Level 2 = log CAN frame dumps (10 second interval)
|
||||||
|
#define TWIZY_DEBUG_LEVEL 1
|
||||||
|
|
||||||
|
// Set to 0 to disable CAN transmissions for testing:
|
||||||
|
#define TWIZY_CAN_SEND 1
|
||||||
|
|
||||||
|
// CAN send timing is normally 10 ms (10.000 us).
|
||||||
|
// You may need to lower this if your Arduino is too slow.
|
||||||
|
#define TWIZY_CAN_CLOCK_US 10000
|
||||||
|
|
||||||
|
// Set your MCP clock frequency here:
|
||||||
|
#define TWIZY_CAN_MCP_FREQ MCP_16MHZ
|
||||||
|
|
||||||
|
// Set your SPI CS pin number here:
|
||||||
|
#define TWIZY_CAN_CS_PIN 10
|
||||||
|
|
||||||
|
// If you've connected the CAN module's IRQ pin:
|
||||||
|
//#define TWIZY_CAN_IRQ_PIN 2
|
||||||
|
|
||||||
|
// Set your 3MW control pin here:
|
||||||
|
#define TWIZY_3MW_CONTROL_PIN 3
|
||||||
|
|
||||||
|
#endif // _TwizyVirtualBMS_config_h
|