forked from vedderb/bldc
-
Notifications
You must be signed in to change notification settings - Fork 0
/
datatypes.h
790 lines (725 loc) · 16.5 KB
/
datatypes.h
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
/*
Copyright 2016 - 2019 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/>.
*/
#ifndef DATATYPES_H_
#define DATATYPES_H_
#include <stdint.h>
#include <stdbool.h>
#include "ch.h"
// Data types
typedef enum {
MC_STATE_OFF = 0,
MC_STATE_DETECTING,
MC_STATE_RUNNING,
MC_STATE_FULL_BRAKE,
} mc_state;
typedef enum {
PWM_MODE_NONSYNCHRONOUS_HISW = 0, // This mode is not recommended
PWM_MODE_SYNCHRONOUS, // The recommended and most tested mode
PWM_MODE_BIPOLAR // Some glitches occasionally, can kill MOSFETs
} mc_pwm_mode;
typedef enum {
COMM_MODE_INTEGRATE = 0,
COMM_MODE_DELAY
} mc_comm_mode;
typedef enum {
SENSOR_MODE_SENSORLESS = 0,
SENSOR_MODE_SENSORED,
SENSOR_MODE_HYBRID
} mc_sensor_mode;
typedef enum {
FOC_SENSOR_MODE_SENSORLESS = 0,
FOC_SENSOR_MODE_ENCODER,
FOC_SENSOR_MODE_HALL
} mc_foc_sensor_mode;
// Auxiliary output mode
typedef enum {
OUT_AUX_MODE_OFF = 0,
OUT_AUX_MODE_ON_AFTER_2S,
OUT_AUX_MODE_ON_AFTER_5S,
OUT_AUX_MODE_ON_AFTER_10S
} out_aux_mode;
// General purpose drive output mode
typedef enum {
GPD_OUTPUT_MODE_NONE = 0,
GPD_OUTPUT_MODE_MODULATION,
GPD_OUTPUT_MODE_VOLTAGE,
GPD_OUTPUT_MODE_CURRENT
} gpd_output_mode;
typedef enum {
MOTOR_TYPE_BLDC = 0,
MOTOR_TYPE_DC,
MOTOR_TYPE_FOC,
MOTOR_TYPE_GPD
} mc_motor_type;
typedef enum {
FAULT_CODE_NONE = 0,
FAULT_CODE_OVER_VOLTAGE,
FAULT_CODE_UNDER_VOLTAGE,
FAULT_CODE_DRV,
FAULT_CODE_ABS_OVER_CURRENT,
FAULT_CODE_OVER_TEMP_FET,
FAULT_CODE_OVER_TEMP_MOTOR,
FAULT_CODE_GATE_DRIVER_OVER_VOLTAGE,
FAULT_CODE_GATE_DRIVER_UNDER_VOLTAGE,
FAULT_CODE_MCU_UNDER_VOLTAGE,
FAULT_CODE_BOOTING_FROM_WATCHDOG_RESET,
FAULT_CODE_ENCODER_SPI,
FAULT_CODE_ENCODER_SINCOS_BELOW_MIN_AMPLITUDE,
FAULT_CODE_ENCODER_SINCOS_ABOVE_MAX_AMPLITUDE,
FAULT_CODE_FLASH_CORRUPTION,
FAULT_CODE_HIGH_OFFSET_CURRENT_SENSOR_1,
FAULT_CODE_HIGH_OFFSET_CURRENT_SENSOR_2,
FAULT_CODE_HIGH_OFFSET_CURRENT_SENSOR_3,
FAULT_CODE_UNBALANCED_CURRENTS
} mc_fault_code;
typedef enum {
CONTROL_MODE_DUTY = 0,
CONTROL_MODE_SPEED,
CONTROL_MODE_CURRENT,
CONTROL_MODE_CURRENT_BRAKE,
CONTROL_MODE_POS,
CONTROL_MODE_HANDBRAKE,
CONTROL_MODE_OPENLOOP,
CONTROL_MODE_OPENLOOP_PHASE,
CONTROL_MODE_OPENLOOP_DUTY,
CONTROL_MODE_OPENLOOP_DUTY_PHASE,
CONTROL_MODE_NONE
} mc_control_mode;
typedef enum {
DISP_POS_MODE_NONE = 0,
DISP_POS_MODE_INDUCTANCE,
DISP_POS_MODE_OBSERVER,
DISP_POS_MODE_ENCODER,
DISP_POS_MODE_PID_POS,
DISP_POS_MODE_PID_POS_ERROR,
DISP_POS_MODE_ENCODER_OBSERVER_ERROR
} disp_pos_mode;
typedef enum {
SENSOR_PORT_MODE_HALL = 0,
SENSOR_PORT_MODE_ABI,
SENSOR_PORT_MODE_AS5047_SPI,
SENSOR_PORT_MODE_AD2S1205,
SENSOR_PORT_MODE_SINCOS
} sensor_port_mode;
typedef struct {
float cycle_int_limit;
float cycle_int_limit_running;
float cycle_int_limit_max;
float comm_time_sum;
float comm_time_sum_min_rpm;
int32_t comms;
float time_at_comm;
} mc_rpm_dep_struct;
typedef enum {
DRV8301_OC_LIMIT = 0,
DRV8301_OC_LATCH_SHUTDOWN,
DRV8301_OC_REPORT_ONLY,
DRV8301_OC_DISABLED
} drv8301_oc_mode;
typedef enum {
DEBUG_SAMPLING_OFF = 0,
DEBUG_SAMPLING_NOW,
DEBUG_SAMPLING_START,
DEBUG_SAMPLING_TRIGGER_START,
DEBUG_SAMPLING_TRIGGER_FAULT,
DEBUG_SAMPLING_TRIGGER_START_NOSEND,
DEBUG_SAMPLING_TRIGGER_FAULT_NOSEND,
DEBUG_SAMPLING_SEND_LAST_SAMPLES
} debug_sampling_mode;
typedef enum {
CAN_BAUD_125K = 0,
CAN_BAUD_250K,
CAN_BAUD_500K,
CAN_BAUD_1M
} CAN_BAUD;
typedef enum {
BATTERY_TYPE_LIION_3_0__4_2,
BATTERY_TYPE_LIIRON_2_6__3_6,
BATTERY_TYPE_LEAD_ACID
} BATTERY_TYPE;
typedef struct {
// Switching and drive
mc_pwm_mode pwm_mode;
mc_comm_mode comm_mode;
mc_motor_type motor_type;
mc_sensor_mode sensor_mode;
// Limits
float l_current_max;
float l_current_min;
float l_in_current_max;
float l_in_current_min;
float l_abs_current_max;
float l_min_erpm;
float l_max_erpm;
float l_erpm_start;
float l_max_erpm_fbrake;
float l_max_erpm_fbrake_cc;
float l_min_vin;
float l_max_vin;
float l_battery_cut_start;
float l_battery_cut_end;
bool l_slow_abs_current;
float l_temp_fet_start;
float l_temp_fet_end;
float l_temp_motor_start;
float l_temp_motor_end;
float l_temp_accel_dec;
float l_min_duty;
float l_max_duty;
float l_watt_max;
float l_watt_min;
float l_current_max_scale;
float l_current_min_scale;
// Overridden limits (Computed during runtime)
float lo_current_max;
float lo_current_min;
float lo_in_current_max;
float lo_in_current_min;
float lo_current_motor_max_now;
float lo_current_motor_min_now;
// Sensorless (bldc)
float sl_min_erpm;
float sl_min_erpm_cycle_int_limit;
float sl_max_fullbreak_current_dir_change;
float sl_cycle_int_limit;
float sl_phase_advance_at_br;
float sl_cycle_int_rpm_br;
float sl_bemf_coupling_k;
// Hall sensor
int8_t hall_table[8];
float hall_sl_erpm;
// FOC
float foc_current_kp;
float foc_current_ki;
float foc_f_sw;
float foc_dt_us;
float foc_encoder_offset;
bool foc_encoder_inverted;
float foc_encoder_ratio;
float foc_encoder_sin_offset;
float foc_encoder_sin_gain;
float foc_encoder_cos_offset;
float foc_encoder_cos_gain;
float foc_encoder_sincos_filter_constant;
float foc_motor_l;
float foc_motor_r;
float foc_motor_flux_linkage;
float foc_observer_gain;
float foc_observer_gain_slow;
float foc_pll_kp;
float foc_pll_ki;
float foc_duty_dowmramp_kp;
float foc_duty_dowmramp_ki;
float foc_openloop_rpm;
float foc_sl_openloop_hyst;
float foc_sl_openloop_time;
float foc_sl_d_current_duty;
float foc_sl_d_current_factor;
mc_foc_sensor_mode foc_sensor_mode;
uint8_t foc_hall_table[8];
float foc_sl_erpm;
bool foc_sample_v0_v7;
bool foc_sample_high_current;
float foc_sat_comp;
bool foc_temp_comp;
float foc_temp_comp_base_temp;
float foc_current_filter_const;
// GPDrive
int gpd_buffer_notify_left;
int gpd_buffer_interpol;
float gpd_current_filter_const;
float gpd_current_kp;
float gpd_current_ki;
// Speed PID
float s_pid_kp;
float s_pid_ki;
float s_pid_kd;
float s_pid_kd_filter;
float s_pid_min_erpm;
bool s_pid_allow_braking;
// Pos PID
float p_pid_kp;
float p_pid_ki;
float p_pid_kd;
float p_pid_kd_filter;
float p_pid_ang_div;
// Current controller
float cc_startup_boost_duty;
float cc_min_current;
float cc_gain;
float cc_ramp_step_max;
// Misc
int32_t m_fault_stop_time_ms;
float m_duty_ramp_step;
float m_current_backoff_gain;
uint32_t m_encoder_counts;
sensor_port_mode m_sensor_port_mode;
bool m_invert_direction;
drv8301_oc_mode m_drv8301_oc_mode;
int m_drv8301_oc_adj;
float m_bldc_f_sw_min;
float m_bldc_f_sw_max;
float m_dc_f_sw;
float m_ntc_motor_beta;
out_aux_mode m_out_aux_mode;
// Setup info
uint8_t si_motor_poles;
float si_gear_ratio;
float si_wheel_diameter;
BATTERY_TYPE si_battery_type;
int si_battery_cells;
float si_battery_ah;
} mc_configuration;
// Applications to use
typedef enum {
APP_NONE = 0,
APP_PPM,
APP_ADC,
APP_UART,
APP_PPM_UART,
APP_ADC_UART,
APP_NUNCHUK,
APP_NRF,
APP_CUSTOM
} app_use;
// Throttle curve mode
typedef enum {
THR_EXP_EXPO = 0,
THR_EXP_NATURAL,
THR_EXP_POLY
} thr_exp_mode;
// PPM control types
typedef enum {
PPM_CTRL_TYPE_NONE = 0,
PPM_CTRL_TYPE_CURRENT,
PPM_CTRL_TYPE_CURRENT_NOREV,
PPM_CTRL_TYPE_CURRENT_NOREV_BRAKE,
PPM_CTRL_TYPE_DUTY,
PPM_CTRL_TYPE_DUTY_NOREV,
PPM_CTRL_TYPE_PID,
PPM_CTRL_TYPE_PID_NOREV,
PPM_CTRL_TYPE_CURRENT_BRAKE_REV_HYST
} ppm_control_type;
typedef struct {
ppm_control_type ctrl_type;
float pid_max_erpm;
float hyst;
float pulse_start;
float pulse_end;
float pulse_center;
bool median_filter;
bool safe_start;
float throttle_exp;
float throttle_exp_brake;
thr_exp_mode throttle_exp_mode;
float ramp_time_pos;
float ramp_time_neg;
bool multi_esc;
bool tc;
float tc_max_diff;
float max_erpm_for_dir;
} ppm_config;
// ADC control types
typedef enum {
ADC_CTRL_TYPE_NONE = 0,
ADC_CTRL_TYPE_CURRENT,
ADC_CTRL_TYPE_CURRENT_REV_CENTER,
ADC_CTRL_TYPE_CURRENT_REV_BUTTON,
ADC_CTRL_TYPE_CURRENT_REV_BUTTON_BRAKE_ADC,
ADC_CTRL_TYPE_CURRENT_REV_BUTTON_BRAKE_CENTER,
ADC_CTRL_TYPE_CURRENT_NOREV_BRAKE_CENTER,
ADC_CTRL_TYPE_CURRENT_NOREV_BRAKE_BUTTON,
ADC_CTRL_TYPE_CURRENT_NOREV_BRAKE_ADC,
ADC_CTRL_TYPE_DUTY,
ADC_CTRL_TYPE_DUTY_REV_CENTER,
ADC_CTRL_TYPE_DUTY_REV_BUTTON,
ADC_CTRL_TYPE_PID,
ADC_CTRL_TYPE_PID_REV_CENTER,
ADC_CTRL_TYPE_PID_REV_BUTTON
} adc_control_type;
typedef struct {
adc_control_type ctrl_type;
float hyst;
float voltage_start;
float voltage_end;
float voltage_center;
float voltage2_start;
float voltage2_end;
bool use_filter;
bool safe_start;
bool cc_button_inverted;
bool rev_button_inverted;
bool voltage_inverted;
bool voltage2_inverted;
float throttle_exp;
float throttle_exp_brake;
thr_exp_mode throttle_exp_mode;
float ramp_time_pos;
float ramp_time_neg;
bool multi_esc;
bool tc;
float tc_max_diff;
uint32_t update_rate_hz;
} adc_config;
// Nunchuk control types
typedef enum {
CHUK_CTRL_TYPE_NONE = 0,
CHUK_CTRL_TYPE_CURRENT,
CHUK_CTRL_TYPE_CURRENT_NOREV
} chuk_control_type;
typedef struct {
chuk_control_type ctrl_type;
float hyst;
float ramp_time_pos;
float ramp_time_neg;
float stick_erpm_per_s_in_cc;
float throttle_exp;
float throttle_exp_brake;
thr_exp_mode throttle_exp_mode;
bool multi_esc;
bool tc;
float tc_max_diff;
} chuk_config;
// NRF Datatypes
typedef enum {
NRF_SPEED_250K = 0,
NRF_SPEED_1M,
NRF_SPEED_2M
} NRF_SPEED;
typedef enum {
NRF_POWER_M18DBM = 0,
NRF_POWER_M12DBM,
NRF_POWER_M6DBM,
NRF_POWER_0DBM,
NRF_POWER_OFF
} NRF_POWER;
typedef enum {
NRF_AW_3 = 0,
NRF_AW_4,
NRF_AW_5
} NRF_AW;
typedef enum {
NRF_CRC_DISABLED = 0,
NRF_CRC_1B,
NRF_CRC_2B
} NRF_CRC;
typedef enum {
NRF_RETR_DELAY_250US = 0,
NRF_RETR_DELAY_500US,
NRF_RETR_DELAY_750US,
NRF_RETR_DELAY_1000US,
NRF_RETR_DELAY_1250US,
NRF_RETR_DELAY_1500US,
NRF_RETR_DELAY_1750US,
NRF_RETR_DELAY_2000US,
NRF_RETR_DELAY_2250US,
NRF_RETR_DELAY_2500US,
NRF_RETR_DELAY_2750US,
NRF_RETR_DELAY_3000US,
NRF_RETR_DELAY_3250US,
NRF_RETR_DELAY_3500US,
NRF_RETR_DELAY_3750US,
NRF_RETR_DELAY_4000US
} NRF_RETR_DELAY;
typedef struct {
NRF_SPEED speed;
NRF_POWER power;
NRF_CRC crc_type;
NRF_RETR_DELAY retry_delay;
unsigned char retries;
unsigned char channel;
unsigned char address[3];
bool send_crc_ack;
} nrf_config;
// CAN status modes
typedef enum {
CAN_STATUS_DISABLED = 0,
CAN_STATUS_1,
CAN_STATUS_1_2,
CAN_STATUS_1_2_3,
CAN_STATUS_1_2_3_4,
CAN_STATUS_1_2_3_4_5
} CAN_STATUS_MODE;
typedef struct {
// Settings
uint8_t controller_id;
uint32_t timeout_msec;
float timeout_brake_current;
CAN_STATUS_MODE send_can_status;
uint32_t send_can_status_rate_hz;
CAN_BAUD can_baud_rate;
bool pairing_done;
bool permanent_uart_enabled;
// UAVCAN
bool uavcan_enable;
uint8_t uavcan_esc_index;
// Application to use
app_use app_to_use;
// PPM application settings
ppm_config app_ppm_conf;
// ADC application settings
adc_config app_adc_conf;
// UART application settings
uint32_t app_uart_baudrate;
// Nunchuk application settings
chuk_config app_chuk_conf;
// NRF application settings
nrf_config app_nrf_conf;
} app_configuration;
// Communication commands
typedef enum {
COMM_FW_VERSION = 0,
COMM_JUMP_TO_BOOTLOADER,
COMM_ERASE_NEW_APP,
COMM_WRITE_NEW_APP_DATA,
COMM_GET_VALUES,
COMM_SET_DUTY,
COMM_SET_CURRENT,
COMM_SET_CURRENT_BRAKE,
COMM_SET_RPM,
COMM_SET_POS,
COMM_SET_HANDBRAKE,
COMM_SET_DETECT,
COMM_SET_SERVO_POS,
COMM_SET_MCCONF,
COMM_GET_MCCONF,
COMM_GET_MCCONF_DEFAULT,
COMM_SET_APPCONF,
COMM_GET_APPCONF,
COMM_GET_APPCONF_DEFAULT,
COMM_SAMPLE_PRINT,
COMM_TERMINAL_CMD,
COMM_PRINT,
COMM_ROTOR_POSITION,
COMM_EXPERIMENT_SAMPLE,
COMM_DETECT_MOTOR_PARAM,
COMM_DETECT_MOTOR_R_L,
COMM_DETECT_MOTOR_FLUX_LINKAGE,
COMM_DETECT_ENCODER,
COMM_DETECT_HALL_FOC,
COMM_REBOOT,
COMM_ALIVE,
COMM_GET_DECODED_PPM,
COMM_GET_DECODED_ADC,
COMM_GET_DECODED_CHUK,
COMM_FORWARD_CAN,
COMM_SET_CHUCK_DATA,
COMM_CUSTOM_APP_DATA,
COMM_NRF_START_PAIRING,
COMM_GPD_SET_FSW,
COMM_GPD_BUFFER_NOTIFY,
COMM_GPD_BUFFER_SIZE_LEFT,
COMM_GPD_FILL_BUFFER,
COMM_GPD_OUTPUT_SAMPLE,
COMM_GPD_SET_MODE,
COMM_GPD_FILL_BUFFER_INT8,
COMM_GPD_FILL_BUFFER_INT16,
COMM_GPD_SET_BUFFER_INT_SCALE,
COMM_GET_VALUES_SETUP,
COMM_SET_MCCONF_TEMP,
COMM_SET_MCCONF_TEMP_SETUP,
COMM_GET_VALUES_SELECTIVE,
COMM_GET_VALUES_SETUP_SELECTIVE,
COMM_EXT_NRF_PRESENT,
COMM_EXT_NRF_ESB_SET_CH_ADDR,
COMM_EXT_NRF_ESB_SEND_DATA,
COMM_EXT_NRF_ESB_RX_DATA,
COMM_EXT_NRF_SET_ENABLED,
COMM_DETECT_MOTOR_FLUX_LINKAGE_OPENLOOP,
COMM_DETECT_APPLY_ALL_FOC,
COMM_JUMP_TO_BOOTLOADER_ALL_CAN,
COMM_ERASE_NEW_APP_ALL_CAN,
COMM_WRITE_NEW_APP_DATA_ALL_CAN,
COMM_PING_CAN,
COMM_APP_DISABLE_OUTPUT,
COMM_TERMINAL_CMD_SYNC,
COMM_GET_IMU_DATA,
COMM_BM_CONNECT,
COMM_BM_ERASE_FLASH_ALL,
COMM_BM_WRITE_FLASH,
COMM_BM_REBOOT,
COMM_BM_DISCONNECT
} COMM_PACKET_ID;
// CAN commands
typedef enum {
CAN_PACKET_SET_DUTY = 0,
CAN_PACKET_SET_CURRENT,
CAN_PACKET_SET_CURRENT_BRAKE,
CAN_PACKET_SET_RPM,
CAN_PACKET_SET_POS,
CAN_PACKET_FILL_RX_BUFFER,
CAN_PACKET_FILL_RX_BUFFER_LONG,
CAN_PACKET_PROCESS_RX_BUFFER,
CAN_PACKET_PROCESS_SHORT_BUFFER,
CAN_PACKET_STATUS,
CAN_PACKET_SET_CURRENT_REL,
CAN_PACKET_SET_CURRENT_BRAKE_REL,
CAN_PACKET_SET_CURRENT_HANDBRAKE,
CAN_PACKET_SET_CURRENT_HANDBRAKE_REL,
CAN_PACKET_STATUS_2,
CAN_PACKET_STATUS_3,
CAN_PACKET_STATUS_4,
CAN_PACKET_PING,
CAN_PACKET_PONG,
CAN_PACKET_DETECT_APPLY_ALL_FOC,
CAN_PACKET_DETECT_APPLY_ALL_FOC_RES,
CAN_PACKET_CONF_CURRENT_LIMITS,
CAN_PACKET_CONF_STORE_CURRENT_LIMITS,
CAN_PACKET_CONF_CURRENT_LIMITS_IN,
CAN_PACKET_CONF_STORE_CURRENT_LIMITS_IN,
CAN_PACKET_CONF_FOC_ERPMS,
CAN_PACKET_CONF_STORE_FOC_ERPMS,
CAN_PACKET_STATUS_5
} CAN_PACKET_ID;
// Logged fault data
typedef struct {
mc_fault_code fault;
float current;
float current_filtered;
float voltage;
float gate_driver_voltage;
float duty;
float rpm;
int tacho;
int cycles_running;
int tim_val_samp;
int tim_current_samp;
int tim_top;
int comm_step;
float temperature;
int drv8301_faults;
} fault_data;
// External LED state
typedef enum {
LED_EXT_OFF = 0,
LED_EXT_NORMAL,
LED_EXT_BRAKE,
LED_EXT_TURN_LEFT,
LED_EXT_TURN_RIGHT,
LED_EXT_BRAKE_TURN_LEFT,
LED_EXT_BRAKE_TURN_RIGHT,
LED_EXT_BATT
} LED_EXT_STATE;
typedef struct {
int js_x;
int js_y;
int acc_x;
int acc_y;
int acc_z;
bool bt_c;
bool bt_z;
bool rev_has_state;
bool is_rev;
} chuck_data;
typedef struct {
int id;
systime_t rx_time;
float rpm;
float current;
float duty;
} can_status_msg;
typedef struct {
int id;
systime_t rx_time;
float amp_hours;
float amp_hours_charged;
} can_status_msg_2;
typedef struct {
int id;
systime_t rx_time;
float watt_hours;
float watt_hours_charged;
} can_status_msg_3;
typedef struct {
int id;
systime_t rx_time;
float temp_fet;
float temp_motor;
float current_in;
float pid_pos_now;
} can_status_msg_4;
typedef struct {
int id;
systime_t rx_time;
float v_in;
int32_t tacho_value;
} can_status_msg_5;
typedef struct {
uint8_t js_x;
uint8_t js_y;
bool bt_c;
bool bt_z;
bool bt_push;
bool rev_has_state;
bool is_rev;
float vbat;
} mote_state;
typedef enum {
MOTE_PACKET_BATT_LEVEL = 0,
MOTE_PACKET_BUTTONS,
MOTE_PACKET_ALIVE,
MOTE_PACKET_FILL_RX_BUFFER,
MOTE_PACKET_FILL_RX_BUFFER_LONG,
MOTE_PACKET_PROCESS_RX_BUFFER,
MOTE_PACKET_PROCESS_SHORT_BUFFER,
MOTE_PACKET_PAIRING_INFO
} MOTE_PACKET;
typedef struct {
float v_in;
float temp_mos1;
float temp_mos2;
float temp_mos3;
float temp_mos4;
float temp_mos5;
float temp_mos6;
float temp_pcb;
float current_motor;
float current_in;
float rpm;
float duty_now;
float amp_hours;
float amp_hours_charged;
float watt_hours;
float watt_hours_charged;
int tachometer;
int tachometer_abs;
mc_fault_code fault_code;
} mc_values;
typedef enum {
NRF_PAIR_STARTED = 0,
NRF_PAIR_OK,
NRF_PAIR_FAIL
} NRF_PAIR_RES;
// Orientation data
typedef struct {
float q0;
float q1;
float q2;
float q3;
float integralFBx;
float integralFBy;
float integralFBz;
float accMagP;
int initialUpdateDone;
} ATTITUDE_INFO;
// Custom EEPROM variables
typedef union {
uint32_t as_u32;
int32_t as_i32;
float as_float;
} eeprom_var;
#define EEPROM_VARS_HW 64
#define EEPROM_VARS_CUSTOM 64
#endif /* DATATYPES_H_ */