forked from vedderb/bldc
-
Notifications
You must be signed in to change notification settings - Fork 0
/
comm_can.c
1513 lines (1324 loc) · 39.8 KB
/
comm_can.c
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
/*
Copyright 2016 - 2020 Benjamin Vedder [email protected]
This file is part of the VESC firmware.
The VESC firmware is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
The VESC firmware 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 General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#include <string.h>
#include <math.h>
#include "comm_can.h"
#include "ch.h"
#include "hal.h"
#include "stm32f4xx_conf.h"
#include "datatypes.h"
#include "buffer.h"
#include "mc_interface.h"
#include "timeout.h"
#include "commands.h"
#include "app.h"
#include "crc.h"
#include "packet.h"
#include "hw.h"
#include "canard_driver.h"
#include "encoder.h"
#include "utils.h"
#include "mempools.h"
#include "shutdown.h"
// Settings
#define RX_FRAMES_SIZE 100
#define RX_BUFFER_SIZE PACKET_MAX_PL_LEN
#if CAN_ENABLE
// Threads
static THD_WORKING_AREA(cancom_read_thread_wa, 512);
static THD_WORKING_AREA(cancom_process_thread_wa, 4096);
static THD_WORKING_AREA(cancom_status_thread_wa, 512);
static THD_FUNCTION(cancom_read_thread, arg);
static THD_FUNCTION(cancom_status_thread, arg);
static THD_FUNCTION(cancom_process_thread, arg);
#ifdef HW_HAS_DUAL_MOTORS
static THD_FUNCTION(cancom_status_internal_thread, arg);
static THD_WORKING_AREA(cancom_status_internal_thread_wa, 512);
#endif
static mutex_t can_mtx;
static mutex_t can_rx_mtx;
static uint8_t rx_buffer[RX_BUFFER_SIZE];
static unsigned int rx_buffer_last_id;
static CANRxFrame rx_frames[RX_FRAMES_SIZE];
static int rx_frame_read;
static int rx_frame_write;
static thread_t *process_tp = 0;
static thread_t *ping_tp = 0;
#endif
// Variables
static can_status_msg stat_msgs[CAN_STATUS_MSGS_TO_STORE];
static can_status_msg_2 stat_msgs_2[CAN_STATUS_MSGS_TO_STORE];
static can_status_msg_3 stat_msgs_3[CAN_STATUS_MSGS_TO_STORE];
static can_status_msg_4 stat_msgs_4[CAN_STATUS_MSGS_TO_STORE];
static can_status_msg_5 stat_msgs_5[CAN_STATUS_MSGS_TO_STORE];
static unsigned int detect_all_foc_res_index = 0;
static int8_t detect_all_foc_res[50];
/*
* 500KBaud, automatic wakeup, automatic recover
* from abort mode.
* See section 22.7.7 on the STM32 reference manual.
*/
static CANConfig cancfg = {
CAN_MCR_ABOM | CAN_MCR_AWUM | CAN_MCR_TXFP,
CAN_BTR_SJW(3) | CAN_BTR_TS2(2) |
CAN_BTR_TS1(9) | CAN_BTR_BRP(5)
};
// Private functions
static void set_timing(int brp, int ts1, int ts2);
#if CAN_ENABLE
static void send_packet_wrapper(unsigned char *data, unsigned int len);
static void decode_msg(uint32_t eid, uint8_t *data8, int len, bool is_replaced);
static void send_status1(uint8_t id, bool replace);
static void send_status2(uint8_t id, bool replace);
static void send_status3(uint8_t id, bool replace);
static void send_status4(uint8_t id, bool replace);
static void send_status5(uint8_t id, bool replace);
#endif
// Function pointers
static void(*sid_callback)(uint32_t id, uint8_t *data, uint8_t len) = 0;
static void(*eid_callback)(uint32_t id, uint8_t *data, uint8_t len) = 0;
void comm_can_init(void) {
for (int i = 0;i < CAN_STATUS_MSGS_TO_STORE;i++) {
stat_msgs[i].id = -1;
stat_msgs_2[i].id = -1;
stat_msgs_3[i].id = -1;
stat_msgs_4[i].id = -1;
}
#if CAN_ENABLE
rx_frame_read = 0;
rx_frame_write = 0;
chMtxObjectInit(&can_mtx);
chMtxObjectInit(&can_rx_mtx);
palSetPadMode(HW_CANRX_PORT, HW_CANRX_PIN,
PAL_MODE_ALTERNATE(HW_CAN_GPIO_AF) |
PAL_STM32_OTYPE_PUSHPULL |
PAL_STM32_OSPEED_MID1);
palSetPadMode(HW_CANTX_PORT, HW_CANTX_PIN,
PAL_MODE_ALTERNATE(HW_CAN_GPIO_AF) |
PAL_STM32_OTYPE_PUSHPULL |
PAL_STM32_OSPEED_MID1);
canStart(&HW_CAN_DEV, &cancfg);
canard_driver_init();
chThdCreateStatic(cancom_read_thread_wa, sizeof(cancom_read_thread_wa), NORMALPRIO + 1,
cancom_read_thread, NULL);
chThdCreateStatic(cancom_status_thread_wa, sizeof(cancom_status_thread_wa), NORMALPRIO,
cancom_status_thread, NULL);
chThdCreateStatic(cancom_process_thread_wa, sizeof(cancom_process_thread_wa), NORMALPRIO,
cancom_process_thread, NULL);
#ifdef HW_HAS_DUAL_MOTORS
chThdCreateStatic(cancom_status_internal_thread_wa, sizeof(cancom_status_internal_thread_wa),
NORMALPRIO, cancom_status_internal_thread, NULL);
#endif
#endif
}
void comm_can_set_baud(CAN_BAUD baud) {
switch (baud) {
case CAN_BAUD_125K: set_timing(15, 14, 4); break;
case CAN_BAUD_250K: set_timing(7, 14, 4); break;
case CAN_BAUD_500K: set_timing(5, 9, 2); break;
case CAN_BAUD_1M: set_timing(2, 9, 2); break;
case CAN_BAUD_10K: set_timing(299, 10, 1); break;
case CAN_BAUD_20K: set_timing(149, 10, 1); break;
case CAN_BAUD_50K: set_timing(59, 10, 1); break;
case CAN_BAUD_75K: set_timing(39, 10, 1); break;
default: break;
}
}
/**
* Transmit CAN packet with extended ID.
*
* @param id
* EID
*
* @param data
* Data
*
* @param len
* Length of data, max 8 bytes.
*
* @param replace
* Process packets for motor2 directly instead of sending them. Unused
* on single motor hardware.
*/
void comm_can_transmit_eid_replace(uint32_t id, const uint8_t *data, uint8_t len, bool replace) {
if (len > 8) {
len = 8;
}
#if CAN_ENABLE
#ifdef HW_HAS_DUAL_MOTORS
if (app_get_configuration()->can_mode == CAN_MODE_VESC) {
if (replace && ((id & 0xFF) == utils_second_motor_id() ||
(id & 0xFF) == app_get_configuration()->controller_id)) {
uint8_t data_tmp[10];
memcpy(data_tmp, data, len);
decode_msg(id, data_tmp, len, true);
return;
}
}
#else
(void)replace;
#endif
CANTxFrame txmsg;
txmsg.IDE = CAN_IDE_EXT;
txmsg.EID = id;
txmsg.RTR = CAN_RTR_DATA;
txmsg.DLC = len;
memcpy(txmsg.data8, data, len);
chMtxLock(&can_mtx);
canTransmit(&HW_CAN_DEV, CAN_ANY_MAILBOX, &txmsg, MS2ST(5));
chMtxUnlock(&can_mtx);
#else
(void)id;
(void)data;
(void)len;
(void)replace;
#endif
}
void comm_can_transmit_eid(uint32_t id, const uint8_t *data, uint8_t len) {
comm_can_transmit_eid_replace(id, data, len, true);
}
void comm_can_transmit_sid(uint32_t id, uint8_t *data, uint8_t len) {
if (len > 8) {
len = 8;
}
#if CAN_ENABLE
CANTxFrame txmsg;
txmsg.IDE = CAN_IDE_STD;
txmsg.SID = id;
txmsg.RTR = CAN_RTR_DATA;
txmsg.DLC = len;
memcpy(txmsg.data8, data, len);
chMtxLock(&can_mtx);
canTransmit(&HW_CAN_DEV, CAN_ANY_MAILBOX, &txmsg, MS2ST(5));
chMtxUnlock(&can_mtx);
#else
(void)id;
(void)data;
(void)len;
#endif
}
/**
* Set function to be called when standard CAN frames are received.
*
* @param p_func
* Pointer to the function.
*/
void comm_can_set_sid_rx_callback(void (*p_func)(uint32_t id, uint8_t *data, uint8_t len)) {
sid_callback = p_func;
}
/**
* Set function to be called when extended CAN frames are received. Will only be called when
* the CAN mode is CAN_MODE_COMM_BRIDGE.
*
* @param p_func
* Pointer to the function.
*/
void comm_can_set_eid_rx_callback(void (*p_func)(uint32_t id, uint8_t *data, uint8_t len)) {
eid_callback = p_func;
}
/**
* Send a buffer up to RX_BUFFER_SIZE bytes as fragments. If the buffer is 6 bytes or less
* it will be sent in a single CAN frame, otherwise it will be split into
* several frames.
*
* @param controller_id
* The controller id to send to.
*
* @param data
* The payload.
*
* @param len
* The payload length.
*
* @param send
* 0: Packet goes to commands_process_packet of receiver
* 1: Packet goes to commands_send_packet of receiver
* 2: Packet goes to commands_process and send function is set to null
* so that no reply is sent back.
*/
void comm_can_send_buffer(uint8_t controller_id, uint8_t *data, unsigned int len, uint8_t send) {
uint8_t send_buffer[8];
if (len <= 6) {
uint32_t ind = 0;
send_buffer[ind++] = app_get_configuration()->controller_id;
send_buffer[ind++] = send;
memcpy(send_buffer + ind, data, len);
ind += len;
comm_can_transmit_eid(controller_id |
((uint32_t)CAN_PACKET_PROCESS_SHORT_BUFFER << 8), send_buffer, ind);
} else {
unsigned int end_a = 0;
for (unsigned int i = 0;i < len;i += 7) {
if (i > 255) {
break;
}
end_a = i + 7;
uint8_t send_len = 7;
send_buffer[0] = i;
if ((i + 7) <= len) {
memcpy(send_buffer + 1, data + i, send_len);
} else {
send_len = len - i;
memcpy(send_buffer + 1, data + i, send_len);
}
comm_can_transmit_eid(controller_id |
((uint32_t)CAN_PACKET_FILL_RX_BUFFER << 8), send_buffer, send_len + 1);
}
for (unsigned int i = end_a;i < len;i += 6) {
uint8_t send_len = 6;
send_buffer[0] = i >> 8;
send_buffer[1] = i & 0xFF;
if ((i + 6) <= len) {
memcpy(send_buffer + 2, data + i, send_len);
} else {
send_len = len - i;
memcpy(send_buffer + 2, data + i, send_len);
}
comm_can_transmit_eid(controller_id |
((uint32_t)CAN_PACKET_FILL_RX_BUFFER_LONG << 8), send_buffer, send_len + 2);
}
uint32_t ind = 0;
send_buffer[ind++] = app_get_configuration()->controller_id;
send_buffer[ind++] = send;
send_buffer[ind++] = len >> 8;
send_buffer[ind++] = len & 0xFF;
unsigned short crc = crc16(data, len);
send_buffer[ind++] = (uint8_t)(crc >> 8);
send_buffer[ind++] = (uint8_t)(crc & 0xFF);
comm_can_transmit_eid(controller_id |
((uint32_t)CAN_PACKET_PROCESS_RX_BUFFER << 8), send_buffer, ind++);
}
}
void comm_can_set_duty(uint8_t controller_id, float duty) {
int32_t send_index = 0;
uint8_t buffer[4];
buffer_append_int32(buffer, (int32_t)(duty * 100000.0), &send_index);
comm_can_transmit_eid(controller_id |
((uint32_t)CAN_PACKET_SET_DUTY << 8), buffer, send_index);
}
void comm_can_set_current(uint8_t controller_id, float current) {
int32_t send_index = 0;
uint8_t buffer[4];
buffer_append_int32(buffer, (int32_t)(current * 1000.0), &send_index);
comm_can_transmit_eid(controller_id |
((uint32_t)CAN_PACKET_SET_CURRENT << 8), buffer, send_index);
}
void comm_can_set_current_brake(uint8_t controller_id, float current) {
int32_t send_index = 0;
uint8_t buffer[4];
buffer_append_int32(buffer, (int32_t)(current * 1000.0), &send_index);
comm_can_transmit_eid(controller_id |
((uint32_t)CAN_PACKET_SET_CURRENT_BRAKE << 8), buffer, send_index);
}
void comm_can_set_rpm(uint8_t controller_id, float rpm) {
int32_t send_index = 0;
uint8_t buffer[4];
buffer_append_int32(buffer, (int32_t)rpm, &send_index);
comm_can_transmit_eid(controller_id |
((uint32_t)CAN_PACKET_SET_RPM << 8), buffer, send_index);
}
void comm_can_set_pos(uint8_t controller_id, float pos) {
int32_t send_index = 0;
uint8_t buffer[4];
buffer_append_int32(buffer, (int32_t)(pos * 1000000.0), &send_index);
comm_can_transmit_eid(controller_id |
((uint32_t)CAN_PACKET_SET_POS << 8), buffer, send_index);
}
/**
* Set current relative to the minimum and maximum current limits.
*
* @param controller_id
* The ID of the VESC to set the current on.
*
* @param current_rel
* The relative current value, range [-1.0 1.0]
*/
void comm_can_set_current_rel(uint8_t controller_id, float current_rel) {
int32_t send_index = 0;
uint8_t buffer[4];
buffer_append_float32(buffer, current_rel, 1e5, &send_index);
comm_can_transmit_eid(controller_id |
((uint32_t)CAN_PACKET_SET_CURRENT_REL << 8), buffer, send_index);
}
/**
* Set brake current relative to the minimum current limit.
*
* @param controller_id
* The ID of the VESC to set the current on.
*
* @param current_rel
* The relative current value, range [0.0 1.0]
*/
void comm_can_set_current_brake_rel(uint8_t controller_id, float current_rel) {
int32_t send_index = 0;
uint8_t buffer[4];
buffer_append_float32(buffer, current_rel, 1e5, &send_index);
comm_can_transmit_eid(controller_id |
((uint32_t)CAN_PACKET_SET_CURRENT_BRAKE_REL << 8), buffer, send_index);
}
/**
* Set handbrake current.
*
* @param controller_id
* The ID of the VESC to set the handbrake current on.
*
* @param current_rel
* The handbrake current value
*/
void comm_can_set_handbrake(uint8_t controller_id, float current) {
int32_t send_index = 0;
uint8_t buffer[4];
buffer_append_float32(buffer, current, 1e3, &send_index);
comm_can_transmit_eid(controller_id |
((uint32_t)CAN_PACKET_SET_CURRENT_HANDBRAKE << 8), buffer, send_index);
}
/**
* Set handbrake current relative to the minimum current limit.
*
* @param controller_id
* The ID of the VESC to set the handbrake current on.
*
* @param current_rel
* The relative handbrake current value, range [0.0 1.0]
*/
void comm_can_set_handbrake_rel(uint8_t controller_id, float current_rel) {
int32_t send_index = 0;
uint8_t buffer[4];
buffer_append_float32(buffer, current_rel, 1e5, &send_index);
comm_can_transmit_eid(controller_id |
((uint32_t)CAN_PACKET_SET_CURRENT_HANDBRAKE_REL << 8), buffer, send_index);
}
/**
* Check if a VESC on the CAN-bus responds.
*
* @param controller_id
* The ID of the VESC.
*
* @return
* True for success, false otherwise.
*/
bool comm_can_ping(uint8_t controller_id) {
#if CAN_ENABLE
if (app_get_configuration()->can_mode != CAN_MODE_VESC) {
return false;
}
#ifdef HW_HAS_DUAL_MOTORS
if (controller_id == app_get_configuration()->controller_id) {
return false;
}
#endif
ping_tp = chThdGetSelfX();
chEvtGetAndClearEvents(ALL_EVENTS);
uint8_t buffer[1];
buffer[0] = app_get_configuration()->controller_id;
comm_can_transmit_eid(controller_id |
((uint32_t)CAN_PACKET_PING << 8), buffer, 1);
int ret = chEvtWaitAnyTimeout(1 << 29, MS2ST(10));
ping_tp = 0;
return ret != 0;
#else
(void)controller_id;
return 0;
#endif
}
/**
* Detect and apply FOC settings.
*
* @param controller_id
* The ID of the VESC.
*
* @param activate_status_msgs
* Activate CAN status messages on the target VESC on success.
*
* @param max_power_loss
* Maximum accepted power losses.
*/
void comm_can_detect_apply_all_foc(uint8_t controller_id, bool activate_status_msgs, float max_power_loss) {
int32_t send_index = 0;
uint8_t buffer[6];
buffer[send_index++] = app_get_configuration()->controller_id;
buffer[send_index++] = activate_status_msgs;
buffer_append_float32(buffer, max_power_loss, 1e3, &send_index);
comm_can_transmit_eid(controller_id |
((uint32_t)CAN_PACKET_DETECT_APPLY_ALL_FOC << 8), buffer, send_index);
}
/**
* Update current limits on VESC on CAN-bus.
*
* @param controller_id
* ID of the VESC.
*
* @param store
* Store parameters in emulated EEPROM (FLASH).
*
* @param min
* Minimum current (negative value).
*
* @param max
* Maximum current.
*/
void comm_can_conf_current_limits(uint8_t controller_id,
bool store, float min, float max) {
int32_t send_index = 0;
uint8_t buffer[8];
buffer_append_float32(buffer, min, 1e3, &send_index);
buffer_append_float32(buffer, max, 1e3, &send_index);
comm_can_transmit_eid(controller_id |
((uint32_t)(store ? CAN_PACKET_CONF_STORE_CURRENT_LIMITS :
CAN_PACKET_CONF_CURRENT_LIMITS) << 8), buffer, send_index);
}
/**
* Update input current limits on VESC on CAN-bus.
*
* @param controller_id
* ID of the VESC.
*
* @param store
* Store parameters in emulated EEPROM (FLASH).
*
* @param min
* Minimum current (negative value).
*
* @param max
* Maximum current.
*/
void comm_can_conf_current_limits_in(uint8_t controller_id,
bool store, float min, float max) {
int32_t send_index = 0;
uint8_t buffer[8];
buffer_append_float32(buffer, min, 1e3, &send_index);
buffer_append_float32(buffer, max, 1e3, &send_index);
comm_can_transmit_eid(controller_id |
((uint32_t)(store ? CAN_PACKET_CONF_STORE_CURRENT_LIMITS_IN :
CAN_PACKET_CONF_CURRENT_LIMITS_IN) << 8), buffer, send_index);
}
/**
* Update FOC ERPM settings on VESC on CAN-bus.
*
* @param controller_id
* ID of the VESC.
*
* @param store
* Store parameters in emulated EEPROM (FLASH).
*
* @param foc_openloop_rpm
* Run in openloop below this ERPM in sensorless mode.
*
* @param foc_sl_erpm
* Use sensors below this ERPM in sensored mode.
*/
void comm_can_conf_foc_erpms(uint8_t controller_id,
bool store, float foc_openloop_rpm, float foc_sl_erpm) {
int32_t send_index = 0;
uint8_t buffer[8];
buffer_append_float32(buffer, foc_openloop_rpm, 1e3, &send_index);
buffer_append_float32(buffer, foc_sl_erpm, 1e3, &send_index);
comm_can_transmit_eid(controller_id |
((uint32_t)(store ? CAN_PACKET_CONF_STORE_FOC_ERPMS :
CAN_PACKET_CONF_FOC_ERPMS) << 8), buffer, send_index);
}
int comm_can_detect_all_foc_res(unsigned int index) {
if (index < detect_all_foc_res_index) {
return detect_all_foc_res[detect_all_foc_res_index];
} else {
return -999;
}
}
int comm_can_detect_all_foc_res_size(void) {
return detect_all_foc_res_index;
}
void comm_can_detect_all_foc_res_clear(void) {
detect_all_foc_res_index = 0;
}
void comm_can_conf_battery_cut(uint8_t controller_id,
bool store, float start, float end) {
int32_t send_index = 0;
uint8_t buffer[8];
buffer_append_float32(buffer, start, 1e3, &send_index);
buffer_append_float32(buffer, end, 1e3, &send_index);
comm_can_transmit_eid(controller_id |
((uint32_t)(store ? CAN_PACKET_CONF_STORE_BATTERY_CUT :
CAN_PACKET_CONF_BATTERY_CUT) << 8), buffer, send_index);
}
void comm_can_shutdown(uint8_t controller_id) {
int32_t send_index = 0;
uint8_t buffer[8];
comm_can_transmit_eid(controller_id |
((uint32_t)(CAN_PACKET_SHUTDOWN) << 8), buffer, send_index);
}
/**
* Get status message by index.
*
* @param index
* Index in the array
*
* @return
* The message or 0 for an invalid index.
*/
can_status_msg *comm_can_get_status_msg_index(int index) {
if (index < CAN_STATUS_MSGS_TO_STORE) {
return &stat_msgs[index];
} else {
return 0;
}
}
/**
* Get status message by id.
*
* @param id
* Id of the controller that sent the status message.
*
* @return
* The message or 0 for an invalid id.
*/
can_status_msg *comm_can_get_status_msg_id(int id) {
for (int i = 0;i < CAN_STATUS_MSGS_TO_STORE;i++) {
if (stat_msgs[i].id == id) {
return &stat_msgs[i];
}
}
return 0;
}
/**
* Get status message 2 by index.
*
* @param index
* Index in the array
*
* @return
* The message or 0 for an invalid index.
*/
can_status_msg_2 *comm_can_get_status_msg_2_index(int index) {
if (index < CAN_STATUS_MSGS_TO_STORE) {
return &stat_msgs_2[index];
} else {
return 0;
}
}
/**
* Get status message 2 by id.
*
* @param id
* Id of the controller that sent the status message.
*
* @return
* The message or 0 for an invalid id.
*/
can_status_msg_2 *comm_can_get_status_msg_2_id(int id) {
for (int i = 0;i < CAN_STATUS_MSGS_TO_STORE;i++) {
if (stat_msgs_2[i].id == id) {
return &stat_msgs_2[i];
}
}
return 0;
}
/**
* Get status message 3 by index.
*
* @param index
* Index in the array
*
* @return
* The message or 0 for an invalid index.
*/
can_status_msg_3 *comm_can_get_status_msg_3_index(int index) {
if (index < CAN_STATUS_MSGS_TO_STORE) {
return &stat_msgs_3[index];
} else {
return 0;
}
}
/**
* Get status message 3 by id.
*
* @param id
* Id of the controller that sent the status message.
*
* @return
* The message or 0 for an invalid id.
*/
can_status_msg_3 *comm_can_get_status_msg_3_id(int id) {
for (int i = 0;i < CAN_STATUS_MSGS_TO_STORE;i++) {
if (stat_msgs_3[i].id == id) {
return &stat_msgs_3[i];
}
}
return 0;
}
/**
* Get status message 4 by index.
*
* @param index
* Index in the array
*
* @return
* The message or 0 for an invalid index.
*/
can_status_msg_4 *comm_can_get_status_msg_4_index(int index) {
if (index < CAN_STATUS_MSGS_TO_STORE) {
return &stat_msgs_4[index];
} else {
return 0;
}
}
/**
* Get status message 4 by id.
*
* @param id
* Id of the controller that sent the status message.
*
* @return
* The message or 0 for an invalid id.
*/
can_status_msg_4 *comm_can_get_status_msg_4_id(int id) {
for (int i = 0;i < CAN_STATUS_MSGS_TO_STORE;i++) {
if (stat_msgs_4[i].id == id) {
return &stat_msgs_4[i];
}
}
return 0;
}
/**
* Get status message 5 by index.
*
* @param index
* Index in the array
*
* @return
* The message or 0 for an invalid index.
*/
can_status_msg_5 *comm_can_get_status_msg_5_index(int index) {
if (index < CAN_STATUS_MSGS_TO_STORE) {
return &stat_msgs_5[index];
} else {
return 0;
}
}
/**
* Get status message 5 by id.
*
* @param id
* Id of the controller that sent the status message.
*
* @return
* The message or 0 for an invalid id.
*/
can_status_msg_5 *comm_can_get_status_msg_5_id(int id) {
for (int i = 0;i < CAN_STATUS_MSGS_TO_STORE;i++) {
if (stat_msgs_5[i].id == id) {
return &stat_msgs_5[i];
}
}
return 0;
}
CANRxFrame *comm_can_get_rx_frame(void) {
#if CAN_ENABLE
chMtxLock(&can_rx_mtx);
if (rx_frame_read != rx_frame_write) {
CANRxFrame *res = &rx_frames[rx_frame_read++];
if (rx_frame_read == RX_FRAMES_SIZE) {
rx_frame_read = 0;
}
chMtxUnlock(&can_rx_mtx);
return res;
} else {
chMtxUnlock(&can_rx_mtx);
return 0;
}
#else
return 0;
#endif
}
#if CAN_ENABLE
static THD_FUNCTION(cancom_read_thread, arg) {
(void)arg;
chRegSetThreadName("CAN read");
event_listener_t el;
CANRxFrame rxmsg;
chEvtRegister(&HW_CAN_DEV.rxfull_event, &el, 0);
while(!chThdShouldTerminateX()) {
// Feed watchdog
timeout_feed_WDT(THREAD_CANBUS);
if (chEvtWaitAnyTimeout(ALL_EVENTS, MS2ST(10)) == 0) {
continue;
}
msg_t result = canReceive(&HW_CAN_DEV, CAN_ANY_MAILBOX, &rxmsg, TIME_IMMEDIATE);
while (result == MSG_OK) {
chMtxLock(&can_rx_mtx);
rx_frames[rx_frame_write++] = rxmsg;
if (rx_frame_write == RX_FRAMES_SIZE) {
rx_frame_write = 0;
}
chMtxUnlock(&can_rx_mtx);
chEvtSignal(process_tp, (eventmask_t) 1);
result = canReceive(&HW_CAN_DEV, CAN_ANY_MAILBOX, &rxmsg, TIME_IMMEDIATE);
}
}
chEvtUnregister(&HW_CAN_DEV.rxfull_event, &el);
}
static THD_FUNCTION(cancom_process_thread, arg) {
(void)arg;
chRegSetThreadName("CAN process");
process_tp = chThdGetSelfX();
for(;;) {
chEvtWaitAny((eventmask_t)1);
if (app_get_configuration()->can_mode == CAN_MODE_UAVCAN) {
continue;
} else if (app_get_configuration()->can_mode == CAN_MODE_COMM_BRIDGE) {
CANRxFrame *rxmsg_tmp;
while ((rxmsg_tmp = comm_can_get_rx_frame()) != 0) {
CANRxFrame rxmsg = *rxmsg_tmp;
commands_fwd_can_frame(rxmsg.DLC, rxmsg.data8,
rxmsg.IDE == CAN_IDE_EXT ? rxmsg.EID : rxmsg.SID,
rxmsg.IDE == CAN_IDE_EXT);
if (rxmsg.IDE == CAN_IDE_STD) {
if (sid_callback) {
sid_callback(rxmsg.SID, rxmsg.data8, rxmsg.DLC);
}
} else {
if (eid_callback) {
eid_callback(rxmsg.EID, rxmsg.data8, rxmsg.DLC);
}
}
}
continue;
}
CANRxFrame *rxmsg_tmp;
while ((rxmsg_tmp = comm_can_get_rx_frame()) != 0) {
CANRxFrame rxmsg = *rxmsg_tmp;
if (rxmsg.IDE == CAN_IDE_EXT) {
decode_msg(rxmsg.EID, rxmsg.data8, rxmsg.DLC, false);
} else {
if (sid_callback) {
sid_callback(rxmsg.SID, rxmsg.data8, rxmsg.DLC);
}
}
}
}
}
#ifdef HW_HAS_DUAL_MOTORS
/*
* This thread sends all status messages and uses the internal decoer. That
* way the second motor always show up on the CAN-bus.
*/
static THD_FUNCTION(cancom_status_internal_thread, arg) {
(void)arg;
chRegSetThreadName("CAN stat loc");
mc_interface_select_motor_thread(2);
for (;;) {
send_status1(utils_second_motor_id(), true);
send_status2(utils_second_motor_id(), true);
send_status3(utils_second_motor_id(), true);
send_status4(utils_second_motor_id(), true);
send_status5(utils_second_motor_id(), true);
chThdSleepMilliseconds(2);
}
}
#endif
static THD_FUNCTION(cancom_status_thread, arg) {
(void)arg;
chRegSetThreadName("CAN status");
for(;;) {
const app_configuration *conf = app_get_configuration();
if (conf->can_mode == CAN_MODE_VESC) {
if (conf->send_can_status == CAN_STATUS_1 ||
conf->send_can_status == CAN_STATUS_1_2 ||
conf->send_can_status == CAN_STATUS_1_2_3 ||
conf->send_can_status == CAN_STATUS_1_2_3_4 ||
conf->send_can_status == CAN_STATUS_1_2_3_4_5) {
mc_interface_select_motor_thread(1);
send_status1(conf->controller_id, false);
#ifdef HW_HAS_DUAL_MOTORS
mc_interface_select_motor_thread(2);
send_status1(utils_second_motor_id(), false);
#endif
}
if (conf->send_can_status == CAN_STATUS_1_2 ||
conf->send_can_status == CAN_STATUS_1_2_3||
conf->send_can_status == CAN_STATUS_1_2_3_4 ||
conf->send_can_status == CAN_STATUS_1_2_3_4_5) {
mc_interface_select_motor_thread(1);
send_status2(conf->controller_id, false);
#ifdef HW_HAS_DUAL_MOTORS
mc_interface_select_motor_thread(2);
send_status2(utils_second_motor_id(), false);
#endif
}
if (conf->send_can_status == CAN_STATUS_1_2_3 ||
conf->send_can_status == CAN_STATUS_1_2_3_4 ||
conf->send_can_status == CAN_STATUS_1_2_3_4_5) {
mc_interface_select_motor_thread(1);
send_status3(conf->controller_id, false);
#ifdef HW_HAS_DUAL_MOTORS
mc_interface_select_motor_thread(2);
send_status3(utils_second_motor_id(), false);
#endif
}
if (conf->send_can_status == CAN_STATUS_1_2_3_4 ||
conf->send_can_status == CAN_STATUS_1_2_3_4_5) {
mc_interface_select_motor_thread(1);
send_status4(conf->controller_id, false);
#ifdef HW_HAS_DUAL_MOTORS
mc_interface_select_motor_thread(2);
send_status4(utils_second_motor_id(), false);
#endif
}
if (conf->send_can_status == CAN_STATUS_1_2_3_4_5) {
mc_interface_select_motor_thread(1);
send_status5(conf->controller_id, false);
#ifdef HW_HAS_DUAL_MOTORS
mc_interface_select_motor_thread(2);
send_status5(utils_second_motor_id(), false);
#endif
}
}
systime_t sleep_time = CH_CFG_ST_FREQUENCY / conf->send_can_status_rate_hz;
if (sleep_time == 0) {