-
Notifications
You must be signed in to change notification settings - Fork 236
/
Copy pathvehicle_nissanleaf.cpp
2384 lines (2194 loc) · 88.3 KB
/
vehicle_nissanleaf.cpp
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
687
688
689
690
691
692
693
694
695
696
697
698
699
700
701
702
703
704
705
706
707
708
709
710
711
712
713
714
715
716
717
718
719
720
721
722
723
724
725
726
727
728
729
730
731
732
733
734
735
736
737
738
739
740
741
742
743
744
745
746
747
748
749
750
751
752
753
754
755
756
757
758
759
760
761
762
763
764
765
766
767
768
769
770
771
772
773
774
775
776
777
778
779
780
781
782
783
784
785
786
787
788
789
790
791
792
793
794
795
796
797
798
799
800
801
802
803
804
805
806
807
808
809
810
811
812
813
814
815
816
817
818
819
820
821
822
823
824
825
826
827
828
829
830
831
832
833
834
835
836
837
838
839
840
841
842
843
844
845
846
847
848
849
850
851
852
853
854
855
856
857
858
859
860
861
862
863
864
865
866
867
868
869
870
871
872
873
874
875
876
877
878
879
880
881
882
883
884
885
886
887
888
889
890
891
892
893
894
895
896
897
898
899
900
901
902
903
904
905
906
907
908
909
910
911
912
913
914
915
916
917
918
919
920
921
922
923
924
925
926
927
928
929
930
931
932
933
934
935
936
937
938
939
940
941
942
943
944
945
946
947
948
949
950
951
952
953
954
955
956
957
958
959
960
961
962
963
964
965
966
967
968
969
970
971
972
973
974
975
976
977
978
979
980
981
982
983
984
985
986
987
988
989
990
991
992
993
994
995
996
997
998
999
1000
/*
; Project: Open Vehicle Monitor System
; Date: 30th September 2017
;
; Changes:
; 1.0 Initial release
;
; (C) 2011 Michael Stegen / Stegen Electronics
; (C) 2011-2017 Mark Webb-Johnson
; (C) 2011 Sonny Chen @ EPRO/DX
; (C) 2017 Tom Parker
;
; Permission is hereby granted, free of charge, to any person obtaining a copy
; of this software and associated documentation files (the "Software"), to deal
; in the Software without restriction, including without limitation the rights
; to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
; copies of the Software, and to permit persons to whom the Software is
; furnished to do so, subject to the following conditions:
;
; The above copyright notice and this permission notice shall be included in
; all copies or substantial portions of the Software.
;
; THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
; IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
; FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
; AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
; LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
; OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
; THE SOFTWARE.
*/
#include "ovms_log.h"
static const char *TAG = "v-nissanleaf";
#include <stdio.h>
#include <string.h>
#include "pcp.h"
#include "vehicle_nissanleaf.h"
#include "ovms_events.h"
#include "ovms_metrics.h"
#include "metrics_standard.h"
#include "ovms_notify.h"
#ifdef CONFIG_OVMS_COMP_WEBSERVER
#include "ovms_webserver.h"
#endif
#include "ovms_command.h"
#include "ovms_config.h"
#define MAX_POLL_DATA_LEN 196
#define BMS_TXID 0x79B
#define BMS_RXID 0x7BB
#define CHARGER_TXID 0x797
#define CHARGER_RXID 0x79a
#define BROADCAST_TXID 0x7df
#define BROADCAST_RXID 0x0
// other pairs 743/763 744/764 745/765 784/78C 792/793 79D/7BD
#define VIN_PID 0x81
#define QC_COUNT_PID 0x1203
#define L1L2_COUNT_PID 0x1205
enum poll_states
{
POLLSTATE_OFF, //- car is off
POLLSTATE_ON, //- car is on
POLLSTATE_RUNNING, //- car is in drive/reverse
POLLSTATE_CHARGING //- car is charging
};
static const OvmsPoller::poll_pid_t obdii_polls[] =
{
// BUS 2
{ CHARGER_TXID, CHARGER_RXID, VEHICLE_POLL_TYPE_OBDIIGROUP, VIN_PID, { 0, 900, 0, 0 }, 2, ISOTP_STD }, // VIN [19]
{ CHARGER_TXID, CHARGER_RXID, VEHICLE_POLL_TYPE_OBDIIEXTENDED, QC_COUNT_PID, { 0, 900, 0, 0 }, 2, ISOTP_STD }, // QC [2]
{ CHARGER_TXID, CHARGER_RXID, VEHICLE_POLL_TYPE_OBDIIEXTENDED, L1L2_COUNT_PID, { 0, 900, 0, 0 }, 2, ISOTP_STD }, // L0/L1/L2 [2]
// BUS 1
{ BMS_TXID, BMS_RXID, VEHICLE_POLL_TYPE_OBDIIGROUP, 0x01, { 0, 60, 0, 60 }, 1, ISOTP_STD }, // bat [39/41]
{ BMS_TXID, BMS_RXID, VEHICLE_POLL_TYPE_OBDIIGROUP, 0x02, { 0, 60, 0, 60 }, 1, ISOTP_STD }, // battery voltages [196]
{ BMS_TXID, BMS_RXID, VEHICLE_POLL_TYPE_OBDIIGROUP, 0x06, { 0, 60, 0, 60 }, 1, ISOTP_STD }, // battery shunts [96]
{ BMS_TXID, BMS_RXID, VEHICLE_POLL_TYPE_OBDIIGROUP, 0x04, { 0, 300, 0, 300 }, 1, ISOTP_STD }, // battery temperatures [14]
POLL_LIST_END
};
void MITMDisableTimerCallback(TimerHandle_t timer)
{
OvmsVehicleNissanLeaf* nl = (OvmsVehicleNissanLeaf*) pvTimerGetTimerID(timer);
nl->MITMDisableTimer();
}
void remoteCommandTimer(TimerHandle_t timer)
{
OvmsVehicleNissanLeaf* nl = (OvmsVehicleNissanLeaf*) pvTimerGetTimerID(timer);
nl->RemoteCommandTimer();
}
void ccDisableTimer(TimerHandle_t timer)
{
OvmsVehicleNissanLeaf* nl = (OvmsVehicleNissanLeaf*) pvTimerGetTimerID(timer);
nl->CcDisableTimer();
}
enum battery_type
{
BATTERY_TYPE_1_24kWh,
BATTERY_TYPE_2_24kWh,
BATTERY_TYPE_2_30kWh,
// there may be more...
};
enum charge_duration_index
{
CHARGE_DURATION_FULL_L2,
CHARGE_DURATION_FULL_L1,
CHARGE_DURATION_FULL_L0,
CHARGE_DURATION_RANGE_L2,
CHARGE_DURATION_RANGE_L1,
CHARGE_DURATION_RANGE_L0,
};
OvmsVehicleNissanLeaf* OvmsVehicleNissanLeaf::GetInstance(OvmsWriter* writer /*=NULL*/)
{
OvmsVehicleNissanLeaf* nl = (OvmsVehicleNissanLeaf*) MyVehicleFactory.ActiveVehicle();
string type = StdMetrics.ms_v_type->AsString();
if (!nl || type != "NL") {
if (writer)
writer->puts("Error: Nissan Leaf vehicle module not selected");
return NULL;
}
return nl;
}
OvmsVehicleNissanLeaf::OvmsVehicleNissanLeaf()
: nl_obd_rxwait(1,1)
{
ESP_LOGI(TAG, "Nissan Leaf v3.0 vehicle module");
BmsSetCellArrangementVoltage(96, 32);
BmsSetCellArrangementTemperature(3, 1);
m_gids = MyMetrics.InitInt("xnl.v.b.gids", SM_STALE_HIGH, 0);
m_max_gids = MyMetrics.InitInt("xnl.v.b.max.gids", SM_STALE_HIGH, 0);
m_hx = MyMetrics.InitFloat("xnl.v.b.hx", SM_STALE_HIGH, 0);
m_soc_new_car = MyMetrics.InitFloat("xnl.v.b.soc.newcar", SM_STALE_HIGH, 0, Percentage);
m_soc_instrument = MyMetrics.InitFloat("xnl.v.b.soc.instrument", SM_STALE_HIGH, 0, Percentage);
m_range_instrument = MyMetrics.InitInt("xnl.v.b.range.instrument", SM_STALE_HIGH, 0, Kilometers);
m_bms_thermistor = MyMetrics.InitVector<int>("xnl.bms.thermistor", SM_STALE_MIN, 0, Native);
m_bms_temp_int = MyMetrics.InitVector<int>("xnl.bms.temp.int", SM_STALE_MIN, 0, Celcius);
m_bms_balancing = MyMetrics.InitBitset<96>("xnl.bms.balancing", SM_STALE_HIGH, 0);
m_soh_new_car = MyMetrics.InitFloat("xnl.v.b.soh.newcar", SM_STALE_HIGH, 0, Percentage);
m_soh_instrument = MyMetrics.InitInt("xnl.v.b.soh.instrument", SM_STALE_HIGH, 0, Percentage);
m_battery_energy_capacity = MyMetrics.InitFloat("xnl.v.b.e.capacity", SM_STALE_HIGH, 0, kWh);
m_battery_energy_available = MyMetrics.InitFloat("xnl.v.b.e.available", SM_STALE_HIGH, 0, kWh);
m_battery_type = MyMetrics.InitInt("xnl.v.b.type", SM_STALE_HIGH, 0); // auto-detect version and size by can traffic
m_battery_heaterpresent = MyMetrics.InitBool("xnl.v.b.heaterpresent", SM_STALE_HIGH, false);
m_battery_heatrequested = MyMetrics.InitBool("xnl.v.b.heatrequested", SM_STALE_HIGH, false);
m_battery_heatergranted = MyMetrics.InitBool("xnl.v.b.heatergranted", SM_STALE_HIGH, false);
m_charge_duration = MyMetrics.InitVector<int>("xnl.v.c.duration", SM_STALE_HIGH, 0, Minutes);
// note vector strings are not handled by ovms_metrics.h and cause web errors loading ev.data in ovms.js
// this will need to be resolved before reinstating metrics
// m_charge_duration_label = new OvmsMetricVector<string>("xnl.v.c.duration.label");
// m_charge_duration_label->SetElemValue(CHARGE_DURATION_FULL_L2, "full.l2");
// m_charge_duration_label->SetElemValue(CHARGE_DURATION_FULL_L1, "full.l1");
// m_charge_duration_label->SetElemValue(CHARGE_DURATION_FULL_L0, "full.l0");
// m_charge_duration_label->SetElemValue(CHARGE_DURATION_RANGE_L2, "range.l2");
// m_charge_duration_label->SetElemValue(CHARGE_DURATION_RANGE_L1, "range.l1");
// m_charge_duration_label->SetElemValue(CHARGE_DURATION_RANGE_L0, "range.l0");
m_charge_minutes_3kW_remaining = MyMetrics.InitInt("xnl.v.c.chargeminutes3kW", SM_STALE_HIGH, 0);
m_quick_charge = MyMetrics.InitInt("xnl.v.c.quick", SM_STALE_HIGH, 0);
m_remaining_chargebars = MyMetrics.InitInt("xnl.v.c.chargebars", SM_STALE_HIGH, 0);
m_soc_nominal = MyMetrics.InitFloat("xnl.v.b.soc.nominal", SM_STALE_HIGH, 0, Percentage);
m_battery_out_power_limit = MyMetrics.InitFloat("xnl.v.b.output.limit", SM_STALE_HIGH, 0, kW);
m_battery_in_power_limit = MyMetrics.InitFloat("xnl.v.b.regen.limit", SM_STALE_HIGH, 0, kW);
m_battery_chargerate_max = MyMetrics.InitFloat("xnl.v.b.charge.limit", SM_STALE_HIGH, 0, kW);
m_charge_limit = MyMetrics.InitString("xnl.v.c.limit.reason", SM_STALE_MIN, 0);
m_charge_count_qc = MyMetrics.InitInt("xnl.v.c.count.qc", SM_STALE_NONE, 0);
m_charge_count_l0l1l2 = MyMetrics.InitInt("xnl.v.c.count.l0l1l2", SM_STALE_NONE, 0);
m_climate_vent = MyMetrics.InitString("v.e.cabinvent", SM_STALE_MIN, 0);
m_climate_intake = MyMetrics.InitString("v.e.cabinintake", SM_STALE_MIN, 0);
m_climate_setpoint = MyMetrics.InitFloat("v.e.cabinsetpoint", SM_STALE_HIGH, 0, Celcius);
m_climate_fan_speed = MyMetrics.InitInt("v.e.cabinfan", SM_STALE_MIN, 0);
m_climate_fan_speed_limit = MyMetrics.InitInt("v.e.cabinfanlimit", SM_STALE_MIN, 0);
m_climate_fan_only = MyMetrics.InitBool("xnl.cc.fan.only", SM_STALE_MIN, false);
m_climate_remoteheat = MyMetrics.InitBool("xnl.cc.remoteheat", SM_STALE_MIN, false);
m_climate_remotecool = MyMetrics.InitBool("xnl.cc.remotecool", SM_STALE_MIN, false);
m_climate_rqinprogress = MyMetrics.InitBool("xnl.cc.rqinprogress", SM_STALE_MIN, false);
m_charge_state_previous = MyMetrics.InitString("xnl.v.c.state.previous", SM_STALE_HIGH, 0);
m_charge_user_notified = MyMetrics.InitString("xnl.v.c.event.notification", SM_STALE_HIGH, 0);
m_charge_event_reason = MyMetrics.InitString("xnl.v.c.event.reason", SM_STALE_HIGH, 0);
m_climate_auto = MyMetrics.InitBool("xnl.v.e.hvac.auto", SM_STALE_MIN, false);
MyMetrics.InitBool("v.e.on", SM_STALE_MIN, false);
MyMetrics.InitBool("v.e.awake", SM_STALE_MID, false);
MyMetrics.InitBool("v.e.locked", SM_STALE_MID, false);
MyMetrics.InitString("v.c.state",SM_STALE_MID,"stopped");
m_ZE0_charger = false;
m_AZE0_charger = false;
m_climate_really_off = false;
RegisterCanBus(1,CAN_MODE_ACTIVE,CAN_SPEED_500KBPS);
RegisterCanBus(2,CAN_MODE_ACTIVE,CAN_SPEED_500KBPS);
PollSetState(POLLSTATE_OFF);
PollSetResponseSeparationTime(0);
PollSetPidList(m_can1,obdii_polls);
MyConfig.RegisterParam("xnl", "Nissan Leaf", true, true);
ConfigChanged(NULL);
#ifdef CONFIG_OVMS_COMP_WEBSERVER
WebInit();
#endif
m_remoteCommandTimer = xTimerCreate("Nissan Leaf Remote Command", 100 / portTICK_PERIOD_MS, pdTRUE, this, remoteCommandTimer);
m_ccDisableTimer = xTimerCreate("Nissan Leaf CC Disable", 1000 / portTICK_PERIOD_MS, pdFALSE, this, ccDisableTimer);
m_MITMstop = xTimerCreate("Nissan Leaf MITM Chargestop Disable", 1000 / portTICK_PERIOD_MS, pdFALSE, this, MITMDisableTimerCallback);
//load custom shell commands
CommandInit();
using std::placeholders::_1;
using std::placeholders::_2;
}
unsigned char leafcrc(int l, unsigned char * b){
const unsigned char crcTable[]={0x0, 0x85, 0x8F, 0x0A, 0x9B, 0x1E, 0x14, 0x91, 0xB3, 0x36, 0x3C, 0xB9, 0x28, 0xAD, 0xA7, 0x22,
0xE3, 0x66, 0x6C, 0xE9, 0x78, 0xFD, 0xF7, 0x72, 0x50, 0xD5, 0xDF, 0x5A, 0xCB, 0x4E, 0x44, 0xC1,
0x43, 0xC6, 0xCC, 0x49, 0xD8, 0x5D, 0x57, 0xD2, 0xF0, 0x75, 0x7F, 0xFA, 0x6B, 0xEE, 0xE4, 0x61,
0xA0, 0x25, 0x2F, 0xAA, 0x3B, 0xBE, 0xB4, 0x31, 0x13, 0x96, 0x9C, 0x19, 0x88, 0x0D, 0x07, 0x82,
0x86, 0x03, 0x09, 0x8C, 0x1D, 0x98, 0x92, 0x17, 0x35, 0xB0, 0xBA, 0x3F, 0xAE, 0x2B, 0x21, 0xA4,
0x65, 0xE0, 0xEA, 0x6F, 0xFE, 0x7B, 0x71, 0xF4, 0xD6, 0x53, 0x59, 0xDC, 0x4D, 0xC8, 0xC2, 0x47,
0xC5, 0x40, 0x4A, 0xCF, 0x5E, 0xDB, 0xD1, 0x54, 0x76, 0xF3, 0xF9, 0x7C, 0xED, 0x68, 0x62, 0xE7,
0x26, 0xA3, 0xA9, 0x2C, 0xBD, 0x38, 0x32, 0xB7, 0x95, 0x10, 0x1A, 0x9F, 0x0E, 0x8B, 0x81, 0x04,
0x89, 0x0C, 0x06, 0x83, 0x12, 0x97, 0x9D, 0x18, 0x3A, 0xBF, 0xB5, 0x30, 0xA1, 0x24, 0x2E, 0xAB,
0x6A, 0xEF, 0xE5, 0x60, 0xF1, 0x74, 0x7E, 0xFB, 0xD9, 0x5C, 0x56, 0xD3, 0x42, 0xC7, 0xCD, 0x48,
0xCA, 0x4F, 0x45, 0xC0, 0x51, 0xD4, 0xDE, 0x5B, 0x79, 0xFC, 0xF6, 0x73, 0xE2, 0x67, 0x6D, 0xE8,
0x29, 0xAC, 0xA6, 0x23, 0xB2, 0x37, 0x3D, 0xB8, 0x9A, 0x1F, 0x15, 0x90, 0x01, 0x84, 0x8E, 0x0B,
0x0F, 0x8A, 0x80, 0x05, 0x94, 0x11, 0x1B, 0x9E, 0xBC, 0x39, 0x33, 0xB6, 0x27, 0xA2, 0xA8, 0x2D,
0xEC, 0x69, 0x63, 0xE6, 0x77, 0xF2, 0xF8, 0x7D, 0x5F, 0xDA, 0xD0, 0x55, 0xC4, 0x41, 0x4B, 0xCE,
0x4C, 0xC9, 0xC3, 0x46, 0xD7, 0x52, 0x58, 0xDD, 0xFF, 0x7A, 0x70, 0xF5, 0x64, 0xE1, 0xEB, 0x6E,
0xAF, 0x2A, 0x20, 0xA5, 0x34, 0xB1, 0xBB, 0x3E, 0x1C, 0x99, 0x93, 0x16, 0x87, 0x02, 0x08, 0x8D
};
unsigned char crc = 0;
for (int i = 0; i < l; i++)
crc = crcTable[crc ^ b[i]];
return crc;
}
OvmsVehicleNissanLeaf::~OvmsVehicleNissanLeaf()
{
ESP_LOGI(TAG, "Shutdown Nissan Leaf vehicle module");
#ifdef CONFIG_OVMS_COMP_WEBSERVER
WebDeInit();
#endif
}
void OvmsVehicleNissanLeaf::CommandInit()
{
cmd_xnl = MyCommandApp.RegisterCommand("xnl","Nissan Leaf framework");
OvmsCommand* obd = cmd_xnl->RegisterCommand("obd", "OBD2 tools");
OvmsCommand* cmd_can1 = obd->RegisterCommand("can1", "Send OBD2 request, output response to EV can bus");
cmd_can1->RegisterCommand("device", "Send OBD2 request to an ECU",shell_obd_request,
"<txid> <rxid> <request>\n"
"Where <request> includes mode (01, 02, 09, 10, 1A, 21 or 22) and pid.\n"
"Example: 79B 7BB 2101", 3, 3);
cmd_can1->RegisterCommand("broadcast", "Send OBD2 request as broadcast", shell_obd_request, "<request>", 1, 1);
OvmsCommand* cmd_can2 = obd->RegisterCommand("can2", "Send to CAR can bus");
cmd_can2->RegisterCommand("device", "Send OBD2 request to a device", shell_obd_request,
"<txid> <rxid> <request>\n"
"Where <request> includes mode (01, 02, 09, 10, 1A, 21 or 22) and pid.\n"
"Example: 79B 7BB 2101", 3, 3);
cmd_can2->RegisterCommand("broadcast", "Send OBD2 request as broadcast", shell_obd_request, "<request>", 1, 1);
}
void OvmsVehicleNissanLeaf::ConfigChanged(OvmsConfigParam* param)
{
if (param && param->GetName() != "xnl")
return;
ESP_LOGD(TAG, "Nissan Leaf reload configuration");
// Note that we do not store a configurable maxRange like Kia Soal and Renault Twizy.
// Instead, we derive maxRange from maxGids
// Instances:
// xnl
// suffsoc Sufficient SOC [%] (Default: 0=disabled)
// suffrange Sufficient range [km] (Default: 0=disabled)
StandardMetrics.ms_v_charge_limit_soc->SetValue( (float) MyConfig.GetParamValueInt("xnl", "suffsoc"), Percentage );
StandardMetrics.ms_v_charge_limit_range->SetValue( (float) MyConfig.GetParamValueInt("xnl", "suffrange"), Kilometers );
cfg_ev_request_port = MyConfig.GetParamValueInt("xnl", "cfg_ev_request_port");
cfg_limit_range_calc = MyConfig.GetParamValue("xnl", "suffrangecalc", DEFAULT_SUFF_RANGE_CALC);
cfg_allowed_rangedrop = MyConfig.GetParamValueInt("xnl", "rangedrop", DEFAULT_RANGEDROP);
cfg_allowed_socdrop = MyConfig.GetParamValueInt("xnl", "socdrop", DEFAULT_SOCDROP);
cfg_enable_autocharge = MyConfig.GetParamValueBool("xnl", "autocharge", DEFAULT_AUTOCHARGE_ENABLED);
//TODO nl_enable_write = MyConfig.GetParamValueBool("xnl", "canwrite", false);
cfg_enable_write = MyConfig.GetParamValueBool("xnl", "canwrite", false);
if (!cfg_enable_write) PollSetState(POLLSTATE_OFF);
}
// Takes care of setting all the state appropriate when the car is on
// or off.
//
void OvmsVehicleNissanLeaf::vehicle_nissanleaf_car_on(bool isOn)
{
if (isOn && !StandardMetrics.ms_v_env_on->AsBool())
{
// Log once that car is being turned on
ESP_LOGI(TAG,"CAR IS ON");
if (cfg_enable_write) PollSetState(POLLSTATE_ON);
// if a can message is found with the state of charge port this can removed
StandardMetrics.ms_v_door_chargeport->SetValue(false);
// Reset trip values
StandardMetrics.ms_v_bat_energy_recd->SetValue(0);
StandardMetrics.ms_v_bat_energy_used->SetValue(0);
m_cum_energy_recd_wh = 0.0f;
m_cum_energy_used_wh = 0.0f;
}
else if (!isOn && StandardMetrics.ms_v_env_on->AsBool())
{
// Log once that car is being turned off
ESP_LOGI(TAG,"CAR IS OFF");
//StandardMetrics.ms_v_env_awake->SetValue(false);
if (StandardMetrics.ms_v_charge_state->AsString() != "charging")
{
PollSetState(POLLSTATE_OFF);
}
}
// Always set this value to prevent it from going stale
StandardMetrics.ms_v_env_on->SetValue(isOn);
//PollSetState( (isOn) ? 1 : 0 ); now based on vehicle states
}
////////////////////////////////////////////////////////////////////////
// vehicle_nissanleaf_charger_status()
// Takes care of setting all the charger state bit when the charger
// switches on or off. Separate from vehicle_nissanleaf_poll1() to make
// it clearer what is going on.
//
void OvmsVehicleNissanLeaf::vehicle_nissanleaf_charger_status(ChargerStatus status)
{
bool fast_charge = false;
switch (status)
{
case CHARGER_STATUS_IDLE:
StandardMetrics.ms_v_charge_inprogress->SetValue(false);
StandardMetrics.ms_v_gen_inprogress->SetValue(false);
StandardMetrics.ms_v_charge_substate->SetValue("stopped");
StandardMetrics.ms_v_charge_state->SetValue("stopped");
StandardMetrics.ms_v_gen_substate->SetValue("stopped");
StandardMetrics.ms_v_gen_state->SetValue("stopped");
break;
case CHARGER_STATUS_PLUGGED_IN_TIMER_WAIT:
StandardMetrics.ms_v_door_chargeport->SetValue(true); //see 0x35d, can't use as only open signal
StandardMetrics.ms_v_charge_inprogress->SetValue(false);
if (StandardMetrics.ms_v_charge_pilot->AsBool())
{
StandardMetrics.ms_v_charge_state->SetValue("timerwait");
}
else
{
StandardMetrics.ms_v_charge_substate->SetValue("powerwait");
StandardMetrics.ms_v_charge_state->SetValue("stopped");
}
break;
case CHARGER_STATUS_QUICK_CHARGING:
fast_charge = true;
FALLTHROUGH;
case CHARGER_STATUS_CHARGING:
if (!StandardMetrics.ms_v_charge_inprogress->AsBool())
{
StandardMetrics.ms_v_charge_kwh->SetValue(0); // Reset charge kWh
m_cum_energy_charge_wh = 0.0f;
}
StandardMetrics.ms_v_door_chargeport->SetValue(true); //see 0x35d, can't use as only open signal
StandardMetrics.ms_v_charge_inprogress->SetValue(true);
StandardMetrics.ms_v_charge_type->SetValue(fast_charge ? "chademo" : "type1");
StdMetrics.ms_v_charge_mode->SetValue(fast_charge ? "performance" : "standard");
StandardMetrics.ms_v_charge_state->SetValue("charging");
if (cfg_enable_write) PollSetState(POLLSTATE_CHARGING);
// TODO only use battery current for Quick Charging, for regular charging
// we should return AC line current and voltage, not battery
// TODO does the leaf know the AC line current and voltage?
// TODO v3 supports negative values here, what happens if we send a negative charge current to a v2 client?
//if (StandardMetrics.ms_v_bat_current->AsFloat() < 0)
// {
// battery current can go negative when climate control draws more than
// is available from the charger. We're abusing the line current which
// is unsigned, so don't underflow it
//
// TODO quick charging can draw current from the vehicle
//StandardMetrics.ms_v_charge_current->SetValue(0);
// }
//else
// {
//StandardMetrics.ms_v_charge_current->SetValue(StandardMetrics.ms_v_bat_current->AsFloat());
// }
if (m_ZE0_charger)
{
StandardMetrics.ms_v_charge_voltage->SetValue(StandardMetrics.ms_v_bat_voltage->AsFloat());
StandardMetrics.ms_v_charge_current->SetValue(StandardMetrics.ms_v_bat_current->AsFloat());
}
break;
case CHARGER_STATUS_V2X:
if (!StandardMetrics.ms_v_gen_inprogress->AsBool())
{
StandardMetrics.ms_v_gen_kwh->SetValue(0); // Reset charge kWh
m_cum_energy_gen_wh = 0.0f;
}
StandardMetrics.ms_v_door_chargeport->SetValue(true); //see 0x35d, can't use as only open signal
StandardMetrics.ms_v_gen_inprogress->SetValue(true);
StandardMetrics.ms_v_gen_type->SetValue("chademo");
StdMetrics.ms_v_gen_mode->SetValue("standard");
StandardMetrics.ms_v_gen_substate->SetValue("onrequest");
StandardMetrics.ms_v_gen_state->SetValue("exporting");
if (cfg_enable_write) PollSetState(POLLSTATE_CHARGING);
break;
case CHARGER_STATUS_INTERRUPTED:
// Charging stopped during charge by user
StandardMetrics.ms_v_charge_current->SetValue(0);
if (m_ZE0_charger)
{
StandardMetrics.ms_v_charge_voltage->SetValue(0);
// TODO set this in ovms v2
// TODO the charger probably knows the line voltage, when we find where it's
// coded, don't zero it out when we're plugged in but not charging
}
if (m_AZE0_charger)
{
StandardMetrics.ms_v_charge_voltage->SetValue(0); //AZE0 doesn't know line voltage
}
StandardMetrics.ms_v_charge_inprogress->SetValue(false);
//StandardMetrics.ms_v_door_chargeport->SetValue(false);
StandardMetrics.ms_v_charge_state->SetValue("stopped");
PollSetState(POLLSTATE_OFF);
break;
case CHARGER_STATUS_FINISHED:
// Charging finished
StandardMetrics.ms_v_charge_current->SetValue(0);
if (m_ZE0_charger)
{
StandardMetrics.ms_v_charge_voltage->SetValue(0);
// TODO set this in ovms v2
// TODO? don't zero it out when we're plugged in but not charging
}
if (m_AZE0_charger)
{
StandardMetrics.ms_v_charge_voltage->SetValue(0); //AZE0 doesn't know line voltage
}
StandardMetrics.ms_v_charge_inprogress->SetValue(false);
//StandardMetrics.ms_v_door_chargeport->SetValue(false);
StandardMetrics.ms_v_charge_state->SetValue("done");
PollSetState(POLLSTATE_OFF);
break;
}
if (status != CHARGER_STATUS_CHARGING && status != CHARGER_STATUS_QUICK_CHARGING)
{
StandardMetrics.ms_v_charge_current->SetValue(0);
if (m_ZE0_charger)
{
// TODO? don't zero it out when we're plugged in but not charging
StandardMetrics.ms_v_charge_voltage->SetValue(0);
}
if (m_AZE0_charger)
{
StandardMetrics.ms_v_charge_voltage->SetValue(0); //AZE0 doesn't know line voltage
}
StandardMetrics.ms_v_charge_mode->SetValue("");
}
}
int OvmsVehicleNissanLeaf::GetNotifyChargeStateDelay(const char* state)
{
if (StandardMetrics.ms_m_monotonic->AsInt() < 10)
return 0; //avoid notify on boot triggered by setting delay
else return 8; //allow time for charger to handshake
}
void OvmsVehicleNissanLeaf::shell_obd_request(int verbosity, OvmsWriter* writer, OvmsCommand* cmd, int argc, const char* const* argv)
{
OvmsVehicleNissanLeaf* nl = GetInstance(writer);
const char* strbus = cmd->GetParent()->GetName();
if (!nl)
return;
if (!MyConfig.GetParamValueBool("xnl", "canwrite", false)) {
writer->puts("ERROR: canwrite not enabled");
return;
}
uint16_t txid = 0, rxid = 0;
uint32_t req = 0;
uint8_t bus = 2; // default to CAR can
string response;
// parse args:
string device = cmd->GetName();
if (device == "device") {
if (argc < 3) {
writer->puts("ERROR: too few args, need: txid rxid request");
return;
}
txid = strtol(argv[0], NULL, 16);
rxid = strtol(argv[1], NULL, 16);
req = strtol(argv[2], NULL, 16);
bus = (strcmp(strbus,"can1") == 0 ? 1 : 2);
} else {
if (argc < 1) {
writer->puts("ERROR: too few args, need: request");
return;
}
req = strtol(argv[0], NULL, 16);
if (device == "broadcast") {
txid = BROADCAST_TXID;
rxid = BROADCAST_RXID;
}
}
// validate request:
uint8_t mode = (req <= 0xffff) ? ((req & 0xff00) >> 8) : ((req & 0xff0000) >> 16);
if (mode != 0x01 && mode != 0x02 && mode != 0x09 &&
mode != 0x10 && mode != 0x1A && mode != 0x21 && mode != 0x22) {
writer->puts("ERROR: mode must be one of: 01, 02, 09, 10, 1A, 21 or 22");
return;
} else if (req > 0xffffff) {
writer->puts("ERROR: PID must be 8 or 16 bit");
return;
}
// execute request:
if (!nl->ObdRequest(txid, rxid, req, response, 3000, bus)) {
if (bus == 1) writer->puts("ERROR: timeout waiting for response on can1");
if (bus == 2) writer->puts("ERROR: timeout waiting for response on can2");
return;
}
// output response as hex dump:
writer->puts("Response:");
char *buf = NULL;
size_t rlen = response.size(), offset = 0;
do {
rlen = FormatHexDump(&buf, response.data() + offset, rlen, 16);
offset += 16;
writer->puts(buf ? buf : "-");
} while (rlen);
if (buf)
free(buf);
}
bool OvmsVehicleNissanLeaf::ObdRequest(uint16_t txid, uint16_t rxid, uint32_t request, string& response, int timeout_ms /*=3000*/, uint8_t bus)
{
OvmsMutexLock lock(&nl_obd_request);
// prepare single poll:
OvmsPoller::poll_pid_t poll[] = {
{ txid, rxid, 0, 0, { 1, 1, 1, 1 }, 0, ISOTP_STD },
POLL_LIST_END
};
if (request < 0x10000) {
poll[0].type = (request & 0xff00) >> 8;
poll[0].pid = request & 0xff;
} else {
poll[0].type = (request & 0xff0000) >> 16;
poll[0].pid = request & 0xffff;
}
poll[0].pollbus = bus;
// stop default polling:
PollSetPidList(NULL);
vTaskDelay(pdMS_TO_TICKS(100));
// clear rx semaphore, start single poll:
nl_obd_rxwait.Take(0);
nl_obd_rxbuf.clear();
PollSetPidList(poll);
// wait for response:
bool rxok = nl_obd_rxwait.Take(pdMS_TO_TICKS(timeout_ms));
if (rxok == pdTRUE) {
response = nl_obd_rxbuf;
nl_obd_rxbuf.clear();
}
// restore default polling:
nl_obd_rxwait.Give();
vTaskDelay(pdMS_TO_TICKS(100));
PollSetPidList(obdii_polls);
return (rxok == pdTRUE);
}
void OvmsVehicleNissanLeaf::PollReply_Battery(uint8_t reply_data[], uint16_t reply_len)
{
if (reply_len != 39 && // 24 KWh Leafs
reply_len != 41) // 30 KWh Leafs with Nissan BMS fix
{
ESP_LOGI(TAG, "PollReply_Battery: len=%d != 39 && != 41", reply_len);
return;
}
// > 0x79b 21 01
// < 0x7bb 61 01
// [ 0.. 5] 0000020d 0287
// [ 6..15] 00000363 ffffffff001c
// [16..23] 2af89a89 2e4b 03a4
// [24..31] 005c 269a 000ecf81
// [32..38] 0009d7b0 800001
//
// or
// > 0x79b 21 01
// < 0x7bb 61 01
// [ 0,, 5] fffffc4e 028a
// [ 6..15] ffffff46 ffffffff 1290
// [16..23] 2af88fcd 32de 038b
// [24..31] 005c 1f3d 000896c6
// [32..38] 000b3290 800001
// [39..40] 0000
uint16_t hx = (reply_data[26] << 8)
| reply_data[27];
m_hx->SetValue(hx / 100.0);
uint32_t ah10000 = (reply_data[33] << 16)
| (reply_data[34] << 8)
| reply_data[35];
float ah = ah10000 / 10000.0;
StandardMetrics.ms_v_bat_cac->SetValue(ah);
// there may be a way to get the SoH directly from the BMS, but for now
// divide by a configurable battery size
// - For 24 KWh : xnl.newCarAh = 66 (default)
// - For 30 KWh : xnl.newCarAh = 80 (i.e. shell command "config set xnl newCarAh 80")
float newCarAh = MyConfig.GetParamValueFloat("xnl", "newCarAh", GEN_1_NEW_CAR_AH);
float soh = ah / newCarAh * 100;
m_soh_new_car->SetValue(soh);
if (MyConfig.GetParamValueBool("xnl", "soh.newcar", false))
{
StandardMetrics.ms_v_bat_soh->SetValue(soh);
}
}
void OvmsVehicleNissanLeaf::PollReply_BMS_Volt(uint8_t reply_data[], uint16_t reply_len)
{
if (reply_len != 196)
{
ESP_LOGI(TAG, "PollReply_BMS_Volt: len=%d != 196", reply_len);
return;
}
// > 0x79b 21 02
// < 0x7bb 61 02
// [ 0..191]: Contains all 96 of the cell voltages, in volts/1000 (2 bytes per cell)
// [192,193]: Pack voltage, in volts/100
// [194,195]: Bus voltage, in volts/100
int i;
for(i=0; i<96; i++)
{
int millivolt = reply_data[i*2] << 8 | reply_data[i*2+1];
if (millivolt < 5000) //ignore invalid readings
{
BmsSetCellVoltage(i, millivolt / 1000.0);
}
}
}
void OvmsVehicleNissanLeaf::PollReply_BMS_Shunt(uint8_t reply_data[], uint16_t reply_len)
{
if (reply_len != 24)
{
ESP_LOGI(TAG, "PollReply_BMS_Shunt: len=%d != 24", reply_len);
return;
}
// > 0x79b 21 06
// < 0x7bb 61 06
// [ 0..23]: Contains all 96 of the cell shunts, where cell1=bit3, cell2=bit2, cell3=bit1, cell4=bit0 of byte0 etc
// referred to as shunt order 8421
std::bitset<96> balancing;
int i;
for(i=0; i<24; i++)
{
if ((reply_data[i] & 0x08) == 0x08) balancing.set(i*4 + 0);
if ((reply_data[i] & 0x04) == 0x04) balancing.set(i*4 + 1);
if ((reply_data[i] & 0x02) == 0x02) balancing.set(i*4 + 2);
if ((reply_data[i] & 0x01) == 0x01) balancing.set(i*4 + 3);
}
m_bms_balancing->SetValue(balancing.flip());
}
void OvmsVehicleNissanLeaf::PollReply_BMS_Temp(uint8_t reply_data[], uint16_t reply_len)
{
if (reply_len != 14)
{
ESP_LOGI(TAG, "PollReply_BMS_Temp: len=%d != 14", reply_len);
return;
}
// > 0x79b 21 04
// < 0x7bb 61 04
// [ 0, 1] pack 1 thermistor
// [ 2] pack 1 temp in degC
// [ 3, 4] pack 2 thermistor
// [ 5] pack 2 temp in degC
// [ 6, 7] pack 3 thermistor (unused)
// [ 8] pack 3 temp in degC (unused)
// [ 9,10] pack 4 thermistor
// [ 11] pack 4 temp in degC
// [ 12] pack 5 temp in degC
// [ 13] unknown; varies in interesting ways
// 14 bytes:
// 0 1 2 3 4 5 6 7 8 9 10 11 12 13
// 14 [02 51 0c 02 4d 0d ff ff ff 02 4d 0d 0c 00 ]
// 14 [02 52 0c 02 4e 0c ff ff ff 02 4e 0c 0c 00 ]
// 14 [02 57 0c 02 57 0c ff ff ff 02 58 0b 0b 00 ]
// 14 [02 5a 0b 02 59 0b ff ff ff 02 5a 0b 0b 00 ]
//
int thermistor[4];
int temp_int[6];
int i;
int out = 0;
for(i=0; i<4; i++)
{
thermistor[i] = reply_data[i*3] << 8 | reply_data[i*3+1];
temp_int[i] = reply_data[i*3+2];
if(thermistor[i] != 0xffff)
{
BmsSetCellTemperature(out++, -0.102 * (thermistor[i] - 710));
}
}
temp_int[i++] = reply_data[12];
temp_int[i++] = reply_data[13];
m_bms_thermistor->SetElemValues(0, 4, thermistor);
m_bms_temp_int->SetElemValues(0, 6, temp_int);
}
void OvmsVehicleNissanLeaf::PollReply_QC(uint8_t reply_data[], uint16_t reply_len)
{
if (reply_len != 2)
{
ESP_LOGI(TAG, "PollReply_QC: len=%d != 2", reply_len);
return;
}
// > 0x797 22 12 03
// < 0x79a 62 12 03
// [ 0..3] 00 0C 00 00
uint16_t count = reply_data[0] * 0x100 + reply_data[1];
if (count != 0xFFFF)
{
m_charge_count_qc->SetValue(count);
}
}
void OvmsVehicleNissanLeaf::PollReply_L0L1L2(uint8_t reply_data[], uint16_t reply_len)
{
if (reply_len != 2)
{
ESP_LOGI(TAG, "PollReply_L0L1L2: len=%d != 2", reply_len);
return;
}
// > 0x797 22 12 05
// < 0x79a 62 12 05
// [ 0..3] 00 5D 00 00
uint16_t count = reply_data[0] * 0x100 + reply_data[1];
if (count != 0xFFFF)
{
m_charge_count_l0l1l2->SetValue(count);
}
}
void OvmsVehicleNissanLeaf::PollReply_VIN(uint8_t reply_data[], uint16_t reply_len)
{
if (reply_len != 19)
{
ESP_LOGI(TAG, "PollReply_VIN: len=%d != 19", reply_len);
return;
}
// > 0x797 21 81
// < 0x79a 61 81
// [ 0..16] 53 4a 4e 46 41 41 5a 45 30 55 3X 3X 3X 3X 3X 3X 3X
// [17..18] 00 00
char buf[19];
strncpy(buf,(char*)reply_data,reply_len);
string strbuf(buf);
std::replace(strbuf.begin(), strbuf.end(), 0x1b, 0x20); // remove ESC character returned by AZE0 models
StandardMetrics.ms_v_vin->SetValue(strbuf); //(char*)reply_data
}
// Reassemble all pieces of a multi-frame reply.
void OvmsVehicleNissanLeaf::IncomingPollReply(const OvmsPoller::poll_job_t &job, uint8_t* data, uint8_t length) {
string& rxbuf = nl_obd_rxbuf;
// init / fill rx buffer:
if (job.mlframe == 0) {
rxbuf.clear();
rxbuf.reserve(length + job.mlremain);
}
rxbuf.append((char*)data, length);
if (job.mlremain)
return;
static uint8_t buf[MAX_POLL_DATA_LEN];
memcpy(buf, rxbuf.c_str(), rxbuf.size());
uint32_t id_pid = job.moduleid_rec<<16 | job.pid;
switch (id_pid)
{
case BMS_RXID<<16 | 0x01: // battery
PollReply_Battery(buf, rxbuf.size());
break;
case BMS_RXID<<16 | 0x02:
PollReply_BMS_Volt(buf, rxbuf.size());
break;
case BMS_RXID<<16 | 0x06:
PollReply_BMS_Shunt(buf, rxbuf.size());
break;
case BMS_RXID<<16 | 0x04:
PollReply_BMS_Temp(buf, rxbuf.size());
break;
case CHARGER_RXID<<16 | QC_COUNT_PID: // QC
PollReply_QC(buf, rxbuf.size());
break;
case CHARGER_RXID<<16 | L1L2_COUNT_PID: // L0/L1/L2
PollReply_L0L1L2(buf, rxbuf.size());
break;
case CHARGER_RXID<<16 | VIN_PID: // VIN
PollReply_VIN(buf, rxbuf.size());
break;
default:
ESP_LOGI(TAG, "IncomingPollReply: unknown reply module|pid=%#" PRIx32 " len=%d", id_pid, rxbuf.size());
break;
}
// single poll?
if (!nl_obd_rxwait.IsAvail()) {
// yes: stop poller & signal response
PollSetPidList(NULL);
nl_obd_rxwait.Give();
}
}
void OvmsVehicleNissanLeaf::IncomingFrameCan1(CAN_frame_t* p_frame)
{ // CAN1 is connected to EV-CAN
uint8_t *d = p_frame->data.u8;
switch (p_frame->MsgID)
{
case 0x1d4:
{ // additional charge status see https://github.com/dalathegreat/leaf_can_bus_messages
if ( (d[6] >> 7) == 0 && StandardMetrics.ms_v_charge_inprogress->AsBool() )
{
vehicle_nissanleaf_charger_status(CHARGER_STATUS_INTERRUPTED);
}
}
break;
case 0x1da:
{ // Motor and inverter messages
// Signed value, negative for reverse
// Values 0x7fff and 0x7ffe are seen during turning on of car
// http://productions.8dromeda.net/c55-leaf-inverter-protocol.html
// d[2] bits[0-2] used, unclear what bits[3-7] represent
// d[4] bit[7] can be 0 or 1
int16_t nl_mot_torq = (int16_t)( (d[2] & 0x07) << 8 | d[3] );
int16_t nl_rpm = (int16_t)( d[4] << 8 | d[5] );
// int16_t nl_inv_volt = (int16_t)( d[0] ) * 2; not currently used
if ( (d[2] & 0x04) == 0x04 ) // indicates negative value
{ // pad leading 1s for 2s complement signed
nl_mot_torq = nl_mot_torq | 0xf800;
}
if ( (d[4] & 0x40) == 0x40 ) // indicates negative value
{ // pad leading 1s for 2s complement signed
nl_rpm = nl_rpm | 0x8000;
}
nl_rpm = nl_rpm / 2;
nl_mot_torq = nl_mot_torq / 2; // guess based on rpm
StandardMetrics.ms_v_mot_rpm ->SetValue(nl_rpm);
// torque (Nm) to power (W) = 2 x pi / 60 * rpm * torque
StandardMetrics.ms_v_inv_power->SetValue(nl_rpm * nl_mot_torq * 0.10472 / 1000.0);
}
break;
case 0x1db:
{
if (m_MITM>0) { // This section used to stop charging upon request
unsigned char new1db[8];
memcpy(new1db, d, 8); // Store current 1DB message content
new1db[1] = (new1db[1] & 0xe0) | 2; // Charging Mode Stop Request
new1db[6] = (new1db[6] + 1) % 4; // Increment PRUN counter
new1db[7] = leafcrc(7, new1db); // Sign message with correct CRC
m_can1->WriteStandard(0x1db, 8, new1db); //Send completed CAN message
if (1==--m_MITM) MITMDisableTimer();
}
// sent by the LBC, measured inside the battery box
// current is 11 bit twos complement big endian starting at bit 0
int16_t nl_battery_current = ((int16_t) d[0] << 3) | (d[1] & 0xe0) >> 5;
if (nl_battery_current & 0x0400)
{
// negative so extend the sign bit
nl_battery_current |= 0xf800;
}
// sign updated to match standard metric definition where battery output is positive
float battery_current = -nl_battery_current / 2.0f;
// voltage is 10 bits unsigned big endian starting at bit 16
int16_t nl_battery_voltage = ((uint16_t) d[2] << 2) | (d[3] & 0xc0) >> 6;
float battery_voltage = nl_battery_voltage / 2.0f;
// Power (in kw) resulting from voltage and current
float battery_power = battery_voltage * battery_current / 1000.0f;
StandardMetrics.ms_v_bat_current->SetValue(battery_current, Amps);
StandardMetrics.ms_v_bat_voltage->SetValue(battery_voltage, Volts);
StandardMetrics.ms_v_bat_power->SetValue(battery_power, kW);
// Energy (in wh) from 10ms worth of power
float energy = battery_power * 10 / 3600;
if (energy < 0.0)
{
m_cum_energy_recd_wh -= energy;
m_cum_energy_charge_wh -= energy;
}
else
{
m_cum_energy_used_wh += energy;
m_cum_energy_gen_wh += energy;
}
// soc displayed on the instrument cluster
uint8_t soc = d[4] & 0x7f;
if (soc != 0x7f)
{
m_soc_instrument->SetValue(soc);
// we use this unless the user has opted otherwise
if (!MyConfig.GetParamValueBool("xnl", "soc.newcar", false))
{
StandardMetrics.ms_v_bat_soc->SetValue(soc);
}
}
}
break;
case 0x1dc:
{ // additional HVBAT messages see https://github.com/dalathegreat/leaf_can_bus_messages
// power into and out of battery while driving
m_battery_out_power_limit->SetValue( ( d[0] << 2 | d[1] >> 6 ) / 4.0 );
m_battery_in_power_limit->SetValue( ( (d[1] & 0x3f) << 2 | d[2] >> 4 ) / 4.0 );
// max allowed power into battery whilst charging, changes with SOC, temp etc
m_battery_chargerate_max->SetValue( ( (d[2] & 0x0f) << 6 | d[3] >> 2 ) / 10.0 );
}
break;
case 0x284:
{
// certain CAN bus activity counts as state "awake"
//StandardMetrics.ms_v_env_awake->SetValue(true);
uint16_t car_speed16 = d[4];
car_speed16 = car_speed16 << 8;
car_speed16 = car_speed16 | d[5];
// this ratio determined by comparing with the dashboard speedometer
// it is approximately correct and converts to km/h on my car with km/h speedo
StandardMetrics.ms_v_pos_speed->SetValue(car_speed16 / 92);
}
break;
case 0x380:
{
m_ZE0_charger = true;
// Gen 1 ZE0 Charger
// see https://github.com/dalathegreat/leaf_can_bus_messages
float max_charge_power = ( (d[2] & 0x01) << 8 | d[3]) * 100; // in W
float ac_voltage = ( ((d[5] & 0x07) << 8 | ( d[6] & 0xFC)) >> 2) * 2; // in V
ac_voltage = ac_voltage + 70; //Offset with 70V
StandardMetrics.ms_v_charge_voltage->SetValue(ac_voltage);
if (StandardMetrics.ms_v_charge_voltage->AsFloat() > 0)
{
StandardMetrics.ms_v_charge_climit->SetValue(max_charge_power / StandardMetrics.ms_v_charge_voltage->AsFloat());
}
}
break;
case 0x390:
{
m_AZE0_charger = true;
// Gen 2 AZE0 Charger
// see https://github.com/dalathegreat/leaf_can_bus_messages
float charge_power = ( (d[0] & 0x01) << 8 | d[1] ) * 100; // in W
float max_charge_power = ( (d[5] & 0x01) << 8 | d[6] ) * 100; // in W
bool ac_state = (d[3] & 0x20) == 0x20; // indicates ac charge state
bool qc_state = (d[4] & 0x40) == 0x40; // indicates chademo relay state
bool vg_state = (d[0] >> 4 == 0x09); // indicates v2x exporting state
if ( (qc_state || ac_state) && !vg_state )
StandardMetrics.ms_v_charge_pilot->SetValue(true);