+
+// BLDCMotor( pole_pairs )
+BLDCMotor motor = BLDCMotor(11);
+// BLDCDriver( pin_pwmA, pin_pwmB, pin_pwmC, enable (optional) )
+BLDCDriver3PWM driver = BLDCDriver3PWM(9, 10, 11, 8);
+// Encoder(pin_A, pin_B, CPR)
+Encoder encoder = Encoder(2, 3, 2048);
+// channel A and B callbacks
+void doA(){encoder.handleA();}
+void doB(){encoder.handleB();}
+
+
+void setup() {
+ // initialize encoder hardware
+ encoder.init();
+ // hardware interrupt enable
+ encoder.enableInterrupts(doA, doB);
+ // link the motor to the sensor
+ motor.linkSensor(&encoder);
+
+ // power supply voltage [V]
+ driver.voltage_power_supply = 12;
+ // initialise driver hardware
+ driver.init();
+ // link driver
+ motor.linkDriver(&driver);
+
+ // set control loop type to be used
+ motor.controller = MotionControlType::velocity;
+ // initialize motor
+ motor.init();
+
+ // align encoder and start FOC
+ motor.initFOC();
+}
+
+void loop() {
+ // FOC algorithm function
+ motor.loopFOC();
+
+ // velocity control loop function
+ // setting the target velocity or 2rad/s
+ motor.move(2);
+}
+```
+You can find more details in the [SimpleFOC documentation](https://docs.simplefoc.com/).
+
+## Example projects
+Here are some of the *Simple**FOC**library* and *Simple**FOC**Shield* application examples.
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+## Citing the *SimpleFOC*
+
+We are very happy that *Simple**FOC**library* has been used as a component of several research project and has made its way to several scientific papers. We are hoping that this trend is going to continue as the project matures and becomes more robust!
+A short resume paper about *Simple**FOC*** has been published in the Journal of Open Source Software:
+
+ SimpleFOC: A Field Oriented Control (FOC) Library for Controlling Brushless Direct Current (BLDC) and Stepper Motors.
+ A. Skuric, HS. Bank, R. Unger, O. Williams, D. González-Reyes
+Journal of Open Source Software, 7(74), 4232, https://doi.org/10.21105/joss.04232
+
+
+If you are interested in citing *Simple**FOC**library* or some other component of *Simple**FOC**project* in your research, we suggest you to cite our paper:
+
+```bib
+@article{simplefoc2022,
+ doi = {10.21105/joss.04232},
+ url = {https://doi.org/10.21105/joss.04232},
+ year = {2022},
+ publisher = {The Open Journal},
+ volume = {7},
+ number = {74},
+ pages = {4232},
+ author = {Antun Skuric and Hasan Sinan Bank and Richard Unger and Owen Williams and David González-Reyes},
+ title = {SimpleFOC: A Field Oriented Control (FOC) Library for Controlling Brushless Direct Current (BLDC) and Stepper Motors},
+ journal = {Journal of Open Source Software}
+}
+
+```
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/hardware_specific_examples/B_G431B_ESC1/B_G431B_ESC1.ino b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/hardware_specific_examples/B_G431B_ESC1/B_G431B_ESC1.ino
new file mode 100644
index 0000000..f1eeefd
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/hardware_specific_examples/B_G431B_ESC1/B_G431B_ESC1.ino
@@ -0,0 +1,114 @@
+/**
+ * B-G431B-ESC1 position motion control example with encoder
+ *
+ */
+#include
+
+// Motor instance
+BLDCMotor motor = BLDCMotor(11);
+BLDCDriver6PWM driver = BLDCDriver6PWM(A_PHASE_UH, A_PHASE_UL, A_PHASE_VH, A_PHASE_VL, A_PHASE_WH, A_PHASE_WL);
+// Gain calculation shown at https://community.simplefoc.com/t/b-g431b-esc1-current-control/521/21
+LowsideCurrentSense currentSense = LowsideCurrentSense(0.003f, -64.0f/7.0f, A_OP1_OUT, A_OP2_OUT, A_OP3_OUT);
+
+
+// encoder instance
+Encoder encoder = Encoder(A_HALL2, A_HALL3, 2048, A_HALL1);
+
+// Interrupt routine intialisation
+// channel A and B callbacks
+void doA(){encoder.handleA();}
+void doB(){encoder.handleB();}
+void doIndex(){encoder.handleIndex();}
+
+// instantiate the commander
+Commander command = Commander(Serial);
+void doTarget(char* cmd) { command.motion(&motor, cmd); }
+
+void setup() {
+
+ // use monitoring with serial
+ Serial.begin(115200);
+ // enable more verbose output for debugging
+ // comment out if not needed
+ SimpleFOCDebug::enable(&Serial);
+
+ // initialize encoder sensor hardware
+ encoder.init();
+ encoder.enableInterrupts(doA, doB);
+
+ // link the motor to the sensor
+ motor.linkSensor(&encoder);
+
+ // driver config
+ // power supply voltage [V]
+ driver.voltage_power_supply = 12;
+ driver.init();
+ // link the motor and the driver
+ motor.linkDriver(&driver);
+ // link current sense and the driver
+ currentSense.linkDriver(&driver);
+
+ // current sensing
+ currentSense.init();
+ // no need for aligning
+ currentSense.skip_align = true;
+ motor.linkCurrentSense(¤tSense);
+
+ // aligning voltage [V]
+ motor.voltage_sensor_align = 3;
+ // index search velocity [rad/s]
+ motor.velocity_index_search = 3;
+
+ // set motion control loop to be used
+ motor.controller = MotionControlType::velocity;
+
+ // contoller configuration
+ // default parameters in defaults.h
+
+ // velocity PI controller parameters
+ motor.PID_velocity.P = 0.2;
+ motor.PID_velocity.I = 20;
+ // default voltage_power_supply
+ motor.voltage_limit = 6;
+ // jerk control using voltage voltage ramp
+ // default value is 300 volts per sec ~ 0.3V per millisecond
+ motor.PID_velocity.output_ramp = 1000;
+
+ // velocity low pass filtering time constant
+ motor.LPF_velocity.Tf = 0.01;
+
+ // angle P controller
+ motor.P_angle.P = 20;
+ // maximal velocity of the position control
+ motor.velocity_limit = 4;
+
+ // comment out if not needed
+ motor.useMonitoring(Serial);
+
+ // initialize motor
+ motor.init();
+ // align encoder and start FOC
+ motor.initFOC();
+
+ // add target command T
+ command.add('T', doTarget, "target angle");
+
+ Serial.println(F("Motor ready."));
+ Serial.println(F("Set the target angle using serial terminal:"));
+ _delay(1000);
+}
+
+void loop() {
+ // main FOC algorithm function
+ motor.loopFOC();
+
+ // Motion control function
+ motor.move();
+
+ // function intended to be used with serial plotter to monitor motor variables
+ // significantly slowing the execution down!!!!
+ // motor.monitor();
+
+ // user communication
+ command.run();
+}
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/hardware_specific_examples/B_G431B_ESC1/build_opt.h b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/hardware_specific_examples/B_G431B_ESC1/build_opt.h
new file mode 100644
index 0000000..6f547ec
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/hardware_specific_examples/B_G431B_ESC1/build_opt.h
@@ -0,0 +1 @@
+-DHAL_OPAMP_MODULE_ENABLED
\ No newline at end of file
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/hardware_specific_examples/Bluepill_examples/encoder/bluepill_position_control/bluepill_position_control.ino b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/hardware_specific_examples/Bluepill_examples/encoder/bluepill_position_control/bluepill_position_control.ino
new file mode 100644
index 0000000..b29e45d
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/hardware_specific_examples/Bluepill_examples/encoder/bluepill_position_control/bluepill_position_control.ino
@@ -0,0 +1,119 @@
+/**
+ *
+ * STM32 Bluepill position motion control example with encoder
+ *
+ * The same example can be ran with any STM32 board - just make sure that put right pin numbers.
+ *
+ */
+#include
+
+// Motor instance
+BLDCMotor motor = BLDCMotor(11);
+// BLDCDriver3PWM(IN1, IN2, IN3, enable(optional))
+BLDCDriver3PWM driver = BLDCDriver3PWM(PB6, PB7, PB8, PB5);
+// BLDCDriver6PWM(IN1_H, IN1_L, IN2_H, IN2_L, IN3_H, IN3_L, enable(optional))
+//BLDCDriver6PWM driver = BLDCDriver6PWM(PA8, PB13, PA9, PB14, PA10, PB15, PB12);
+
+// encoder instance
+Encoder encoder = Encoder(PA8, PA9, 8192, PA10);
+
+// Interrupt routine intialisation
+// channel A and B callbacks
+void doA(){encoder.handleA();}
+void doB(){encoder.handleB();}
+void doI(){encoder.handleIndex();}
+
+
+// angle set point variable
+float target_angle = 0;
+// instantiate the commander
+Commander command = Commander(Serial);
+void doTarget(char* cmd) { command.scalar(&target_angle, cmd); }
+
+
+void setup() {
+
+ // use monitoring with serial
+ Serial.begin(115200);
+ // enable more verbose output for debugging
+ // comment out if not needed
+ SimpleFOCDebug::enable(&Serial);
+
+ // initialize encoder sensor hardware
+ encoder.init();
+ encoder.enableInterrupts(doA, doB, doI);
+ // link the motor to the sensor
+ motor.linkSensor(&encoder);
+
+ // driver config
+ // power supply voltage [V]
+ driver.voltage_power_supply = 12;
+ driver.init();
+ // link the motor and the driver
+ motor.linkDriver(&driver);
+
+ // aligning voltage [V]
+ motor.voltage_sensor_align = 3;
+ // index search velocity [rad/s]
+ motor.velocity_index_search = 3;
+
+ // set motion control loop to be used
+ motor.controller = MotionControlType::velocity;
+
+ // contoller configuration
+ // default parameters in defaults.h
+
+ // velocity PI controller parameters
+ motor.PID_velocity.P = 0.2f;
+ motor.PID_velocity.I = 20;
+ // default voltage_power_supply
+ motor.voltage_limit = 6;
+ // jerk control using voltage voltage ramp
+ // default value is 300 volts per sec ~ 0.3V per millisecond
+ motor.PID_velocity.output_ramp = 1000;
+
+ // velocity low pass filtering time constant
+ motor.LPF_velocity.Tf = 0.01f;
+
+ // angle P controller
+ motor.P_angle.P = 20;
+ // maximal velocity of the position control
+ motor.velocity_limit = 4;
+
+
+ // comment out if not needed
+ motor.useMonitoring(Serial);
+
+ // initialize motor
+ motor.init();
+ // align encoder and start FOC
+ motor.initFOC();
+
+ // add target command T
+ command.add('T', doTarget, "target angle");
+
+ Serial.println(F("Motor ready."));
+ Serial.println(F("Set the target angle using serial terminal:"));
+ _delay(1000);
+}
+
+void loop() {
+ // main FOC algorithm function
+ // the faster you run this function the better
+ // Arduino UNO loop ~1kHz
+ // Bluepill loop ~10kHz
+ motor.loopFOC();
+
+ // Motion control function
+ // velocity, position or voltage (defined in motor.controller)
+ // this function can be run at much lower frequency than loopFOC() function
+ // You can also use motor.move() and set the motor.target in the code
+ motor.move(target_angle);
+
+ // function intended to be used with serial plotter to monitor motor variables
+ // significantly slowing the execution down!!!!
+ // motor.monitor();
+
+ // user communication
+ command.run();
+}
\ No newline at end of file
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/hardware_specific_examples/Bluepill_examples/magnetic_sensor/bluepill_position_control/bluepill_position_control.ino b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/hardware_specific_examples/Bluepill_examples/magnetic_sensor/bluepill_position_control/bluepill_position_control.ino
new file mode 100644
index 0000000..caef7ff
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/hardware_specific_examples/Bluepill_examples/magnetic_sensor/bluepill_position_control/bluepill_position_control.ino
@@ -0,0 +1,119 @@
+/**
+ *
+ * STM32 Bluepill position motion control example with magnetic sensor
+ *
+ * The same example can be ran with any STM32 board - just make sure that put right pin numbers.
+ *
+ */
+#include
+
+// SPI Magnetic sensor instance (AS5047U example)
+// MISO PA7
+// MOSI PA6
+// SCK PA5
+MagneticSensorSPI sensor = MagneticSensorSPI(PA4, 14, 0x3FFF);
+
+// I2C Magnetic sensor instance (AS5600 example)
+// make sure to use the pull-ups!!
+// SDA PB7
+// SCL PB6
+//MagneticSensorI2C sensor = MagneticSensorI2C(0x36, 12, 0X0C, 4);
+
+// Motor instance
+BLDCMotor motor = BLDCMotor(11);
+// BLDCDriver3PWM(IN1, IN2, IN3, enable(optional))
+BLDCDriver3PWM driver = BLDCDriver3PWM(PB6, PB7, PB8, PB5);
+// BLDCDriver6PWM(IN1_H, IN1_L, IN2_H, IN2_L, IN3_H, IN3_L, enable(optional))
+//BLDCDriver6PWM driver = BLDCDriver6PWM(PA8, PB13, PA9, PB14, PA10, PB15, PB12);
+
+
+// angle set point variable
+float target_angle = 0;
+// instantiate the commander
+Commander command = Commander(Serial);
+void doTarget(char* cmd) { command.scalar(&target_angle, cmd); }
+
+
+void setup() {
+
+ // use monitoring with serial
+ Serial.begin(115200);
+ // enable more verbose output for debugging
+ // comment out if not needed
+ SimpleFOCDebug::enable(&Serial);
+
+ // initialise magnetic sensor hardware
+ sensor.init();
+ // link the motor to the sensor
+ motor.linkSensor(&sensor);
+
+ // driver config
+ // power supply voltage [V]
+ driver.voltage_power_supply = 12;
+ driver.init();
+ // link the motor and the driver
+ motor.linkDriver(&driver);
+
+ // choose FOC modulation (optional)
+ motor.foc_modulation = FOCModulationType::SpaceVectorPWM;
+
+ // set motion control loop to be used
+ motor.controller = MotionControlType::angle;
+
+ // contoller configuration
+ // default parameters in defaults.h
+
+ // velocity PI controller parameters
+ motor.PID_velocity.P = 0.2f;
+ motor.PID_velocity.I = 20;
+ // maximal voltage to be set to the motor
+ motor.voltage_limit = 6;
+
+ // velocity low pass filtering time constant
+ // the lower the less filtered
+ motor.LPF_velocity.Tf = 0.01f;
+
+ // angle P controller
+ motor.P_angle.P = 20;
+ // maximal velocity of the position control
+ motor.velocity_limit = 40;
+
+ // comment out if not needed
+ motor.useMonitoring(Serial);
+
+
+ // initialize motor
+ motor.init();
+ // align sensor and start FOC
+ motor.initFOC();
+
+ // add target command T
+ command.add('T', doTarget, "target angle");
+
+ Serial.println(F("Motor ready."));
+ Serial.println(F("Set the target angle using serial terminal:"));
+ _delay(1000);
+}
+
+void loop() {
+
+ // main FOC algorithm function
+ // the faster you run this function the better
+ // Arduino UNO loop ~1kHz
+ // Bluepill loop ~10kHz
+ motor.loopFOC();
+
+ // Motion control function
+ // velocity, position or voltage (defined in motor.controller)
+ // this function can be run at much lower frequency than loopFOC() function
+ // You can also use motor.move() and set the motor.target in the code
+ motor.move(target_angle);
+
+
+ // function intended to be used with serial plotter to monitor motor variables
+ // significantly slowing the execution down!!!!
+ // motor.monitor();
+
+ // user communication
+ command.run();
+}
\ No newline at end of file
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/hardware_specific_examples/DRV8302_driver/3pwm_example/encoder/full_control_serial/full_control_serial.ino b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/hardware_specific_examples/DRV8302_driver/3pwm_example/encoder/full_control_serial/full_control_serial.ino
new file mode 100644
index 0000000..3d90db1
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/hardware_specific_examples/DRV8302_driver/3pwm_example/encoder/full_control_serial/full_control_serial.ino
@@ -0,0 +1,133 @@
+/**
+ * Comprehensive BLDC motor control example using encoder and the DRV8302 board
+ *
+ * Using serial terminal user can send motor commands and configure the motor and FOC in real-time:
+ * - configure PID controller constants
+ * - change motion control loops
+ * - monitor motor variabels
+ * - set target values
+ * - check all the configuration values
+ *
+ * check the https://docs.simplefoc.com for full list of motor commands
+ *
+ */
+#include
+
+// DRV8302 pins connections
+// don't forget to connect the common ground pin
+#define INH_A 9
+#define INH_B 10
+#define INH_C 11
+
+#define EN_GATE 7
+#define M_PWM A1
+#define M_OC A2
+#define OC_ADJ A3
+
+// Motor instance
+BLDCMotor motor = BLDCMotor(11);
+BLDCDriver3PWM driver = BLDCDriver3PWM(INH_A, INH_B, INH_C, EN_GATE);
+
+// encoder instance
+Encoder encoder = Encoder(2, 3, 8192);
+
+// Interrupt routine intialisation
+// channel A and B callbacks
+void doA(){encoder.handleA();}
+void doB(){encoder.handleB();}
+
+
+// commander interface
+Commander command = Commander(Serial);
+void onMotor(char* cmd){ command.motor(&motor, cmd); }
+
+void setup() {
+
+ // use monitoring with serial
+ Serial.begin(115200);
+ // enable more verbose output for debugging
+ // comment out if not needed
+ SimpleFOCDebug::enable(&Serial);
+
+ // initialize encoder sensor hardware
+ encoder.init();
+ encoder.enableInterrupts(doA, doB);
+ // link the motor to the sensor
+ motor.linkSensor(&encoder);
+
+ // DRV8302 specific code
+ // M_OC - enable overcurrent protection
+ pinMode(M_OC,OUTPUT);
+ digitalWrite(M_OC,LOW);
+ // M_PWM - enable 3pwm mode
+ pinMode(M_PWM,OUTPUT);
+ digitalWrite(M_PWM,HIGH);
+ // OD_ADJ - set the maximum overcurrent limit possible
+ // Better option would be to use voltage divisor to set exact value
+ pinMode(OC_ADJ,OUTPUT);
+ digitalWrite(OC_ADJ,HIGH);
+
+
+ // driver config
+ // power supply voltage [V]
+ driver.voltage_power_supply = 12;
+ driver.init();
+ // link the motor and the driver
+ motor.linkDriver(&driver);
+
+
+ // choose FOC modulation
+ motor.foc_modulation = FOCModulationType::SpaceVectorPWM;
+
+ // set control loop type to be used
+ motor.controller = MotionControlType::torque;
+
+ // contoller configuration based on the controll type
+ motor.PID_velocity.P = 0.2f;
+ motor.PID_velocity.I = 20;
+ // default voltage_power_supply
+ motor.voltage_limit = 12;
+
+ // velocity low pass filtering time constant
+ motor.LPF_velocity.Tf = 0.01f;
+
+ // angle loop controller
+ motor.P_angle.P = 20;
+ // angle loop velocity limit
+ motor.velocity_limit = 50;
+
+ // comment out if not needed
+ motor.useMonitoring(Serial);
+
+ // initialise motor
+ motor.init();
+ // align encoder and start FOC
+ motor.initFOC();
+
+ // set the inital target value
+ motor.target = 2;
+
+ // define the motor id
+ command.add('A', onMotor, "motor");
+
+ Serial.println(F("Full control example: "));
+ Serial.println(F("Run user commands to configure and the motor (find the full command list in docs.simplefoc.com) \n "));
+ Serial.println(F("Initial motion control loop is voltage loop."));
+ Serial.println(F("Initial target voltage 2V."));
+
+ _delay(1000);
+}
+
+
+void loop() {
+ // iterative setting FOC phase voltage
+ motor.loopFOC();
+
+ // iterative function setting the outter loop target
+ // velocity, position or voltage
+ // if tatget not set in parameter uses motor.target variable
+ motor.move();
+
+ // user communication
+ command.run();
+}
\ No newline at end of file
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/hardware_specific_examples/DRV8302_driver/6pwm_example/encoder/full_control_serial/full_control_serial.ino b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/hardware_specific_examples/DRV8302_driver/6pwm_example/encoder/full_control_serial/full_control_serial.ino
new file mode 100644
index 0000000..af56e06
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/hardware_specific_examples/DRV8302_driver/6pwm_example/encoder/full_control_serial/full_control_serial.ino
@@ -0,0 +1,132 @@
+/**
+ * Comprehensive BLDC motor control example using encoder and the DRV8302 board
+ *
+ * Using serial terminal user can send motor commands and configure the motor and FOC in real-time:
+ * - configure PID controller constants
+ * - change motion control loops
+ * - monitor motor variabels
+ * - set target values
+ * - check all the configuration values
+ *
+ * check the https://docs.simplefoc.com for full list of motor commands
+ *
+ */
+#include
+
+// DRV8302 pins connections
+// don't forget to connect the common ground pin
+#define INH_A 3
+#define INH_B 5
+#define INH_C 9
+#define INL_A 11
+#define INL_B 6
+#define INL_C 10
+
+#define EN_GATE 7
+#define M_PWM A1
+#define M_OC A2
+#define OC_ADJ A3
+
+// Motor instance
+BLDCMotor motor = BLDCMotor(11);
+BLDCDriver6PWM driver = BLDCDriver6PWM(INH_A,INL_A, INH_B,INL_B, INH_C,INL_C, EN_GATE);
+
+// encoder instance
+Encoder encoder = Encoder(2, 3, 8192);
+
+// Interrupt routine intialisation
+// channel A and B callbacks
+void doA(){encoder.handleA();}
+void doB(){encoder.handleB();}
+
+
+// commander interface
+Commander command = Commander(Serial);
+void onMotor(char* cmd){ command.motor(&motor, cmd); }
+
+void setup() {
+
+ // use monitoring with serial
+ Serial.begin(115200);
+ // enable more verbose output for debugging
+ // comment out if not needed
+ SimpleFOCDebug::enable(&Serial);
+
+ // initialize encoder sensor hardware
+ encoder.init();
+ encoder.enableInterrupts(doA, doB);
+ // link the motor to the sensor
+ motor.linkSensor(&encoder);
+
+ // DRV8302 specific code
+ // M_OC - enable overcurrent protection
+ pinMode(M_OC,OUTPUT);
+ digitalWrite(M_OC,LOW);
+ // M_PWM - disable 3pwm mode
+ pinMode(M_PWM,OUTPUT);
+ digitalWrite(M_PWM, LOW);
+ // OD_ADJ - set the maximum overcurrent limit possible
+ // Better option would be to use voltage divisor to set exact value
+ pinMode(OC_ADJ,OUTPUT);
+ digitalWrite(OC_ADJ,HIGH);
+
+ // driver config
+ // power supply voltage [V]
+ driver.voltage_power_supply = 12;
+ driver.init();
+ // link the motor and the driver
+ motor.linkDriver(&driver);
+
+ // choose FOC modulation
+ motor.foc_modulation = FOCModulationType::SpaceVectorPWM;
+
+ // set control loop type to be used
+ motor.controller = MotionControlType::torque;
+
+ // contoller configuration based on the controll type
+ motor.PID_velocity.P = 0.2f;
+ motor.PID_velocity.I = 20;
+ // default voltage_power_supply
+ motor.voltage_limit = 12;
+
+ // velocity low pass filtering time constant
+ motor.LPF_velocity.Tf = 0.01f;
+
+ // angle loop controller
+ motor.P_angle.P = 20;
+ // angle loop velocity limit
+ motor.velocity_limit = 50;
+
+ // comment out if not needed
+ motor.useMonitoring(Serial);
+
+ // initialise motor
+ motor.init();
+ // align encoder and start FOC
+ motor.initFOC();
+
+ // set the inital target value
+ motor.target = 2;
+
+ // define the motor id
+ command.add('M', onMotor, "motor");
+
+ Serial.println(F("Initial motion control loop is voltage loop."));
+ Serial.println(F("Initial target voltage 2V."));
+
+ _delay(1000);
+}
+
+
+void loop() {
+ // iterative setting FOC phase voltage
+ motor.loopFOC();
+
+ // iterative function setting the outter loop target
+ // velocity, position or voltage
+ // if tatget not set in parameter uses motor.target variable
+ motor.move();
+
+ // user communication
+ command.run();
+}
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/hardware_specific_examples/DRV8302_driver/esp32_current_control_low_side/esp32_current_control_low_side.ino b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/hardware_specific_examples/DRV8302_driver/esp32_current_control_low_side/esp32_current_control_low_side.ino
new file mode 100644
index 0000000..7d7fe14
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/hardware_specific_examples/DRV8302_driver/esp32_current_control_low_side/esp32_current_control_low_side.ino
@@ -0,0 +1,169 @@
+/**
+ * Comprehensive BLDC motor control example using encoder and the DRV8302 board
+ *
+ * Using serial terminal user can send motor commands and configure the motor and FOC in real-time:
+ * - configure PID controller constants
+ * - change motion control loops
+ * - monitor motor variabels
+ * - set target values
+ * - check all the configuration values
+ *
+ * check the https://docs.simplefoc.com for full list of motor commands
+ *
+ */
+#include
+
+// DRV8302 pins connections
+// don't forget to connect the common ground pin
+#define INH_A 21
+#define INH_B 19
+#define INH_C 18
+
+#define EN_GATE 5
+#define M_PWM 25
+#define M_OC 26
+#define OC_ADJ 12
+#define OC_GAIN 14
+
+#define IOUTA 34
+#define IOUTB 35
+#define IOUTC 32
+
+// Motor instance
+BLDCMotor motor = BLDCMotor(7);
+BLDCDriver3PWM driver = BLDCDriver3PWM(INH_A, INH_B, INH_C, EN_GATE);
+
+// DRV8302 board has 0.005Ohm shunt resistors and the gain of 12.22 V/V
+LowsideCurrentSense cs = LowsideCurrentSense(0.005f, 12.22f, IOUTA, IOUTB, IOUTC);
+
+// encoder instance
+Encoder encoder = Encoder(22, 23, 500);
+
+// Interrupt routine intialisation
+// channel A and B callbacks
+void doA(){encoder.handleA();}
+void doB(){encoder.handleB();}
+
+
+// commander interface
+Commander command = Commander(Serial);
+void onMotor(char* cmd){ command.motor(&motor, cmd); }
+
+void setup() {
+
+ // use monitoring with serial
+ Serial.begin(115200);
+ // enable more verbose output for debugging
+ // comment out if not needed
+ SimpleFOCDebug::enable(&Serial);
+
+ // initialize encoder sensor hardware
+ encoder.init();
+ encoder.enableInterrupts(doA, doB);
+ // link the motor to the sensor
+ motor.linkSensor(&encoder);
+
+ // DRV8302 specific code
+ // M_OC - enable overcurrent protection
+ pinMode(M_OC,OUTPUT);
+ digitalWrite(M_OC,LOW);
+ // M_PWM - enable 3pwm mode
+ pinMode(M_PWM,OUTPUT);
+ digitalWrite(M_PWM,HIGH);
+ // OD_ADJ - set the maximum overcurrent limit possible
+ // Better option would be to use voltage divisor to set exact value
+ pinMode(OC_ADJ,OUTPUT);
+ digitalWrite(OC_ADJ,HIGH);
+ pinMode(OC_GAIN,OUTPUT);
+ digitalWrite(OC_GAIN,LOW);
+
+
+ // driver config
+ // power supply voltage [V]
+ driver.voltage_power_supply = 12;
+ driver.pwm_frequency = 15000;
+ driver.init();
+ // link the motor and the driver
+ motor.linkDriver(&driver);
+ // link current sense and the driver
+ cs.linkDriver(&driver);
+
+ // align voltage
+ motor.voltage_sensor_align = 0.5;
+
+ // control loop type and torque mode
+ motor.torque_controller = TorqueControlType::voltage;
+ motor.controller = MotionControlType::torque;
+ motor.motion_downsample = 0.0;
+
+ // velocity loop PID
+ motor.PID_velocity.P = 0.2;
+ motor.PID_velocity.I = 5.0;
+ // Low pass filtering time constant
+ motor.LPF_velocity.Tf = 0.02;
+ // angle loop PID
+ motor.P_angle.P = 20.0;
+ // Low pass filtering time constant
+ motor.LPF_angle.Tf = 0.0;
+ // current q loop PID
+ motor.PID_current_q.P = 3.0;
+ motor.PID_current_q.I = 100.0;
+ // Low pass filtering time constant
+ motor.LPF_current_q.Tf = 0.02;
+ // current d loop PID
+ motor.PID_current_d.P = 3.0;
+ motor.PID_current_d.I = 100.0;
+ // Low pass filtering time constant
+ motor.LPF_current_d.Tf = 0.02;
+
+ // Limits
+ motor.velocity_limit = 100.0; // 100 rad/s velocity limit
+ motor.voltage_limit = 12.0; // 12 Volt limit
+ motor.current_limit = 2.0; // 2 Amp current limit
+
+ // comment out if not needed
+ motor.useMonitoring(Serial);
+ motor.monitor_variables = _MON_CURR_Q | _MON_CURR_D; // monitor the two currents d and q
+ motor.monitor_downsample = 1000;
+
+ // initialise motor
+ motor.init();
+
+ cs.init();
+ // driver 8302 has inverted gains on all channels
+ cs.gain_a *=-1;
+ cs.gain_b *=-1;
+ cs.gain_c *=-1;
+ motor.linkCurrentSense(&cs);
+
+ // align encoder and start FOC
+ motor.initFOC();
+
+ // set the inital target value
+ motor.target = 0;
+
+ // define the motor id
+ command.add('M', onMotor, "motor");
+
+ Serial.println(F("Full control example: "));
+ Serial.println(F("Run user commands to configure and the motor (find the full command list in docs.simplefoc.com) \n "));
+ Serial.println(F("Initial motion control loop is voltage loop."));
+ Serial.println(F("Initial target voltage 2V."));
+
+ _delay(1000);
+}
+
+
+void loop() {
+ // iterative setting FOC phase voltage
+ motor.loopFOC();
+
+ // iterative function setting the outter loop target
+ motor.move();
+
+ // monitoring the state variables
+ motor.monitor();
+
+ // user communication
+ command.run();
+}
\ No newline at end of file
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/hardware_specific_examples/DRV8302_driver/stm32_current_control_low_side/stm32_current_control_low_side.ino b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/hardware_specific_examples/DRV8302_driver/stm32_current_control_low_side/stm32_current_control_low_side.ino
new file mode 100644
index 0000000..e1b4c39
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/hardware_specific_examples/DRV8302_driver/stm32_current_control_low_side/stm32_current_control_low_side.ino
@@ -0,0 +1,169 @@
+/**
+ * Comprehensive BLDC motor control example using encoder and the DRV8302 board
+ *
+ * Using serial terminal user can send motor commands and configure the motor and FOC in real-time:
+ * - configure PID controller constants
+ * - change motion control loops
+ * - monitor motor variabels
+ * - set target values
+ * - check all the configuration values
+ *
+ * check the https://docs.simplefoc.com for full list of motor commands
+ *
+ */
+#include
+
+// DRV8302 pins connections
+// don't forget to connect the common ground pin
+#define INH_A PA8
+#define INH_B PA9
+#define INH_C PA10
+
+#define EN_GATE PB7
+#define M_PWM PB4
+#define M_OC PB3
+#define OC_ADJ PB6
+#define OC_GAIN PB5
+
+#define IOUTA PA0
+#define IOUTB PA1
+#define IOUTC PA2
+
+// Motor instance
+BLDCMotor motor = BLDCMotor(7);
+BLDCDriver3PWM driver = BLDCDriver3PWM(INH_A, INH_B, INH_C, EN_GATE);
+
+// DRV8302 board has 0.005Ohm shunt resistors and the gain of 12.22 V/V
+LowsideCurrentSense cs = LowsideCurrentSense(0.005f, 12.22f, IOUTA, IOUTB, IOUTC);
+
+// encoder instance
+Encoder encoder = Encoder(PB14, PB15, 2048);
+
+// Interrupt routine intialisation
+// channel A and B callbacks
+void doA(){encoder.handleA();}
+void doB(){encoder.handleB();}
+
+
+// commander interface
+Commander command = Commander(Serial);
+void onMotor(char* cmd){ command.motor(&motor, cmd); }
+
+void setup() {
+
+ // use monitoring with serial
+ Serial.begin(115200);
+ // enable more verbose output for debugging
+ // comment out if not needed
+ SimpleFOCDebug::enable(&Serial);
+
+ // initialize encoder sensor hardware
+ encoder.init();
+ encoder.enableInterrupts(doA, doB);
+ // link the motor to the sensor
+ motor.linkSensor(&encoder);
+
+ // DRV8302 specific code
+ // M_OC - enable overcurrent protection
+ pinMode(M_OC,OUTPUT);
+ digitalWrite(M_OC,LOW);
+ // M_PWM - enable 3pwm mode
+ pinMode(M_PWM,OUTPUT);
+ digitalWrite(M_PWM,HIGH);
+ // OD_ADJ - set the maximum overcurrent limit possible
+ // Better option would be to use voltage divisor to set exact value
+ pinMode(OC_ADJ,OUTPUT);
+ digitalWrite(OC_ADJ,HIGH);
+ pinMode(OC_GAIN,OUTPUT);
+ digitalWrite(OC_GAIN,LOW);
+
+
+ // driver config
+ // power supply voltage [V]
+ driver.voltage_power_supply = 19;
+ driver.pwm_frequency = 15000; // suggested under 18khz
+ driver.init();
+ // link the motor and the driver
+ motor.linkDriver(&driver);
+ // link current sense and the driver
+ cs.linkDriver(&driver);
+
+ // align voltage
+ motor.voltage_sensor_align = 0.5;
+
+ // control loop type and torque mode
+ motor.torque_controller = TorqueControlType::voltage;
+ motor.controller = MotionControlType::torque;
+ motor.motion_downsample = 0.0;
+
+ // velocity loop PID
+ motor.PID_velocity.P = 0.2;
+ motor.PID_velocity.I = 5.0;
+ // Low pass filtering time constant
+ motor.LPF_velocity.Tf = 0.02;
+ // angle loop PID
+ motor.P_angle.P = 20.0;
+ // Low pass filtering time constant
+ motor.LPF_angle.Tf = 0.0;
+ // current q loop PID
+ motor.PID_current_q.P = 3.0;
+ motor.PID_current_q.I = 100.0;
+ // Low pass filtering time constant
+ motor.LPF_current_q.Tf = 0.02;
+ // current d loop PID
+ motor.PID_current_d.P = 3.0;
+ motor.PID_current_d.I = 100.0;
+ // Low pass filtering time constant
+ motor.LPF_current_d.Tf = 0.02;
+
+ // Limits
+ motor.velocity_limit = 100.0; // 100 rad/s velocity limit
+ motor.voltage_limit = 12.0; // 12 Volt limit
+ motor.current_limit = 2.0; // 2 Amp current limit
+
+ // comment out if not needed
+ motor.useMonitoring(Serial);
+ motor.monitor_variables = _MON_CURR_Q | _MON_CURR_D; // monitor the two currents d and q
+ motor.monitor_downsample = 0;
+
+ // initialise motor
+ motor.init();
+
+ cs.init();
+ // driver 8302 has inverted gains on all channels
+ cs.gain_a *=-1;
+ cs.gain_b *=-1;
+ cs.gain_c *=-1;
+ motor.linkCurrentSense(&cs);
+
+ // align encoder and start FOC
+ motor.initFOC();
+
+ // set the inital target value
+ motor.target = 0;
+
+ // define the motor id
+ command.add('M', onMotor, "motor");
+
+ Serial.println(F("Full control example: "));
+ Serial.println(F("Run user commands to configure and the motor (find the full command list in docs.simplefoc.com) \n "));
+ Serial.println(F("Initial motion control loop is voltage loop."));
+ Serial.println(F("Initial target voltage 2V."));
+
+ _delay(1000);
+}
+
+
+void loop() {
+ // iterative setting FOC phase voltage
+ motor.loopFOC();
+
+ // iterative function setting the outter loop target
+ motor.move();
+
+ // monitoring the state variables
+ motor.monitor();
+
+ // user communication
+ command.run();
+}
\ No newline at end of file
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/hardware_specific_examples/DRV8302_driver/teensy4_current_control_low_side/teensy4_current_control_low_side.ino b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/hardware_specific_examples/DRV8302_driver/teensy4_current_control_low_side/teensy4_current_control_low_side.ino
new file mode 100644
index 0000000..c9b4516
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/hardware_specific_examples/DRV8302_driver/teensy4_current_control_low_side/teensy4_current_control_low_side.ino
@@ -0,0 +1,170 @@
+/**
+ * Comprehensive BLDC motor control example using encoder and the DRV8302 board
+ *
+ * Using serial terminal user can send motor commands and configure the motor and FOC in real-time:
+ * - configure PID controller constants
+ * - change motion control loops
+ * - monitor motor variabels
+ * - set target values
+ * - check all the configuration values
+ *
+ * check the https://docs.simplefoc.com for full list of motor commands
+ *
+ */
+#include
+
+// DRV8302 pins connections
+// don't forget to connect the common ground pin
+#define EN_GATE 11
+#define M_PWM 22
+#define GAIN 20
+#define M_OC 23
+#define OC_ADJ 19
+
+#define INH_A 2
+#define INL_A 3
+#define INH_B 8
+#define INL_B 7
+#define INH_C 6
+#define INL_C 9
+
+#define IOUTA 14
+#define IOUTB 15
+#define IOUTC 16
+
+// Motor instance
+BLDCMotor motor = BLDCMotor(7);
+BLDCDriver3PWM driver = BLDCDriver3PWM(INH_A, INH_B, INH_C, EN_GATE);
+
+// DRV8302 board has 0.005Ohm shunt resistors and the gain of 12.22 V/V
+LowsideCurrentSense cs = LowsideCurrentSense(0.005f, 12.22f, IOUTA, IOUTB);
+
+// encoder instance
+Encoder encoder = Encoder(10, 11, 2048);
+
+// Interrupt routine intialisation
+// channel A and B callbacks
+void doA(){encoder.handleA();}
+void doB(){encoder.handleB();}
+
+
+// commander interface
+Commander command = Commander(Serial);
+void onMotor(char* cmd){ command.motor(&motor, cmd); }
+
+void setup() {
+
+ // use monitoring with serial
+ Serial.begin(115200);
+ // enable more verbose output for debugging
+ // comment out if not needed
+ SimpleFOCDebug::enable(&Serial);
+
+ // initialize encoder sensor hardware
+ encoder.init();
+ encoder.enableInterrupts(doA, doB);
+ // link the motor to the sensor
+ motor.linkSensor(&encoder);
+
+ // DRV8302 specific code
+ // M_OC - enable overcurrent protection
+ pinMode(M_OC,OUTPUT);
+ digitalWrite(M_OC,LOW);
+ // M_PWM - enable 6pwm mode
+ pinMode(M_PWM, OUTPUT);
+ digitalWrite(M_PWM,LOW); // high for 3pwm
+ // OD_ADJ - set the maximum overcurrent limit possible
+ // Better option would be to use voltage divisor to set exact value
+ pinMode(OC_ADJ,OUTPUT);
+ digitalWrite(OC_ADJ,HIGH);
+
+
+ // driver config
+ // power supply voltage [V]
+ driver.voltage_power_supply = 19;
+ driver.pwm_frequency = 20000; // suggested not higher than 22khz
+ driver.init();
+ // link the motor and the driver
+ motor.linkDriver(&driver);
+ // link current sense and the driver
+ cs.linkDriver(&driver);
+
+ // align voltage
+ motor.voltage_sensor_align = 0.5;
+
+ // control loop type and torque mode
+ motor.torque_controller = TorqueControlType::voltage;
+ motor.controller = MotionControlType::torque;
+ motor.motion_downsample = 0.0;
+
+ // velocity loop PID
+ motor.PID_velocity.P = 0.2;
+ motor.PID_velocity.I = 5.0;
+ // Low pass filtering time constant
+ motor.LPF_velocity.Tf = 0.02;
+ // angle loop PID
+ motor.P_angle.P = 20.0;
+ // Low pass filtering time constant
+ motor.LPF_angle.Tf = 0.0;
+ // current q loop PID
+ motor.PID_current_q.P = 3.0;
+ motor.PID_current_q.I = 100.0;
+ // Low pass filtering time constant
+ motor.LPF_current_q.Tf = 0.02;
+ // current d loop PID
+ motor.PID_current_d.P = 3.0;
+ motor.PID_current_d.I = 100.0;
+ // Low pass filtering time constant
+ motor.LPF_current_d.Tf = 0.02;
+
+ // Limits
+ motor.velocity_limit = 100.0; // 100 rad/s velocity limit
+ motor.voltage_limit = 12.0; // 12 Volt limit
+ motor.current_limit = 2.0; // 2 Amp current limit
+
+ // comment out if not needed
+ motor.useMonitoring(Serial);
+ motor.monitor_variables = _MON_CURR_Q | _MON_CURR_D; // monitor the two currents d and q
+ motor.monitor_downsample = 0;
+
+ // initialise motor
+ motor.init();
+
+ cs.init();
+ // driver 8302 has inverted gains on all channels
+ cs.gain_a *=-1;
+ cs.gain_b *=-1;
+ cs.gain_c *=-1;
+ motor.linkCurrentSense(&cs);
+
+ // align encoder and start FOC
+ motor.initFOC();
+
+ // set the inital target value
+ motor.target = 0;
+
+ // define the motor id
+ command.add('M', onMotor, "motor");
+
+ Serial.println(F("Full control example: "));
+ Serial.println(F("Run user commands to configure and the motor (find the full command list in docs.simplefoc.com) \n "));
+ Serial.println(F("Initial motion control loop is voltage loop."));
+ Serial.println(F("Initial target voltage 2V."));
+
+ _delay(1000);
+}
+
+
+void loop() {
+ // iterative setting FOC phase voltage
+ motor.loopFOC();
+
+ // iterative function setting the outter loop target
+ motor.move();
+
+ // monitoring the state variables
+ motor.monitor();
+
+ // user communication
+ command.run();
+}
\ No newline at end of file
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/hardware_specific_examples/ESP32/encoder/esp32_position_control/esp32_position_control.ino b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/hardware_specific_examples/ESP32/encoder/esp32_position_control/esp32_position_control.ino
new file mode 100644
index 0000000..7f6b33c
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/hardware_specific_examples/ESP32/encoder/esp32_position_control/esp32_position_control.ino
@@ -0,0 +1,110 @@
+/**
+ * ESP32 position motion control example with encoder
+ *
+ */
+#include
+
+// Motor instance
+BLDCMotor motor = BLDCMotor(11);
+BLDCDriver3PWM driver = BLDCDriver3PWM(25, 26, 27, 7);
+
+// encoder instance
+Encoder encoder = Encoder(4, 2, 1024);
+
+// Interrupt routine intialisation
+// channel A and B callbacks
+void doA(){encoder.handleA();}
+void doB(){encoder.handleB();}
+
+// angle set point variable
+float target_angle = 0;
+// instantiate the commander
+Commander command = Commander(Serial);
+void doTarget(char* cmd) { command.scalar(&target_angle, cmd); }
+
+void setup() {
+
+ // use monitoring with serial
+ Serial.begin(115200);
+ // enable more verbose output for debugging
+ // comment out if not needed
+ SimpleFOCDebug::enable(&Serial);
+
+ // initialize encoder sensor hardware
+ encoder.init();
+ encoder.enableInterrupts(doA, doB);
+
+ // link the motor to the sensor
+ motor.linkSensor(&encoder);
+
+ // driver config
+ // power supply voltage [V]
+ driver.voltage_power_supply = 12;
+ driver.init();
+ // link the motor and the driver
+ motor.linkDriver(&driver);
+
+ // aligning voltage [V]
+ motor.voltage_sensor_align = 3;
+ // index search velocity [rad/s]
+ motor.velocity_index_search = 3;
+
+ // set motion control loop to be used
+ motor.controller = MotionControlType::velocity;
+
+ // contoller configuration
+ // default parameters in defaults.h
+
+ // velocity PI controller parameters
+ motor.PID_velocity.P = 0.2f;
+ motor.PID_velocity.I = 20;
+ // default voltage_power_supply
+ motor.voltage_limit = 6;
+ // jerk control using voltage voltage ramp
+ // default value is 300 volts per sec ~ 0.3V per millisecond
+ motor.PID_velocity.output_ramp = 1000;
+
+ // velocity low pass filtering time constant
+ motor.LPF_velocity.Tf = 0.01f;
+
+ // angle P controller
+ motor.P_angle.P = 20;
+ // maximal velocity of the position control
+ motor.velocity_limit = 4;
+
+ // comment out if not needed
+ motor.useMonitoring(Serial);
+
+ // initialize motor
+ motor.init();
+ // align encoder and start FOC
+ motor.initFOC();
+
+ // add target command T
+ command.add('T', doTarget, "target angle");
+
+ Serial.println(F("Motor ready."));
+ Serial.println(F("Set the target angle using serial terminal:"));
+ _delay(1000);
+}
+
+void loop() {
+ // main FOC algorithm function
+ // the faster you run this function the better
+ // Arduino UNO loop ~1kHz
+ // Bluepill loop ~10kHz
+ motor.loopFOC();
+
+ // Motion control function
+ // velocity, position or voltage (defined in motor.controller)
+ // this function can be run at much lower frequency than loopFOC() function
+ // You can also use motor.move() and set the motor.target in the code
+ motor.move(target_angle);
+
+ // function intended to be used with serial plotter to monitor motor variables
+ // significantly slowing the execution down!!!!
+ // motor.monitor();
+
+ // user communication
+ command.run();
+}
\ No newline at end of file
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/hardware_specific_examples/ESP32/magnetic_sensor/esp32_position_control/esp32_position_control.ino b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/hardware_specific_examples/ESP32/magnetic_sensor/esp32_position_control/esp32_position_control.ino
new file mode 100644
index 0000000..9ba9604
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/hardware_specific_examples/ESP32/magnetic_sensor/esp32_position_control/esp32_position_control.ino
@@ -0,0 +1,116 @@
+/**
+ * ESP32 position motion control example with magnetic sensor
+ */
+#include
+
+// SPI Magnetic sensor instance (AS5047U example)
+// MISO 12
+// MOSI 9
+// SCK 14
+// magnetic sensor instance - SPI
+MagneticSensorSPI sensor = MagneticSensorSPI(AS5147_SPI, 15);
+
+// I2C Magnetic sensor instance (AS5600 example)
+// make sure to use the pull-ups!!
+// SDA 21
+// SCL 22
+// magnetic sensor instance - I2C
+//MagneticSensorI2C sensor = MagneticSensorI2C(AS5600_I2C);
+
+// Analog output Magnetic sensor instance (AS5600)
+// MagneticSensorAnalog sensor = MagneticSensorAnalog(A1, 14, 1020);
+
+// Motor instance
+BLDCMotor motor = BLDCMotor(11);
+BLDCDriver3PWM driver = BLDCDriver3PWM(25, 26, 27, 7);
+
+
+// angle set point variable
+float target_angle = 0;
+// instantiate the commander
+Commander command = Commander(Serial);
+void doTarget(char* cmd) { command.scalar(&target_angle, cmd); }
+
+void setup() {
+
+ // use monitoring with serial
+ Serial.begin(115200);
+ // enable more verbose output for debugging
+ // comment out if not needed
+ SimpleFOCDebug::enable(&Serial);
+
+ // initialise magnetic sensor hardware
+ sensor.init();
+ // link the motor to the sensor
+ motor.linkSensor(&sensor);
+
+ // driver config
+ // power supply voltage [V]
+ driver.voltage_power_supply = 12;
+ driver.init();
+ // link the motor and the driver
+ motor.linkDriver(&driver);
+
+ // choose FOC modulation (optional)
+ motor.foc_modulation = FOCModulationType::SpaceVectorPWM;
+
+ // set motion control loop to be used
+ motor.controller = MotionControlType::angle;
+
+ // contoller configuration
+ // default parameters in defaults.h
+
+ // velocity PI controller parameters
+ motor.PID_velocity.P = 0.2f;
+ motor.PID_velocity.I = 20;
+ // maximal voltage to be set to the motor
+ motor.voltage_limit = 6;
+
+ // velocity low pass filtering time constant
+ // the lower the less filtered
+ motor.LPF_velocity.Tf = 0.01f;
+
+ // angle P controller
+ motor.P_angle.P = 20;
+ // maximal velocity of the position control
+ motor.velocity_limit = 40;
+
+ // comment out if not needed
+ motor.useMonitoring(Serial);
+
+
+ // initialize motor
+ motor.init();
+ // align sensor and start FOC
+ motor.initFOC();
+
+ // add target command T
+ command.add('T', doTarget, "target angle");
+
+ Serial.println(F("Motor ready."));
+ Serial.println(F("Set the target angle using serial terminal:"));
+ _delay(1000);
+}
+
+void loop() {
+
+ // main FOC algorithm function
+ // the faster you run this function the better
+ // Arduino UNO loop ~1kHz
+ // Bluepill loop ~10kHz
+ motor.loopFOC();
+
+ // Motion control function
+ // velocity, position or voltage (defined in motor.controller)
+ // this function can be run at much lower frequency than loopFOC() function
+ // You can also use motor.move() and set the motor.target in the code
+ motor.move(target_angle);
+
+
+ // function intended to be used with serial plotter to monitor motor variables
+ // significantly slowing the execution down!!!!
+ // motor.monitor();
+
+ // user communication
+ command.run();
+}
\ No newline at end of file
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/hardware_specific_examples/HMBGC_example/position_control/position_control.ino b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/hardware_specific_examples/HMBGC_example/position_control/position_control.ino
new file mode 100644
index 0000000..d910765
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/hardware_specific_examples/HMBGC_example/position_control/position_control.ino
@@ -0,0 +1,127 @@
+/**
+ *
+ * HMBGC position motion control example with encoder
+ *
+ * - Motor is connected the MOT1 connector (MOT1 9,10,11; MOT2 3,5,6)
+ * - Encoder is connected to A0 and A1
+ *
+ * This board doesn't have any interrupt pins so we need to run all the encoder channels with the software interrupt library
+ * - For this example we use: PciManager library : https://github.com/prampec/arduino-pcimanager
+ *
+ * See docs.simplefoc.com for more info.
+ *
+ */
+#include
+// software interrupt library
+#include
+#include
+
+
+// BLDC motor & driver instance
+BLDCMotor motor = BLDCMotor(11);
+BLDCDriver3PWM driver = BLDCDriver3PWM(9, 10, 11);
+
+// encoder instance
+Encoder encoder = Encoder(A0, A1, 2048);
+
+// Interrupt routine intialisation
+// channel A and B callbacks
+void doA(){encoder.handleA();}
+void doB(){encoder.handleB();}
+
+// encoder interrupt init
+PciListenerImp listenerA(encoder.pinA, doA);
+PciListenerImp listenerB(encoder.pinB, doB);
+
+
+// angle set point variable
+float target_angle = 0;
+// instantiate the commander
+Commander command = Commander(Serial);
+void doTarget(char* cmd) { command.scalar(&target_angle, cmd); }
+
+void setup() {
+
+ // use monitoring with serial
+ Serial.begin(115200);
+
+ // initialise encoder hardware
+ encoder.init();
+ // interrupt initialization
+ PciManager.registerListener(&listenerA);
+ PciManager.registerListener(&listenerB);
+ // link the motor to the sensor
+ motor.linkSensor(&encoder);
+
+ // driver config
+ // power supply voltage [V]
+ driver.voltage_power_supply = 12;
+ driver.init();
+ // link the motor and the driver
+ motor.linkDriver(&driver);
+
+ // aligning voltage [V]
+ motor.voltage_sensor_align = 3;
+ // index search velocity [rad/s]
+ motor.velocity_index_search = 3;
+
+ // set motion control loop to be used
+ motor.controller = MotionControlType::angle;
+
+ // contoller configuration
+ // default parameters in defaults.h
+
+ // velocity PI controller parameters
+ motor.PID_velocity.P = 0.2f;
+ motor.PID_velocity.I = 20;
+ // default voltage_power_supply
+ motor.voltage_limit = 6;
+ // jerk control using voltage voltage ramp
+ // default value is 300 volts per sec ~ 0.3V per millisecond
+ motor.PID_velocity.output_ramp = 1000;
+
+ // velocity low pass filtering time constant
+ motor.LPF_velocity.Tf = 0.01f;
+
+ // angle P controller
+ motor.P_angle.P = 20;
+ // maximal velocity of the position control
+ motor.velocity_limit = 4;
+
+ // comment out if not needed
+ motor.useMonitoring(Serial);
+
+ // initialize motor
+ motor.init();
+ // align encoder and start FOC
+ motor.initFOC();
+
+ // add target command T
+ command.add('T', doTarget, "target angle");
+
+ Serial.println(F("Motor ready."));
+ Serial.println(F("Set the target angle using serial terminal:"));
+ _delay(1000);
+}
+
+
+void loop() {
+ // main FOC algorithm function
+ // the faster you run this function the better
+ // Arduino UNO loop ~1kHz
+ // Bluepill loop ~10kHz
+ motor.loopFOC();
+
+ // Motion control function
+ // velocity, position or voltage (defined in motor.controller)
+ // this function can be run at much lower frequency than loopFOC() function
+ // You can also use motor.move() and set the motor.target in the code
+ motor.move(target_angle);
+
+ // function intended to be used with serial plotter to monitor motor variables
+ // significantly slowing the execution down!!!!
+ // motor.monitor();
+
+ // user communication
+ command.run();
+}
\ No newline at end of file
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/hardware_specific_examples/HMBGC_example/voltage_control/voltage_control.ino b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/hardware_specific_examples/HMBGC_example/voltage_control/voltage_control.ino
new file mode 100644
index 0000000..9c9655f
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/hardware_specific_examples/HMBGC_example/voltage_control/voltage_control.ino
@@ -0,0 +1,110 @@
+/**
+ *
+ * HMBGC torque control example using voltage control loop.
+ *
+ * - Motor is connected the MOT1 connector (MOT1 9,10,11; MOT2 3,5,6)
+ * - Encoder is connected to A0 and A1
+ *
+ * Most of the low-end BLDC driver boards doesn't have current measurement therefore SimpleFOC offers
+ * you a way to control motor torque by setting the voltage to the motor instead hte current.
+ *
+ * This makes the BLDC motor effectively a DC motor, and you can use it in a same way. position motion control example with encoder
+ *
+ * NOTE:
+ * > HMBGC doesn't have any interrupt pins so we need to run all the encoder channels with the software interrupt library
+ * > - For this example we use: PciManager library : https://github.com/prampec/arduino-pcimanager
+ *
+ * See docs.simplefoc.com for more info.
+ *
+ */
+#include
+// software interrupt library
+#include
+#include
+
+
+// BLDC motor & driver instance
+BLDCMotor motor = BLDCMotor(11);
+BLDCDriver3PWM driver = BLDCDriver3PWM(9, 10, 11);
+
+// encoder instance
+Encoder encoder = Encoder(A0, A1, 8192);
+
+// Interrupt routine intialisation
+// channel A and B callbacks
+void doA(){encoder.handleA();}
+void doB(){encoder.handleB();}
+
+// encoder interrupt init
+PciListenerImp listenerA(encoder.pinA, doA);
+PciListenerImp listenerB(encoder.pinB, doB);
+
+
+// voltage set point variable
+float target_voltage = 2;
+// instantiate the commander
+Commander command = Commander(Serial);
+void doTarget(char* cmd) { command.scalar(&target_voltage, cmd); }
+
+void setup() {
+
+ // initialize encoder sensor hardware
+ encoder.init();
+ // interrupt initialization
+ PciManager.registerListener(&listenerA);
+ PciManager.registerListener(&listenerB);
+ // link the motor to the sensor
+ motor.linkSensor(&encoder);
+
+ // driver config
+ // power supply voltage [V]
+ driver.voltage_power_supply = 12;
+ driver.init();
+ // link the motor and the driver
+ motor.linkDriver(&driver);
+
+ // choose FOC modulation (optional)
+ motor.foc_modulation = FOCModulationType::SpaceVectorPWM;
+
+ // set motion control loop to be used
+ motor.controller = MotionControlType::torque;
+
+ // use monitoring with serial for motor init
+ // comment out if not needed
+ motor.useMonitoring(Serial);
+
+ // use monitoring with serial
+ Serial.begin(115200);
+ // comment out if not needed
+ motor.useMonitoring(Serial);
+
+ // initialize motor
+ motor.init();
+ // align sensor and start FOC
+ motor.initFOC();
+
+ // add target command T
+ command.add('T', doTarget, "target voltage");
+
+ Serial.println(F("Motor ready."));
+ Serial.println(F("Set the target voltage using serial terminal:"));
+ _delay(1000);
+}
+
+void loop() {
+
+ // main FOC algorithm function
+ // the faster you run this function the better
+ // Arduino UNO loop ~1kHz
+ // Bluepill loop ~10kHz
+ motor.loopFOC();
+
+ // Motion control function
+ // velocity, position or voltage (defined in motor.controller)
+ // this function can be run at much lower frequency than loopFOC() function
+ // You can also use motor.move() and set the motor.target in the code
+ motor.move(target_voltage);
+
+ // user communication
+ command.run();
+}
\ No newline at end of file
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/hardware_specific_examples/Odrive_examples/odrive_example_encoder/odrive_example_encoder.ino b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/hardware_specific_examples/Odrive_examples/odrive_example_encoder/odrive_example_encoder.ino
new file mode 100644
index 0000000..504ab9c
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/hardware_specific_examples/Odrive_examples/odrive_example_encoder/odrive_example_encoder.ino
@@ -0,0 +1,138 @@
+/*
+ Odrive robotics' hardware is one of the best BLDC motor foc supporting hardware out there.
+
+ This is an example code that can be directly uploaded to the Odrive using the SWD programmer.
+ This code uses an encoder with 500 cpr and a BLDC motor with 7 pole pairs connected to the M0 interface of the Odrive.
+
+ This is a short template code and the idea is that you are able to adapt to your needs not to be a complete solution. :D
+*/
+#include
+
+// Odrive M0 motor pinout
+#define M0_INH_A PA8
+#define M0_INH_B PA9
+#define M0_INH_C PA10
+#define M0_INL_A PB13
+#define M0_INL_B PB14
+#define M0_INL_C PB15
+// M0 currnets
+#define M0_IB PC0
+#define M0_IC PC1
+// Odrive M0 encoder pinout
+#define M0_ENC_A PB4
+#define M0_ENC_B PB5
+#define M0_ENC_Z PC9
+
+
+// Odrive M1 motor pinout
+#define M1_INH_A PC6
+#define M1_INH_B PC7
+#define M1_INH_C PC8
+#define M1_INL_A PA7
+#define M1_INL_B PB0
+#define M1_INL_C PB1
+// M0 currnets
+#define M1_IB PC2
+#define M1_IC PC3
+// Odrive M1 encoder pinout
+#define M1_ENC_A PB6
+#define M1_ENC_B PB7
+#define M1_ENC_Z PC15
+
+// M1 & M2 common enable pin
+#define EN_GATE PB12
+
+// SPI pinout
+#define SPI3_SCL PC10
+#define SPI3_MISO PC11
+#define SPI3_MOSO PC12
+
+// Motor instance
+BLDCMotor motor = BLDCMotor(7);
+BLDCDriver6PWM driver = BLDCDriver6PWM(M0_INH_A,M0_INL_A, M0_INH_B,M0_INL_B, M0_INH_C,M0_INL_C, EN_GATE);
+
+// instantiate the commander
+Commander command = Commander(Serial);
+void doMotor(char* cmd) { command.motor(&motor, cmd); }
+
+// low side current sensing define
+// 0.0005 Ohm resistor
+// gain of 10x
+// current sensing on B and C phases, phase A not connected
+LowsideCurrentSense current_sense = LowsideCurrentSense(0.0005f, 10.0f, _NC, M0_IB, M0_IC);
+
+Encoder encoder = Encoder(M0_ENC_A, M0_ENC_B, 500,M0_ENC_Z);
+// Interrupt routine intialisation
+// channel A and B callbacks
+void doA(){encoder.handleA();}
+void doB(){encoder.handleB();}
+void doI(){encoder.handleIndex();}
+
+void setup(){
+
+ // use monitoring with serial
+ Serial.begin(115200);
+ // enable more verbose output for debugging
+ // comment out if not needed
+ SimpleFOCDebug::enable(&Serial);
+
+ // pwm frequency to be used [Hz]
+ driver.pwm_frequency = 20000;
+ // power supply voltage [V]
+ driver.voltage_power_supply = 20;
+ // Max DC voltage allowed - default voltage_power_supply
+ driver.voltage_limit = 20;
+ // driver init
+ driver.init();
+ // link the motor and the driver
+ motor.linkDriver(&driver);
+
+ // initialize encoder sensor hardware
+ encoder.init();
+ encoder.enableInterrupts(doA, doB, doI);
+ // link the motor to the sensor
+ motor.linkSensor(&encoder);
+
+ // control loop type and torque mode
+ motor.torque_controller = TorqueControlType::voltage;
+ motor.controller = MotionControlType::torque;
+
+ // max voltage allowed for motion control
+ motor.voltage_limit = 8.0;
+ // alignment voltage limit
+ motor.voltage_sensor_align = 0.5;
+
+ // comment out if not needed
+ motor.useMonitoring(Serial);
+ motor.monitor_variables = _MON_CURR_Q | _MON_CURR_D;
+ motor.monitor_downsample = 1000;
+
+ // add target command T
+ command.add('M', doMotor, "motor M0");
+
+ // initialise motor
+ motor.init();
+
+ // link the driver
+ current_sense.linkDriver(&driver);
+ // init the current sense
+ current_sense.init();
+ current_sense.skip_align = true;
+ motor.linkCurrentSense(¤t_sense);
+
+ // init FOC
+ motor.initFOC();
+ delay(1000);
+}
+
+void loop(){
+
+ // foc loop
+ motor.loopFOC();
+ // motion control
+ motor.move();
+ // monitoring
+ motor.monitor();
+ // user communication
+ command.run();
+}
\ No newline at end of file
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/hardware_specific_examples/Odrive_examples/odrive_example_spi/odrive_example_spi.ino b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/hardware_specific_examples/Odrive_examples/odrive_example_spi/odrive_example_spi.ino
new file mode 100644
index 0000000..7abcde5
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/hardware_specific_examples/Odrive_examples/odrive_example_spi/odrive_example_spi.ino
@@ -0,0 +1,136 @@
+/*
+ Odrive robotics' hardware is one of the best BLDC motor foc supporting hardware out there.
+
+ This is an example code that can be directly uploaded to the Odrive using the SWD programmer.
+ This code uses an magnetic spi sensor AS5047 and a BLDC motor with 11 pole pairs connected to the M0 interface of the Odrive.
+
+ This is a short template code and the idea is that you are able to adapt to your needs not to be a complete solution. :D
+*/
+#include
+
+// Odrive M0 motor pinout
+#define M0_INH_A PA8
+#define M0_INH_B PA9
+#define M0_INH_C PA10
+#define M0_INL_A PB13
+#define M0_INL_B PB14
+#define M0_INL_C PB15
+// M0 currnets
+#define M0_IB PC0
+#define M0_IC PC1
+// Odrive M0 encoder pinout
+#define M0_ENC_A PB4
+#define M0_ENC_B PB5
+#define M0_ENC_Z PC9
+
+
+// Odrive M1 motor pinout
+#define M1_INH_A PC6
+#define M1_INH_B PC7
+#define M1_INH_C PC8
+#define M1_INL_A PA7
+#define M1_INL_B PB0
+#define M1_INL_C PB1
+// M0 currnets
+#define M1_IB PC2
+#define M1_IC PC3
+// Odrive M1 encoder pinout
+#define M1_ENC_A PB6
+#define M1_ENC_B PB7
+#define M1_ENC_Z PC15
+
+// M1 & M2 common enable pin
+#define EN_GATE PB12
+
+// SPI pinout
+#define SPI3_SCL PC10
+#define SPI3_MISO PC11
+#define SPI3_MOSO PC12
+
+// Motor instance
+BLDCMotor motor = BLDCMotor(11);
+BLDCDriver6PWM driver = BLDCDriver6PWM(M0_INH_A,M0_INL_A, M0_INH_B,M0_INL_B, M0_INH_C,M0_INL_C, EN_GATE);
+
+// instantiate the commander
+Commander command = Commander(Serial);
+void doMotor(char* cmd) { command.motor(&motor, cmd); }
+
+// low side current sensing define
+// 0.0005 Ohm resistor
+// gain of 10x
+// current sensing on B and C phases, phase A not connected
+LowsideCurrentSense current_sense = LowsideCurrentSense(0.0005f, 10.0f, _NC, M0_IB, M0_IC);
+
+// MagneticSensorSPI(int cs, float _cpr, int _angle_register)
+// config - SPI config
+// cs - SPI chip select pin
+MagneticSensorSPI sensor = MagneticSensorSPI(AS5147_SPI, M0_ENC_A);
+SPIClass SPI_3(SPI3_MOSO, SPI3_MISO, SPI3_SCL);
+
+void setup(){
+
+ // use monitoring with serial
+ Serial.begin(115200);
+ // enable more verbose output for debugging
+ // comment out if not needed
+ SimpleFOCDebug::enable(&Serial);
+
+ // pwm frequency to be used [Hz]
+ driver.pwm_frequency = 20000;
+ // power supply voltage [V]
+ driver.voltage_power_supply = 20;
+ // Max DC voltage allowed - default voltage_power_supply
+ driver.voltage_limit = 20;
+ // driver init
+ driver.init();
+ // link the motor and the driver
+ motor.linkDriver(&driver);
+
+ // initialise magnetic sensor hardware
+ sensor.init(&SPI_3);
+ // link the motor to the sensor
+ motor.linkSensor(&sensor);
+
+ // control loop type and torque mode
+ motor.torque_controller = TorqueControlType::voltage;
+ motor.controller = MotionControlType::torque;
+
+ // max voltage allowed for motion control
+ motor.voltage_limit = 8.0;
+ // alignment voltage limit
+ motor.voltage_sensor_align = 0.5;
+
+ // comment out if not needed
+ motor.useMonitoring(Serial);
+ motor.monitor_variables = _MON_CURR_Q | _MON_CURR_D;
+ motor.monitor_downsample = 1000;
+
+ // add target command T
+ command.add('M', doMotor, "motor M0");
+
+ // initialise motor
+ motor.init();
+
+ // link the driver
+ current_sense.linkDriver(&driver);
+ // init the current sense
+ current_sense.init();
+ current_sense.skip_align = true;
+ motor.linkCurrentSense(¤t_sense);
+
+ // init FOC
+ motor.initFOC();
+ delay(1000);
+}
+
+void loop(){
+
+ // foc loop
+ motor.loopFOC();
+ // motion control
+ motor.move();
+ // monitoring
+ motor.monitor();
+ // user communication
+ command.run();
+}
\ No newline at end of file
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/hardware_specific_examples/SAMD_examples/README.md b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/hardware_specific_examples/SAMD_examples/README.md
new file mode 100644
index 0000000..d1a5258
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/hardware_specific_examples/SAMD_examples/README.md
@@ -0,0 +1,62 @@
+
+# SAMD Support
+
+SimpleFOC supports many SAMD21 MCUs, really any SAMD21 supported by Arduino core should work.
+
+## Pin assignments
+
+The SAMD chips have some very powerful PWM features, but do not have flexible pin assignments.
+
+You should be able to use *most* (but not all!), pin combinations for attaching your motor's PWM pins. Please ignore the board descriptions and pinout diagrammes regarding PWM-pins on SAMD boards. They are pretty much all incorrect to varying degrees of awfulness.
+
+On SAMD we use TCC and TC timer peripherals (built into the SAMD chip) to control the PWM. Depending on the chip there are various timer units, whose PWM outputs are attached to various different pins, and it is all very complicated. Luckily SimpleFOC sets it all up automatically *if* there is a compatible configuration for those pins.
+
+Not all timers are created equal. The TCC timers are pretty awesome for PWM motor control, while the TC timers are just ok for the job. So to get best performance, you want to use just TCC timer pins if you can.
+
+By enabling
+
+```
+ #define SIMPLEFOC_SAMD_DEBUG
+```
+
+in drivers/hardware_specific/samd_mcu.cpp
+you will see a table of pin assignments printed on the serial console, as well as the timers SimpleFOC was able to find and configure on the pins you specified. You can use this to optimize your choice of pins if you want.
+
+You can configure up to 12 pins for PWM motor control, i.e. 6x 2-PWM motors, 4x 3-PWM motors, 3x 4-PWM motors or 2x 6-PWM motors.
+
+## PWM control modes
+
+All modes (3-PWM, 6-PWM, Stepper 2-PWM and Stepper 4-PWM) are supported.
+
+For 2-, 3- amd 4- PWM, any valid pin-combinations can be used. If you stick to TCC timers rather than using TC timers, then you'll get getter PWM waveforms. If you use pins which are all on the same TCC unit, you'll get the best result, with the PWM signals all perfectly aligned as well.
+
+For 6-PWM, the situation is much more complicated:
+TC timers cannot be used for 6-PWM, only TCC timers.
+
+For Hardware Dead-Time insertion, you must use H and L pins for one phase from the same TCC unit, and on the same channel, but using complementary WOs (Waveform Outputs, i.e. PWM output pins). Check the table to find pins on the same channel (like TCC0-0) but complementary WOs (like TCC0-0[0] and TCC0-0[4] or TCC1-0[0] and TCC1-0[2]).
+
+For Software Dead-Time insertion, you must use the same TCC and different channels for the H and L pins of the same phase.
+
+Note: in all of the above note that you *cannot* set the timers or WOs used - they are fixed, and determined by the pins you selected. SimpleFOC will find the best combination of timers given the pins, trying to use TCC timers before TC, and trying to keep things on the same timers as much as possible. If you configure multiple motors, it will take into account the pins already assigned to other motors.
+So it is matter of choosing the right pins, nothing else.
+
+Note also: Unfortunately you can't set the PWM frequency. It is currently fixed at 24KHz. This is a tradeoff between limiting PWM resolution vs
+increasing frequency, and also due to keeping the pin assignemts flexible, which would not be possible if we ran the timers at different rates.
+
+## Status
+
+Currently, SAMD21 is supported, and SAMD51 is unsupported. SAMD51 support is in progress.
+
+Boards tested:
+
+ * Arduino Nano 33 IoT
+ * Arduino MKR1000
+ * Arduino MKR1010 Wifi
+ * Seeduino XIAO
+ * Feather M0 Basic
+
+Environments tested:
+
+ * Arduino IDE
+ * Arduino Pro IDE
+ * Sloeber
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/hardware_specific_examples/SAMD_examples/nano33IoT/nano33IoT_velocity_control/nano33IoT_velocity_control.ino b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/hardware_specific_examples/SAMD_examples/nano33IoT/nano33IoT_velocity_control/nano33IoT_velocity_control.ino
new file mode 100644
index 0000000..650050e
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/hardware_specific_examples/SAMD_examples/nano33IoT/nano33IoT_velocity_control/nano33IoT_velocity_control.ino
@@ -0,0 +1,69 @@
+
+// show the infos for SAMD pin assignment on serial console
+// set this #define SIMPLEFOC_SAMD_DEBUG in drivers/hardware_specific/samd21_mcu.h
+
+
+#include "Arduino.h"
+#include
+#include
+
+// this is for an AS5048B absolute magnetic encoder on I2C address 0x41
+MagneticSensorI2C sensor = MagneticSensorI2C(0x41, 14, 0xFE, 8);
+
+// small BLDC gimbal motor, 7 pole-pairs
+BLDCMotor motor = BLDCMotor(7);
+// 3-PWM driving on pins 6, 5 and 8 - these are all on the same timer unit (TCC0), but different channels
+BLDCDriver3PWM driver = BLDCDriver3PWM(6,5,8);
+
+// velocity set point variable
+float target_velocity = 2.0f;
+// instantiate the commander
+Commander command = Commander(SerialUSB);
+void doTarget(char* cmd) { command.scalar(&target_velocity, cmd); }
+
+
+void setup() {
+ // use monitoring with serial
+ Serial.begin(115200);
+ // enable more verbose output for debugging
+ // comment out if not needed
+ SimpleFOCDebug::enable(&Serial);
+
+ delay(1000);
+ Serial.println("Initializing...");
+
+ sensor.init();
+ Wire.setClock(400000);
+ motor.linkSensor(&sensor);
+ driver.voltage_power_supply = 9;
+ driver.init();
+ motor.linkDriver(&driver);
+ motor.controller = MotionControlType::velocity;
+ motor.PID_velocity.P = 0.2f;
+ motor.PID_velocity.I = 20;
+ motor.PID_velocity.D = 0.001f;
+ motor.PID_velocity.output_ramp = 1000;
+ motor.LPF_velocity.Tf = 0.01f;
+ motor.voltage_limit = 9;
+ //motor.P_angle.P = 20;
+ motor.init();
+ motor.initFOC();
+
+ // add target command T
+ command.add('T', doTarget, "target velocity");
+
+ Serial.println(F("Motor ready."));
+ Serial.println(F("Set the target velocity using serial terminal:"));
+ delay(100);
+}
+
+
+
+void loop() {
+// Serial.print("Sensor: ");
+// Serial.println(sensor.getAngle());
+ motor.loopFOC();
+ motor.move(target_velocity);
+ // user communication
+ command.run();
+}
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/hardware_specific_examples/SimpleFOC-PowerShield/version_v02/single_full_control_example/single_full_control_example.ino b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/hardware_specific_examples/SimpleFOC-PowerShield/version_v02/single_full_control_example/single_full_control_example.ino
new file mode 100644
index 0000000..bc38743
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/hardware_specific_examples/SimpleFOC-PowerShield/version_v02/single_full_control_example/single_full_control_example.ino
@@ -0,0 +1,105 @@
+
+#include
+
+// BLDC motor & driver instance
+BLDCMotor motor = BLDCMotor(7);
+BLDCDriver3PWM driver = BLDCDriver3PWM(9, 5, 6, 8, 4, 7);
+
+// encoder instance
+Encoder encoder = Encoder(10, 11, 500);
+// channel A and B callbacks
+void doA(){encoder.handleA();}
+void doB(){encoder.handleB();}
+
+// inline current sensor instance
+InlineCurrentSense current_sense = InlineCurrentSense(0.001f, 50.0f, A0, A1);
+
+// commander communication instance
+Commander command = Commander(Serial);
+// void doMotor(char* cmd){ command.motor(&motor, cmd); }
+void doTarget(char* cmd){ command.scalar(&motor.target, cmd); }
+
+void setup() {
+
+ // use monitoring with serial
+ Serial.begin(115200);
+ // enable more verbose output for debugging
+ // comment out if not needed
+ SimpleFOCDebug::enable(&Serial);
+
+ // initialize encoder sensor hardware
+ encoder.init();
+ encoder.enableInterrupts(doA, doB);
+ // link the motor to the sensor
+ motor.linkSensor(&encoder);
+
+ // driver config
+ // power supply voltage [V]
+ driver.voltage_power_supply = 20;
+ driver.init();
+ // link driver
+ motor.linkDriver(&driver);
+ // link current sense and the driver
+ current_sense.linkDriver(&driver);
+
+ motor.voltage_sensor_align = 1;
+ // set control loop type to be used
+ motor.torque_controller = TorqueControlType::foc_current;
+ motor.controller = MotionControlType::torque;
+
+ // contoller configuration based on the controll type
+ motor.PID_velocity.P = 0.05f;
+ motor.PID_velocity.I = 1;
+ motor.PID_velocity.D = 0;
+ // default voltage_power_supply
+ motor.voltage_limit = 12;
+
+ // velocity low pass filtering time constant
+ motor.LPF_velocity.Tf = 0.01f;
+
+ // angle loop controller
+ motor.P_angle.P = 20;
+ // angle loop velocity limit
+ motor.velocity_limit = 20;
+
+ // comment out if not needed
+ motor.useMonitoring(Serial);
+ motor.monitor_downsample = 0; // disable intially
+ motor.monitor_variables = _MON_TARGET | _MON_VEL | _MON_ANGLE; // monitor target velocity and angle
+
+ // current sense init and linking
+ current_sense.init();
+ motor.linkCurrentSense(¤t_sense);
+
+ // initialise motor
+ motor.init();
+ // align encoder and start FOC
+ motor.initFOC();
+
+ // set the inital target value
+ motor.target = 0;
+
+ // subscribe motor to the commander
+ // command.add('M', doMotor, "motor");
+ command.add('T', doTarget, "target");
+
+ // Run user commands to configure and the motor (find the full command list in docs.simplefoc.com)
+ Serial.println("Motor ready.");
+
+ _delay(1000);
+}
+
+
+void loop() {
+ // iterative setting FOC phase voltage
+ motor.loopFOC();
+
+ // iterative function setting the outter loop target
+ motor.move();
+
+ // motor monitoring
+ motor.monitor();
+
+ // user communication
+ command.run();
+}
\ No newline at end of file
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/hardware_specific_examples/SimpleFOCMini/angle_control/angle_control.ino b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/hardware_specific_examples/SimpleFOCMini/angle_control/angle_control.ino
new file mode 100644
index 0000000..8eb122a
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/hardware_specific_examples/SimpleFOCMini/angle_control/angle_control.ino
@@ -0,0 +1,128 @@
+/**
+ *
+ * SimpleFOCMini motor control example
+ *
+ * For Arduino UNO, the most convenient way to use the board is to stack it to the pins:
+ * - 12 - GND
+ * - 11 - IN1
+ * - 10 - IN2
+ * - 9 - IN3
+ * - 8 - EN
+ *
+ * For other boards with UNO headers but more PWM channles such as esp32, nucleo-64, samd51 metro etc, the best way to most convenient pinout is:
+ * - GND - GND
+ * - 13 - IN1
+ * - 12 - IN2
+ * - 11 - IN3
+ * - 9 - EN
+ *
+ * For the boards without arduino uno headers, the choice of pinout is a lot less constrained.
+ *
+ */
+#include
+
+
+// BLDC motor & driver instance
+BLDCMotor motor = BLDCMotor(11);
+BLDCDriver3PWM driver = BLDCDriver3PWM(11, 10, 9, 8);
+
+// encoder instance
+Encoder encoder = Encoder(2, 3, 500);
+// Interrupt routine intialisation
+// channel A and B callbacks
+void doA(){encoder.handleA();}
+void doB(){encoder.handleB();}
+
+// instantiate the commander
+Commander command = Commander(Serial);
+void doMotor(char* cmd) { command.motor(&motor, cmd); }
+
+void setup() {
+ // use monitoring with serial
+ Serial.begin(115200);
+ // enable more verbose output for debugging
+ // comment out if not needed
+ SimpleFOCDebug::enable(&Serial);
+
+ // if SimpleFOCMini is stacked in arduino headers
+ // on pins 12,11,10,9,8
+ // pin 12 is used as ground
+ pinMode(12,OUTPUT);
+ pinMode(12,LOW);
+
+ // initialize encoder sensor hardware
+ encoder.init();
+ encoder.enableInterrupts(doA, doB);
+ // link the motor to the sensor
+ motor.linkSensor(&encoder);
+
+ // driver config
+ // power supply voltage [V]
+ driver.voltage_power_supply = 12;
+ driver.init();
+ // link the motor and the driver
+ motor.linkDriver(&driver);
+
+ // aligning voltage [V]
+ motor.voltage_sensor_align = 3;
+
+ // set motion control loop to be used
+ motor.controller = MotionControlType::angle;
+
+ // contoller configuration
+ // default parameters in defaults.h
+
+ // velocity PI controller parameters
+ motor.PID_velocity.P = 0.2f;
+ motor.PID_velocity.I = 20;
+ motor.PID_velocity.D = 0;
+ // default voltage_power_supply
+ motor.voltage_limit = 6;
+ // jerk control using voltage voltage ramp
+ // default value is 300 volts per sec ~ 0.3V per millisecond
+ motor.PID_velocity.output_ramp = 1000;
+
+ // velocity low pass filtering time constant
+ motor.LPF_velocity.Tf = 0.01f;
+
+ // angle P controller
+ motor.P_angle.P = 20;
+ // maximal velocity of the position control
+ motor.velocity_limit = 4;
+
+ // comment out if not needed
+ motor.useMonitoring(Serial);
+
+ // initialize motor
+ motor.init();
+ // align encoder and start FOC
+ motor.initFOC();
+
+ // add target command M
+ command.add('M', doMotor, "motor");
+
+ Serial.println(F("Motor ready."));
+ Serial.println(F("Set the target angle using serial terminal:"));
+ _delay(1000);
+}
+
+void loop() {
+ // main FOC algorithm function
+ // the faster you run this function the better
+ // Arduino UNO loop ~1kHz
+ // Bluepill loop ~10kHz
+ motor.loopFOC();
+
+ // Motion control function
+ // velocity, position or voltage (defined in motor.controller)
+ // this function can be run at much lower frequency than loopFOC() function
+ // You can also use motor.move() and set the motor.target in the code
+ motor.move();
+
+ // function intended to be used with serial plotter to monitor motor variables
+ // significantly slowing the execution down!!!!
+ // motor.monitor();
+
+ // user communication
+ command.run();
+}
\ No newline at end of file
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/hardware_specific_examples/SimpleFOCMini/open_loop/open_loop.ino b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/hardware_specific_examples/SimpleFOCMini/open_loop/open_loop.ino
new file mode 100644
index 0000000..c458718
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/hardware_specific_examples/SimpleFOCMini/open_loop/open_loop.ino
@@ -0,0 +1,93 @@
+/**
+ *
+ * SimpleFOCMini motor control example
+ *
+ * For Arduino UNO or the other boards with the UNO headers
+ * the most convenient way to use the board is to stack it to the pins:
+ * - 12 - ENABLE
+ * - 11 - IN1
+ * - 10 - IN2
+ * - 9 - IN3
+ *
+ */
+#include
+
+
+// BLDC motor & driver instance
+BLDCMotor motor = BLDCMotor(11);
+// BLDCDriver3PWM driver = BLDCDriver3PWM(11, 10, 9, 8); // mini v1.0
+BLDCDriver3PWM driver = BLDCDriver3PWM(9, 10, 11, 12); // mini v1.1
+
+// instantiate the commander
+Commander command = Commander(Serial);
+void doMotor(char* cmd) { command.motor(&motor, cmd); }
+
+void setup() {
+ // use monitoring with serial
+ Serial.begin(115200);
+ // enable more verbose output for debugging
+ // comment out if not needed
+ SimpleFOCDebug::enable(&Serial);
+
+ // if SimpleFOCMini is stacked in arduino headers
+ // on pins 12,11,10,9,8
+ // pin 12 is used as ground
+ pinMode(12,OUTPUT);
+ pinMode(12,LOW);
+
+ // driver config
+ // power supply voltage [V]
+ driver.voltage_power_supply = 12;
+ driver.init();
+ // link the motor and the driver
+ motor.linkDriver(&driver);
+
+ // aligning voltage [V]
+ motor.voltage_sensor_align = 3;
+
+ // set motion control loop to be used
+ motor.controller = MotionControlType::velocity_openloop;
+
+ // default voltage_power_supply
+ motor.voltage_limit = 2; // Volts
+
+ // comment out if not needed
+ motor.useMonitoring(Serial);
+
+ // initialize motor
+ motor.init();
+ // align encoder and start FOC
+ motor.initFOC();
+
+ // add target command M
+ command.add('M', doMotor, "motor");
+
+ Serial.println(F("Motor ready."));
+ Serial.println(F("Set the target velocity using serial terminal:"));
+
+ motor.target = 1; //initial target velocity 1 rad/s
+ Serial.println("Target velocity: 1 rad/s");
+ Serial.println("Voltage limit 2V");
+ _delay(1000);
+}
+
+void loop() {
+ // main FOC algorithm function
+ // the faster you run this function the better
+ // Arduino UNO loop ~1kHz
+ // Bluepill loop ~10kHz
+ motor.loopFOC();
+
+ // Motion control function
+ // velocity, position or voltage (defined in motor.controller)
+ // this function can be run at much lower frequency than loopFOC() function
+ // You can also use motor.move() and set the motor.target in the code
+ motor.move();
+
+ // function intended to be used with serial plotter to monitor motor variables
+ // significantly slowing the execution down!!!!
+ // motor.monitor();
+
+ // user communication
+ command.run();
+}
\ No newline at end of file
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/hardware_specific_examples/SimpleFOCShield/version_v1/double_full_control_example/double_full_control_example.ino b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/hardware_specific_examples/SimpleFOCShield/version_v1/double_full_control_example/double_full_control_example.ino
new file mode 100644
index 0000000..fb5e156
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/hardware_specific_examples/SimpleFOCShield/version_v1/double_full_control_example/double_full_control_example.ino
@@ -0,0 +1,121 @@
+
+#include
+
+// BLDC motor & driver instance
+BLDCMotor motor1 = BLDCMotor(11);
+BLDCDriver3PWM driver1 = BLDCDriver3PWM(9, 5, 6, 8);
+
+// BLDC motor & driver instance
+BLDCMotor motor2 = BLDCMotor(11);
+BLDCDriver3PWM driver2 = BLDCDriver3PWM(3, 10, 11, 7);
+
+// encoder instance
+Encoder encoder1 = Encoder(2, A3, 500);
+// channel A and B callbacks
+void doA1(){encoder1.handleA();}
+void doB1(){encoder1.handleB();}
+
+// encoder instance
+Encoder encoder2 = Encoder(A1, A2, 500);
+// channel A and B callbacks
+void doA2(){encoder2.handleA();}
+void doB2(){encoder2.handleB();}
+
+// commander communication instance
+Commander command = Commander(Serial);
+void doMotor1(char* cmd){ command.motor(&motor1, cmd); }
+void doMotor2(char* cmd){ command.motor(&motor2, cmd); }
+
+void setup() {
+
+ // use monitoring with serial
+ Serial.begin(115200);
+ // enable more verbose output for debugging
+ // comment out if not needed
+ SimpleFOCDebug::enable(&Serial);
+
+ // initialize encoder sensor hardware
+ encoder1.init();
+ encoder1.enableInterrupts(doA1, doB1);
+ // initialize encoder sensor hardware
+ encoder2.init();
+ encoder2.enableInterrupts(doA2, doB2);
+ // link the motor to the sensor
+ motor1.linkSensor(&encoder1);
+ motor2.linkSensor(&encoder2);
+
+
+ // driver config
+ // power supply voltage [V]
+ driver1.voltage_power_supply = 12;
+ driver1.init();
+ // link driver
+ motor1.linkDriver(&driver1);
+ // power supply voltage [V]
+ driver2.voltage_power_supply = 12;
+ driver2.init();
+ // link driver
+ motor2.linkDriver(&driver2);
+
+ // set control loop type to be used
+ motor1.controller = MotionControlType::torque;
+ motor2.controller = MotionControlType::torque;
+
+ // contoller configuration based on the controll type
+ motor1.PID_velocity.P = 0.05f;
+ motor1.PID_velocity.I = 1;
+ motor1.PID_velocity.D = 0;
+ // default voltage_power_supply
+ motor1.voltage_limit = 12;
+ // contoller configuration based on the controll type
+ motor2.PID_velocity.P = 0.05f;
+ motor2.PID_velocity.I = 1;
+ motor2.PID_velocity.D = 0;
+ // default voltage_power_supply
+ motor2.voltage_limit = 12;
+
+ // angle loop velocity limit
+ motor1.velocity_limit = 20;
+ motor2.velocity_limit = 20;
+
+ // comment out if not needed
+ motor1.useMonitoring(Serial);
+ motor2.useMonitoring(Serial);
+
+ // initialise motor
+ motor1.init();
+ // align encoder and start FOC
+ motor1.initFOC();
+
+ // initialise motor
+ motor2.init();
+ // align encoder and start FOC
+ motor2.initFOC();
+
+ // set the inital target value
+ motor1.target = 2;
+ motor2.target = 2;
+
+ // subscribe motor to the commander
+ command.add('A', doMotor1, "motor 1");
+ command.add('B', doMotor2, "motor 2");
+
+ // Run user commands to configure and the motor (find the full command list in docs.simplefoc.com)
+ Serial.println(F("Double motor sketch ready."));
+
+ _delay(1000);
+}
+
+
+void loop() {
+ // iterative setting FOC phase voltage
+ motor1.loopFOC();
+ motor2.loopFOC();
+
+ // iterative function setting the outter loop target
+ motor1.move();
+ motor2.move();
+
+ // user communication
+ command.run();
+}
\ No newline at end of file
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/hardware_specific_examples/SimpleFOCShield/version_v1/single_full_control_example/single_full_control_example.ino b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/hardware_specific_examples/SimpleFOCShield/version_v1/single_full_control_example/single_full_control_example.ino
new file mode 100644
index 0000000..3faa38b
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/hardware_specific_examples/SimpleFOCShield/version_v1/single_full_control_example/single_full_control_example.ino
@@ -0,0 +1,92 @@
+
+#include
+
+// BLDC motor & driver instance
+BLDCMotor motor = BLDCMotor(11);
+BLDCDriver3PWM driver = BLDCDriver3PWM(9, 5, 6, 8);
+
+// encoder instance
+Encoder encoder = Encoder(2, 3, 500);
+// channel A and B callbacks
+void doA(){encoder.handleA();}
+void doB(){encoder.handleB();}
+
+// commander communication instance
+Commander command = Commander(Serial);
+void doMotor(char* cmd){ command.motor(&motor, cmd); }
+
+void setup() {
+
+ // use monitoring with serial
+ Serial.begin(115200);
+ // enable more verbose output for debugging
+ // comment out if not needed
+ SimpleFOCDebug::enable(&Serial);
+
+ // initialize encoder sensor hardware
+ encoder.init();
+ encoder.enableInterrupts(doA, doB);
+ // link the motor to the sensor
+ motor.linkSensor(&encoder);
+
+ // driver config
+ // power supply voltage [V]
+ driver.voltage_power_supply = 12;
+ driver.init();
+ // link driver
+ motor.linkDriver(&driver);
+
+ // set control loop type to be used
+ motor.controller = MotionControlType::torque;
+
+ // contoller configuration based on the controll type
+ motor.PID_velocity.P = 0.05f;
+ motor.PID_velocity.I = 1;
+ motor.PID_velocity.D = 0;
+ // default voltage_power_supply
+ motor.voltage_limit = 12;
+
+ // velocity low pass filtering time constant
+ motor.LPF_velocity.Tf = 0.01f;
+
+ // angle loop controller
+ motor.P_angle.P = 20;
+ // angle loop velocity limit
+ motor.velocity_limit = 20;
+
+ // comment out if not needed
+ motor.useMonitoring(Serial);
+ motor.monitor_downsample = 0; // disable intially
+ motor.monitor_variables = _MON_TARGET | _MON_VEL | _MON_ANGLE; // monitor target velocity and angle
+
+ // initialise motor
+ motor.init();
+ // align encoder and start FOC
+ motor.initFOC();
+
+ // set the inital target value
+ motor.target = 2;
+
+ // subscribe motor to the commander
+ command.add('M', doMotor, "motor");
+
+ // Run user commands to configure and the motor (find the full command list in docs.simplefoc.com)
+ Serial.println(F("Motor commands sketch | Initial motion control > torque/voltage : target 2V."));
+
+ _delay(1000);
+}
+
+
+void loop() {
+ // iterative setting FOC phase voltage
+ motor.loopFOC();
+
+ // iterative function setting the outter loop target
+ motor.move();
+
+ // motor monitoring
+ motor.monitor();
+
+ // user communication
+ command.run();
+}
\ No newline at end of file
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/hardware_specific_examples/SimpleFOCShield/version_v2/double_full_control_example/double_full_control_example.ino b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/hardware_specific_examples/SimpleFOCShield/version_v2/double_full_control_example/double_full_control_example.ino
new file mode 100644
index 0000000..8eb3a86
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/hardware_specific_examples/SimpleFOCShield/version_v2/double_full_control_example/double_full_control_example.ino
@@ -0,0 +1,147 @@
+
+#include
+
+// BLDC motor & driver instance
+BLDCMotor motor1 = BLDCMotor(11);
+BLDCDriver3PWM driver1 = BLDCDriver3PWM(5, 10, 6, 8);
+
+// BLDC motor & driver instance
+BLDCMotor motor2 = BLDCMotor(11);
+BLDCDriver3PWM driver2 = BLDCDriver3PWM(3, 9, 11, 7);
+
+// encoder instance
+Encoder encoder1 = Encoder(12, 2, 500);
+// channel A and B callbacks
+void doA1(){encoder1.handleA();}
+void doB1(){encoder1.handleB();}
+
+// encoder instance
+Encoder encoder2 = Encoder(A5, A4, 500);
+// channel A and B callbacks
+void doA2(){encoder2.handleA();}
+void doB2(){encoder2.handleB();}
+
+
+// inline current sensor instance
+// check if your board has R010 (0.01 ohm resistor) or R006 (0.006 mOhm resistor)
+InlineCurrentSense current_sense1 = InlineCurrentSense(0.01f, 50.0f, A0, A2);
+
+// inline current sensor instance
+// check if your board has R010 (0.01 ohm resistor) or R006 (0.006 mOhm resistor)
+InlineCurrentSense current_sense2 = InlineCurrentSense(0.01f, 50.0f, A1, A3);
+
+// commander communication instance
+Commander command = Commander(Serial);
+// void doMotor1(char* cmd){ command.motor(&motor1, cmd); }
+// void doMotor2(char* cmd){ command.motor(&motor2, cmd); }
+void doTarget1(char* cmd){ command.scalar(&motor1.target, cmd); }
+void doTarget2(char* cmd){ command.scalar(&motor2.target, cmd); }
+
+void setup() {
+
+ // use monitoring with serial
+ Serial.begin(115200);
+ // enable more verbose output for debugging
+ // comment out if not needed
+ SimpleFOCDebug::enable(&Serial);
+
+ // initialize encoder sensor hardware
+ encoder1.init();
+ encoder1.enableInterrupts(doA1, doB1);
+ // initialize encoder sensor hardware
+ encoder2.init();
+ encoder2.enableInterrupts(doA2, doB2);
+ // link the motor to the sensor
+ motor1.linkSensor(&encoder1);
+ motor2.linkSensor(&encoder2);
+
+
+ // driver config
+ // power supply voltage [V]
+ driver1.voltage_power_supply = 12;
+ driver1.init();
+ // link driver
+ motor1.linkDriver(&driver1);
+ // link current sense and the driver
+ current_sense1.linkDriver(&driver1);
+
+ // power supply voltage [V]
+ driver2.voltage_power_supply = 12;
+ driver2.init();
+ // link driver
+ motor2.linkDriver(&driver2);
+ // link current sense and the driver
+ current_sense2.linkDriver(&driver2);
+
+ // set control loop type to be used
+ motor1.controller = MotionControlType::torque;
+ motor2.controller = MotionControlType::torque;
+
+ // contoller configuration based on the controll type
+ motor1.PID_velocity.P = 0.05f;
+ motor1.PID_velocity.I = 1;
+ motor1.PID_velocity.D = 0;
+ // default voltage_power_supply
+ motor1.voltage_limit = 12;
+ // contoller configuration based on the controll type
+ motor2.PID_velocity.P = 0.05f;
+ motor2.PID_velocity.I = 1;
+ motor2.PID_velocity.D = 0;
+ // default voltage_power_supply
+ motor2.voltage_limit = 12;
+
+ // angle loop velocity limit
+ motor1.velocity_limit = 20;
+ motor2.velocity_limit = 20;
+
+ // comment out if not needed
+ motor1.useMonitoring(Serial);
+ motor2.useMonitoring(Serial);
+
+
+ // current sense init and linking
+ current_sense1.init();
+ motor1.linkCurrentSense(¤t_sense1);
+ // current sense init and linking
+ current_sense2.init();
+ motor2.linkCurrentSense(¤t_sense2);
+
+ // initialise motor
+ motor1.init();
+ // align encoder and start FOC
+ motor1.initFOC();
+
+ // initialise motor
+ motor2.init();
+ // align encoder and start FOC
+ motor2.initFOC();
+
+ // set the inital target value
+ motor1.target = 2;
+ motor2.target = 2;
+
+ // subscribe motor to the commander
+ // command.add('A', doMotor1, "motor 1");
+ // command.add('B', doMotor2, "motor 2");
+ command.add('A', doTarget1, "target 1");
+ command.add('B', doTarget2, "target 2");
+
+ // Run user commands to configure and the motor (find the full command list in docs.simplefoc.com)
+ Serial.println("Motors ready.");
+
+ _delay(1000);
+}
+
+
+void loop() {
+ // iterative setting FOC phase voltage
+ motor1.loopFOC();
+ motor2.loopFOC();
+
+ // iterative function setting the outter loop target
+ motor1.move();
+ motor2.move();
+
+ // user communication
+ command.run();
+}
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/hardware_specific_examples/SimpleFOCShield/version_v2/single_full_control_example/single_full_control_example.ino b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/hardware_specific_examples/SimpleFOCShield/version_v2/single_full_control_example/single_full_control_example.ino
new file mode 100644
index 0000000..b65a9cb
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/hardware_specific_examples/SimpleFOCShield/version_v2/single_full_control_example/single_full_control_example.ino
@@ -0,0 +1,104 @@
+
+#include
+
+// BLDC motor & driver instance
+BLDCMotor motor = BLDCMotor(11);
+BLDCDriver3PWM driver = BLDCDriver3PWM(5, 10, 6, 8);
+
+// encoder instance
+Encoder encoder = Encoder(2, 3, 500);
+// channel A and B callbacks
+void doA(){encoder.handleA();}
+void doB(){encoder.handleB();}
+
+// inline current sensor instance
+// check if your board has R010 (0.01 ohm resistor) or R006 (0.006 mOhm resistor)
+InlineCurrentSense current_sense = InlineCurrentSense(0.01f, 50.0f, A0, A2);
+
+// commander communication instance
+Commander command = Commander(Serial);
+void doMotion(char* cmd){ command.motion(&motor, cmd); }
+// void doMotor(char* cmd){ command.motor(&motor, cmd); }
+
+void setup() {
+
+ // use monitoring with serial
+ Serial.begin(115200);
+ // enable more verbose output for debugging
+ // comment out if not needed
+ SimpleFOCDebug::enable(&Serial);
+
+ // initialize encoder sensor hardware
+ encoder.init();
+ encoder.enableInterrupts(doA, doB);
+ // link the motor to the sensor
+ motor.linkSensor(&encoder);
+
+ // driver config
+ // power supply voltage [V]
+ driver.voltage_power_supply = 12;
+ driver.init();
+ // link driver
+ motor.linkDriver(&driver);
+ // link current sense and the driver
+ current_sense.linkDriver(&driver);
+
+ // set control loop type to be used
+ motor.controller = MotionControlType::torque;
+
+ // contoller configuration based on the controll type
+ motor.PID_velocity.P = 0.05f;
+ motor.PID_velocity.I = 1;
+ motor.PID_velocity.D = 0;
+ // default voltage_power_supply
+ motor.voltage_limit = 12;
+
+ // velocity low pass filtering time constant
+ motor.LPF_velocity.Tf = 0.01f;
+
+ // angle loop controller
+ motor.P_angle.P = 20;
+ // angle loop velocity limit
+ motor.velocity_limit = 20;
+
+ // comment out if not needed
+ motor.useMonitoring(Serial);
+ motor.monitor_downsample = 0; // disable intially
+ motor.monitor_variables = _MON_TARGET | _MON_VEL | _MON_ANGLE; // monitor target velocity and angle
+
+ // current sense init and linking
+ current_sense.init();
+ motor.linkCurrentSense(¤t_sense);
+
+ // initialise motor
+ motor.init();
+ // align encoder and start FOC
+ motor.initFOC();
+
+ // set the inital target value
+ motor.target = 2;
+
+ // subscribe motor to the commander
+ command.add('T', doMotion, "motion control");
+ // command.add('M', doMotor, "motor");
+
+ // Run user commands to configure and the motor (find the full command list in docs.simplefoc.com)
+ Serial.println("Motor ready.");
+
+ _delay(1000);
+}
+
+
+void loop() {
+ // iterative setting FOC phase voltage
+ motor.loopFOC();
+
+ // iterative function setting the outter loop target
+ motor.move();
+
+ // motor monitoring
+ motor.monitor();
+
+ // user communication
+ command.run();
+}
\ No newline at end of file
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/hardware_specific_examples/SimpleFOCShield/version_v3/single_full_control_example/single_full_control_example.ino b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/hardware_specific_examples/SimpleFOCShield/version_v3/single_full_control_example/single_full_control_example.ino
new file mode 100644
index 0000000..6359f20
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/hardware_specific_examples/SimpleFOCShield/version_v3/single_full_control_example/single_full_control_example.ino
@@ -0,0 +1,104 @@
+
+#include
+
+// BLDC motor & driver instance
+BLDCMotor motor = BLDCMotor(11);
+BLDCDriver3PWM driver = BLDCDriver3PWM(6, 10, 5, 8);
+
+// encoder instance
+Encoder encoder = Encoder(2, 3, 500);
+// channel A and B callbacks
+void doA(){encoder.handleA();}
+void doB(){encoder.handleB();}
+
+// inline current sensor instance
+// ACS712-05B has the resolution of 0.185mV per Amp
+InlineCurrentSense current_sense = InlineCurrentSense(185.0f, A0, A2);
+
+// commander communication instance
+Commander command = Commander(Serial);
+void doMotion(char* cmd){ command.motion(&motor, cmd); }
+// void doMotor(char* cmd){ command.motor(&motor, cmd); }
+
+void setup() {
+
+ // use monitoring with serial
+ Serial.begin(115200);
+ // enable more verbose output for debugging
+ // comment out if not needed
+ SimpleFOCDebug::enable(&Serial);
+
+ // initialize encoder sensor hardware
+ encoder.init();
+ encoder.enableInterrupts(doA, doB);
+ // link the motor to the sensor
+ motor.linkSensor(&encoder);
+
+ // driver config
+ // power supply voltage [V]
+ driver.voltage_power_supply = 12;
+ driver.init();
+ // link driver
+ motor.linkDriver(&driver);
+ // link current sense and the driver
+ current_sense.linkDriver(&driver);
+
+ // set control loop type to be used
+ motor.controller = MotionControlType::torque;
+
+ // controller configuration based on the control type
+ motor.PID_velocity.P = 0.05f;
+ motor.PID_velocity.I = 1;
+ motor.PID_velocity.D = 0;
+ // default voltage_power_supply
+ motor.voltage_limit = 12;
+
+ // velocity low pass filtering time constant
+ motor.LPF_velocity.Tf = 0.01f;
+
+ // angle loop controller
+ motor.P_angle.P = 20;
+ // angle loop velocity limit
+ motor.velocity_limit = 20;
+
+ // comment out if not needed
+ motor.useMonitoring(Serial);
+ motor.monitor_downsample = 0; // disable intially
+ motor.monitor_variables = _MON_TARGET | _MON_VEL | _MON_ANGLE; // monitor target velocity and angle
+
+ // current sense init and linking
+ current_sense.init();
+ motor.linkCurrentSense(¤t_sense);
+
+ // initialise motor
+ motor.init();
+ // align encoder and start FOC
+ motor.initFOC();
+
+ // set the inital target value
+ motor.target = 2;
+
+ // subscribe motor to the commander
+ command.add('T', doMotion, "motion control");
+ // command.add('M', doMotor, "motor");
+
+ // Run user commands to configure and the motor (find the full command list in docs.simplefoc.com)
+ Serial.println("Motor ready.");
+
+ _delay(1000);
+}
+
+
+void loop() {
+ // iterative setting FOC phase voltage
+ motor.loopFOC();
+
+ // iterative function setting the outter loop target
+ motor.move();
+
+ // motor monitoring
+ motor.monitor();
+
+ // user communication
+ command.run();
+}
\ No newline at end of file
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/hardware_specific_examples/Smart_Stepper/smartstepper_control/smartstepper_control.ino b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/hardware_specific_examples/Smart_Stepper/smartstepper_control/smartstepper_control.ino
new file mode 100644
index 0000000..1804710
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/hardware_specific_examples/Smart_Stepper/smartstepper_control/smartstepper_control.ino
@@ -0,0 +1,65 @@
+/**
+ * Smart Stepper support with SimpleFOClibrary
+ */
+#include
+
+// magnetic sensor instance - SPI
+MagneticSensorSPI sensor = MagneticSensorSPI(AS5147_SPI, A2);
+
+// Stepper motor & driver instance
+StepperMotor motor = StepperMotor(50);
+int in1[2] = {5, 6};
+int in2[2] = {A4, 7};
+StepperDriver2PWM driver = StepperDriver2PWM(4, in1, 9, in2);
+
+// instantiate the commander
+Commander command = Commander(SerialUSB);
+void doMotor(char* cmd) { command.motor(&motor, cmd); }
+
+void setup() {
+
+ // use monitoring with SerialUSB
+ SerialUSB.begin(115200);
+ // enable more verbose output for debugging
+ // comment out if not needed
+ SimpleFOCDebug::enable(&SerialUSB);
+
+ // initialise magnetic sensor hardware
+ sensor.init();
+ // link the motor to the sensor
+ motor.linkSensor(&sensor);
+
+ // power supply voltage
+ driver.voltage_power_supply = 12;
+ driver.init();
+ motor.linkDriver(&driver);
+
+ // set motion control loop to be used
+ motor.controller = MotionControlType::torque;
+
+ // comment out if not needed
+ motor.useMonitoring(SerialUSB);
+
+ // initialize motor
+ motor.init();
+ // align sensor and start FOC
+ motor.initFOC();
+
+ // add target command M
+ command.add('M', doMotor, "my motor");
+
+ SerialUSB.println(F("Motor ready."));
+ SerialUSB.println(F("Set the target voltage using Serial terminal:"));
+ _delay(1000);
+}
+
+void loop() {
+ // main FOC algorithm function
+ motor.loopFOC();
+
+ // Motion control function
+ motor.move();
+
+ // user communication
+ command.run();
+}
\ No newline at end of file
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/hardware_specific_examples/Teensy/Teensy3/bldc_driver_6pwm_standalone/bldc_driver_6pwm_standalone.ino b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/hardware_specific_examples/Teensy/Teensy3/bldc_driver_6pwm_standalone/bldc_driver_6pwm_standalone.ino
new file mode 100644
index 0000000..7f59551
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/hardware_specific_examples/Teensy/Teensy3/bldc_driver_6pwm_standalone/bldc_driver_6pwm_standalone.ino
@@ -0,0 +1,41 @@
+// 6pwm standalone example code for Teensy 3.x boards
+#include
+
+
+// BLDC driver instance
+// using FTM0 timer
+BLDCDriver6PWM driver = BLDCDriver6PWM(22,23, 9,10, 6,20, 8);
+// using FTM3 timer - available on Teensy3.5 and Teensy3.6
+// BLDCDriver6PWM driver = BLDCDriver6PWM(2,14, 7,8, 35,36, 8);
+
+void setup() {
+ Serial.begin(115200);
+ // Enable debugging
+ // Driver init will show debugging output
+ SimpleFOCDebug::enable(&Serial);
+
+ // pwm frequency to be used [Hz]
+ driver.pwm_frequency = 30000;
+ // dead zone percentage of the duty cycle - default 0.02 - 2%
+ driver.dead_zone=0.02;
+ // power supply voltage [V]
+ driver.voltage_power_supply = 12;
+ // Max DC voltage allowed - default voltage_power_supply
+ driver.voltage_limit = 12;
+
+ // driver init
+ driver.init();
+
+ // enable driver
+ driver.enable();
+
+ _delay(1000);
+}
+
+void loop() {
+ // setting pwm
+ // phase A: 3V
+ // phase B: 6V
+ // phase C: 5V
+ driver.setPwm(3,6,5);
+}
\ No newline at end of file
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/hardware_specific_examples/Teensy/Teensy3/open_loop_velocity_6pwm/open_loop_velocity_6pwm.ino b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/hardware_specific_examples/Teensy/Teensy3/open_loop_velocity_6pwm/open_loop_velocity_6pwm.ino
new file mode 100644
index 0000000..9143dde
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/hardware_specific_examples/Teensy/Teensy3/open_loop_velocity_6pwm/open_loop_velocity_6pwm.ino
@@ -0,0 +1,70 @@
+// 6pwm openloop velocity example
+#include
+
+
+// BLDC motor & driver instance
+// BLDCMotor motor = BLDCMotor(pole pair number);
+BLDCMotor motor = BLDCMotor(11);
+// using FTM0 timer
+// BLDCDriver6PWM(pwmA_H, pwmA_L, pwmB_H,pwmB_L, pwmC_H, pwmC_L)
+BLDCDriver6PWM driver = BLDCDriver6PWM(22,23, 9,10, 6,20, 8);
+// using FTM3 timer - available on Teensy3.5 and Teensy3.6
+// BLDCDriver6PWM driver = BLDCDriver6PWM(2,14, 7,8, 35,36, 8);
+
+// instantiate the commander
+Commander command = Commander(Serial);
+void doTarget(char* cmd) { command.scalar(&motor.target, cmd); }
+void doLimit(char* cmd) { command.scalar(&motor.voltage_limit, cmd); }
+
+void setup() {
+
+ // use monitoring with serial
+ Serial.begin(115200);
+ // enable more verbose output for debugging
+ // comment out if not needed
+ SimpleFOCDebug::enable(&Serial);
+
+ // driver config
+ // power supply voltage [V]
+ driver.voltage_power_supply = 12;
+ // limit the maximal dc voltage the driver can set
+ // as a protection measure for the low-resistance motors
+ // this value is fixed on startup
+ driver.voltage_limit = 6;
+ driver.init();
+ // link the motor and the driver
+ motor.linkDriver(&driver);
+
+ // limiting motor movements
+ // limit the voltage to be set to the motor
+ // start very low for high resistance motors
+ // currnet = resistance*voltage, so try to be well under 1Amp
+ motor.voltage_limit = 3; // [V]
+
+ // open loop control config
+ motor.controller = MotionControlType::velocity_openloop;
+
+ // init motor hardware
+ motor.init();
+
+ //initial motor target
+ motor.target=0;
+
+ // add target command T
+ command.add('T', doTarget, "target velocity");
+ command.add('L', doLimit, "voltage limit");
+
+ Serial.println("Motor ready!");
+ Serial.println("Set target velocity [rad/s]");
+ _delay(1000);
+}
+
+void loop() {
+
+ // open loop velocity movement
+ // using motor.voltage_limit
+ motor.move();
+
+ // user communication
+ command.run();
+}
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/hardware_specific_examples/Teensy/Teensy4/bldc_driver_6pwm_standalone/bldc_driver_6pwm_standalone.ino b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/hardware_specific_examples/Teensy/Teensy4/bldc_driver_6pwm_standalone/bldc_driver_6pwm_standalone.ino
new file mode 100644
index 0000000..f3df3db
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/hardware_specific_examples/Teensy/Teensy4/bldc_driver_6pwm_standalone/bldc_driver_6pwm_standalone.ino
@@ -0,0 +1,57 @@
+// 6pwm standalone example code for Teensy 4.x boards
+//
+// Teensy4.x 6pwm driver generates a 6pwm signal using FlexTimers and it doesn't support the QuadTimers
+// - Each high-low pair of the 6pwm has to be A and B channels of the same FlexTimer and to the same submodule
+//
+// List of available teensy 4.1 pins with their respective submodules and channels
+// FlexPWM(timer number)_(submodule)_(channel)
+// FlexPWM4_2_A pin 2
+// FlexPWM4_2_B pin 3
+// FlexPWM1_3_B pin 7
+// FlexPWM1_3_A pin 8
+// FlexPWM2_2_A pin 6
+// FlexPWM2_2_B pin 9
+// FlexPWM3_1_B pin 28
+// FlexPWM3_1_A pin 29
+// FlexPWM2_3_A pin 36
+// FlexPWM2_3_B pin 37
+#include
+
+
+// BLDC driver instance
+// make sure to provide channel A for high side and channel B for low side
+// BLDCDriver6PWM(pwmA_H, pwmA_L, pwmB_H,pwmB_L, pwmC_H, pwmC_L)
+// Example configuration
+BLDCDriver6PWM driver = BLDCDriver6PWM(2,3, 6,9, 8,7);
+
+void setup() {
+ Serial.begin(115200);
+ // Enable debugging
+ // Driver init will show debugging output
+ SimpleFOCDebug::enable(&Serial);
+
+ // pwm frequency to be used [Hz]
+ driver.pwm_frequency = 30000;
+ // dead zone percentage of the duty cycle - default 0.02 - 2%
+ driver.dead_zone=0.02;
+ // power supply voltage [V]
+ driver.voltage_power_supply = 12;
+ // Max DC voltage allowed - default voltage_power_supply
+ driver.voltage_limit = 12;
+
+ // driver init
+ driver.init();
+
+ // enable driver
+ driver.enable();
+
+ _delay(1000);
+}
+
+void loop() {
+ // setting pwm
+ // phase A: 3V
+ // phase B: 6V
+ // phase C: 5V
+ driver.setPwm(3,6,5);
+}
\ No newline at end of file
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/hardware_specific_examples/Teensy/Teensy4/open_loop_velocity_6pwm/open_loop_velocity_6pwm.ino b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/hardware_specific_examples/Teensy/Teensy4/open_loop_velocity_6pwm/open_loop_velocity_6pwm.ino
new file mode 100644
index 0000000..5ff5331
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/hardware_specific_examples/Teensy/Teensy4/open_loop_velocity_6pwm/open_loop_velocity_6pwm.ino
@@ -0,0 +1,85 @@
+// 6pwm openloop velocity example
+//
+// Teensy4.x 6pwm driver generates a 6pwm signal using FlexTimers and it doesn't support the QuadTimers
+// - Each high-low pair of the 6pwm has to be A and B channels of the same FlexTimer and to the same submodule
+//
+// List of available teensy 4.1 pins with their respective submodules and channels
+// FlexPWM(timer number)_(submodule)_(channel)
+// FlexPWM4_2_A pin 2
+// FlexPWM4_2_B pin 3
+// FlexPWM1_3_B pin 7
+// FlexPWM1_3_A pin 8
+// FlexPWM2_2_A pin 6
+// FlexPWM2_2_B pin 9
+// FlexPWM3_1_B pin 28
+// FlexPWM3_1_A pin 29
+// FlexPWM2_3_A pin 36
+// FlexPWM2_3_B pin 37
+#include
+
+
+// BLDC motor & driver instance
+// BLDCMotor motor = BLDCMotor(pole pair number);
+BLDCMotor motor = BLDCMotor(11);
+// make sure to provide channel A for high side and channel B for low side
+// BLDCDriver6PWM(pwmA_H, pwmA_L, pwmB_H,pwmB_L, pwmC_H, pwmC_L)
+// Example configuration
+BLDCDriver6PWM driver = BLDCDriver6PWM(2,3, 6,9, 8,7);
+
+// instantiate the commander
+Commander command = Commander(Serial);
+void doTarget(char* cmd) { command.scalar(&motor.target, cmd); }
+void doLimit(char* cmd) { command.scalar(&motor.voltage_limit, cmd); }
+
+void setup() {
+
+ // use monitoring with serial
+ Serial.begin(115200);
+ // enable more verbose output for debugging
+ // comment out if not needed
+ SimpleFOCDebug::enable(&Serial);
+
+ // driver config
+ // power supply voltage [V]
+ driver.voltage_power_supply = 12;
+ // limit the maximal dc voltage the driver can set
+ // as a protection measure for the low-resistance motors
+ // this value is fixed on startup
+ driver.voltage_limit = 6;
+ driver.init();
+ // link the motor and the driver
+ motor.linkDriver(&driver);
+
+ // limiting motor movements
+ // limit the voltage to be set to the motor
+ // start very low for high resistance motors
+ // currnet = resistance*voltage, so try to be well under 1Amp
+ motor.voltage_limit = 3; // [V]
+
+ // open loop control config
+ motor.controller = MotionControlType::velocity_openloop;
+
+ // init motor hardware
+ motor.init();
+
+ //initial motor target
+ motor.target=0;
+
+ // add target command T
+ command.add('T', doTarget, "target velocity");
+ command.add('L', doLimit, "voltage limit");
+
+ Serial.println("Motor ready!");
+ Serial.println("Set target velocity [rad/s]");
+ _delay(1000);
+}
+
+void loop() {
+
+ // open loop velocity movement
+ // using motor.voltage_limit
+ motor.move();
+
+ // user communication
+ command.run();
+}
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/motion_control/open_loop_motor_control/open_loop_position_example/open_loop_position_example.ino b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/motion_control/open_loop_motor_control/open_loop_position_example/open_loop_position_example.ino
new file mode 100644
index 0000000..c1ff7bb
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/motion_control/open_loop_motor_control/open_loop_position_example/open_loop_position_example.ino
@@ -0,0 +1,81 @@
+// Open loop motor control example
+ #include
+
+
+// BLDC motor & driver instance
+// BLDCMotor motor = BLDCMotor(pole pair number);
+BLDCMotor motor = BLDCMotor(11);
+// BLDCDriver3PWM driver = BLDCDriver3PWM(pwmA, pwmB, pwmC, Enable(optional));
+BLDCDriver3PWM driver = BLDCDriver3PWM(9, 5, 6, 8);
+
+// Stepper motor & driver instance
+//StepperMotor motor = StepperMotor(50);
+//StepperDriver4PWM driver = StepperDriver4PWM(9, 5, 10, 6, 8);
+
+//target variable
+float target_position = 0;
+
+// instantiate the commander
+Commander command = Commander(Serial);
+void doTarget(char* cmd) { command.scalar(&target_position, cmd); }
+void doLimit(char* cmd) { command.scalar(&motor.voltage_limit, cmd); }
+void doVelocity(char* cmd) { command.scalar(&motor.velocity_limit, cmd); }
+
+void setup() {
+
+ // use monitoring with serial
+ Serial.begin(115200);
+ // enable more verbose output for debugging
+ // comment out if not needed
+ SimpleFOCDebug::enable(&Serial);
+
+ // driver config
+ // power supply voltage [V]
+ driver.voltage_power_supply = 12;
+ // limit the maximal dc voltage the driver can set
+ // as a protection measure for the low-resistance motors
+ // this value is fixed on startup
+ driver.voltage_limit = 6;
+ if(!driver.init()){
+ Serial.println("Driver init failed!");
+ return;
+ }
+ // link the motor and the driver
+ motor.linkDriver(&driver);
+
+ // limiting motor movements
+ // limit the voltage to be set to the motor
+ // start very low for high resistance motors
+ // currnet = resistance*voltage, so try to be well under 1Amp
+ motor.voltage_limit = 3; // [V]
+ // limit/set the velocity of the transition in between
+ // target angles
+ motor.velocity_limit = 5; // [rad/s] cca 50rpm
+ // open loop control config
+ motor.controller = MotionControlType::angle_openloop;
+
+ // init motor hardware
+ if(!motor.init()){
+ Serial.println("Motor init failed!");
+ return;
+ }
+
+ // add target command T
+ command.add('T', doTarget, "target angle");
+ command.add('L', doLimit, "voltage limit");
+ command.add('V', doLimit, "movement velocity");
+
+ Serial.println("Motor ready!");
+ Serial.println("Set target position [rad]");
+ _delay(1000);
+}
+
+void loop() {
+ // open loop angle movements
+ // using motor.voltage_limit and motor.velocity_limit
+ // angles can be positive or negative, negative angles correspond to opposite motor direction
+ motor.move(target_position);
+
+ // user communication
+ command.run();
+}
\ No newline at end of file
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/motion_control/open_loop_motor_control/open_loop_velocity_example/open_loop_velocity_example.ino b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/motion_control/open_loop_motor_control/open_loop_velocity_example/open_loop_velocity_example.ino
new file mode 100644
index 0000000..b1bc276
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/motion_control/open_loop_motor_control/open_loop_velocity_example/open_loop_velocity_example.ino
@@ -0,0 +1,79 @@
+// Open loop motor control example
+#include
+
+
+// BLDC motor & driver instance
+// BLDCMotor motor = BLDCMotor(pole pair number);
+BLDCMotor motor = BLDCMotor(11);
+// BLDCDriver3PWM driver = BLDCDriver3PWM(pwmA, pwmB, pwmC, Enable(optional));
+BLDCDriver3PWM driver = BLDCDriver3PWM(9, 5, 6, 8);
+
+// Stepper motor & driver instance
+//StepperMotor motor = StepperMotor(50);
+//StepperDriver4PWM driver = StepperDriver4PWM(9, 5, 10, 6, 8);
+
+
+//target variable
+float target_velocity = 0;
+
+// instantiate the commander
+Commander command = Commander(Serial);
+void doTarget(char* cmd) { command.scalar(&target_velocity, cmd); }
+void doLimit(char* cmd) { command.scalar(&motor.voltage_limit, cmd); }
+
+void setup() {
+
+ // use monitoring with serial
+ Serial.begin(115200);
+ // enable more verbose output for debugging
+ // comment out if not needed
+ SimpleFOCDebug::enable(&Serial);
+
+ // driver config
+ // power supply voltage [V]
+ driver.voltage_power_supply = 12;
+ // limit the maximal dc voltage the driver can set
+ // as a protection measure for the low-resistance motors
+ // this value is fixed on startup
+ driver.voltage_limit = 6;
+ if(!driver.init()){
+ Serial.println("Driver init failed!");
+ return;
+ }
+ // link the motor and the driver
+ motor.linkDriver(&driver);
+
+ // limiting motor movements
+ // limit the voltage to be set to the motor
+ // start very low for high resistance motors
+ // current = voltage / resistance, so try to be well under 1Amp
+ motor.voltage_limit = 3; // [V]
+
+ // open loop control config
+ motor.controller = MotionControlType::velocity_openloop;
+
+ // init motor hardware
+ if(!motor.init()){
+ Serial.println("Motor init failed!");
+ return;
+ }
+
+ // add target command T
+ command.add('T', doTarget, "target velocity");
+ command.add('L', doLimit, "voltage limit");
+
+ Serial.println("Motor ready!");
+ Serial.println("Set target velocity [rad/s]");
+ _delay(1000);
+}
+
+void loop() {
+
+ // open loop velocity movement
+ // using motor.voltage_limit and motor.velocity_limit
+ // to turn the motor "backwards", just set a negative target_velocity
+ motor.move(target_velocity);
+
+ // user communication
+ command.run();
+}
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/motion_control/position_motion_control/encoder/angle_control/angle_control.ino b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/motion_control/position_motion_control/encoder/angle_control/angle_control.ino
new file mode 100644
index 0000000..03e6ea7
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/motion_control/position_motion_control/encoder/angle_control/angle_control.ino
@@ -0,0 +1,132 @@
+/**
+ *
+ * Position/angle motion control example
+ * Steps:
+ * 1) Configure the motor and encoder
+ * 2) Run the code
+ * 3) Set the target angle (in radians) from serial terminal
+ *
+ *
+ * NOTE :
+ * > Arduino UNO example code for running velocity motion control using an encoder with index significantly
+ * > Since Arduino UNO doesn't have enough interrupt pins we have to use software interrupt library PciManager.
+ *
+ * > If running this code with Nucleo or Bluepill or any other board which has more than 2 interrupt pins
+ * > you can supply doIndex directly to the encoder.enableInterrupts(doA,doB,doIndex) and avoid using PciManger
+ *
+ * > If you don't want to use index pin initialize the encoder class without index pin number:
+ * > For example:
+ * > - Encoder encoder = Encoder(2, 3, 8192);
+ * > and initialize interrupts like this:
+ * > - encoder.enableInterrupts(doA,doB)
+ *
+ * Check the docs.simplefoc.com for more info about the possible encoder configuration.
+ *
+ */
+#include
+
+// BLDC motor & driver instance
+BLDCMotor motor = BLDCMotor(11);
+BLDCDriver3PWM driver = BLDCDriver3PWM(9, 5, 6, 8);
+// Stepper motor & driver instance
+//StepperMotor motor = StepperMotor(50);
+//StepperDriver4PWM driver = StepperDriver4PWM(9, 5, 10, 6, 8);
+
+// encoder instance
+Encoder encoder = Encoder(2, 3, 8192);
+
+// Interrupt routine intialisation
+// channel A and B callbacks
+void doA(){encoder.handleA();}
+void doB(){encoder.handleB();}
+
+// angle set point variable
+float target_angle = 0;
+// instantiate the commander
+Commander command = Commander(Serial);
+void doTarget(char* cmd) { command.scalar(&target_angle, cmd); }
+
+void setup() {
+
+ // use monitoring with serial
+ Serial.begin(115200);
+ // enable more verbose output for debugging
+ // comment out if not needed
+ SimpleFOCDebug::enable(&Serial);
+
+ // initialize encoder sensor hardware
+ encoder.init();
+ encoder.enableInterrupts(doA, doB);
+ // link the motor to the sensor
+ motor.linkSensor(&encoder);
+
+ // driver config
+ // power supply voltage [V]
+ driver.voltage_power_supply = 12;
+ driver.init();
+ // link the motor and the driver
+ motor.linkDriver(&driver);
+
+ // aligning voltage [V]
+ motor.voltage_sensor_align = 3;
+
+ // set motion control loop to be used
+ motor.controller = MotionControlType::angle;
+
+ // contoller configuration
+ // default parameters in defaults.h
+
+ // velocity PI controller parameters
+ motor.PID_velocity.P = 0.2f;
+ motor.PID_velocity.I = 20;
+ motor.PID_velocity.D = 0;
+ // default voltage_power_supply
+ motor.voltage_limit = 6;
+ // jerk control using voltage voltage ramp
+ // default value is 300 volts per sec ~ 0.3V per millisecond
+ motor.PID_velocity.output_ramp = 1000;
+
+ // velocity low pass filtering time constant
+ motor.LPF_velocity.Tf = 0.01f;
+
+ // angle P controller
+ motor.P_angle.P = 20;
+ // maximal velocity of the position control
+ motor.velocity_limit = 4;
+
+ // comment out if not needed
+ motor.useMonitoring(Serial);
+
+ // initialize motor
+ motor.init();
+ // align encoder and start FOC
+ motor.initFOC();
+
+ // add target command T
+ command.add('T', doTarget, "target angle");
+
+ Serial.println(F("Motor ready."));
+ Serial.println(F("Set the target angle using serial terminal:"));
+ _delay(1000);
+}
+
+void loop() {
+ // main FOC algorithm function
+ // the faster you run this function the better
+ // Arduino UNO loop ~1kHz
+ // Bluepill loop ~10kHz
+ motor.loopFOC();
+
+ // Motion control function
+ // velocity, position or voltage (defined in motor.controller)
+ // this function can be run at much lower frequency than loopFOC() function
+ // You can also use motor.move() and set the motor.target in the code
+ motor.move(target_angle);
+
+ // function intended to be used with serial plotter to monitor motor variables
+ // significantly slowing the execution down!!!!
+ // motor.monitor();
+
+ // user communication
+ command.run();
+}
\ No newline at end of file
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/motion_control/position_motion_control/hall_sensor/angle_control/angle_control.ino b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/motion_control/position_motion_control/hall_sensor/angle_control/angle_control.ino
new file mode 100644
index 0000000..4bd7163
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/motion_control/position_motion_control/hall_sensor/angle_control/angle_control.ino
@@ -0,0 +1,133 @@
+/**
+ *
+ * Position/angle motion control example
+ * Steps:
+ * 1) Configure the motor and hall sensor
+ * 2) Run the code
+ * 3) Set the target angle (in radians) from serial terminal
+ *
+ *
+ * NOTE :
+ * > This is for Arduino UNO example code for running angle motion control specifically
+ * > Since Arduino UNO doesn't have enough interrupt pins we have to use software interrupt library PciManager.
+ *
+ * > If running this code with Nucleo or Bluepill or any other board which has more than 2 interrupt pins
+ * > you can supply doIndex directly to the sensr.enableInterrupts(doA,doB,doC) and avoid using PciManger
+ *
+ *
+ */
+#include
+// software interrupt library
+#include
+#include
+
+// BLDC motor & driver instance
+BLDCMotor motor = BLDCMotor(11);
+BLDCDriver3PWM driver = BLDCDriver3PWM(9, 5, 6, 8);
+// Stepper motor & driver instance
+//StepperMotor motor = StepperMotor(50);
+//StepperDriver4PWM driver = StepperDriver4PWM(9, 5, 10, 6, 8);
+
+// hall sensor instance
+HallSensor sensor = HallSensor(2, 3, 4, 11);
+
+// Interrupt routine intialisation
+// channel A and B callbacks
+void doA(){sensor.handleA();}
+void doB(){sensor.handleB();}
+void doC(){sensor.handleC();}
+// If no available hadware interrupt pins use the software interrupt
+PciListenerImp listenC(sensor.pinC, doC);
+
+// angle set point variable
+float target_angle = 0;
+// instantiate the commander
+Commander command = Commander(Serial);
+void doTarget(char* cmd) { command.scalar(&target_angle, cmd); }
+
+void setup() {
+
+ // initialize sensor hardware
+ sensor.init();
+ sensor.enableInterrupts(doA, doB); //, doC);
+ // software interrupts
+ PciManager.registerListener(&listenC);
+ // link the motor to the sensor
+ motor.linkSensor(&sensor);
+
+ // driver config
+ // power supply voltage [V]
+ driver.voltage_power_supply = 12;
+ driver.init();
+ // link the motor and the driver
+ motor.linkDriver(&driver);
+
+
+ // aligning voltage [V]
+ motor.voltage_sensor_align = 3;
+ // index search velocity [rad/s]
+ motor.velocity_index_search = 3;
+
+ // set motion control loop to be used
+ motor.controller = MotionControlType::angle;
+
+ // contoller configuration
+ // default parameters in defaults.h
+
+ // velocity PI controller parameters
+ motor.PID_velocity.P = 0.2f;
+ motor.PID_velocity.I = 2;
+ motor.PID_velocity.D = 0;
+ // default voltage_power_supply
+ motor.voltage_limit = 6;
+ // jerk control using voltage voltage ramp
+ // default value is 300 volts per sec ~ 0.3V per millisecond
+ motor.PID_velocity.output_ramp = 1000;
+
+ // velocity low pass filtering time constant
+ motor.LPF_velocity.Tf = 0.01f;
+
+ // angle P controller
+ motor.P_angle.P = 20;
+ // maximal velocity of the position control
+ motor.velocity_limit = 4;
+
+
+ // use monitoring with serial
+ Serial.begin(115200);
+ // comment out if not needed
+ motor.useMonitoring(Serial);
+
+ // initialize motor
+ motor.init();
+ // align sensor and start FOC
+ motor.initFOC();
+
+ // add target command T
+ command.add('T', doTarget, "target angle");
+
+ Serial.println(F("Motor ready."));
+ Serial.println(F("Set the target angle using serial terminal:"));
+ _delay(1000);
+}
+
+void loop() {
+ // main FOC algorithm function
+ // the faster you run this function the better
+ // Arduino UNO loop ~1kHz
+ // Bluepill loop ~10kHz
+ motor.loopFOC();
+
+ // Motion control function
+ // velocity, position or voltage (defined in motor.controller)
+ // this function can be run at much lower frequency than loopFOC() function
+ // You can also use motor.move() and set the motor.target in the code
+ motor.move(target_angle);
+
+ // function intended to be used with serial plotter to monitor motor variables
+ // significantly slowing the execution down!!!!
+ // motor.monitor();
+
+ // user communication
+ command.run();
+}
\ No newline at end of file
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/motion_control/position_motion_control/magnetic_sensor/angle_control/angle_control.ino b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/motion_control/position_motion_control/magnetic_sensor/angle_control/angle_control.ino
new file mode 100644
index 0000000..f0f9b27
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/motion_control/position_motion_control/magnetic_sensor/angle_control/angle_control.ino
@@ -0,0 +1,116 @@
+/**
+ *
+ * Position/angle motion control example
+ * Steps:
+ * 1) Configure the motor and magnetic sensor
+ * 2) Run the code
+ * 3) Set the target angle (in radians) from serial terminal
+ *
+ */
+#include
+
+// magnetic sensor instance - SPI
+MagneticSensorSPI sensor = MagneticSensorSPI(AS5147_SPI, 10);
+// magnetic sensor instance - MagneticSensorI2C
+//MagneticSensorI2C sensor = MagneticSensorI2C(AS5600_I2C);
+// magnetic sensor instance - analog output
+// MagneticSensorAnalog sensor = MagneticSensorAnalog(A1, 14, 1020);
+
+// BLDC motor & driver instance
+BLDCMotor motor = BLDCMotor(11);
+BLDCDriver3PWM driver = BLDCDriver3PWM(9, 5, 6, 8);
+// Stepper motor & driver instance
+//StepperMotor motor = StepperMotor(50);
+//StepperDriver4PWM driver = StepperDriver4PWM(9, 5, 10, 6, 8);
+
+// angle set point variable
+float target_angle = 0;
+// instantiate the commander
+Commander command = Commander(Serial);
+void doTarget(char* cmd) { command.scalar(&target_angle, cmd); }
+
+void setup() {
+
+ // use monitoring with serial
+ Serial.begin(115200);
+ // enable more verbose output for debugging
+ // comment out if not needed
+ SimpleFOCDebug::enable(&Serial);
+
+ // initialise magnetic sensor hardware
+ sensor.init();
+ // link the motor to the sensor
+ motor.linkSensor(&sensor);
+
+ // driver config
+ // power supply voltage [V]
+ driver.voltage_power_supply = 12;
+ driver.init();
+ // link the motor and the driver
+ motor.linkDriver(&driver);
+
+ // choose FOC modulation (optional)
+ motor.foc_modulation = FOCModulationType::SpaceVectorPWM;
+
+ // set motion control loop to be used
+ motor.controller = MotionControlType::angle;
+
+ // contoller configuration
+ // default parameters in defaults.h
+
+ // velocity PI controller parameters
+ motor.PID_velocity.P = 0.2f;
+ motor.PID_velocity.I = 20;
+ motor.PID_velocity.D = 0;
+ // maximal voltage to be set to the motor
+ motor.voltage_limit = 6;
+
+ // velocity low pass filtering time constant
+ // the lower the less filtered
+ motor.LPF_velocity.Tf = 0.01f;
+
+ // angle P controller
+ motor.P_angle.P = 20;
+ // maximal velocity of the position control
+ motor.velocity_limit = 20;
+
+ // comment out if not needed
+ motor.useMonitoring(Serial);
+
+
+ // initialize motor
+ motor.init();
+ // align sensor and start FOC
+ motor.initFOC();
+
+ // add target command T
+ command.add('T', doTarget, "target angle");
+
+ Serial.println(F("Motor ready."));
+ Serial.println(F("Set the target angle using serial terminal:"));
+ _delay(1000);
+}
+
+
+void loop() {
+
+ // main FOC algorithm function
+ // the faster you run this function the better
+ // Arduino UNO loop ~1kHz
+ // Bluepill loop ~10kHz
+ motor.loopFOC();
+
+ // Motion control function
+ // velocity, position or voltage (defined in motor.controller)
+ // this function can be run at much lower frequency than loopFOC() function
+ // You can also use motor.move() and set the motor.target in the code
+ motor.move(target_angle);
+
+
+ // function intended to be used with serial plotter to monitor motor variables
+ // significantly slowing the execution down!!!!
+ // motor.monitor();
+
+ // user communication
+ command.run();
+}
\ No newline at end of file
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/motion_control/torque_control/encoder/current_control/current_control.ino b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/motion_control/torque_control/encoder/current_control/current_control.ino
new file mode 100644
index 0000000..82aec86
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/motion_control/torque_control/encoder/current_control/current_control.ino
@@ -0,0 +1,111 @@
+/**
+ *
+ * Torque control example using current control loop.
+ *
+ */
+#include
+
+
+// BLDC motor & driver instance
+BLDCMotor motor = BLDCMotor(11);
+BLDCDriver3PWM driver = BLDCDriver3PWM(9, 5, 6, 8);
+
+// encoder instance
+Encoder encoder = Encoder(2, 3, 500);
+// channel A and B callbacks
+void doA(){encoder.handleA();}
+void doB(){encoder.handleB();}
+
+// current sensor
+InlineCurrentSense current_sense = InlineCurrentSense(0.01f, 50.0f, A0, A2);
+
+// current set point variable
+float target_current = 0;
+// instantiate the commander
+Commander command = Commander(Serial);
+void doTarget(char* cmd) { command.scalar(&target_current, cmd); }
+
+void setup() {
+
+ // use monitoring with serial
+ Serial.begin(115200);
+ // enable more verbose output for debugging
+ // comment out if not needed
+ SimpleFOCDebug::enable(&Serial);
+
+ // initialize encoder sensor hardware
+ encoder.init();
+ encoder.enableInterrupts(doA, doB);
+ // link the motor to the sensor
+ motor.linkSensor(&encoder);
+
+ // driver config
+ // power supply voltage [V]
+ driver.voltage_power_supply = 12;
+ driver.init();
+ // link driver
+ motor.linkDriver(&driver);
+ // link current sense and the driver
+ current_sense.linkDriver(&driver);
+
+ // current sense init hardware
+ current_sense.init();
+ // link the current sense to the motor
+ motor.linkCurrentSense(¤t_sense);
+
+ // set torque mode:
+ // TorqueControlType::dc_current
+ // TorqueControlType::voltage
+ // TorqueControlType::foc_current
+ motor.torque_controller = TorqueControlType::foc_current;
+ // set motion control loop to be used
+ motor.controller = MotionControlType::torque;
+
+ // foc currnet control parameters (Arduino UNO/Mega)
+ motor.PID_current_q.P = 5;
+ motor.PID_current_q.I= 300;
+ motor.PID_current_d.P= 5;
+ motor.PID_current_d.I = 300;
+ motor.LPF_current_q.Tf = 0.01f;
+ motor.LPF_current_d.Tf = 0.01f;
+ // foc currnet control parameters (stm/esp/due/teensy)
+ // motor.PID_current_q.P = 5;
+ // motor.PID_current_q.I= 1000;
+ // motor.PID_current_d.P= 5;
+ // motor.PID_current_d.I = 1000;
+ // motor.LPF_current_q.Tf = 0.002f; // 1ms default
+ // motor.LPF_current_d.Tf = 0.002f; // 1ms default
+
+ // comment out if not needed
+ motor.useMonitoring(Serial);
+
+ // initialize motor
+ motor.init();
+ // align sensor and start FOC
+ motor.initFOC();
+
+ // add target command T
+ command.add('T', doTarget, "target current");
+
+ Serial.println(F("Motor ready."));
+ Serial.println(F("Set the target current using serial terminal:"));
+ _delay(1000);
+}
+
+void loop() {
+
+ // main FOC algorithm function
+ // the faster you run this function the better
+ // Arduino UNO loop ~1kHz
+ // Bluepill loop ~10kHz
+ motor.loopFOC();
+
+ // Motion control function
+ // velocity, position or torque (defined in motor.controller)
+ // this function can be run at much lower frequency than loopFOC() function
+ // You can also use motor.move() and set the motor.target in the code
+ motor.move(target_current);
+
+ // user communication
+ command.run();
+}
\ No newline at end of file
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/motion_control/torque_control/encoder/voltage_control/voltage_control.ino b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/motion_control/torque_control/encoder/voltage_control/voltage_control.ino
new file mode 100644
index 0000000..219637c
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/motion_control/torque_control/encoder/voltage_control/voltage_control.ino
@@ -0,0 +1,96 @@
+/**
+ *
+ * Torque control example using voltage control loop.
+ *
+ * Most of the low-end BLDC driver boards doesn't have current measurement therefore SimpleFOC offers
+ * you a way to control motor torque by setting the voltage to the motor instead hte current.
+ *
+ * This makes the BLDC motor effectively a DC motor, and you can use it in a same way.
+ */
+#include
+
+
+// BLDC motor & driver instance
+BLDCMotor motor = BLDCMotor(11);
+BLDCDriver3PWM driver = BLDCDriver3PWM(9, 5, 6, 8);
+// Stepper motor & driver instance
+//StepperMotor motor = StepperMotor(50);
+//StepperDriver4PWM driver = StepperDriver4PWM(9, 5, 10, 6, 8);
+
+// encoder instance
+Encoder encoder = Encoder(2, 3, 8192);
+
+// Interrupt routine intialisation
+// channel A and B callbacks
+void doA(){encoder.handleA();}
+void doB(){encoder.handleB();}
+
+// voltage set point variable
+float target_voltage = 2;
+// instantiate the commander
+Commander command = Commander(Serial);
+void doTarget(char* cmd) { command.scalar(&target_voltage, cmd); }
+
+void setup() {
+
+ // use monitoring with serial
+ Serial.begin(115200);
+ // enable more verbose output for debugging
+ // comment out if not needed
+ SimpleFOCDebug::enable(&Serial);
+
+ // initialize encoder sensor hardware
+ encoder.init();
+ encoder.enableInterrupts(doA, doB);
+ // link the motor to the sensor
+ motor.linkSensor(&encoder);
+
+ // driver config
+ // power supply voltage [V]
+ driver.voltage_power_supply = 12;
+ driver.init();
+ // link driver
+ motor.linkDriver(&driver);
+
+
+ // aligning voltage
+ motor.voltage_sensor_align = 5;
+ // choose FOC modulation (optional)
+ motor.foc_modulation = FOCModulationType::SpaceVectorPWM;
+
+ // set motion control loop to be used
+ motor.controller = MotionControlType::torque;
+
+ // comment out if not needed
+ motor.useMonitoring(Serial);
+
+ // initialize motor
+ motor.init();
+ // align sensor and start FOC
+ motor.initFOC();
+
+ // add target command T
+ command.add('T', doTarget, "target voltage");
+
+ Serial.println(F("Motor ready."));
+ Serial.println(F("Set the target voltage using serial terminal:"));
+ _delay(1000);
+}
+
+void loop() {
+
+ // main FOC algorithm function
+ // the faster you run this function the better
+ // Arduino UNO loop ~1kHz
+ // Bluepill loop ~10kHz
+ motor.loopFOC();
+
+ // Motion control function
+ // velocity, position or voltage (defined in motor.controller)
+ // this function can be run at much lower frequency than loopFOC() function
+ // You can also use motor.move() and set the motor.target in the code
+ motor.move(target_voltage);
+
+ // user communication
+ command.run();
+}
\ No newline at end of file
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/motion_control/torque_control/hall_sensor/voltage_control/voltage_control.ino b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/motion_control/torque_control/hall_sensor/voltage_control/voltage_control.ino
new file mode 100644
index 0000000..c72c922
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/motion_control/torque_control/hall_sensor/voltage_control/voltage_control.ino
@@ -0,0 +1,99 @@
+/**
+ *
+ * Torque control example using voltage control loop.
+ *
+ * Most of the low-end BLDC driver boards doesn't have current measurement therefore SimpleFOC offers
+ * you a way to control motor torque by setting the voltage to the motor instead of the current.
+ *
+ * This makes the BLDC motor effectively a DC motor, and you can use it in a same way.
+ */
+#include
+
+
+// BLDC motor & driver instance
+BLDCMotor motor = BLDCMotor(11);
+BLDCDriver3PWM driver = BLDCDriver3PWM(9, 5, 6, 8);
+// Stepper motor & driver instance
+//StepperMotor motor = StepperMotor(50);
+//StepperDriver4PWM driver = StepperDriver4PWM(9, 5, 10, 6, 8);
+
+// hall sensor instance
+HallSensor sensor = HallSensor(2, 3, 4, 11);
+
+// Interrupt routine intialisation
+// channel A and B callbacks
+void doA(){sensor.handleA();}
+void doB(){sensor.handleB();}
+void doC(){sensor.handleC();}
+
+
+// voltage set point variable
+float target_voltage = 2;
+// instantiate the commander
+Commander command = Commander(Serial);
+void doTarget(char* cmd) { command.scalar(&target_voltage, cmd); }
+
+void setup() {
+
+ // use monitoring with serial
+ Serial.begin(115200);
+ // enable more verbose output for debugging
+ // comment out if not needed
+ SimpleFOCDebug::enable(&Serial);
+
+ // initialize encoder sensor hardware
+ sensor.init();
+ sensor.enableInterrupts(doA, doB, doC);
+ // link the motor to the sensor
+ motor.linkSensor(&sensor);
+
+ // driver config
+ // power supply voltage [V]
+ driver.voltage_power_supply = 12;
+ driver.init();
+ // link driver
+ motor.linkDriver(&driver);
+
+ // aligning voltage
+ motor.voltage_sensor_align = 3;
+
+ // choose FOC modulation (optional)
+ motor.foc_modulation = FOCModulationType::SpaceVectorPWM;
+
+ // set motion control loop to be used
+ motor.controller = MotionControlType::torque;
+
+ // comment out if not needed
+ motor.useMonitoring(Serial);
+
+ // initialize motor
+ motor.init();
+ // align sensor and start FOC
+ motor.initFOC();
+
+ // add target command T
+ command.add('T', doTarget, "target voltage");
+
+ Serial.println(F("Motor ready."));
+ Serial.println(F("Set the target voltage using serial terminal:"));
+ _delay(1000);
+}
+
+
+void loop() {
+
+ // main FOC algorithm function
+ // the faster you run this function the better
+ // Arduino UNO loop ~1kHz
+ // Bluepill loop ~10kHz
+ motor.loopFOC();
+
+ // Motion control function
+ // velocity, position or voltage (defined in motor.controller)
+ // this function can be run at much lower frequency than loopFOC() function
+ // You can also use motor.move() and set the motor.target in the code
+ motor.move(target_voltage);
+
+ // user communication
+ command.run();
+}
\ No newline at end of file
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/motion_control/torque_control/magnetic_sensor/voltage_control/voltage_control.ino b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/motion_control/torque_control/magnetic_sensor/voltage_control/voltage_control.ino
new file mode 100644
index 0000000..dbb5608
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/motion_control/torque_control/magnetic_sensor/voltage_control/voltage_control.ino
@@ -0,0 +1,88 @@
+/**
+ * Torque control example using voltage control loop.
+ *
+ * Most of the low-end BLDC driver boards doesn't have current measurement therefore SimpleFOC offers
+ * you a way to control motor torque by setting the voltage to the motor instead hte current.
+ *
+ * This makes the BLDC motor effectively a DC motor, and you can use it in a same way.
+ */
+#include
+
+// magnetic sensor instance - SPI
+MagneticSensorSPI sensor = MagneticSensorSPI(AS5147_SPI, 10);
+// magnetic sensor instance - I2C
+// MagneticSensorI2C sensor = MagneticSensorI2C(AS5600_I2C);
+// magnetic sensor instance - analog output
+// MagneticSensorAnalog sensor = MagneticSensorAnalog(A1, 14, 1020);
+
+// BLDC motor & driver instance
+BLDCMotor motor = BLDCMotor(11);
+BLDCDriver3PWM driver = BLDCDriver3PWM(9, 5, 6, 8);
+// Stepper motor & driver instance
+//StepperMotor motor = StepperMotor(50);
+//StepperDriver4PWM driver = StepperDriver4PWM(9, 5, 10, 6, 8);
+
+// voltage set point variable
+float target_voltage = 2;
+// instantiate the commander
+Commander command = Commander(Serial);
+void doTarget(char* cmd) { command.scalar(&target_voltage, cmd); }
+
+void setup() {
+
+ // use monitoring with serial
+ Serial.begin(115200);
+ // enable more verbose output for debugging
+ // comment out if not needed
+ SimpleFOCDebug::enable(&Serial);
+
+ // initialise magnetic sensor hardware
+ sensor.init();
+ // link the motor to the sensor
+ motor.linkSensor(&sensor);
+
+ // power supply voltage
+ driver.voltage_power_supply = 12;
+ driver.init();
+ motor.linkDriver(&driver);
+
+ // aligning voltage
+ motor.voltage_sensor_align = 5;
+ // choose FOC modulation (optional)
+ motor.foc_modulation = FOCModulationType::SpaceVectorPWM;
+ // set motion control loop to be used
+ motor.controller = MotionControlType::torque;
+
+ // comment out if not needed
+ motor.useMonitoring(Serial);
+
+ // initialize motor
+ motor.init();
+ // align sensor and start FOC
+ motor.initFOC();
+
+ // add target command T
+ command.add('T', doTarget, "target voltage");
+
+ Serial.println(F("Motor ready."));
+ Serial.println(F("Set the target voltage using serial terminal:"));
+ _delay(1000);
+}
+
+void loop() {
+
+ // main FOC algorithm function
+ // the faster you run this function the better
+ // Arduino UNO loop ~1kHz
+ // Bluepill loop ~10kHz
+ motor.loopFOC();
+
+ // Motion control function
+ // velocity, position or voltage (defined in motor.controller)
+ // this function can be run at much lower frequency than loopFOC() function
+ // You can also use motor.move() and set the motor.target in the code
+ motor.move(target_voltage);
+
+ // user communication
+ command.run();
+}
\ No newline at end of file
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/motion_control/velocity_motion_control/encoder/velocity_control/velocity_control.ino b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/motion_control/velocity_motion_control/encoder/velocity_control/velocity_control.ino
new file mode 100644
index 0000000..f0f1e3e
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/motion_control/velocity_motion_control/encoder/velocity_control/velocity_control.ino
@@ -0,0 +1,137 @@
+/**
+ *
+ * Velocity motion control example
+ * Steps:
+ * 1) Configure the motor and encoder
+ * 2) Run the code
+ * 3) Set the target velocity (in radians per second) from serial terminal
+ *
+ *
+ *
+ * NOTE :
+ * > Arduino UNO example code for running velocity motion control using an encoder with index significantly
+ * > Since Arduino UNO doesn't have enough interrupt pins we have to use software interrupt library PciManager.
+ *
+ * > If running this code with Nucleo or Bluepill or any other board which has more than 2 interrupt pins
+ * > you can supply doIndex directly to the encoder.enableInterrupts(doA,doB,doIndex) and avoid using PciManger
+ *
+ * > If you don't want to use index pin initialize the encoder class without index pin number:
+ * > For example:
+ * > - Encoder encoder = Encoder(2, 3, 8192);
+ * > and initialize interrupts like this:
+ * > - encoder.enableInterrupts(doA,doB)
+ *
+ * Check the docs.simplefoc.com for more info about the possible encoder configuration.
+ *
+ */
+#include
+// software interrupt library
+#include
+#include
+
+// BLDC motor & driver instance
+BLDCMotor motor = BLDCMotor(11);
+BLDCDriver3PWM driver = BLDCDriver3PWM(9, 5, 6, 8);
+// Stepper motor & driver instance
+//StepperMotor motor = StepperMotor(50);
+//StepperDriver4PWM driver = StepperDriver4PWM(9, 5, 10, 6, 8);
+
+// encoder instance
+Encoder encoder = Encoder(2, 3, 8192, A0);
+
+// Interrupt routine intialisation
+// channel A and B callbacks
+void doA(){encoder.handleA();}
+void doB(){encoder.handleB();}
+void doIndex(){encoder.handleIndex();}
+// If no available hadware interrupt pins use the software interrupt
+PciListenerImp listenerIndex(encoder.index_pin, doIndex);
+
+
+// velocity set point variable
+float target_velocity = 0;
+// instantiate the commander
+Commander command = Commander(Serial);
+void doTarget(char* cmd) { command.scalar(&target_velocity, cmd); }
+
+
+void setup() {
+
+ // initialize encoder sensor hardware
+ encoder.init();
+ encoder.enableInterrupts(doA, doB);
+ // software interrupts
+ PciManager.registerListener(&listenerIndex);
+ // link the motor to the sensor
+ motor.linkSensor(&encoder);
+
+ // driver config
+ // power supply voltage [V]
+ driver.voltage_power_supply = 12;
+ driver.init();
+ // link the motor and the driver
+ motor.linkDriver(&driver);
+
+ // aligning voltage [V]
+ motor.voltage_sensor_align = 3;
+ // index search velocity [rad/s]
+ motor.velocity_index_search = 3;
+
+ // set motion control loop to be used
+ motor.controller = MotionControlType::velocity;
+
+ // contoller configuration
+ // default parameters in defaults.h
+
+ // velocity PI controller parameters
+ motor.PID_velocity.P = 0.2f;
+ motor.PID_velocity.I = 20;
+ motor.PID_velocity.D = 0;
+ // default voltage_power_supply
+ motor.voltage_limit = 6;
+ // jerk control using voltage voltage ramp
+ // default value is 300 volts per sec ~ 0.3V per millisecond
+ motor.PID_velocity.output_ramp = 1000;
+
+ // velocity low pass filtering time constant
+ motor.LPF_velocity.Tf = 0.01f;
+
+ // use monitoring with serial
+ Serial.begin(115200);
+ // comment out if not needed
+ motor.useMonitoring(Serial);
+
+ // initialize motor
+ motor.init();
+ // align sensor and start FOC
+ motor.initFOC();
+
+ // add target command T
+ command.add('T', doTarget, "target velocity");
+
+ Serial.println(F("Motor ready."));
+ Serial.println(F("Set the target velocity using serial terminal:"));
+ _delay(1000);
+}
+
+
+void loop() {
+ // main FOC algorithm function
+ // the faster you run this function the better
+ // Arduino UNO loop ~1kHz
+ // Bluepill loop ~10kHz
+ motor.loopFOC();
+
+ // Motion control function
+ // velocity, position or voltage (defined in motor.controller)
+ // this function can be run at much lower frequency than loopFOC() function
+ // You can also use motor.move() and set the motor.target in the code
+ motor.move(target_velocity);
+
+ // function intended to be used with serial plotter to monitor motor variables
+ // significantly slowing the execution down!!!!
+ // motor.monitor();
+
+ // user communication
+ command.run();
+}
\ No newline at end of file
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/motion_control/velocity_motion_control/hall_sensor/velocity_control/velocity_control.ino b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/motion_control/velocity_motion_control/hall_sensor/velocity_control/velocity_control.ino
new file mode 100644
index 0000000..4fb47f0
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/motion_control/velocity_motion_control/hall_sensor/velocity_control/velocity_control.ino
@@ -0,0 +1,129 @@
+/**
+ *
+ * Velocity motion control example
+ * Steps:
+ * 1) Configure the motor and sensor
+ * 2) Run the code
+ * 3) Set the target velocity (in radians per second) from serial terminal
+ *
+ *
+ *
+ * NOTE :
+ * > Specifically for Arduino UNO example code for running velocity motion control using a hall sensor
+ * > Since Arduino UNO doesn't have enough interrupt pins we have to use software interrupt library PciManager.
+ *
+ * > If running this code with Nucleo or Bluepill or any other board which has more than 2 interrupt pins
+ * > you can supply doC directly to the sensor.enableInterrupts(doA,doB,doC) and avoid using PciManger
+ *
+ */
+#include
+// software interrupt library
+#include
+#include
+
+// BLDC motor & driver instance
+BLDCMotor motor = BLDCMotor(11);
+BLDCDriver3PWM driver = BLDCDriver3PWM(9, 5, 6, 8);
+// Stepper motor & driver instance
+//StepperMotor motor = StepperMotor(50);
+//StepperDriver4PWM driver = StepperDriver4PWM(9, 5, 10, 6, 8);
+
+// hall sensor instance
+HallSensor sensor = HallSensor(2, 3, 4, 11);
+
+// Interrupt routine intialisation
+// channel A and B callbacks
+void doA(){sensor.handleA();}
+void doB(){sensor.handleB();}
+void doC(){sensor.handleC();}
+// If no available hadware interrupt pins use the software interrupt
+PciListenerImp listenerIndex(sensor.pinC, doC);
+
+// velocity set point variable
+float target_velocity = 0;
+// instantiate the commander
+Commander command = Commander(Serial);
+void doTarget(char* cmd) { command.scalar(&target_velocity, cmd); }
+
+void setup() {
+
+ // use monitoring with serial
+ Serial.begin(115200);
+ // enable more verbose output for debugging
+ // comment out if not needed
+ SimpleFOCDebug::enable(&Serial);
+
+ // initialize sensor sensor hardware
+ sensor.init();
+ sensor.enableInterrupts(doA, doB); //, doC);
+ // software interrupts
+ PciManager.registerListener(&listenerIndex);
+ // link the motor to the sensor
+ motor.linkSensor(&sensor);
+
+ // driver config
+ // power supply voltage [V]
+ driver.voltage_power_supply = 12;
+ driver.init();
+ // link the motor and the driver
+ motor.linkDriver(&driver);
+
+ // aligning voltage [V]
+ motor.voltage_sensor_align = 3;
+
+ // set motion control loop to be used
+ motor.controller = MotionControlType::velocity;
+
+ // contoller configuration
+ // default parameters in defaults.h
+
+ // velocity PI controller parameters
+ motor.PID_velocity.P = 0.2f;
+ motor.PID_velocity.I = 2;
+ motor.PID_velocity.D = 0;
+ // default voltage_power_supply
+ motor.voltage_limit = 6;
+ // jerk control using voltage voltage ramp
+ // default value is 300 volts per sec ~ 0.3V per millisecond
+ motor.PID_velocity.output_ramp = 1000;
+
+ // velocity low pass filtering time constant
+ motor.LPF_velocity.Tf = 0.01f;
+
+ // comment out if not needed
+ motor.useMonitoring(Serial);
+
+ // initialize motor
+ motor.init();
+ // align sensor and start FOC
+ motor.initFOC();
+
+ // add target command T
+ command.add('T', doTarget, "target voltage");
+
+ Serial.println(F("Motor ready."));
+ Serial.println(F("Set the target velocity using serial terminal:"));
+ _delay(1000);
+}
+
+
+void loop() {
+ // main FOC algorithm function
+ // the faster you run this function the better
+ // Arduino UNO loop ~1kHz
+ // Bluepill loop ~10kHz
+ motor.loopFOC();
+
+ // Motion control function
+ // velocity, position or voltage (defined in motor.controller)
+ // this function can be run at much lower frequency than loopFOC() function
+ // You can also use motor.move() and set the motor.target in the code
+ motor.move(target_velocity);
+
+ // function intended to be used with serial plotter to monitor motor variables
+ // significantly slowing the execution down!!!!
+ // motor.monitor();
+
+ // user communication
+ command.run();
+}
\ No newline at end of file
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/motion_control/velocity_motion_control/magnetic_sensor/velocity_control/velocity_control.ino b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/motion_control/velocity_motion_control/magnetic_sensor/velocity_control/velocity_control.ino
new file mode 100644
index 0000000..40299b8
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/motion_control/velocity_motion_control/magnetic_sensor/velocity_control/velocity_control.ino
@@ -0,0 +1,110 @@
+/**
+ *
+ * Velocity motion control example
+ * Steps:
+ * 1) Configure the motor and magnetic sensor
+ * 2) Run the code
+ * 3) Set the target velocity (in radians per second) from serial terminal
+ *
+ *
+ * By using the serial terminal set the velocity value you want to motor to obtain
+ *
+ */
+#include
+
+// magnetic sensor instance - SPI
+MagneticSensorSPI sensor = MagneticSensorSPI(AS5147_SPI, 10);
+// magnetic sensor instance - MagneticSensorI2C
+//MagneticSensorI2C sensor = MagneticSensorI2C(AS5600_I2C);
+// MagneticSensorAnalog sensor = MagneticSensorAnalog(A1, 14, 1020);
+
+// BLDC motor & driver instance
+BLDCMotor motor = BLDCMotor(11);
+BLDCDriver3PWM driver = BLDCDriver3PWM(9, 5, 6, 8);
+// Stepper motor & driver instance
+//StepperMotor motor = StepperMotor(50);
+//StepperDriver4PWM driver = StepperDriver4PWM(9, 5, 10, 6, 8);
+
+// velocity set point variable
+float target_velocity = 0;
+// instantiate the commander
+Commander command = Commander(Serial);
+void doTarget(char* cmd) { command.scalar(&target_velocity, cmd); }
+
+void setup() {
+
+ // use monitoring with serial
+ Serial.begin(115200);
+ // enable more verbose output for debugging
+ // comment out if not needed
+ SimpleFOCDebug::enable(&Serial);
+
+ // initialise magnetic sensor hardware
+ sensor.init();
+ // link the motor to the sensor
+ motor.linkSensor(&sensor);
+
+ // driver config
+ // power supply voltage [V]
+ driver.voltage_power_supply = 12;
+ driver.init();
+ // link the motor and the driver
+ motor.linkDriver(&driver);
+
+ // set motion control loop to be used
+ motor.controller = MotionControlType::velocity;
+
+ // contoller configuration
+ // default parameters in defaults.h
+
+ // velocity PI controller parameters
+ motor.PID_velocity.P = 0.2f;
+ motor.PID_velocity.I = 20;
+ motor.PID_velocity.D = 0;
+ // default voltage_power_supply
+ motor.voltage_limit = 6;
+ // jerk control using voltage voltage ramp
+ // default value is 300 volts per sec ~ 0.3V per millisecond
+ motor.PID_velocity.output_ramp = 1000;
+
+ // velocity low pass filtering
+ // default 5ms - try different values to see what is the best.
+ // the lower the less filtered
+ motor.LPF_velocity.Tf = 0.01f;
+
+ // comment out if not needed
+ motor.useMonitoring(Serial);
+
+ // initialize motor
+ motor.init();
+ // align sensor and start FOC
+ motor.initFOC();
+
+ // add target command T
+ command.add('T', doTarget, "target velocity");
+
+ Serial.println(F("Motor ready."));
+ Serial.println(F("Set the target velocity using serial terminal:"));
+ _delay(1000);
+}
+
+void loop() {
+ // main FOC algorithm function
+ // the faster you run this function the better
+ // Arduino UNO loop ~1kHz
+ // Bluepill loop ~10kHz
+ motor.loopFOC();
+
+ // Motion control function
+ // velocity, position or voltage (defined in motor.controller)
+ // this function can be run at much lower frequency than loopFOC() function
+ // You can also use motor.move() and set the motor.target in the code
+ motor.move(target_velocity);
+
+ // function intended to be used with serial plotter to monitor motor variables
+ // significantly slowing the execution down!!!!
+ // motor.monitor();
+
+ // user communication
+ command.run();
+}
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/motor_commands_serial_examples/encoder/full_control_serial/full_control_serial.ino b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/motor_commands_serial_examples/encoder/full_control_serial/full_control_serial.ino
new file mode 100644
index 0000000..d6ddc6b
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/motor_commands_serial_examples/encoder/full_control_serial/full_control_serial.ino
@@ -0,0 +1,109 @@
+/**
+ * Comprehensive BLDC motor control example using encoder
+ *
+ * Using serial terminal user can send motor commands and configure the motor and FOC in real-time:
+ * - configure PID controller constants
+ * - change motion control loops
+ * - monitor motor variabels
+ * - set target values
+ * - check all the configuration values
+ *
+ * See more info in docs.simplefoc.com/commander_interface
+ */
+#include
+
+// BLDC motor & driver instance
+BLDCMotor motor = BLDCMotor(11);
+BLDCDriver3PWM driver = BLDCDriver3PWM(9, 5, 6, 8);
+// Stepper motor & driver instance
+//StepperMotor motor = StepperMotor(50);
+//StepperDriver4PWM driver = StepperDriver4PWM(9, 5, 10, 6, 8);
+
+// encoder instance
+Encoder encoder = Encoder(2, 3, 8192);
+
+// Interrupt routine intialisation
+// channel A and B callbacks
+void doA(){encoder.handleA();}
+void doB(){encoder.handleB();}
+
+
+// commander interface
+Commander command = Commander(Serial);
+void onMotor(char* cmd){ command.motor(&motor, cmd); }
+
+void setup() {
+
+ // use monitoring with serial
+ Serial.begin(115200);
+ // enable more verbose output for debugging
+ // comment out if not needed
+ SimpleFOCDebug::enable(&Serial);
+
+ // initialize encoder sensor hardware
+ encoder.init();
+ encoder.enableInterrupts(doA, doB);
+ // link the motor to the sensor
+ motor.linkSensor(&encoder);
+
+ // driver config
+ // power supply voltage [V]
+ driver.voltage_power_supply = 12;
+ driver.init();
+ // link driver
+ motor.linkDriver(&driver);
+
+
+ // choose FOC modulation
+ motor.foc_modulation = FOCModulationType::SpaceVectorPWM;
+ // set control loop type to be used
+ motor.controller = MotionControlType::torque;
+
+ // contoller configuration based on the controll type
+ motor.PID_velocity.P = 0.2f;
+ motor.PID_velocity.I = 20;
+ motor.PID_velocity.D = 0;
+ // default voltage_power_supply
+ motor.voltage_limit = 12;
+
+ // velocity low pass filtering time constant
+ motor.LPF_velocity.Tf = 0.01f;
+
+ // angle loop controller
+ motor.P_angle.P = 20;
+ // angle loop velocity limit
+ motor.velocity_limit = 50;
+
+ // comment out if not needed
+ motor.useMonitoring(Serial);
+
+ // initialise motor
+ motor.init();
+ // align encoder and start FOC
+ motor.initFOC();
+
+ // set the inital target value
+ motor.target = 2;
+
+ // define the motor id
+ command.add('A', onMotor, "motor");
+
+ // Run user commands to configure and the motor (find the full command list in docs.simplefoc.com)
+ Serial.println(F("Motor commands sketch | Initial motion control > torque/voltage : target 2V."));
+
+ _delay(1000);
+}
+
+
+void loop() {
+ // iterative setting FOC phase voltage
+ motor.loopFOC();
+
+ // iterative function setting the outter loop target
+ // velocity, position or voltage
+ // if tatget not set in parameter uses motor.target variable
+ motor.move();
+
+ // user communication
+ command.run();
+}
\ No newline at end of file
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/motor_commands_serial_examples/hall_sensor/full_control_serial/full_control_serial.ino b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/motor_commands_serial_examples/hall_sensor/full_control_serial/full_control_serial.ino
new file mode 100644
index 0000000..ff6fe7f
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/motor_commands_serial_examples/hall_sensor/full_control_serial/full_control_serial.ino
@@ -0,0 +1,117 @@
+/**
+ * Comprehensive BLDC motor control example using Hall sensor
+ *
+ * Using serial terminal user can send motor commands and configure the motor and FOC in real-time:
+ * - configure PID controller constants
+ * - change motion control loops
+ * - monitor motor variabels
+ * - set target values
+ * - check all the configuration values
+ *
+ * See more info in docs.simplefoc.com/commander_interface
+ */
+#include
+// software interrupt library
+#include
+#include
+
+// BLDC motor & driver instance
+BLDCMotor motor = BLDCMotor(11);
+BLDCDriver3PWM driver = BLDCDriver3PWM(9, 5, 6, 8);
+// Stepper motor & driver instance
+//StepperMotor motor = StepperMotor(50);
+//StepperDriver4PWM driver = StepperDriver4PWM(9, 5, 10, 6, 8);
+
+// hall sensor instance
+HallSensor sensor = HallSensor(2, 3, 4, 11);
+
+// Interrupt routine intialisation
+// channel A, B and C callbacks
+void doA(){sensor.handleA();}
+void doB(){sensor.handleB();}
+void doC(){sensor.handleC();}
+// If no available hadware interrupt pins use the software interrupt
+PciListenerImp listenC(sensor.pinC, doC);
+
+
+// commander interface
+Commander command = Commander(Serial);
+void onMotor(char* cmd){ command.motor(&motor, cmd); }
+
+
+void setup() {
+
+ // use monitoring with serial
+ Serial.begin(115200);
+ // enable more verbose output for debugging
+ // comment out if not needed
+ SimpleFOCDebug::enable(&Serial);
+
+ // initialize encoder sensor hardware
+ sensor.init();
+ sensor.enableInterrupts(doA, doB); //, doC);
+ // software interrupts
+ PciManager.registerListener(&listenC);
+ // link the motor to the sensor
+ motor.linkSensor(&sensor);
+
+ // driver config
+ // power supply voltage [V]
+ driver.voltage_power_supply = 12;
+ driver.init();
+ // link driver
+ motor.linkDriver(&driver);
+
+
+ // choose FOC modulation
+ motor.foc_modulation = FOCModulationType::SpaceVectorPWM;
+ // set control loop type to be used
+ motor.controller = MotionControlType::torque;
+ // contoller configuration based on the controll type
+ motor.PID_velocity.P = 0.2f;
+ motor.PID_velocity.I = 20;
+ motor.PID_velocity.D = 0;
+ // default voltage_power_supply
+ motor.voltage_limit = 12;
+
+ // velocity low pass filtering time constant
+ motor.LPF_velocity.Tf = 0.01f;
+
+ // angle loop controller
+ motor.P_angle.P = 20;
+ // angle loop velocity limit
+ motor.velocity_limit = 50;
+
+ // comment out if not needed
+ motor.useMonitoring(Serial);
+
+ // initialise motor
+ motor.init();
+ // align encoder and start FOC
+ motor.initFOC();
+
+ // set the inital target value
+ motor.target = 2;
+
+ // define the motor id
+ command.add('A', onMotor, "motor");
+
+ // Run user commands to configure and the motor (find the full command list in docs.simplefoc.com)
+ Serial.println(F("Motor commands sketch | Initial motion control > torque/voltage : target 2V."));
+
+ _delay(1000);
+}
+
+
+void loop() {
+ // iterative setting FOC phase voltage
+ motor.loopFOC();
+
+ // iterative function setting the outter loop target
+ // velocity, position or voltage
+ // if tatget not set in parameter uses motor.target variable
+ motor.move();
+
+ // user communication
+ command.run();
+}
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/motor_commands_serial_examples/magnetic_sensor/full_control_serial/full_control_serial.ino b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/motor_commands_serial_examples/magnetic_sensor/full_control_serial/full_control_serial.ino
new file mode 100644
index 0000000..e863d8c
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/motor_commands_serial_examples/magnetic_sensor/full_control_serial/full_control_serial.ino
@@ -0,0 +1,107 @@
+/**
+ * Comprehensive BLDC motor control example using magnetic sensor
+ *
+ * Using serial terminal user can send motor commands and configure the motor and FOC in real-time:
+ * - configure PID controller constants
+ * - change motion control loops
+ * - monitor motor variabels
+ * - set target values
+ * - check all the configuration values
+ *
+ * See more info in docs.simplefoc.com/commander_interface
+ */
+#include
+
+// magnetic sensor instance - SPI
+MagneticSensorSPI sensor = MagneticSensorSPI(AS5147_SPI, 10);
+// magnetic sensor instance - MagneticSensorI2C
+//MagneticSensorI2C sensor = MagneticSensorI2C(AS5600_I2C);
+// magnetic sensor instance - analog output
+// MagneticSensorAnalog sensor = MagneticSensorAnalog(A1, 14, 1020);
+
+
+// BLDC motor & driver instance
+BLDCMotor motor = BLDCMotor(11);
+BLDCDriver3PWM driver = BLDCDriver3PWM(9, 5, 6, 8);
+// Stepper motor & driver instance
+//StepperMotor motor = StepperMotor(50);
+//StepperDriver4PWM driver = StepperDriver4PWM(9, 5, 10, 6, 8);
+
+// commander interface
+Commander command = Commander(Serial);
+void onMotor(char* cmd){ command.motor(&motor, cmd); }
+
+void setup() {
+
+ // use monitoring with serial
+ Serial.begin(115200);
+ // enable more verbose output for debugging
+ // comment out if not needed
+ SimpleFOCDebug::enable(&Serial);
+
+ // initialise magnetic sensor hardware
+ sensor.init();
+ // link the motor to the sensor
+ motor.linkSensor(&sensor);
+
+ // driver config
+ // power supply voltage [V]
+ driver.voltage_power_supply = 12;
+ driver.init();
+ // link driver
+ motor.linkDriver(&driver);
+
+ // choose FOC modulation
+ motor.foc_modulation = FOCModulationType::SpaceVectorPWM;
+
+ // set control loop type to be used
+ motor.controller = MotionControlType::torque;
+
+ // contoller configuration based on the control type
+ motor.PID_velocity.P = 0.2f;
+ motor.PID_velocity.I = 20;
+ motor.PID_velocity.D = 0;
+ // default voltage_power_supply
+ motor.voltage_limit = 12;
+
+ // velocity low pass filtering time constant
+ motor.LPF_velocity.Tf = 0.01f;
+
+ // angle loop controller
+ motor.P_angle.P = 20;
+ // angle loop velocity limit
+ motor.velocity_limit = 50;
+
+ // comment out if not needed
+ motor.useMonitoring(Serial);
+
+ // initialise motor
+ motor.init();
+ // align encoder and start FOC
+ motor.initFOC();
+
+ // set the inital target value
+ motor.target = 2;
+
+ // define the motor id
+ command.add('A', onMotor, "motor");
+
+ // Run user commands to configure and the motor (find the full command list in docs.simplefoc.com)
+ Serial.println(F("Motor commands sketch | Initial motion control > torque/voltage : target 2V."));
+
+ _delay(1000);
+}
+
+
+void loop() {
+ // iterative setting FOC phase voltage
+ motor.loopFOC();
+
+ // iterative function setting the outter loop target
+ // velocity, position or voltage
+ // if tatget not set in parameter uses motor.target variable
+ motor.move();
+
+ // user communication
+ command.run();
+}
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/osc_control_examples/README.md b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/osc_control_examples/README.md
new file mode 100644
index 0000000..bd6f776
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/osc_control_examples/README.md
@@ -0,0 +1,28 @@
+
+# OSC control examples
+
+OSC - opensoundcontrol.org is a simple message exchange protocol. Widely used in the Audio world it is being hailed as the successor to MIDI. But MIDI itself, and now OSC, has always been about sending and receiving fairly simple control messages, at medium speed, and that makes it well suited for the same kind of task in robotics or other control applications.
+
+As a protocol it is simple, making implementation quite easy, and while binary, simple enough to be fairly "human readable", which aids in debugging and reduces errors.
+
+The main advantage of using it is that there is a bunch of ready made software, and also libraries to use in your own programs, neaning you don't have to re-invent these things from scratch.
+
+## TouchOSC
+
+The first example shows how to set up control of a motor from TouchOSC. It's a super-fast way to set up a customizable GUI for your motor-project, that runs on your phone...
+
+## purr-Data
+
+The second example, "simplefoc\_osc\_esp32\_fullcontrol.ino" allows setting the variables and tuning the motor parameters, in the same way as the serial control but via OSC. The file "osc\_fullcontrol.pd" contains a sample GUI to go with that sketch, allowing the control and tuning of 2 BLDC motors.
+
+Here a screenshot of what it looks like in purr-Data:
+
+
+
+
+## Links to software used in examples
+
+- OSC - opensoundcontrol.org
+- pD - https://puredata.info
+- TouchOSC - https://hexler.net/products/touchosc
+
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/osc_control_examples/osc_esp32_3pwm/layout1.touchosc b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/osc_control_examples/osc_esp32_3pwm/layout1.touchosc
new file mode 100644
index 0000000..ba4d2af
Binary files /dev/null and b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/osc_control_examples/osc_esp32_3pwm/layout1.touchosc differ
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/osc_control_examples/osc_esp32_3pwm/osc_esp32_3pwm.ino b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/osc_control_examples/osc_esp32_3pwm/osc_esp32_3pwm.ino
new file mode 100644
index 0000000..14d4867
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/osc_control_examples/osc_esp32_3pwm/osc_esp32_3pwm.ino
@@ -0,0 +1,187 @@
+/**
+ * Arduino SimpleFOC + OSC control example
+ *
+ * Simple example to show how you can control SimpleFOC via OSC.
+ *
+ * It's a nice way to work, easier than changing speeds via Seerial text input. It could also be the basis for
+ * a functional UI, for example in a lab, art-gallery or similar situation.
+ *
+ * For this example we used an ESP32 to run the code, a AS5048B I2C absolute encoder
+ * and a generic L298 driver board to drive a Emax 4114 gimbal motor. But there is no reason the OSC part will
+ * not work with any other setup.
+ *
+ * You will need:
+ *
+ * - a working SimpleFOC setup - motor, driver, encoder
+ * - a MCU with WiFi and UDP support, for example an ESP32, or an Arduino with Ethernet Shield
+ * - a device to run an OSC UI
+ * - a configured OSC UI
+ * - a WiFi network
+ *
+ * To do the OSC UI I used TouchOSC from https://hexler.net/products/touchosc
+ * There is an example UI file that works with this sketch, see "layout1.touchosc"
+ * You can open the UI file in 'TouchOSC Editor' (free program) and transfer it to the TouchOSC app on your device.
+ *
+ * Alternatively, there are other OSC UIs which may work, e.g. http://opensoundcontrol.org/implementations
+ *
+ * Using:
+ *
+ * Change the values below to match the WiFi ssid/password of your network.
+ * Load and run the code on your ESP32. Take a note of the IP address of your ESP32.
+ * Load and run the UI in TouchOSC.
+ * Configure TouchOSC to connect to your ESP32.
+ * The first command you send will cause the ESP32 to start sending responses to your TouchOSC device.
+ * After this you will see motor position and speed in the UI.
+ * Have fun controlling your SimpleFOC motors from your smartphone!
+ *
+ */
+
+
+#include "Arduino.h"
+#include
+
+#include
+#include
+
+#include
+#include
+#include
+#include
+
+
+const char ssid[] = "myssid"; // your network SSID (name)
+const char pass[] = "mypassword"; // your network password
+WiFiUDP Udp;
+IPAddress outIp(192,168,1,17); // remote IP (not needed for receive)
+const unsigned int outPort = 8000; // remote port (not needed for receive)
+const unsigned int inPort = 8000; // local port to listen for UDP packets (here's where we send the packets)
+
+
+OSCErrorCode error;
+
+MagneticSensorI2C sensor = MagneticSensorI2C(0x40, 14, 0xFE, 8);
+BLDCMotor motor = BLDCMotor(11);
+BLDCDriver3PWM driver = BLDCDriver3PWM(25, 26, 27);
+
+// commander interface
+Commander command = Commander(Serial);
+
+void setup() {
+ // use monitoring with serial
+ Serial.begin(115200);
+ // enable more verbose output for debugging
+ // comment out if not needed
+ SimpleFOCDebug::enable(&Serial);
+
+ WiFi.begin(ssid, pass);
+
+ Serial.print("Connecting WiFi ");
+ Serial.println(ssid);
+ while (WiFi.status() != WL_CONNECTED) {
+ delay(500);
+ Serial.print(".");
+ }
+ Udp.begin(inPort);
+ Serial.println();
+ Serial.print("WiFi connected. Local OSC address: ");
+ Serial.print(WiFi.localIP());
+ Serial.print(":");
+ Serial.println(inPort);
+
+ delay(2000);
+ Serial.println("Initializing motor.");
+
+ sensor.init();
+ motor.linkSensor(&sensor);
+ driver.voltage_power_supply = 9;
+ driver.init();
+ motor.linkDriver(&driver);
+ motor.controller = MotionControlType::velocity;
+ motor.PID_velocity.P = 0.2f;
+ motor.PID_velocity.I = 20;
+ motor.PID_velocity.D = 0.001f;
+ motor.PID_velocity.output_ramp = 1000;
+ motor.LPF_velocity.Tf = 0.01f;
+ motor.voltage_limit = 8;
+ //motor.P_angle.P = 20;
+ motor.init();
+ motor.initFOC();
+
+ Serial.println("All initialization complete.");
+}
+
+// velocity set point variable
+float target_velocity = 2.0f;
+// angle set point variable
+float target_angle = 1.0f;
+
+
+void motorControl(OSCMessage &msg){
+ if (msg.isInt(0))
+ target_velocity = radians(msg.getInt(0));
+ else if (msg.isFloat(0))
+ target_velocity = radians(msg.getFloat(0));
+ else if (msg.isDouble(0))
+ target_velocity = radians(msg.getDouble(0));
+ Serial.print("Velocity set to ");
+ Serial.println(target_velocity);
+}
+
+void cmdControl(OSCMessage &msg){
+ char cmdStr[16];
+ if (msg.isString(0)) {
+ msg.getString(0,cmdStr,16);
+ command.motor(&motor,cmdStr);
+ }
+}
+
+long lastSend = 0;
+OSCMessage bundleIN;
+
+void loop() {
+ OSCBundle bundleOUT;
+
+ // FOC algorithm function
+ motor.move(target_velocity);
+ motor.loopFOC();
+
+
+ int size = Udp.parsePacket();
+ if (size > 0) {
+ while (size--) {
+ bundleIN.fill(Udp.read());
+ }
+ if (!bundleIN.hasError()) {
+ bundleIN.dispatch("/mot1/S", motorControl);
+ bundleIN.dispatch("/mot1/C", cmdControl);
+ IPAddress ip = Udp.remoteIP();
+ if (!( ip==outIp )) {
+ Serial.print("New connection from ");
+ Serial.println(ip);
+ outIp = ip;
+ }
+ }
+ else {
+ error = bundleIN.getError();
+ Serial.print("error: ");
+ Serial.println(error);
+ }
+ bundleIN.empty();
+ }
+ else { // don't receive and send in the same loop...
+ long now = millis();
+ if (now - lastSend > 100) {
+ int ang = (int)degrees(motor.shaftAngle()) % 360;
+ if (ang<0) ang = 360-abs(ang);
+ //BOSCBundle's add' returns the OSCMessage so the message's 'add' can be composed together
+ bundleOUT.add("/mot1/A").add((int)ang);
+ bundleOUT.add("/mot1/V").add((int)degrees(motor.shaftVelocity()));
+ Udp.beginPacket(outIp, outPort);
+ bundleOUT.send(Udp);
+ Udp.endPacket();
+ bundleOUT.empty(); // empty the bundle to free room for a new one
+ lastSend = now;
+ }
+ }
+
+}
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/osc_control_examples/osc_esp32_fullcontrol/osc_esp32_fullcontrol.ino b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/osc_control_examples/osc_esp32_fullcontrol/osc_esp32_fullcontrol.ino
new file mode 100644
index 0000000..940b59c
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/osc_control_examples/osc_esp32_fullcontrol/osc_esp32_fullcontrol.ino
@@ -0,0 +1,356 @@
+/**
+ *
+ * Control 2 motors on ESP32 using OSC
+ *
+ * In this example, all the commands available on the serial command interface are also available via OSC.
+ * Also, the example is for 2 motors. If you have only 1 motor, comment out the lines for the second motor.
+ *
+ *
+ *
+ *
+ */
+
+
+#include "Arduino.h"
+#include
+#include
+#include "ssid.h" // create this file, which defines the constants MYSSID and MYPASS
+#include
+#include
+#include
+
+#include
+#include
+#include
+
+
+const char ssid[] = MYSSID; // your network SSID (name)
+const char pass[] = MYPASS; // your network password
+WiFiUDP Udp;
+IPAddress outIp(192,168,1,13); // remote IP (not needed for receive)
+const unsigned int outPort = 8000; // remote port (not needed for receive)
+const unsigned int inPort = 8000; // local port to listen for UDP packets (here's where we send the packets)
+#define POWER_SUPPLY 7.4f
+
+
+
+MagneticSensorI2C sensor2 = MagneticSensorI2C(0x40, 14, 0xFE, 8);
+MagneticSensorI2C sensor1 = MagneticSensorI2C(0x41, 14, 0xFE, 8);
+BLDCMotor motor1 = BLDCMotor(7);
+BLDCMotor motor2 = BLDCMotor(7);
+BLDCDriver3PWM driver1 = BLDCDriver3PWM(25, 26, 27);
+BLDCDriver3PWM driver2 = BLDCDriver3PWM(0, 4, 16);
+
+String m1Prefix("/M1");
+String m2Prefix("/M2");
+
+
+// we store seperate set-points for each motor, of course
+float set_point1 = 0.0f;
+float set_point2 = 0.0f;
+
+
+OSCErrorCode error;
+OSCBundle bundleOUT; // outgoing message, gets re-used
+
+
+
+void setupOTA(const char* hostname) {
+ ArduinoOTA
+ .setPort(8266)
+ .onStart([]() {
+ String type;
+ if (ArduinoOTA.getCommand() == U_FLASH)
+ type = "sketch";
+ else // U_SPIFFS
+ type = "filesystem";
+
+ // NOTE: if updating SPIFFS this would be the place to unmount SPIFFS using SPIFFS.end()
+ Serial.println("Start updating " + type);
+ })
+ .onEnd([]() {
+ Serial.println("\nEnd");
+ })
+ .onProgress([](unsigned int progress, unsigned int total) {
+ Serial.printf("Progress: %u%%\n", (progress / (total / 100)));
+ })
+ .onError([](ota_error_t error) {
+ Serial.printf("Error[%u]: ", error);
+ if (error == OTA_AUTH_ERROR) Serial.println("Auth Failed");
+ else if (error == OTA_BEGIN_ERROR) Serial.println("Begin Failed");
+ else if (error == OTA_CONNECT_ERROR) Serial.println("Connect Failed");
+ else if (error == OTA_RECEIVE_ERROR) Serial.println("Receive Failed");
+ else if (error == OTA_END_ERROR) Serial.println("End Failed");
+ })
+ .setHostname(hostname)
+ .setMdnsEnabled(true);
+ ArduinoOTA.begin();
+}
+
+
+void setup() {
+ // set pins low - motor initialization can take some time,
+ // and you don't want current flowing through the other motor while it happens...
+ pinMode(0,OUTPUT);
+ pinMode(4,OUTPUT);
+ pinMode(16,OUTPUT);
+ pinMode(25,OUTPUT);
+ pinMode(26,OUTPUT);
+ pinMode(27,OUTPUT);
+ digitalWrite(0, 0);
+ digitalWrite(4, 0);
+ digitalWrite(16, 0);
+ digitalWrite(25, 0);
+ digitalWrite(26, 0);
+ digitalWrite(27, 0);
+
+ // use monitoring with serial
+ Serial.begin(115200);
+ // enable more verbose output for debugging
+ // comment out if not needed
+ SimpleFOCDebug::enable(&Serial);
+
+ delay(200);
+
+ WiFi.begin(ssid, pass);
+
+ Serial.print("Connecting WiFi ");
+ Serial.println(ssid);
+ while (WiFi.status() != WL_CONNECTED) {
+ delay(500);
+ Serial.print(".");
+ }
+ Udp.begin(inPort);
+ Serial.println();
+ Serial.print("WiFi connected. Local OSC address: ");
+ Serial.print(WiFi.localIP());
+ Serial.print(":");
+ Serial.println(inPort);
+
+ setupOTA("smallrobot1");
+
+ Serial.println("Initializing motors.");
+
+ Wire.setClock(400000);
+
+ sensor1.init();
+ motor1.linkSensor(&sensor1);
+ driver1.voltage_power_supply = POWER_SUPPLY;
+ driver1.init();
+ motor1.linkDriver(&driver1);
+ motor1.foc_modulation = FOCModulationType::SpaceVectorPWM;
+ motor1.controller = MotionControlType::velocity;
+ motor1.PID_velocity.P = 0.2f;
+ motor1.PID_velocity.I = 20;
+ motor1.PID_velocity.D = 0.001f;
+ motor1.PID_velocity.output_ramp = 1000;
+ motor1.LPF_velocity.Tf = 0.01f;
+ motor1.voltage_limit = POWER_SUPPLY;
+ motor1.P_angle.P = 20;
+ motor1.init();
+ motor1.initFOC();
+
+ sensor2.init();
+ motor2.linkSensor(&sensor2);
+ driver2.voltage_power_supply = POWER_SUPPLY;
+ driver2.init();
+ motor2.linkDriver(&driver2);
+ motor2.foc_modulation = FOCModulationType::SpaceVectorPWM;
+ motor2.controller = MotionControlType::velocity;
+ motor2.PID_velocity.P = 0.2f;
+ motor2.PID_velocity.I = 20;
+ motor2.PID_velocity.D = 0.001f;
+ motor2.PID_velocity.output_ramp = 1000;
+ motor2.LPF_velocity.Tf = 0.01f;
+ motor2.voltage_limit = POWER_SUPPLY;
+ motor2.P_angle.P = 20;
+ motor2.init();
+ motor2.initFOC();
+
+ sendMotorParams(motor1, m1Prefix);
+ sendMotorParams(motor2, m2Prefix);
+ Serial.println("All initialization complete.");
+ _delay(1000);
+}
+
+
+
+
+template
+void sendMessage(String& addr, T datum) {
+ bundleOUT.add(addr.c_str()).add(datum);
+ Udp.beginPacket(outIp, outPort);
+ bundleOUT.send(Udp);
+ Udp.endPacket();
+ bundleOUT.empty(); // empty the bundle to free room for a new one
+}
+
+
+
+
+float getNumber(OSCMessage &msg, int index) {
+ if (msg.getType(index)=='i')
+ return msg.getInt(index);
+ if (msg.getType(index)=='f')
+ return msg.getFloat(index);
+ if (msg.getType(index)=='d')
+ return msg.getDouble(index);
+ return 0;
+}
+
+
+
+void motorCmd(OSCMessage &msg, int offset, BLDCMotor& motor, float* set_point, String& prefix){
+ Serial.print("Command for ");
+ Serial.println(prefix);
+ if (msg.fullMatch("/P", offset)) {
+ motor.PID_velocity.P = getNumber(msg,0);
+ sendMessage(prefix+"/P", motor.PID_velocity.P);
+ }
+ else if (msg.fullMatch("/I", offset)) {
+ motor.PID_velocity.I = getNumber(msg,0);
+ sendMessage(prefix+"/I", motor.PID_velocity.I);
+ }
+ else if (msg.fullMatch("/D", offset)) {
+ motor.PID_velocity.D = getNumber(msg,0);
+ sendMessage(prefix+"/D", motor.PID_velocity.D);
+ }
+ else if (msg.fullMatch("/R", offset)) {
+ motor.PID_velocity.output_ramp = getNumber(msg,0);
+ sendMessage(prefix+"/R", motor.PID_velocity.output_ramp);
+ }
+ else if (msg.fullMatch("/F", offset)) {
+ motor.LPF_velocity.Tf = getNumber(msg,0);
+ sendMessage(prefix+"/F", motor.LPF_velocity.Tf);
+ }
+ else if (msg.fullMatch("/K", offset)) {
+ motor.P_angle.P = getNumber(msg,0);
+ sendMessage(prefix+"/K", motor.P_angle.P);
+ }
+ else if (msg.fullMatch("/N", offset)) {
+ motor.velocity_limit = getNumber(msg,0);
+ sendMessage(prefix+"/N", motor.velocity_limit);
+ }
+ else if (msg.fullMatch("/L", offset)) {
+ motor.voltage_limit = getNumber(msg,0);
+ sendMessage(prefix+"/L", motor.voltage_limit);
+ }
+ else if (msg.fullMatch("/C", offset)) {
+ motor.controller = (MotionControlType)msg.getInt(0);
+ sendMessage(prefix+"/C", motor.controller);
+ }
+ else if (msg.fullMatch("/t", offset)) {
+ *set_point = getNumber(msg,0);
+ sendMessage(prefix+"/3", *set_point); // TODO is the set-point the same as motor.target?
+ Serial.print("Setting set-point to ");
+ Serial.println(*set_point);
+ }
+ else if (msg.fullMatch("/o", offset)) {
+ motor.disable();
+ }
+ else if (msg.fullMatch("/e", offset)) {
+ motor.enable();
+ }
+ else if (msg.fullMatch("/params", offset)) {
+ sendMotorParams(motor, prefix);
+ }
+ else if (msg.fullMatch("/reinit", offset)) {
+ motor.disable();
+ motor.init();
+ motor.initFOC();
+ }
+
+}
+
+
+
+
+
+
+void sendMotorMonitoring() {
+ //Serial.println("Sending monitoring...");
+ bundleOUT.add("/M1/0").add(motor1.voltage.q);
+ bundleOUT.add("/M1/1").add(motor1.shaft_velocity);
+ bundleOUT.add("/M1/2").add(motor1.shaft_angle);
+ bundleOUT.add("/M1/3").add(motor1.target);
+ bundleOUT.add("/M2/0").add(motor2.voltage.q);
+ bundleOUT.add("/M2/1").add(motor2.shaft_velocity);
+ bundleOUT.add("/M2/2").add(motor2.shaft_angle);
+ bundleOUT.add("/M2/3").add(motor2.target);
+ // TODO pack it into one message bundleOUT.add("/M2/i").add(motor2.voltage_q).add(motor2.shaft_velocity).add(motor2.shaft_angle).add(motor2.target);
+ Udp.beginPacket(outIp, outPort);
+ bundleOUT.send(Udp);
+ Udp.endPacket();
+ bundleOUT.empty(); // empty the bundle to free room for a new one
+}
+
+
+
+void sendMotorParams(BLDCMotor& motor, String& prefix) {
+ bundleOUT.add((prefix+"/P").c_str()).add(motor.PID_velocity.P);
+ bundleOUT.add((prefix+"/I").c_str()).add(motor.PID_velocity.I);
+ bundleOUT.add((prefix+"/D").c_str()).add(motor.PID_velocity.D);
+ bundleOUT.add((prefix+"/R").c_str()).add(motor.PID_velocity.output_ramp);
+ bundleOUT.add((prefix+"/F").c_str()).add(motor.LPF_velocity.Tf);
+ bundleOUT.add((prefix+"/K").c_str()).add(motor.P_angle.P);
+ bundleOUT.add((prefix+"/N").c_str()).add(motor.velocity_limit);
+ bundleOUT.add((prefix+"/L").c_str()).add(motor.voltage_limit);
+ bundleOUT.add((prefix+"/C").c_str()).add(motor.controller);
+ Udp.beginPacket(outIp, outPort);
+ bundleOUT.send(Udp);
+ Udp.endPacket();
+ bundleOUT.empty(); // empty the bundle to free room for a new one
+}
+
+
+
+
+
+long lastSend = 0;
+OSCMessage bundleIN;
+int size;
+
+
+void loop() {
+
+ // FOC algorithm function
+ motor1.loopFOC();
+ motor1.move(set_point1);
+ motor2.loopFOC();
+ motor2.move(set_point2);
+
+
+ int size = Udp.parsePacket();
+ if (size > 0) {
+ while (size--) {
+ bundleIN.fill(Udp.read());
+ }
+ if (!bundleIN.hasError()) {
+ bundleIN.route("/M1", [](OSCMessage& msg, int offset){ motorCmd(msg, offset, motor1, &set_point1, m1Prefix); }, 0);
+ bundleIN.route("/M2", [](OSCMessage& msg, int offset){ motorCmd(msg, offset, motor2, &set_point2, m2Prefix); }, 0);
+ IPAddress ip = Udp.remoteIP();
+ if (!( ip==outIp )) {
+ Serial.print("New connection from ");
+ Serial.println(ip);
+ outIp = ip;
+ sendMotorParams(motor1, m1Prefix);
+ sendMotorParams(motor2, m2Prefix);
+ }
+ }
+ else {
+ error = bundleIN.getError();
+ Serial.print("error: ");
+ Serial.println(error);
+ }
+ bundleIN.empty();
+ }
+ else { // don't receive and send in the same loop...
+ long now = millis();
+ if (now - lastSend > 100) {
+ sendMotorMonitoring();
+ lastSend = now;
+ }
+ }
+
+ ArduinoOTA.handle();
+}
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/osc_control_examples/osc_esp32_fullcontrol/osc_fullcontrol.pd b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/osc_control_examples/osc_esp32_fullcontrol/osc_fullcontrol.pd
new file mode 100644
index 0000000..ddbf2f9
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/osc_control_examples/osc_esp32_fullcontrol/osc_fullcontrol.pd
@@ -0,0 +1,384 @@
+#N struct text float x float y text t;
+#N canvas 1842 146 1519 1052 12;
+#X obj 501 697 cnv 15 193 209 empty empty Tuning\ M1 20 12 0 14 #e0e0e0
+#404040 0;
+#X obj 787 477 mrpeach/unpackOSC;
+#X obj 132 586 print oscin;
+#X obj 787 504 print oscout;
+#X obj 723 449 spigot;
+#X obj 774 452 tgl 15 1 empty empty Debug 17 7 0 10 #fcfcfc #000000
+#000000 1 1;
+#X msg 591 503 disconnect;
+#X obj 132 558 spigot;
+#X obj 114 562 tgl 15 1 empty empty Debug -34 6 0 10 #fcfcfc #000000
+#000000 0 1;
+#X obj 132 531 mrpeach/unpackOSC;
+#X obj 673 477 mrpeach/udpsend;
+#X obj 132 496 mrpeach/udpreceive 8000;
+#X obj 673 422 mrpeach/packOSC;
+#X obj 1043 150 hsl 249 25 -5000 5000 0 0 empty empty Set\ Point\ M1
+-2 -8 0 10 #fcfcfc #000000 #000000 0 1;
+#X obj 1044 197 hsl 247 25 -15 15 0 0 empty empty Set\ Point\ M2 -2
+-8 0 10 #fcfcfc #000000 #000000 12300 1;
+#X obj 120 153 bng 53 250 50 0 empty empty STOP 14 26 0 10 #fc1204
+#000000 #ffffff;
+#X obj 200 102 * 0.10472;
+#X obj 202 169 hsl 235 30 -520 520 0 0 empty empty Set\ point\ (Velocity)
+-2 -8 0 10 #fcfcfc #000000 #000000 11500 1;
+#X obj 673 449 spigot;
+#X obj 653 452 tgl 15 1 empty empty Enable\ send -71 6 0 10 #fcfcfc
+#000000 #000000 1 1;
+#X msg 484 478 connect 192.168.1.43 8000;
+#X obj 673 395 speedlim 100;
+#X obj 231 573 mrpeach/routeOSC /M1 /M2;
+#X obj 231 610 mrpeach/routeOSC /0 /1 /2 /3 /P /I /D /R /F /K /N /L
+/C;
+#X obj 326 844 hsl 101 29 0 6.3 0 0 empty empty rad -2 -8 0 10 #fcfcfc
+#000000 #000000 0 1;
+#X obj 326 812 % 6.28319;
+#X obj 326 704 nbx 7 27 -1e+37 1e+37 0 0 empty empty V -5 0 0 18 #fcfcfc
+#000000 #000000 0.137548 256 3;
+#X obj 113 804 nbx 7 27 -1e+37 1e+37 0 0 empty empty Set\ point 0 -15
+0 18 #fcfcfc #000000 #000000 0 256 3;
+#X obj 326 776 nbx 7 27 -1e+37 1e+37 0 0 empty empty Position -80 0
+0 18 #fcfcfc #000000 #000000 -348.637 256 3;
+#X obj 326 740 nbx 7 27 -1e+37 1e+37 0 0 empty empty Velocity -80 0
+0 18 #fcfcfc #000000 #000000 0.0649328 256 3;
+#X obj 538 747 nbx 5 14 -1e+37 1e+37 0 0 empty empty P\ gain 0 -8 0
+10 #fcfcfc #000000 #000000 0.2 256 3;
+#X obj 537 776 nbx 5 14 -1e+37 1e+37 0 0 empty empty I\ gain 0 -8 0
+10 #fcfcfc #000000 #000000 20 256 3;
+#X obj 538 808 nbx 5 14 -1e+37 1e+37 0 0 empty empty D\ gain 0 -8 0
+10 #fcfcfc #000000 #000000 0.0001 256 3;
+#X obj 539 838 nbx 5 14 -1e+37 1e+37 0 0 empty empty V\ Ramp 0 -8 0
+10 #fcfcfc #000000 #000000 1000 256 3;
+#X obj 539 868 nbx 5 14 -1e+37 1e+37 0 0 empty empty LP\ time 0 -8
+0 10 #fcfcfc #000000 #000000 0.01 256 3;
+#X obj 605 747 nbx 5 14 -1e+37 1e+37 0 0 empty empty angP\ gain 0 -8
+0 10 #fcfcfc #000000 #000000 20 256 3;
+#X obj 608 779 nbx 5 14 -1e+37 1e+37 0 0 empty empty angP\ lim 0 -8
+0 10 #fcfcfc #000000 #000000 20 256 3;
+#X obj 609 836 nbx 5 14 -1e+37 1e+37 0 0 empty empty V\ limit 0 -8
+0 10 #fcfcfc #000000 #000000 8 256 3;
+#X obj 122 278 hradio 53 0 1 3 motorselect empty empty 0 -8 0 10 #fcfcfc
+#000000 #000000 0;
+#X scalar text 172 305 \; \;;
+#X obj 122 372 select 0 1 2;
+#X msg 122 399 prefix /M?;
+#X msg 149 423 prefix /M1;
+#X msg 178 445 prefix /M2;
+#X obj 789 422 mrpeach/packOSC;
+#X obj 789 395 speedlim 100;
+#X msg 592 531 typetags \$1;
+#X obj 571 535 tgl 15 1 empty empty OSC\ type\ tags -80 7 0 10 #ffffff
+#000000 #000000 1 1;
+#X text 63 286 Choose Motor, f 7;
+#X text 137 339 All, f 4;
+#X text 191 339 M1, f 4;
+#X text 247 339 M2, f 4;
+#X text 152 77 RPM;
+#X obj 1008 148 bng 29 250 50 0 empty empty STOP 2 13 0 10 #fc1204
+#000000 #ffffff;
+#X obj 1009 195 bng 29 250 50 0 empty empty STOP 2 13 0 10 #fc1204
+#000000 #ffffff;
+#X obj 74 696 hradio 53 0 1 3 empty empty empty 0 -8 0 10 #fcfcfc #000000
+#000000 1;
+#X text 8 711 Control;
+#X text 67 752 Voltage;
+#X text 124 753 Velocity;
+#X text 189 754 Position;
+#X obj 312 101 /;
+#X obj 312 129 * 6.28319;
+#X text 424 75 cm, f 4;
+#X text 393 51 Wheel diameter;
+#X obj 394 100 * 0.0314159;
+#X msg 348 636 set \$1;
+#X msg 376 637 set \$1;
+#X msg 407 636 set \$1;
+#X msg 435 636 set \$1;
+#X msg 466 636 set \$1;
+#X msg 495 636 set \$1;
+#X msg 524 637 set \$1;
+#X msg 554 637 set \$1;
+#X msg 583 637 set \$1;
+#X obj 75 898 s osctargetedout;
+#X obj 75 866 prepend /M1/C;
+#X obj 773 304 r osctargetedout;
+#X obj 593 912 prepend /M1/K;
+#X obj 602 925 prepend /M1/N;
+#X obj 609 936 prepend /M1/L;
+#X obj 564 976 s osctargetedout;
+#X obj 1271 697 cnv 15 193 209 empty empty Tuning\ M2 20 12 0 14 #e0e0e0
+#404040 0;
+#X obj 1001 610 mrpeach/routeOSC /0 /1 /2 /3 /P /I /D /R /F /K /N /L
+/C;
+#X obj 1096 844 hsl 101 29 0 6.3 0 0 empty empty rad -2 -8 0 10 #fcfcfc
+#000000 #000000 0 1;
+#X obj 1096 812 % 6.28319;
+#X obj 1096 704 nbx 7 27 -1e+37 1e+37 0 0 empty empty V -5 0 0 18 #fcfcfc
+#000000 #000000 -0.13018 256 3;
+#X obj 883 804 nbx 7 27 -1e+37 1e+37 0 0 setpointin2 empty Set\ point
+0 -15 0 18 #fcfcfc #000000 #000000 0 256 3;
+#X obj 1096 776 nbx 7 27 -1e+37 1e+37 0 0 empty empty Position -80
+0 0 18 #fcfcfc #000000 #000000 -346.273 256 3;
+#X obj 1096 740 nbx 7 27 -1e+37 1e+37 0 0 empty empty Velocity -80
+0 0 18 #fcfcfc #000000 #000000 0.0657255 256 3;
+#X obj 1308 747 nbx 5 14 -1e+37 1e+37 0 0 empty empty P\ gain 0 -8
+0 10 #fcfcfc #000000 #000000 0.2 256 3;
+#X obj 1308 778 nbx 5 14 -1e+37 1e+37 0 0 empty empty I\ gain 0 -8
+0 10 #fcfcfc #000000 #000000 20 256 3;
+#X obj 1308 808 nbx 5 14 -1e+37 1e+37 0 0 empty empty D\ gain 0 -8
+0 10 #fcfcfc #000000 #000000 0.001 256 3;
+#X obj 1309 838 nbx 5 14 -1e+37 1e+37 0 0 empty empty V\ Ramp 0 -8
+0 10 #fcfcfc #000000 #000000 1000 256 3;
+#X obj 1309 868 nbx 5 14 -1e+37 1e+37 0 0 empty empty LP\ time 0 -8
+0 10 #fcfcfc #000000 #000000 0.01 256 3;
+#X obj 1375 747 nbx 5 14 -1e+37 1e+37 0 0 empty empty angP\ gain 0
+-8 0 10 #fcfcfc #000000 #000000 20 256 3;
+#X obj 1378 779 nbx 5 14 -1e+37 1e+37 0 0 empty empty angP\ lim 0 -8
+0 10 #fcfcfc #000000 #000000 20 256 3;
+#X obj 1379 836 nbx 5 14 -1e+37 1e+37 0 0 empty empty V\ limit 0 -8
+0 10 #fcfcfc #000000 #000000 8 256 3;
+#X obj 844 696 hradio 53 0 1 3 empty empty empty 0 -8 0 10 #fcfcfc
+#000000 #000000 1;
+#X text 778 711 Control;
+#X text 837 752 Voltage;
+#X text 894 753 Velocity;
+#X text 959 754 Position;
+#X msg 1118 636 set \$1;
+#X msg 1146 637 set \$1;
+#X msg 1177 636 set \$1;
+#X msg 1205 636 set \$1;
+#X msg 1236 636 set \$1;
+#X msg 1265 636 set \$1;
+#X msg 1294 637 set \$1;
+#X msg 1324 637 set \$1;
+#X msg 1353 637 set \$1;
+#X obj 845 898 s osctargetedout;
+#X obj 1325 976 s osctargetedout;
+#X obj 1379 936 prepend /M2/L;
+#X obj 1372 925 prepend /M2/N;
+#X obj 1364 912 prepend /M2/K;
+#X obj 1296 947 prepend /M2/F;
+#X obj 1291 940 prepend /M2/R;
+#X obj 1287 933 prepend /M2/D;
+#X obj 1281 925 prepend /M2/I;
+#X obj 1276 917 prepend /M2/P;
+#X obj 526 947 prepend /M1/F;
+#X obj 521 940 prepend /M1/R;
+#X obj 517 933 prepend /M1/D;
+#X obj 511 925 prepend /M1/I;
+#X obj 506 917 prepend /M1/P;
+#X obj 393 78 nbx 2 14 0 50 0 1 empty empty empty 0 -8 0 10 #fcfcfc
+#000000 #000000 6 256 2;
+#X obj 299 71 nbx 5 24 -20 20 0 0 empty empty empty 0 -8 0 10 #fcfcfc
+#000000 #000000 -0.266666 256 2;
+#X obj 179 74 nbx 7 23 -5000 5000 0 0 empty empty empty 0 -8 0 10 #fcfcfc
+#000000 #000000 -84.8824 256 2;
+#X obj 577 169 hsl 104 30 -3.1415 3.1415 0 0 empty empty Set\ point\ (Position)
+-2 -8 0 10 #fcfcfc #000000 #000000 10300 1;
+#X obj 708 68 vsl 31 122 0 12 0 0 empty empty Set\ point\ (Voltage)
+0 -9 0 10 #fcfcfc #000000 #000000 0 1;
+#X obj 246 13 / 0.10472;
+#X msg 318 13 set \$1;
+#X obj 457 11 *;
+#X obj 384 11 / 6.28319;
+#X obj 547 96 /;
+#X obj 547 125 * 6.28319;
+#X obj 547 66 nbx 5 24 -100 100 0 0 empty empty empty 0 -8 0 10 #fcfcfc
+#000000 #000000 0.0599999 256 2;
+#X text 534 68 m;
+#X obj 20 6 r setpointin;
+#X obj 17 36 r setpointin2;
+#X obj 120 6 spigot;
+#X obj 120 42 spigot;
+#X obj 16 63 r motorselect;
+#X obj 1339 99 r setpointin;
+#X obj 1345 150 r setpointin2;
+#X msg 493 11 set \$1;
+#X obj 22 103 > 1;
+#X obj 59 103 <= 1;
+#X msg 1110 529 /M?/params;
+#X obj 1110 502 loadbang;
+#X msg 1339 126 set \$1;
+#X msg 1343 174 set \$1;
+#X obj 639 9 *;
+#X obj 566 9 / 6.28319;
+#X msg 675 9 set \$1;
+#X obj 483 448 loadbang;
+#X text 284 74 m/s;
+#X obj 845 866 prepend /M2/C;
+#X msg 163 226 sendtyped /M?/t f 0;
+#X obj 458 224 prepend sendtyped /t f;
+#X msg 991 301 sendtyped /M2/t f 0;
+#X msg 983 274 sendtyped /M1/t f 0;
+#X obj 1051 286 prepend sendtyped /M1/t f;
+#X obj 1047 322 prepend sendtyped /M2/t f;
+#X obj 475 171 nbx 7 21 -1e+37 1e+37 0 0 empty empty rad 0 -8 0 10
+#fcfcfc #000000 #000000 2 256 2;
+#X connect 1 0 3 0;
+#X connect 4 0 1 0;
+#X connect 5 0 4 1;
+#X connect 6 0 10 0;
+#X connect 7 0 2 0;
+#X connect 8 0 7 1;
+#X connect 9 0 7 0;
+#X connect 9 0 22 0;
+#X connect 11 0 9 0;
+#X connect 12 0 18 0;
+#X connect 12 0 4 0;
+#X connect 13 0 163 0;
+#X connect 14 0 164 0;
+#X connect 15 0 159 0;
+#X connect 16 0 17 0;
+#X connect 17 0 131 0;
+#X connect 17 0 134 0;
+#X connect 17 0 160 0;
+#X connect 18 0 10 0;
+#X connect 19 0 18 1;
+#X connect 20 0 10 0;
+#X connect 21 0 12 0;
+#X connect 22 0 23 0;
+#X connect 22 1 82 0;
+#X connect 23 0 26 0;
+#X connect 23 1 29 0;
+#X connect 23 2 28 0;
+#X connect 23 3 27 0;
+#X connect 23 4 65 0;
+#X connect 23 5 66 0;
+#X connect 23 6 67 0;
+#X connect 23 7 68 0;
+#X connect 23 8 69 0;
+#X connect 23 9 70 0;
+#X connect 23 10 71 0;
+#X connect 23 11 72 0;
+#X connect 23 12 73 0;
+#X connect 25 0 24 0;
+#X connect 28 0 25 0;
+#X connect 30 0 125 0;
+#X connect 31 0 124 0;
+#X connect 32 0 123 0;
+#X connect 33 0 122 0;
+#X connect 34 0 121 0;
+#X connect 35 0 77 0;
+#X connect 36 0 78 0;
+#X connect 37 0 79 0;
+#X connect 38 0 40 0;
+#X connect 40 0 41 0;
+#X connect 40 1 42 0;
+#X connect 40 2 43 0;
+#X connect 41 0 12 0;
+#X connect 42 0 12 0;
+#X connect 43 0 12 0;
+#X connect 44 0 18 0;
+#X connect 44 0 4 0;
+#X connect 45 0 44 0;
+#X connect 46 0 12 0;
+#X connect 47 0 46 0;
+#X connect 53 0 162 0;
+#X connect 54 0 161 0;
+#X connect 55 0 75 0;
+#X connect 60 0 61 0;
+#X connect 61 0 17 0;
+#X connect 64 0 60 1;
+#X connect 64 0 133 1;
+#X connect 64 0 135 1;
+#X connect 64 0 153 1;
+#X connect 65 0 30 0;
+#X connect 66 0 31 0;
+#X connect 67 0 32 0;
+#X connect 68 0 33 0;
+#X connect 69 0 34 0;
+#X connect 70 0 35 0;
+#X connect 71 0 36 0;
+#X connect 72 0 37 0;
+#X connect 73 0 55 0;
+#X connect 75 0 74 0;
+#X connect 76 0 45 0;
+#X connect 77 0 80 0;
+#X connect 78 0 80 0;
+#X connect 79 0 80 0;
+#X connect 82 0 85 0;
+#X connect 82 1 88 0;
+#X connect 82 2 87 0;
+#X connect 82 3 86 0;
+#X connect 82 4 102 0;
+#X connect 82 5 103 0;
+#X connect 82 6 104 0;
+#X connect 82 7 105 0;
+#X connect 82 8 106 0;
+#X connect 82 9 107 0;
+#X connect 82 10 108 0;
+#X connect 82 11 109 0;
+#X connect 82 12 110 0;
+#X connect 84 0 83 0;
+#X connect 87 0 84 0;
+#X connect 89 0 120 0;
+#X connect 90 0 119 0;
+#X connect 91 0 118 0;
+#X connect 92 0 117 0;
+#X connect 93 0 116 0;
+#X connect 94 0 115 0;
+#X connect 95 0 114 0;
+#X connect 96 0 113 0;
+#X connect 97 0 158 0;
+#X connect 102 0 89 0;
+#X connect 103 0 90 0;
+#X connect 104 0 91 0;
+#X connect 105 0 92 0;
+#X connect 106 0 93 0;
+#X connect 107 0 94 0;
+#X connect 108 0 95 0;
+#X connect 109 0 96 0;
+#X connect 110 0 97 0;
+#X connect 113 0 112 0;
+#X connect 114 0 112 0;
+#X connect 115 0 112 0;
+#X connect 116 0 112 0;
+#X connect 117 0 112 0;
+#X connect 118 0 112 0;
+#X connect 119 0 112 0;
+#X connect 120 0 112 0;
+#X connect 121 0 80 0;
+#X connect 122 0 80 0;
+#X connect 123 0 80 0;
+#X connect 124 0 80 0;
+#X connect 125 0 80 0;
+#X connect 126 0 64 0;
+#X connect 127 0 60 0;
+#X connect 128 0 16 0;
+#X connect 129 0 165 0;
+#X connect 130 0 160 0;
+#X connect 131 0 132 0;
+#X connect 132 0 128 0;
+#X connect 133 0 146 0;
+#X connect 134 0 133 0;
+#X connect 135 0 136 0;
+#X connect 136 0 165 0;
+#X connect 137 0 135 0;
+#X connect 139 0 141 0;
+#X connect 140 0 142 0;
+#X connect 143 0 147 0;
+#X connect 143 0 148 0;
+#X connect 144 0 151 0;
+#X connect 145 0 152 0;
+#X connect 146 0 127 0;
+#X connect 147 0 142 1;
+#X connect 148 0 141 1;
+#X connect 149 0 44 0;
+#X connect 150 0 149 0;
+#X connect 151 0 13 0;
+#X connect 152 0 14 0;
+#X connect 153 0 155 0;
+#X connect 154 0 153 0;
+#X connect 155 0 137 0;
+#X connect 156 0 20 0;
+#X connect 158 0 111 0;
+#X connect 159 0 44 0;
+#X connect 160 0 21 0;
+#X connect 161 0 44 0;
+#X connect 162 0 44 0;
+#X connect 163 0 45 0;
+#X connect 164 0 45 0;
+#X connect 165 0 160 0;
+#X connect 165 0 154 0;
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/osc_control_examples/osc_esp32_fullcontrol/ssid.h_rename_me b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/osc_control_examples/osc_esp32_fullcontrol/ssid.h_rename_me
new file mode 100644
index 0000000..9d3b03c
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/osc_control_examples/osc_esp32_fullcontrol/ssid.h_rename_me
@@ -0,0 +1,4 @@
+
+#define MYSSID "yourssid"
+#define MYPASS "yourpassword"
+
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/utils/calibration/alignment_and_cogging_test/alignment_and_cogging_test.ino b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/utils/calibration/alignment_and_cogging_test/alignment_and_cogging_test.ino
new file mode 100644
index 0000000..9c523c2
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/utils/calibration/alignment_and_cogging_test/alignment_and_cogging_test.ino
@@ -0,0 +1,128 @@
+#include
+#include
+
+BLDCMotor motor = BLDCMotor(11);
+BLDCDriver3PWM driver = BLDCDriver3PWM(9, 10, 11, 8);
+//StepperMotor motor = StepperMotor(50);
+//StepperDriver4PWM driver = StepperDriver4PWM(9, 5, 10, 6, 8);
+MagneticSensorI2C sensor = MagneticSensorI2C(0x36, 12, 0X0C, 4);
+
+
+/**
+ * This measures how closely sensor and electrical angle agree and how much your motor is affected by 'cogging'.
+ * It can be used to investigate how much non linearity there is between what we set (electrical angle) and what we read (sensor angle)
+ * This non linearity could be down to magnet placement, coil winding differences or simply that the magnetic field when travelling through a pole pair is not linear
+ * An alignment error of ~10 degrees and cogging of ~4 degrees is normal for small gimbal.
+ * The following article is an interesting read
+ * https://hackaday.com/2016/02/23/anti-cogging-algorithm-brings-out-the-best-in-your-hobby-brushless-motors/
+ */
+void testAlignmentAndCogging(int direction) {
+
+ motor.move(0);
+ _delay(200);
+
+ sensor.update();
+ float initialAngle = sensor.getAngle();
+
+ const int shaft_rotation = 720; // 720 deg test - useful to see repeating cog pattern
+ int sample_count = int(shaft_rotation * motor.pole_pairs); // test every electrical degree
+
+ float stDevSum = 0;
+
+ float mean = 0.0f;
+ float prev_mean = 0.0f;
+
+
+ for (int i = 0; i < sample_count; i++) {
+
+ float shaftAngle = (float) direction * i * shaft_rotation / sample_count;
+ float electricAngle = (float) shaftAngle * motor.pole_pairs;
+ // move and wait
+ motor.move(shaftAngle * PI / 180);
+ _delay(5);
+
+ // measure
+ sensor.update();
+ float sensorAngle = (sensor.getAngle() - initialAngle) * 180 / PI;
+ float sensorElectricAngle = sensorAngle * motor.pole_pairs;
+ float electricAngleError = electricAngle - sensorElectricAngle;
+
+ // plot this - especially electricAngleError
+ Serial.print(electricAngle);
+ Serial.print("\t");
+ Serial.print(sensorElectricAngle );
+ Serial.print("\t");
+ Serial.println(electricAngleError);
+
+ // use knuth standard deviation algorithm so that we don't need an array too big for an Uno
+ prev_mean = mean;
+ mean = mean + (electricAngleError-mean)/(i+1);
+ stDevSum = stDevSum + (electricAngleError-mean)*(electricAngleError-prev_mean);
+
+ }
+
+ Serial.println();
+ Serial.println(F("ALIGNMENT AND COGGING REPORT"));
+ Serial.println();
+ Serial.print(F("Direction: "));
+ Serial.println(direction);
+ Serial.print(F("Mean error (alignment): "));
+ Serial.print(mean);
+ Serial.println(" deg (electrical)");
+ Serial.print(F("Standard Deviation (cogging): "));
+ Serial.print(sqrt(stDevSum/sample_count));
+ Serial.println(F(" deg (electrical)"));
+ Serial.println();
+ Serial.println(F("Plotting 3rd column of data (electricAngleError) will likely show sinusoidal cogging pattern with a frequency of 4xpole_pairs per rotation"));
+ Serial.println();
+
+}
+
+void setup() {
+
+ // use monitoring with serial
+ Serial.begin(115200);
+ // enable more verbose output for debugging
+ // comment out if not needed
+ SimpleFOCDebug::enable(&Serial);
+
+ // driver config
+ driver.voltage_power_supply = 12;
+ driver.init();
+ motor.linkDriver(&driver);
+
+ motor.voltage_sensor_align = 3;
+ motor.foc_modulation = FOCModulationType::SpaceVectorPWM;
+
+ motor.controller = MotionControlType::angle_openloop;
+ motor.voltage_limit=motor.voltage_sensor_align;
+
+ sensor.init();
+ motor.linkSensor(&sensor);
+
+ motor.useMonitoring(Serial);
+ motor.init();
+ motor.initFOC();
+
+ testAlignmentAndCogging(1);
+
+ motor.move(0);
+ Serial.println(F("Press any key to test in CCW direction"));
+ while (!Serial.available()) { }
+
+ testAlignmentAndCogging(-1);
+
+ Serial.println(F("Complete"));
+
+ motor.voltage_limit = 0;
+ motor.move(0);
+ while (true) ; //do nothing;
+
+}
+
+
+
+
+void loop() {
+
+}
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/utils/calibration/find_kv_rating/encoder/find_kv_rating/find_kv_rating.ino b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/utils/calibration/find_kv_rating/encoder/find_kv_rating/find_kv_rating.ino
new file mode 100644
index 0000000..c39657b
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/utils/calibration/find_kv_rating/encoder/find_kv_rating/find_kv_rating.ino
@@ -0,0 +1,106 @@
+/**
+ *
+ * Find KV rating for motor with encoder
+ *
+ * Motor KV rating is defiend as the increase of the motor velocity expressed in rotations per minute [rpm] per each 1 Volt int voltage control mode.
+ *
+ * This example will set your motor in the torque control mode using voltage and set 1 volt to the motor. By reading the velocity it will calculat the motors KV rating.
+ * - To make this esimation more credible you can try increasing the target voltage (or decrease in some cases)
+ * - The KV rating should be realatively static number - it should not change considerably with the increase in the voltage
+ *
+ */
+#include
+
+
+// BLDC motor & driver instance
+BLDCMotor motor = BLDCMotor(11);
+BLDCDriver3PWM driver = BLDCDriver3PWM(9, 5, 6, 8);
+// Stepper motor & driver instance
+//StepperMotor motor = StepperMotor(50);
+//StepperDriver4PWM driver = StepperDriver4PWM(9, 5, 10, 6, 8);
+
+// encoder instance
+Encoder sensor = Encoder(2, 3, 8192);
+
+// Interrupt routine intialisation
+// channel A and B callbacks
+void doA(){sensor.handleA();}
+void doB(){sensor.handleB();}
+
+
+// voltage set point variable
+float target_voltage = 1;
+
+// instantiate the commander
+Commander command = Commander(Serial);
+void doTarget(char* cmd) { command.scalar(&target_voltage, cmd); }
+void calcKV(char* cmd) {
+ // calculate the KV
+ Serial.println(motor.shaft_velocity/motor.target/_SQRT3*30.0f/_PI);
+
+}
+
+void setup() {
+
+ // use monitoring with serial
+ Serial.begin(115200);
+ // enable more verbose output for debugging
+ // comment out if not needed
+ SimpleFOCDebug::enable(&Serial);
+
+ // initialize encoder sensor hardware
+ sensor.init();
+ sensor.enableInterrupts(doA, doB);
+ // link the motor to the sensor
+ motor.linkSensor(&sensor);
+
+ // driver config
+ // IMPORTANT!
+ // make sure to set the correct power supply voltage [V]
+ driver.voltage_power_supply = 12;
+ driver.init();
+ // link driver
+ motor.linkDriver(&driver);
+
+ // aligning voltage
+ motor.voltage_sensor_align = 3;
+
+ // set motion control loop to be used
+ motor.controller = MotionControlType::torque;
+
+ // comment out if not needed
+ motor.useMonitoring(Serial);
+
+ // initialize motor
+ motor.init();
+ // align sensor and start FOC
+ motor.initFOC();
+
+ // add target command T
+ command.add('T', doTarget, "target voltage");
+ command.add('K', calcKV, "calculate KV rating");
+
+ Serial.println(F("Motor ready."));
+ Serial.println(F("Set the target voltage : - commnad T"));
+ Serial.println(F("Calculate the motor KV : - command K"));
+ _delay(1000);
+}
+
+
+void loop() {
+
+ // main FOC algorithm function
+ // the faster you run this function the better
+ // Arduino UNO loop ~1kHz
+ // Bluepill loop ~10kHz
+ motor.loopFOC();
+
+ // Motion control function
+ // velocity, position or voltage (defined in motor.controller)
+ // this function can be run at much lower frequency than loopFOC() function
+ // You can also use motor.move() and set the motor.target in the code
+ motor.move(target_voltage);
+
+ // user communication
+ command.run();
+}
\ No newline at end of file
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/utils/calibration/find_kv_rating/hall_sensor/find_kv_rating/find_kv_rating.ino b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/utils/calibration/find_kv_rating/hall_sensor/find_kv_rating/find_kv_rating.ino
new file mode 100644
index 0000000..4eadd37
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/utils/calibration/find_kv_rating/hall_sensor/find_kv_rating/find_kv_rating.ino
@@ -0,0 +1,103 @@
+/**
+ *
+ * Find KV rating for motor with Hall sensors
+ *
+ * Motor KV rating is defiend as the increase of the motor velocity expressed in rotations per minute [rpm] per each 1 Volt int voltage control mode.
+ *
+ * This example will set your motor in the torque control mode using voltage and set 1 volt to the motor. By reading the velocity it will calculat the motors KV rating.
+ * - To make this esimation more credible you can try increasing the target voltage (or decrease in some cases)
+ * - The KV rating should be realatively static number - it should not change considerably with the increase in the voltage
+ */
+#include
+
+
+// BLDC motor & driver instance
+BLDCMotor motor = BLDCMotor(11);
+BLDCDriver3PWM driver = BLDCDriver3PWM(9, 5, 6, 8);
+
+// hall sensor instance
+HallSensor sensor = HallSensor(2, 3, 4, 11);
+
+// Interrupt routine intialisation
+// channel A and B callbacks
+void doA(){sensor.handleA();}
+void doB(){sensor.handleB();}
+void doC(){sensor.handleC();}
+
+
+// voltage set point variable
+float target_voltage = 1;
+
+// instantiate the commander
+Commander command = Commander(Serial);
+void doTarget(char* cmd) { command.scalar(&target_voltage, cmd); }
+void calcKV(char* cmd) {
+ // calculate the KV
+ Serial.println(motor.shaft_velocity/motor.target/_SQRT3*30.0f/_PI);
+
+}
+
+void setup() {
+
+ // use monitoring with serial
+ Serial.begin(115200);
+ // enable more verbose output for debugging
+ // comment out if not needed
+ SimpleFOCDebug::enable(&Serial);
+
+ // initialize encoder sensor hardware
+ sensor.init();
+ sensor.enableInterrupts(doA, doB, doC);
+ // link the motor to the sensor
+ motor.linkSensor(&sensor);
+
+ // driver config
+ // IMPORTANT!
+ // make sure to set the correct power supply voltage [V]
+ driver.voltage_power_supply = 12;
+ driver.init();
+ // link driver
+ motor.linkDriver(&driver);
+
+ // aligning voltage
+ motor.voltage_sensor_align = 3;
+
+ // set motion control loop to be used
+ motor.controller = MotionControlType::torque;
+
+ // comment out if not needed
+ motor.useMonitoring(Serial);
+
+ // initialize motor
+ motor.init();
+ // align sensor and start FOC
+ motor.initFOC();
+
+ // add target command T
+ command.add('T', doTarget, "target voltage");
+ command.add('K', calcKV, "calculate KV rating");
+
+ Serial.println(F("Motor ready."));
+ Serial.println(F("Set the target voltage : - commnad T"));
+ Serial.println(F("Calculate the motor KV : - command K"));
+ _delay(1000);
+}
+
+
+void loop() {
+
+ // main FOC algorithm function
+ // the faster you run this function the better
+ // Arduino UNO loop ~1kHz
+ // Bluepill loop ~10kHz
+ motor.loopFOC();
+
+ // Motion control function
+ // velocity, position or voltage (defined in motor.controller)
+ // this function can be run at much lower frequency than loopFOC() function
+ // You can also use motor.move() and set the motor.target in the code
+ motor.move(target_voltage);
+
+ // user communication
+ command.run();
+}
\ No newline at end of file
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/utils/calibration/find_kv_rating/magnetic_sensor/find_kv_rating/find_kv_rating.ino b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/utils/calibration/find_kv_rating/magnetic_sensor/find_kv_rating/find_kv_rating.ino
new file mode 100644
index 0000000..1df631a
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/utils/calibration/find_kv_rating/magnetic_sensor/find_kv_rating/find_kv_rating.ino
@@ -0,0 +1,100 @@
+/**
+ * Find KV rating for motor with magnetic sensors
+ *
+ * Motor KV rating is defiend as the increase of the motor velocity expressed in rotations per minute [rpm] per each 1 Volt int voltage control mode.
+ *
+ * This example will set your motor in the torque control mode using voltage and set 1 volt to the motor. By reading the velocity it will calculat the motors KV rating.
+ * - To make this esimation more credible you can try increasing the target voltage (or decrease in some cases)
+ * - The KV rating should be realatively static number - it should not change considerably with the increase in the voltage
+ */
+#include
+
+// magnetic sensor instance - SPI
+MagneticSensorSPI sensor = MagneticSensorSPI(AS5147_SPI, 10);
+// magnetic sensor instance - I2C
+// MagneticSensorI2C sensor = MagneticSensorI2C(AS5600_I2C);
+// magnetic sensor instance - analog output
+// MagneticSensorAnalog sensor = MagneticSensorAnalog(A1, 14, 1020);
+
+// BLDC motor & driver instance
+BLDCMotor motor = BLDCMotor(11);
+BLDCDriver3PWM driver = BLDCDriver3PWM(9, 5, 6, 8);
+// Stepper motor & driver instance
+//StepperMotor motor = StepperMotor(50);
+//StepperDriver4PWM driver = StepperDriver4PWM(9, 5, 10, 6, 8);
+
+// voltage set point variable
+float target_voltage = 1;
+
+// instantiate the commander
+Commander command = Commander(Serial);
+void doTarget(char* cmd) { command.scalar(&target_voltage, cmd); }
+void calcKV(char* cmd) {
+ // calculate the KV
+ Serial.println(motor.shaft_velocity/motor.target/_SQRT3*30.0f/_PI);
+
+}
+
+void setup() {
+
+ // use monitoring with serial
+ Serial.begin(115200);
+ // enable more verbose output for debugging
+ // comment out if not needed
+ SimpleFOCDebug::enable(&Serial);
+
+ // initialize encoder sensor hardware
+ sensor.init();
+ // link the motor to the sensor
+ motor.linkSensor(&sensor);
+
+ // driver config
+ // IMPORTANT!
+ // make sure to set the correct power supply voltage [V]
+ driver.voltage_power_supply = 12;
+ driver.init();
+ // link driver
+ motor.linkDriver(&driver);
+
+ // aligning voltage
+ motor.voltage_sensor_align = 3;
+
+ // set motion control loop to be used
+ motor.controller = MotionControlType::torque;
+
+ // comment out if not needed
+ motor.useMonitoring(Serial);
+
+ // initialize motor
+ motor.init();
+ // align sensor and start FOC
+ motor.initFOC();
+
+ // add target command T
+ command.add('T', doTarget, "target voltage");
+ command.add('K', calcKV, "calculate KV rating");
+
+ Serial.println(F("Motor ready."));
+ Serial.println(F("Set the target voltage : - commnad T"));
+ Serial.println(F("Calculate the motor KV : - command K"));
+ _delay(1000);
+}
+
+
+void loop() {
+
+ // main FOC algorithm function
+ // the faster you run this function the better
+ // Arduino UNO loop ~1kHz
+ // Bluepill loop ~10kHz
+ motor.loopFOC();
+
+ // Motion control function
+ // velocity, position or voltage (defined in motor.controller)
+ // this function can be run at much lower frequency than loopFOC() function
+ // You can also use motor.move() and set the motor.target in the code
+ motor.move(target_voltage);
+
+ // user communication
+ command.run();
+}
\ No newline at end of file
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/utils/calibration/find_pole_pair_number/encoder/find_pole_pairs_number/find_pole_pairs_number.ino b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/utils/calibration/find_pole_pair_number/encoder/find_pole_pairs_number/find_pole_pairs_number.ino
new file mode 100644
index 0000000..ad8e69c
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/utils/calibration/find_pole_pair_number/encoder/find_pole_pairs_number/find_pole_pairs_number.ino
@@ -0,0 +1,177 @@
+/**
+ * Utility arduino sketch which finds pole pair number of the motor
+ *
+ * To run it just set the correct pin numbers for the BLDC driver and encoder A and B channel as well as the encoder PPR value.
+ *
+ * The program will rotate your motor a specific amount and check how much it moved, and by doing a simple calculation calculate your pole pair number.
+ * The pole pair number will be outputted to the serial terminal.
+ *
+ * If the pole pair number is well estimated your motor will start to spin in voltage mode with 2V target.
+ *
+ * If the code calculates negative pole pair number please invert your encoder A and B channel pins or motor connector.
+ *
+ * Try running this code several times to avoid statistical errors.
+ * > But in general if your motor spins, you have a good pole pairs number.
+ */
+#include
+
+// BLDC motor instance
+// its important to put pole pairs number as 1!!!
+BLDCMotor motor = BLDCMotor(1);
+BLDCDriver3PWM driver = BLDCDriver3PWM(9, 5, 6, 8);
+// Stepper motor instance
+// its important to put pole pairs number as 1!!!
+//StepperMotor motor = StepperMotor(1);
+//StepperDriver4PWM driver = StepperDriver4PWM(9, 5, 10, 6, 8);
+
+// Encoder(int encA, int encB , int cpr, int index)
+Encoder encoder = Encoder(2, 3, 2048);
+// interrupt routine intialisation
+void doA(){encoder.handleA();}
+void doB(){encoder.handleB();}
+
+void setup() {
+
+ // use monitoring with serial
+ Serial.begin(115200);
+ // enable more verbose output for debugging
+ // comment out if not needed
+ SimpleFOCDebug::enable(&Serial);
+
+ // initialise encoder hardware
+ encoder.init();
+ // hardware interrupt enable
+ encoder.enableInterrupts(doA, doB);
+ // link the motor to the sensor
+ motor.linkSensor(&encoder);
+
+ // power supply voltage
+ // default 12V
+ driver.voltage_power_supply = 12;
+ driver.init();
+ motor.linkDriver(&driver);
+
+
+ // initialize motor
+ motor.init();
+
+ // pole pairs calculation routine
+ Serial.println("Pole pairs (PP) estimator");
+ Serial.println("-\n");
+
+ float pp_search_voltage = 4; // maximum power_supply_voltage/2
+ float pp_search_angle = 6*_PI; // search electrical angle to turn
+
+ // move motor to the electrical angle 0
+ motor.controller = MotionControlType::angle_openloop;
+ motor.voltage_limit=pp_search_voltage;
+ motor.move(0);
+ _delay(1000);
+ // read the encoder angle
+ encoder.update();
+ float angle_begin = encoder.getAngle();
+ _delay(50);
+
+ // move the motor slowly to the electrical angle pp_search_angle
+ float motor_angle = 0;
+ while(motor_angle <= pp_search_angle){
+ motor_angle += 0.01f;
+ motor.move(motor_angle);
+ _delay(1);
+ }
+ _delay(1000);
+ // read the encoder value for 180
+ encoder.update();
+ float angle_end = encoder.getAngle();
+ _delay(50);
+ // turn off the motor
+ motor.move(0);
+ _delay(1000);
+
+ // calculate the pole pair number
+ int pp = round((pp_search_angle)/(angle_end-angle_begin));
+
+ Serial.print(F("Estimated PP : "));
+ Serial.println(pp);
+ Serial.println(F("PP = Electrical angle / Encoder angle "));
+ Serial.print(pp_search_angle*180/_PI);
+ Serial.print("/");
+ Serial.print((angle_end-angle_begin)*180/_PI);
+ Serial.print(" = ");
+ Serial.println((pp_search_angle)/(angle_end-angle_begin));
+ Serial.println();
+
+
+ // a bit of monitoring the result
+ if(pp <= 0 ){
+ Serial.println(F("PP number cannot be negative"));
+ Serial.println(F(" - Try changing the search_voltage value or motor/encoder configuration."));
+ return;
+ }else if(pp > 30){
+ Serial.println(F("PP number very high, possible error."));
+ }else{
+ Serial.println(F("If PP is estimated well your motor should turn now!"));
+ Serial.println(F(" - If it is not moving try to relaunch the program!"));
+ Serial.println(F(" - You can also try to adjust the target voltage using serial terminal!"));
+ }
+
+
+ // set FOC loop to be used
+ motor.controller = MotionControlType::torque;
+ // set the pole pair number to the motor
+ motor.pole_pairs = pp;
+ //align encoder and start FOC
+ motor.initFOC();
+ _delay(1000);
+
+ Serial.println(F("\n Motor ready."));
+ Serial.println(F("Set the target voltage using serial terminal:"));
+}
+
+// uq voltage
+float target_voltage = 2;
+
+void loop() {
+
+ // main FOC algorithm function
+ // the faster you run this function the better
+ // Arduino UNO loop ~1kHz
+ // Bluepill loop ~10kHz
+ motor.loopFOC();
+
+ // Motion control function
+ // velocity, position or voltage (defined in motor.controller)
+ // this function can be run at much lower frequency than loopFOC() function
+ // You can also use motor.move() and set the motor.target in the code
+ motor.move(target_voltage);
+
+ // communicate with the user
+ serialReceiveUserCommand();
+}
+
+
+// utility function enabling serial communication with the user to set the target values
+// this function can be implemented in serialEvent function as well
+void serialReceiveUserCommand() {
+
+ // a string to hold incoming data
+ static String received_chars;
+
+ while (Serial.available()) {
+ // get the new byte:
+ char inChar = (char)Serial.read();
+ // add it to the string buffer:
+ received_chars += inChar;
+ // end of user input
+ if (inChar == '\n') {
+
+ // change the motor target
+ target_voltage = received_chars.toFloat();
+ Serial.print("Target voltage: ");
+ Serial.println(target_voltage);
+
+ // reset the command buffer
+ received_chars = "";
+ }
+ }
+}
\ No newline at end of file
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/utils/calibration/find_pole_pair_number/magnetic_sensor/find_pole_pairs_number/find_pole_pairs_number.ino b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/utils/calibration/find_pole_pair_number/magnetic_sensor/find_pole_pairs_number/find_pole_pairs_number.ino
new file mode 100644
index 0000000..b44bc0b
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/utils/calibration/find_pole_pair_number/magnetic_sensor/find_pole_pairs_number/find_pole_pairs_number.ino
@@ -0,0 +1,176 @@
+/**
+ * Utility arduino sketch which finds pole pair number of the motor
+ *
+ * To run it just set the correct pin numbers for the BLDC driver and sensor CPR value and chip select pin.
+ *
+ * The program will rotate your motor a specific amount and check how much it moved, and by doing a simple calculation calculate your pole pair number.
+ * The pole pair number will be outputted to the serial terminal.
+ *
+ * If the pole pair number is well estimated your motor will start to spin in voltage mode with 2V target.
+ *
+ * If the code calculates negative pole pair number please invert your motor connector.
+ *
+ * Try running this code several times to avoid statistical errors.
+ * > But in general if your motor spins, you have a good pole pairs number.
+ */
+#include
+
+// BLDC motor instance
+// its important to put pole pairs number as 1!!!
+BLDCMotor motor = BLDCMotor(1);
+BLDCDriver3PWM driver = BLDCDriver3PWM(9, 5, 6, 8);
+// Stepper motor instance
+// its important to put pole pairs number as 1!!!
+//StepperMotor motor = StepperMotor(1);
+//StepperDriver4PWM driver = StepperDriver4PWM(9, 5, 10, 6, 8);
+
+// magnetic sensor instance - SPI
+MagneticSensorSPI sensor = MagneticSensorSPI(10, 14, 0x3FFF);
+// magnetic sensor instance - I2C
+//MagneticSensorI2C sensor = MagneticSensorI2C(0x36, 12, 0X0C, 4);
+// magnetic sensor instance - analog output
+// MagneticSensorAnalog sensor = MagneticSensorAnalog(A1, 14, 1020);
+
+void setup() {
+
+ // use monitoring with serial
+ Serial.begin(115200);
+ // enable more verbose output for debugging
+ // comment out if not needed
+ SimpleFOCDebug::enable(&Serial);
+
+ // initialise magnetic sensor hardware
+ sensor.init();
+ // link the motor to the sensor
+ motor.linkSensor(&sensor);
+
+ // power supply voltage
+ // default 12V
+ driver.voltage_power_supply = 12;
+ driver.init();
+ motor.linkDriver(&driver);
+
+ // initialize motor hardware
+ motor.init();
+
+ // pole pairs calculation routine
+ Serial.println("Pole pairs (PP) estimator");
+ Serial.println("-\n");
+
+ float pp_search_voltage = 4; // maximum power_supply_voltage/2
+ float pp_search_angle = 6*_PI; // search electrical angle to turn
+
+ // move motor to the electrical angle 0
+ motor.controller = MotionControlType::angle_openloop;
+ motor.voltage_limit=pp_search_voltage;
+ motor.move(0);
+ _delay(1000);
+ // read the sensor angle
+ sensor.update();
+ float angle_begin = sensor.getAngle();
+ _delay(50);
+
+ // move the motor slowly to the electrical angle pp_search_angle
+ float motor_angle = 0;
+ while(motor_angle <= pp_search_angle){
+ motor_angle += 0.01f;
+ sensor.update(); // keep track of the overflow
+ motor.move(motor_angle);
+ _delay(1);
+ }
+ _delay(1000);
+ // read the sensor value for 180
+ sensor.update();
+ float angle_end = sensor.getAngle();
+ _delay(50);
+ // turn off the motor
+ motor.move(0);
+ _delay(1000);
+
+ // calculate the pole pair number
+ int pp = round((pp_search_angle)/(angle_end-angle_begin));
+
+ Serial.print(F("Estimated PP : "));
+ Serial.println(pp);
+ Serial.println(F("PP = Electrical angle / Encoder angle "));
+ Serial.print(pp_search_angle*180/_PI);
+ Serial.print(F("/"));
+ Serial.print((angle_end-angle_begin)*180/_PI);
+ Serial.print(F(" = "));
+ Serial.println((pp_search_angle)/(angle_end-angle_begin));
+ Serial.println();
+
+
+ // a bit of monitoring the result
+ if(pp <= 0 ){
+ Serial.println(F("PP number cannot be negative"));
+ Serial.println(F(" - Try changing the search_voltage value or motor/sensor configuration."));
+ return;
+ }else if(pp > 30){
+ Serial.println(F("PP number very high, possible error."));
+ }else{
+ Serial.println(F("If PP is estimated well your motor should turn now!"));
+ Serial.println(F(" - If it is not moving try to relaunch the program!"));
+ Serial.println(F(" - You can also try to adjust the target voltage using serial terminal!"));
+ }
+
+
+ // set motion control loop to be used
+ motor.controller = MotionControlType::torque;
+ // set the pole pair number to the motor
+ motor.pole_pairs = pp;
+ //align sensor and start FOC
+ motor.initFOC();
+ _delay(1000);
+
+ Serial.println(F("\n Motor ready."));
+ Serial.println(F("Set the target voltage using serial terminal:"));
+}
+
+// uq voltage
+float target_voltage = 2;
+
+void loop() {
+
+ // main FOC algorithm function
+ // the faster you run this function the better
+ // Arduino UNO loop ~1kHz
+ // Bluepill loop ~10kHz
+ motor.loopFOC();
+
+ // Motion control function
+ // velocity, position or voltage (defined in motor.controller)
+ // this function can be run at much lower frequency than loopFOC() function
+ // You can also use motor.move() and set the motor.target in the code
+ motor.move(target_voltage);
+
+ // communicate with the user
+ serialReceiveUserCommand();
+}
+
+
+// utility function enabling serial communication with the user to set the target values
+// this function can be implemented in serialEvent function as well
+void serialReceiveUserCommand() {
+
+ // a string to hold incoming data
+ static String received_chars;
+
+ while (Serial.available()) {
+ // get the new byte:
+ char inChar = (char)Serial.read();
+ // add it to the string buffer:
+ received_chars += inChar;
+ // end of user input
+ if (inChar == '\n') {
+
+ // change the motor target
+ target_voltage = received_chars.toFloat();
+ Serial.print("Target voltage: ");
+ Serial.println(target_voltage);
+
+ // reset the command buffer
+ received_chars = "";
+ }
+ }
+}
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/utils/calibration/find_sensor_offset_and_direction/find_sensor_offset_and_direction.ino b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/utils/calibration/find_sensor_offset_and_direction/find_sensor_offset_and_direction.ino
new file mode 100644
index 0000000..407469f
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/utils/calibration/find_sensor_offset_and_direction/find_sensor_offset_and_direction.ino
@@ -0,0 +1,89 @@
+/**
+ * Simple example intended to help users find the zero offset and natural direction of the sensor.
+ *
+ * These values can further be used to avoid motor and sensor alignment procedure.
+ * To use these values add them to the code:");
+ * motor.sensor_direction=Direction::CW; // or Direction::CCW
+ * motor.zero_electric_angle=1.2345; // use the real value!
+ *
+ * This will only work for abosolute value sensors - magnetic sensors.
+ * Bypassing the alignment procedure is not possible for the encoders and for the current implementation of the Hall sensors.
+ * library version 1.4.2.
+ *
+ */
+#include
+
+// magnetic sensor instance - SPI
+//MagneticSensorSPI sensor = MagneticSensorSPI(10, 14, 0x3FFF);
+// magnetic sensor instance - I2C
+//MagneticSensorI2C sensor = MagneticSensorI2C(0x36, 12, 0X0C, 4);
+// magnetic sensor instance - analog output
+MagneticSensorAnalog sensor = MagneticSensorAnalog(A1, 14, 1020);
+
+// BLDC motor instance
+BLDCMotor motor = BLDCMotor(11);
+BLDCDriver3PWM driver = BLDCDriver3PWM(9, 5, 6, 8);
+// Stepper motor instance
+//StepperMotor motor = StepperMotor(50);
+//StepperDriver4PWM driver = StepperDriver4PWM(9, 5, 10, 6, 8);
+
+void setup() {
+
+ // use monitoring with serial
+ Serial.begin(115200);
+ // enable more verbose output for debugging
+ // comment out if not needed
+ SimpleFOCDebug::enable(&Serial);
+
+ // power supply voltage
+ driver.voltage_power_supply = 12;
+ driver.init();
+ motor.linkDriver(&driver);
+
+ // initialise magnetic sensor hardware
+ sensor.init();
+ // link the motor to the sensor
+ motor.linkSensor(&sensor);
+
+ // aligning voltage
+ motor.voltage_sensor_align = 7;
+
+ // set motion control loop to be used
+ motor.controller = MotionControlType::torque;
+
+ // force direction search - because default is CW
+ motor.sensor_direction = Direction::UNKNOWN;
+
+ // initialize motor
+ motor.init();
+ // align sensor and start FOC
+ motor.initFOC();
+
+
+ Serial.println("Sensor zero offset is:");
+ Serial.println(motor.zero_electric_angle, 4);
+ Serial.println("Sensor natural direction is: ");
+ Serial.println(motor.sensor_direction == Direction::CW ? "Direction::CW" : "Direction::CCW");
+
+ Serial.println("To use these values add them to the code:");
+ Serial.print(" motor.sensor_direction=");
+ Serial.print(motor.sensor_direction == Direction::CW ? "Direction::CW" : "Direction::CCW");
+ Serial.println(";");
+ Serial.print(" motor.zero_electric_angle=");
+ Serial.print(motor.zero_electric_angle, 4);
+ Serial.println(";");
+
+ _delay(1000);
+ Serial.println("If motor is not moving the alignment procedure was not successfull!!");
+}
+
+
+void loop() {
+
+ // main FOC algorithm function
+ motor.loopFOC();
+
+ // Motion control function
+ motor.move(2);
+}
+
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/utils/communication_test/commander/commander_extend_example/commander_extend_example.ino b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/utils/communication_test/commander/commander_extend_example/commander_extend_example.ino
new file mode 100644
index 0000000..60bbcf1
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/utils/communication_test/commander/commander_extend_example/commander_extend_example.ino
@@ -0,0 +1,53 @@
+/**
+ * Simple example of custom commands that have nothing to do with the simple foc library
+ */
+
+#include
+
+// instantiate the commander
+Commander command = Commander(Serial);
+
+// led control function
+void doLed(char* cmd){
+ if(atoi(cmd)) digitalWrite(LED_BUILTIN, HIGH);
+ else digitalWrite(LED_BUILTIN, LOW);
+};
+// get analog input
+void doAnalog(char* cmd){
+ if (cmd[0] == '0') Serial.println(analogRead(A0));
+ else if (cmd[0] == '1') Serial.println(analogRead(A1));
+ else if (cmd[0] == '2') Serial.println(analogRead(A2));
+ else if (cmd[0] == '3') Serial.println(analogRead(A3));
+ else if (cmd[0] == '4') Serial.println(analogRead(A4));
+};
+
+void setup() {
+ // define pins
+ pinMode(LED_BUILTIN, OUTPUT);
+ pinMode(A0, INPUT);
+ pinMode(A1, INPUT);
+ pinMode(A2, INPUT);
+ pinMode(A3, INPUT);
+ pinMode(A4, INPUT);
+
+ // Serial port to be used
+ Serial.begin(115200);
+
+ // add new commands
+ command.add('L', doLed, "led on/off");
+ command.add('A', doAnalog, "analog read A0-A4");
+
+ Serial.println(F("Commander listening"));
+ Serial.println(F(" - Send ? to see the node list..."));
+ Serial.println(F(" - Send L0 to turn the led off and L1 to turn it off"));
+ Serial.println(F(" - Send A0-A4 to read the analog pins"));
+ _delay(1000);
+}
+
+
+void loop() {
+
+ // user communication
+ command.run();
+ _delay(10);
+}
\ No newline at end of file
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/utils/communication_test/commander/commander_no_serial/commander_no_serial.ino b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/utils/communication_test/commander/commander_no_serial/commander_no_serial.ino
new file mode 100644
index 0000000..1381515
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/utils/communication_test/commander/commander_no_serial/commander_no_serial.ino
@@ -0,0 +1,51 @@
+/**
+ * Simple example of how to use the commander without serial - using just strings
+ */
+
+#include
+
+// instantiate the commander
+Commander command = Commander();
+
+// led control function
+void doLed(char* cmd){
+ if(atoi(cmd)) digitalWrite(LED_BUILTIN, HIGH);
+ else digitalWrite(LED_BUILTIN, LOW);
+};
+// get analog input
+void doAnalog(char* cmd){
+ if (cmd[0] == '0') Serial.println(analogRead(A0));
+ else if (cmd[0] == '1') Serial.println(analogRead(A1));
+};
+
+void setup() {
+ // define pins
+ pinMode(LED_BUILTIN, OUTPUT);
+ pinMode(A0, INPUT);
+ pinMode(A1, INPUT);
+
+ // Serial port to be used
+ Serial.begin(115200);
+
+ // add new commands
+ command.add('L', doLed, "led control");
+ command.add('A', doAnalog, "analog read A0-A1");
+
+ Serial.println(F("Commander running"));
+ _delay(1000);
+}
+
+
+void loop() {
+ // user communication
+ command.run("?");
+ _delay(2000);
+ command.run("L0");
+ _delay(1000);
+ command.run("A0");
+ _delay(1000);
+ command.run("A1");
+ _delay(1000);
+ command.run("L1");
+ _delay(1000);
+}
\ No newline at end of file
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/utils/communication_test/commander/commander_tune_custom_loop/commander_tune_custom_loop.ino b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/utils/communication_test/commander/commander_tune_custom_loop/commander_tune_custom_loop.ino
new file mode 100644
index 0000000..074538a
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/utils/communication_test/commander/commander_tune_custom_loop/commander_tune_custom_loop.ino
@@ -0,0 +1,84 @@
+/**
+ * A simple example to show how to use the commander with the control loops outside of the scope of the SimpleFOC library
+*/
+#include
+
+// BLDC motor & driver instance
+BLDCMotor motor = BLDCMotor(11);
+BLDCDriver3PWM driver = BLDCDriver3PWM(5, 10, 6, 8);
+
+// encoder instance
+Encoder encoder = Encoder(2, 3, 500);
+// channel A and B callbacks
+void doA() { encoder.handleA(); }
+void doB() { encoder.handleB(); }
+
+// target voltage to be set to the motor
+float target_velocity = 0;
+
+// PID controllers and low pass filters
+PIDController PIDv{0.05, 1, 0, 100000000, 12};
+LowPassFilter LPFv{0.01};
+
+//add communication
+Commander command = Commander(Serial);
+void doController(char* cmd) { command.pid(&PIDv, cmd); }
+void doFilter(char* cmd) { command.lpf(&LPFv, cmd); }
+void doTarget(char* cmd) { command.scalar(&target_velocity, cmd); }
+
+
+void setup() {
+
+ // use monitoring with serial
+ Serial.begin(115200);
+ // enable more verbose output for debugging
+ // comment out if not needed
+ SimpleFOCDebug::enable(&Serial);
+
+ // initialize encoder sensor hardware
+ encoder.init();
+ encoder.enableInterrupts(doA, doB);
+ // link the motor to the sensor
+ motor.linkSensor(&encoder);
+
+ // driver config
+ // power supply voltage [V]
+ driver.init();
+ // link driver
+ motor.linkDriver(&driver);
+
+ // set motion control loop to be used ( doing nothing )
+ motor.torque_controller = TorqueControlType::voltage;
+ motor.controller = MotionControlType::torque;
+
+ // use monitoring with serial
+ motor.useMonitoring(Serial);
+ // initialize motor
+ motor.init();
+ // align sensor and start FOC
+ motor.initFOC();
+
+ // subscribe the new commands
+ command.add('C', doController, "tune velocity pid");
+ command.add('F', doFilter, "tune velocity LPF");
+ command.add('T', doTarget, "motor target");
+
+ _delay(1000);
+ Serial.println(F("Commander listening"));
+ Serial.println(F(" - Send ? to see the node list..."));
+}
+
+
+
+void loop() {
+ // looping foc
+ motor.loopFOC();
+
+ // calculate voltage
+ float target_voltage = PIDv(target_velocity - LPFv(motor.shaft_velocity));
+ // set the voltage
+ motor.move(target_voltage);
+
+ // user communication
+ command.run();
+}
\ No newline at end of file
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/utils/communication_test/step_dir/step_dir_listener_simple/step_dir_listener_simple.ino b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/utils/communication_test/step_dir/step_dir_listener_simple/step_dir_listener_simple.ino
new file mode 100644
index 0000000..a0bebc3
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/utils/communication_test/step_dir/step_dir_listener_simple/step_dir_listener_simple.ino
@@ -0,0 +1,36 @@
+/**
+ * A simple example of reading step/dir communication
+ * - this example uses hadware interrupts
+*/
+
+#include
+
+// angle
+float received_angle = 0;
+
+// StepDirListener( step_pin, dir_pin, counter_to_value)
+StepDirListener step_dir = StepDirListener(2, 3, 360.0/200.0); // receive the angle in degrees
+void onStep() { step_dir.handle(); }
+
+void setup() {
+
+ Serial.begin(115200);
+
+ // init step and dir pins
+ step_dir.init();
+ // enable interrupts
+ step_dir.enableInterrupt(onStep);
+ // attach the variable to be updated on each step (optional)
+ // the same can be done asynchronously by caling step_dir.getValue();
+ step_dir.attach(&received_angle);
+
+ Serial.println(F("Step/Dir listenning."));
+ _delay(1000);
+}
+
+void loop() {
+ Serial.print(received_angle);
+ Serial.print("\t");
+ Serial.println(step_dir.getValue());
+ _delay(500);
+}
\ No newline at end of file
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/utils/communication_test/step_dir/step_dir_listener_software_interrupt/step_dir_listener_software_interrupt.ino b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/utils/communication_test/step_dir/step_dir_listener_software_interrupt/step_dir_listener_software_interrupt.ino
new file mode 100644
index 0000000..b6f0ea5
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/utils/communication_test/step_dir/step_dir_listener_software_interrupt/step_dir_listener_software_interrupt.ino
@@ -0,0 +1,44 @@
+/**
+ * A simple example of reading step/dir communication
+ * - this example uses software interrupts - this code is intended primarily
+ * for Arduino UNO/Mega and similar boards with very limited number of interrupt pins
+*/
+
+#include
+// software interrupt library
+#include
+#include
+
+
+// angle
+float received_angle = 0;
+
+// StepDirListener( step_pin, dir_pin, counter_to_value)
+StepDirListener step_dir = StepDirListener(4, 5, 2.0f*_PI/200.0); // receive the angle in radians
+void onStep() { step_dir.handle(); }
+
+// If no available hadware interrupt pins use the software interrupt
+PciListenerImp listenStep(step_dir.pin_step, onStep);
+
+void setup() {
+
+ Serial.begin(115200);
+
+ // init step and dir pins
+ step_dir.init();
+ // enable software interrupts
+ PciManager.registerListener(&listenStep);
+ // attach the variable to be updated on each step (optional)
+ // the same can be done asynchronously by caling step_dir.getValue();
+ step_dir.attach(&received_angle);
+
+ Serial.println(F("Step/Dir listenning."));
+ _delay(1000);
+}
+
+void loop() {
+ Serial.print(received_angle);
+ Serial.print("\t");
+ Serial.println(step_dir.getValue());
+ _delay(500);
+}
\ No newline at end of file
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/utils/communication_test/step_dir/step_dir_motor_example/step_dir_motor_example.ino b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/utils/communication_test/step_dir/step_dir_motor_example/step_dir_motor_example.ino
new file mode 100644
index 0000000..4cd8797
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/utils/communication_test/step_dir/step_dir_motor_example/step_dir_motor_example.ino
@@ -0,0 +1,102 @@
+/**
+ * A position control example using step/dir interface to update the motor position
+ */
+
+#include
+
+// BLDC motor & driver instance
+BLDCMotor motor = BLDCMotor(11);
+BLDCDriver3PWM driver = BLDCDriver3PWM(10, 5, 6, 8);
+
+// Stepper motor & driver instance
+//StepperMotor motor = StepperMotor(50);
+//StepperDriver4PWM driver = StepperDriver4PWM(9, 5, 10, 6, 8);
+
+// encoder instance
+Encoder encoder = Encoder(2, 3, 500);
+// channel A and B callbacks
+void doA() { encoder.handleA(); }
+void doB() { encoder.handleB(); }
+
+// StepDirListener( step_pin, dir_pin, counter_to_value)
+StepDirListener step_dir = StepDirListener(A4, A5, 2.0f*_PI/200.0);
+void onStep() { step_dir.handle(); }
+
+void setup() {
+
+ // use monitoring with serial
+ Serial.begin(115200);
+ // enable more verbose output for debugging
+ // comment out if not needed
+ SimpleFOCDebug::enable(&Serial);
+
+ // initialize encoder sensor hardware
+ encoder.init();
+ encoder.enableInterrupts(doA, doB);
+ // link the motor to the sensor
+ motor.linkSensor(&encoder);
+
+ // driver config
+ // power supply voltage [V]
+ driver.voltage_power_supply = 12;
+ driver.init();
+ // link the motor and the driver
+ motor.linkDriver(&driver);
+
+ // aligning voltage [V]
+ motor.voltage_sensor_align = 3;
+ // index search velocity [rad/s]
+ motor.velocity_index_search = 3;
+
+ // set motion control loop to be used
+ motor.controller = MotionControlType::angle;
+
+ // contoller configuration
+ // default parameters in defaults.h
+ // velocity PI controller parameters
+ motor.PID_velocity.P = 0.2f;
+ motor.PID_velocity.I = 20;
+ motor.PID_velocity.D = 0;
+ // default voltage_power_supply
+ motor.voltage_limit = 12;
+ // jerk control using voltage voltage ramp
+ // default value is 300 volts per sec ~ 0.3V per millisecond
+ motor.PID_velocity.output_ramp = 1000;
+
+ // velocity low pass filtering time constant
+ motor.LPF_velocity.Tf = 0.01f;
+
+ // angle P controller
+ motor.P_angle.P = 10;
+ // maximal velocity of the position control
+ motor.velocity_limit = 100;
+
+ // comment out if not needed
+ motor.useMonitoring(Serial);
+
+ // initialize motor
+ motor.init();
+ // align encoder and start FOC
+ motor.initFOC();
+
+ // init step and dir pins
+ step_dir.init();
+ // enable interrupts
+ step_dir.enableInterrupt(onStep);
+ // attach the variable to be updated on each step (optional)
+ // the same can be done asynchronously by caling motor.move(step_dir.getValue());
+ step_dir.attach(&motor.target);
+
+ Serial.println(F("Motor ready."));
+ Serial.println(F("Listening to step/dir commands!"));
+ _delay(1000);
+}
+
+void loop() {
+
+ // main FOC algorithm function
+ motor.loopFOC();
+
+ // Motion control function
+ motor.move();
+}
\ No newline at end of file
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/utils/current_sense_test/generic_current_sense/generic_current_sense.ino b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/utils/current_sense_test/generic_current_sense/generic_current_sense.ino
new file mode 100644
index 0000000..2448a51
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/utils/current_sense_test/generic_current_sense/generic_current_sense.ino
@@ -0,0 +1,66 @@
+/**
+ * An example code for the generic current sensing implementation
+*/
+#include
+
+
+// user defined function for reading the phase currents
+// returning the value per phase in amps
+PhaseCurrent_s readCurrentSense(){
+ PhaseCurrent_s c;
+ // dummy example only reading analog pins
+ c.a = analogRead(A0);
+ c.b = analogRead(A1);
+ c.c = analogRead(A2); // if no 3rd current sense set it to 0
+ return(c);
+}
+
+// user defined function for intialising the current sense
+// it is optional and if provided it will be called in current_sense.init()
+void initCurrentSense(){
+ pinMode(A0,INPUT);
+ pinMode(A1,INPUT);
+ pinMode(A2,INPUT);
+}
+
+
+// GenericCurrentSense class constructor
+// it receives the user defined callback for reading the current sense
+// and optionally the user defined callback for current sense initialisation
+GenericCurrentSense current_sense = GenericCurrentSense(readCurrentSense, initCurrentSense);
+
+
+void setup() {
+
+ // use monitoring with serial
+ Serial.begin(115200);
+ // enable more verbose output for debugging
+ // comment out if not needed
+ SimpleFOCDebug::enable(&Serial);
+
+
+ // if callbacks are not provided in the constructor
+ // they can be assigned directly:
+ //current_sense.readCallback = readCurrentSense;
+ //current_sense.initCallback = initCurrentSense;
+
+ // initialise the current sensing
+ current_sense.init();
+
+
+ Serial.println("Current sense ready.");
+}
+
+void loop() {
+
+ PhaseCurrent_s currents = current_sense.getPhaseCurrents();
+ float current_magnitude = current_sense.getDCCurrent();
+
+ Serial.print(currents.a); // milli Amps
+ Serial.print("\t");
+ Serial.print(currents.b); // milli Amps
+ Serial.print("\t");
+ Serial.print(currents.c); // milli Amps
+ Serial.print("\t");
+ Serial.println(current_magnitude); // milli Amps
+}
\ No newline at end of file
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/utils/current_sense_test/inline_current_sense_test/inline_current_sense_test.ino b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/utils/current_sense_test/inline_current_sense_test/inline_current_sense_test.ino
new file mode 100644
index 0000000..1198cdc
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/utils/current_sense_test/inline_current_sense_test/inline_current_sense_test.ino
@@ -0,0 +1,45 @@
+/**
+ * Testing example code for the Inline current sensing class
+*/
+#include
+
+// current sensor
+// shunt resistor value
+// gain value
+// pins phase A,B, (C optional)
+InlineCurrentSense current_sense = InlineCurrentSense(0.01f, 50.0f, A0, A2);
+
+
+void setup() {
+
+ // use monitoring with serial
+ Serial.begin(115200);
+ // enable more verbose output for debugging
+ // comment out if not needed
+ SimpleFOCDebug::enable(&Serial);
+
+ // initialise the current sensing
+ if(!current_sense.init()){
+ Serial.println("Current sense init failed.");
+ return;
+ }
+
+ // for SimpleFOCShield v2.01/v2.0.2
+ current_sense.gain_b *= -1;
+
+ Serial.println("Current sense ready.");
+}
+
+void loop() {
+
+ PhaseCurrent_s currents = current_sense.getPhaseCurrents();
+ float current_magnitude = current_sense.getDCCurrent();
+
+ Serial.print(currents.a*1000); // milli Amps
+ Serial.print("\t");
+ Serial.print(currents.b*1000); // milli Amps
+ Serial.print("\t");
+ Serial.print(currents.c*1000); // milli Amps
+ Serial.print("\t");
+ Serial.println(current_magnitude*1000); // milli Amps
+}
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/utils/driver_standalone_test/bldc_driver_3pwm_standalone/bldc_driver_3pwm_standalone.ino b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/utils/driver_standalone_test/bldc_driver_3pwm_standalone/bldc_driver_3pwm_standalone.ino
new file mode 100644
index 0000000..eef793d
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/utils/driver_standalone_test/bldc_driver_3pwm_standalone/bldc_driver_3pwm_standalone.ino
@@ -0,0 +1,43 @@
+// BLDC driver standalone example
+#include
+
+
+// BLDC driver instance
+BLDCDriver3PWM driver = BLDCDriver3PWM(9, 5, 6, 8);
+
+void setup() {
+
+ // use monitoring with serial
+ Serial.begin(115200);
+ // enable more verbose output for debugging
+ // comment out if not needed
+ SimpleFOCDebug::enable(&Serial);
+
+ // pwm frequency to be used [Hz]
+ // for atmega328 fixed to 32kHz
+ // esp32/stm32/teensy configurable
+ driver.pwm_frequency = 50000;
+ // power supply voltage [V]
+ driver.voltage_power_supply = 12;
+ // Max DC voltage allowed - default voltage_power_supply
+ driver.voltage_limit = 12;
+
+ // driver init
+ if (!driver.init()){
+ Serial.println("Driver init failed!");
+ return;
+ }
+
+ // enable driver
+ driver.enable();
+ Serial.println("Driver ready!");
+ _delay(1000);
+}
+
+void loop() {
+ // setting pwm
+ // phase A: 3V
+ // phase B: 6V
+ // phase C: 5V
+ driver.setPwm(3,6,5);
+}
\ No newline at end of file
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/utils/driver_standalone_test/bldc_driver_6pwm_standalone/bldc_driver_6pwm_standalone.ino b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/utils/driver_standalone_test/bldc_driver_6pwm_standalone/bldc_driver_6pwm_standalone.ino
new file mode 100644
index 0000000..56a1afb
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/utils/driver_standalone_test/bldc_driver_6pwm_standalone/bldc_driver_6pwm_standalone.ino
@@ -0,0 +1,44 @@
+// BLDC driver standalone example
+#include
+
+// BLDC driver instance
+BLDCDriver6PWM driver = BLDCDriver6PWM(5, 6, 9,10, 3, 11, 8);
+
+void setup() {
+
+ // use monitoring with serial
+ Serial.begin(115200);
+ // enable more verbose output for debugging
+ // comment out if not needed
+ SimpleFOCDebug::enable(&Serial);
+
+ // pwm frequency to be used [Hz]
+ // for atmega328 fixed to 32kHz
+ // esp32/stm32/teensy configurable
+ driver.pwm_frequency = 50000;
+ // power supply voltage [V]
+ driver.voltage_power_supply = 12;
+ // Max DC voltage allowed - default voltage_power_supply
+ driver.voltage_limit = 12;
+ // daad_zone [0,1] - default 0.02f - 2%
+ driver.dead_zone = 0.05f;
+
+ // driver init
+ if (!driver.init()){
+ Serial.println("Driver init failed!");
+ return;
+ }
+
+ // enable driver
+ driver.enable();
+ Serial.println("Driver ready!");
+ _delay(1000);
+}
+
+void loop() {
+ // setting pwm
+ // phase A: 3V
+ // phase B: 6V
+ // phase C: 5V
+ driver.setPwm(3,6,5);
+}
\ No newline at end of file
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/utils/driver_standalone_test/stepper_driver_2pwm_standalone/stepper_driver_2pwm_standalone.ino b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/utils/driver_standalone_test/stepper_driver_2pwm_standalone/stepper_driver_2pwm_standalone.ino
new file mode 100644
index 0000000..59343a1
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/utils/driver_standalone_test/stepper_driver_2pwm_standalone/stepper_driver_2pwm_standalone.ino
@@ -0,0 +1,48 @@
+// Stepper driver standalone example
+#include
+
+
+// Stepper driver instance
+// StepperDriver2PWM(pwm1, in1, pwm2, in2, (en1, en2 optional))
+int in1[] = {4,5};
+int in2[] = {9,8};
+StepperDriver2PWM driver = StepperDriver2PWM(3, in1, 10 , in2, 11, 12);
+
+// StepperDriver2PWM(pwm1, dir1, pwm2, dir2,(en1, en2 optional))
+// StepperDriver2PWM driver = StepperDriver2PWM(3, 4, 5, 6, 11, 12);
+
+void setup() {
+
+ // use monitoring with serial
+ Serial.begin(115200);
+ // enable more verbose output for debugging
+ // comment out if not needed
+ SimpleFOCDebug::enable(&Serial);
+
+ // pwm frequency to be used [Hz]
+ // for atmega328 fixed to 32kHz
+ // esp32/stm32/teensy configurable
+ driver.pwm_frequency = 30000;
+ // power supply voltage [V]
+ driver.voltage_power_supply = 12;
+ // Max DC voltage allowed - default voltage_power_supply
+ driver.voltage_limit = 12;
+
+ // driver init
+ if (!driver.init()){
+ Serial.println("Driver init failed!");
+ return;
+ }
+
+ // enable driver
+ driver.enable();
+ Serial.println("Driver ready!");
+ _delay(1000);
+}
+
+void loop() {
+ // setting pwm
+ // phase A: 3V
+ // phase B: 6V
+ driver.setPwm(3,6);
+}
\ No newline at end of file
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/utils/driver_standalone_test/stepper_driver_4pwm_standalone/stepper_driver_4pwm_standalone.ino b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/utils/driver_standalone_test/stepper_driver_4pwm_standalone/stepper_driver_4pwm_standalone.ino
new file mode 100644
index 0000000..a58d794
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/utils/driver_standalone_test/stepper_driver_4pwm_standalone/stepper_driver_4pwm_standalone.ino
@@ -0,0 +1,43 @@
+// Stepper driver standalone example
+#include
+
+
+// Stepper driver instance
+// StepperDriver4PWM(ph1A, ph1B, ph2A, ph2B, (en1, en2 optional))
+StepperDriver4PWM driver = StepperDriver4PWM(5, 6, 9,10, 7, 8);
+
+void setup() {
+
+ // use monitoring with serial
+ Serial.begin(115200);
+ // enable more verbose output for debugging
+ // comment out if not needed
+ SimpleFOCDebug::enable(&Serial);
+
+ // pwm frequency to be used [Hz]
+ // for atmega328 fixed to 32kHz
+ // esp32/stm32/teensy configurable
+ driver.pwm_frequency = 30000;
+ // power supply voltage [V]
+ driver.voltage_power_supply = 12;
+ // Max DC voltage allowed - default voltage_power_supply
+ driver.voltage_limit = 12;
+
+ // driver init
+ if (!driver.init()){
+ Serial.println("Driver init failed!");
+ return;
+ }
+
+ // enable driver
+ driver.enable();
+ Serial.println("Driver ready!");
+ _delay(1000);
+}
+
+void loop() {
+ // setting pwm
+ // phase A: 3V
+ // phase B: 6V
+ driver.setPwm(3,6);
+}
\ No newline at end of file
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/utils/sensor_test/encoder/encoder_example/encoder_example.ino b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/utils/sensor_test/encoder/encoder_example/encoder_example.ino
new file mode 100644
index 0000000..f105f5b
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/utils/sensor_test/encoder/encoder_example/encoder_example.ino
@@ -0,0 +1,44 @@
+/**
+ * Encoder example code
+ *
+ * This is a code intended to test the encoder connections and to demonstrate the encoder setup.
+ *
+ */
+
+#include
+
+
+Encoder encoder = Encoder(2, 3, 8192);
+// interrupt routine intialisation
+void doA(){encoder.handleA();}
+void doB(){encoder.handleB();}
+
+void setup() {
+ // monitoring port
+ Serial.begin(115200);
+
+ // enable/disable quadrature mode
+ encoder.quadrature = Quadrature::ON;
+
+ // check if you need internal pullups
+ encoder.pullup = Pullup::USE_EXTERN;
+
+ // initialise encoder hardware
+ encoder.init();
+ // hardware interrupt enable
+ encoder.enableInterrupts(doA, doB);
+
+ Serial.println("Encoder ready");
+ _delay(1000);
+}
+
+void loop() {
+ // iterative function updating the sensor internal variables
+ // it is usually called in motor.loopFOC()
+ // not doing much for the encoder though
+ encoder.update();
+ // display the angle and the angular velocity to the terminal
+ Serial.print(encoder.getAngle());
+ Serial.print("\t");
+ Serial.println(encoder.getVelocity());
+}
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/utils/sensor_test/encoder/encoder_software_interrupts_example/encoder_software_interrupts_example.ino b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/utils/sensor_test/encoder/encoder_software_interrupts_example/encoder_software_interrupts_example.ino
new file mode 100644
index 0000000..ebf2dd4
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/utils/sensor_test/encoder/encoder_software_interrupts_example/encoder_software_interrupts_example.ino
@@ -0,0 +1,57 @@
+/**
+ * Encoder example code using only software interrupts
+ *
+ * This is a code intended to test the encoder connections and to
+ * demonstrate the encoder setup fully using software interrupts.
+ * - We use PciManager library: https://github.com/prampec/arduino-pcimanager
+ *
+ * This code will work on Arduino devices but not on STM32 devices
+ *
+ */
+
+#include
+// software interrupt library
+#include
+#include
+
+// encoder instance
+Encoder encoder = Encoder(A0, A1, 2048);
+// interrupt routine intialisation
+void doA(){encoder.handleA();}
+void doB(){encoder.handleB();}
+
+// encoder interrupt init
+PciListenerImp listenerA(encoder.pinA, doA);
+PciListenerImp listenerB(encoder.pinB, doB);
+
+void setup() {
+ // monitoring port
+ Serial.begin(115200);
+
+ // enable/disable quadrature mode
+ encoder.quadrature = Quadrature::ON;
+
+ // check if you need internal pullups
+ encoder.pullup = Pullup::USE_EXTERN;
+
+ // initialise encoder hardware
+ encoder.init();
+
+ // interrupt initialization
+ PciManager.registerListener(&listenerA);
+ PciManager.registerListener(&listenerB);
+
+ Serial.println("Encoder ready");
+ _delay(1000);
+}
+
+void loop() {
+ // iterative function updating the sensor internal variables
+ // it is usually called in motor.loopFOC()
+ // not doing much for the encoder though
+ encoder.update();
+ // display the angle and the angular velocity to the terminal
+ Serial.print(encoder.getAngle());
+ Serial.print("\t");
+ Serial.println(encoder.getVelocity());
+}
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/utils/sensor_test/generic_sensor/generic_sensor.ino b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/utils/sensor_test/generic_sensor/generic_sensor.ino
new file mode 100644
index 0000000..4a470e5
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/utils/sensor_test/generic_sensor/generic_sensor.ino
@@ -0,0 +1,51 @@
+/**
+ * Generic sensor example code
+ *
+ * This is a code intended to demonstrate how to implement the generic sensor class
+ *
+ */
+
+#include
+
+// sensor reading function example
+// for the magnetic sensor with analog communication
+// returning an angle in radians in between 0 and 2PI
+float readSensor(){
+ return analogRead(A0)*_2PI/1024.0;
+}
+
+// sensor intialising function
+void initSensor(){
+ pinMode(A0,INPUT);
+}
+
+// generic sensor class contructor
+// - read sensor callback
+// - init sensor callback (optional)
+GenericSensor sensor = GenericSensor(readSensor, initSensor);
+
+void setup() {
+ // monitoring port
+ Serial.begin(115200);
+
+ // if callbacks are not provided in the constructor
+ // they can be assigned directly:
+ //sensor.readCallback = readSensor;
+ //sensor.initCallback = initSensor;
+
+ sensor.init();
+
+ Serial.println("Sensor ready");
+ _delay(1000);
+}
+
+void loop() {
+ // iterative function updating the sensor internal variables
+ // it is usually called in motor.loopFOC()
+ sensor.update();
+
+ // display the angle and the angular velocity to the terminal
+ Serial.print(sensor.getAngle());
+ Serial.print("\t");
+ Serial.println(sensor.getVelocity());
+}
\ No newline at end of file
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/utils/sensor_test/hall_sensors/hall_sensor_example/hall_sensor_example.ino b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/utils/sensor_test/hall_sensors/hall_sensor_example/hall_sensor_example.ino
new file mode 100644
index 0000000..cc8dfdb
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/utils/sensor_test/hall_sensors/hall_sensor_example/hall_sensor_example.ino
@@ -0,0 +1,39 @@
+/**
+ * Hall sensor example code
+ *
+ * This is a code intended to test the hall sensors connections and to demonstrate the hall sensor setup.
+ *
+ */
+
+#include
+
+// Hall sensor instance
+// HallSensor(int hallA, int hallB , int cpr, int index)
+// - hallA, hallB, hallC - HallSensor A, B and C pins
+// - pp - pole pairs
+HallSensor sensor = HallSensor(2, 3, 4, 14);
+
+void setup() {
+ // monitoring port
+ Serial.begin(115200);
+
+ // check if you need internal pullups
+ sensor.pullup = Pullup::USE_EXTERN;
+
+ // initialise encoder hardware
+ sensor.init();
+
+ Serial.println("Sensor ready");
+ _delay(1000);
+}
+
+void loop() {
+ // iterative function updating the sensor internal variables
+ // it is usually called in motor.loopFOC()
+ sensor.update();
+ // display the angle and the angular velocity to the terminal
+ Serial.print(sensor.getAngle());
+ Serial.print("\t");
+ Serial.println(sensor.getVelocity());
+ delay(100);
+}
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/utils/sensor_test/hall_sensors/hall_sensor_hardware_interrupts_example/hall_sensor_hardware_interrupts_example.ino b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/utils/sensor_test/hall_sensors/hall_sensor_hardware_interrupts_example/hall_sensor_hardware_interrupts_example.ino
new file mode 100644
index 0000000..c4777ba
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/utils/sensor_test/hall_sensors/hall_sensor_hardware_interrupts_example/hall_sensor_hardware_interrupts_example.ino
@@ -0,0 +1,48 @@
+/**
+ * Hall sensor example code
+ *
+ * This is a code intended to test the hall sensors connections and to demonstrate the hall sensor setup.
+ *
+ */
+
+#include
+
+// Hall sensor instance
+// HallSensor(int hallA, int hallB , int cpr, int index)
+// - hallA, hallB, hallC - HallSensor A, B and C pins
+// - pp - pole pairs
+HallSensor sensor = HallSensor(2, 3, 4, 14);
+
+// Interrupt routine intialisation
+// channel A and B callbacks
+void doA(){sensor.handleA();}
+void doB(){sensor.handleB();}
+void doC(){sensor.handleC();}
+
+
+void setup() {
+ // monitoring port
+ Serial.begin(115200);
+
+ // check if you need internal pullups
+ sensor.pullup = Pullup::USE_EXTERN;
+
+ // initialise encoder hardware
+ sensor.init();
+ // hardware interrupt enable
+ sensor.enableInterrupts(doA, doB, doC);
+
+ Serial.println("Sensor ready");
+ _delay(1000);
+}
+
+void loop() {
+ // iterative function updating the sensor internal variables
+ // it is usually called in motor.loopFOC()
+ sensor.update();
+ // display the angle and the angular velocity to the terminal
+ Serial.print(sensor.getAngle());
+ Serial.print("\t");
+ Serial.println(sensor.getVelocity());
+ delay(100);
+}
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/utils/sensor_test/hall_sensors/hall_sensor_software_interrupts_example/hall_sensor_software_interrupts_example.ino b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/utils/sensor_test/hall_sensors/hall_sensor_software_interrupts_example/hall_sensor_software_interrupts_example.ino
new file mode 100644
index 0000000..238eb2c
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/utils/sensor_test/hall_sensors/hall_sensor_software_interrupts_example/hall_sensor_software_interrupts_example.ino
@@ -0,0 +1,59 @@
+/**
+ * Hall sensors example code using only software interrupts
+ *
+ * This is a code intended to test the hall sensor connections and to
+ * demonstrate the hall sensor setup fully using software interrupts.
+ * - We use PciManager library: https://github.com/prampec/arduino-pcimanager
+ *
+ * This code will work on Arduino devices but not on STM32 devices
+ */
+
+#include
+// software interrupt library
+#include
+#include
+
+// Hall sensor instance
+// HallSensor(int hallA, int hallB , int cpr, int index)
+// - hallA, hallB, hallC - HallSensor A, B and C pins
+// - pp - pole pairs
+HallSensor sensor = HallSensor(2, 3, 4, 11);
+
+// Interrupt routine intialisation
+// channel A and B callbacks
+void doA(){sensor.handleA();}
+void doB(){sensor.handleB();}
+void doC(){sensor.handleC();}
+// If no available hadware interrupt pins use the software interrupt
+PciListenerImp listenA(sensor.pinA, doA);
+PciListenerImp listenB(sensor.pinB, doB);
+PciListenerImp listenC(sensor.pinC, doC);
+
+void setup() {
+ // monitoring port
+ Serial.begin(115200);
+
+ // check if you need internal pullups
+ sensor.pullup = Pullup::USE_EXTERN;
+
+ // initialise encoder hardware
+ sensor.init();
+
+ // software interrupts
+ PciManager.registerListener(&listenA);
+ PciManager.registerListener(&listenB);
+ PciManager.registerListener(&listenC);
+
+ Serial.println("Sensor ready");
+ _delay(1000);
+}
+
+void loop() {
+ // iterative function updating the sensor internal variables
+ // it is usually called in motor.loopFOC()
+ sensor.update();
+ // display the angle and the angular velocity to the terminal
+ Serial.print(sensor.getAngle());
+ Serial.print("\t");
+ Serial.println(sensor.getVelocity());
+}
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/utils/sensor_test/linear_hall_sensors/find_raw_centers/find_raw_centers.ino b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/utils/sensor_test/linear_hall_sensors/find_raw_centers/find_raw_centers.ino
new file mode 100644
index 0000000..5fda5f5
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/utils/sensor_test/linear_hall_sensors/find_raw_centers/find_raw_centers.ino
@@ -0,0 +1,62 @@
+/**
+ * An example to find the center offsets for both ADC channels used in the LinearHall sensor constructor
+ * Spin your motor through at least one full revolution to average out all of the variations in magnet strength.
+ */
+
+//Change these defines to match the analog input pins that your hall sensors are connected to
+#define LINEAR_HALL_CHANNEL_A 39
+#define LINEAR_HALL_CHANNEL_B 33
+
+
+//program variables
+int minA, maxA, minB, maxB, centerA, centerB;
+unsigned long timestamp;
+
+void setup() {
+ // monitoring port
+ Serial.begin(115200);
+
+ // initialise magnetic sensor hardware
+ pinMode(LINEAR_HALL_CHANNEL_A, INPUT);
+ pinMode(LINEAR_HALL_CHANNEL_B, INPUT);
+
+ minA = analogRead(LINEAR_HALL_CHANNEL_A);
+ maxA = minA;
+ centerA = (minA + maxA) / 2;
+ minB = analogRead(LINEAR_HALL_CHANNEL_B);
+ maxB = minB;
+ centerB = (minB + maxB) / 2;
+
+ Serial.println("Sensor ready");
+ delay(1000);
+ timestamp = millis();
+}
+
+void loop() {
+ //read sensors and update variables
+ int tempA = analogRead(LINEAR_HALL_CHANNEL_A);
+ if (tempA < minA) minA = tempA;
+ if (tempA > maxA) maxA = tempA;
+ centerA = (minA + maxA) / 2;
+ int tempB = analogRead(LINEAR_HALL_CHANNEL_B);
+ if (tempB < minB) minB = tempB;
+ if (tempB > maxB) maxB = tempB;
+ centerB = (minB + maxB) / 2;
+
+ if (millis() > timestamp + 100) {
+ timestamp = millis();
+ // display the center counts, and max and min count
+ Serial.print("A:");
+ Serial.print(centerA);
+ Serial.print("\t, B:");
+ Serial.print(centerB);
+ Serial.print("\t, min A:");
+ Serial.print(minA);
+ Serial.print("\t, max A:");
+ Serial.print(maxA);
+ Serial.print("\t, min B:");
+ Serial.print(minB);
+ Serial.print("\t, max B:");
+ Serial.println(maxB);
+ }
+}
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/utils/sensor_test/magnetic_sensors/magnetic_sensor_analog/find_raw_min_max/find_raw_min_max.ino b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/utils/sensor_test/magnetic_sensors/magnetic_sensor_analog/find_raw_min_max/find_raw_min_max.ino
new file mode 100644
index 0000000..34e68a1
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/utils/sensor_test/magnetic_sensors/magnetic_sensor_analog/find_raw_min_max/find_raw_min_max.ino
@@ -0,0 +1,56 @@
+#include
+
+/**
+ * An example to find out the raw max and min count to be provided to the constructor
+ * Spin your motor/sensor/magnet to see what is the maximum output of the sensor and what is the minimum value
+ * And replace values 14 and 1020 with new values. Once when you replace them make sure there is no jump in the angle reading sensor.getAngle().
+ * If there is a jump that means you can still find better values.
+ */
+
+/**
+ * Magnetic sensor reading analog voltage on pin A1. This voltage is proportional to rotation position.
+ * Tested on AS5600 magnetic sensor running in 'analog mode'. Note AS5600 works better in 'i2C mode' (less noise) but only supports one sensor per i2c bus.
+ *
+ * MagneticSensorAnalog(uint8_t _pinAnalog, int _min, int _max)
+ * - pinAnalog - the pin that is reading the pwm from magnetic sensor
+ * - min_raw_count - the smallest expected reading. Whilst you might expect it to be 0 it is often ~15. Getting this wrong results in a small click once per revolution
+ * - max_raw_count - the largest value read. whilst you might expect it to be 2^10 = 1023 it is often ~ 1020. Note ESP32 will be closer to 4096 with its 12bit ADC
+ */
+MagneticSensorAnalog sensor = MagneticSensorAnalog(A1, 14, 1020);
+
+void setup() {
+ // monitoring port
+ Serial.begin(115200);
+
+ // initialise magnetic sensor hardware
+ sensor.init();
+
+ Serial.println("Sensor ready");
+ _delay(1000);
+}
+
+int max_count = 0;
+int min_count = 100000;
+
+void loop() {
+ // iterative function updating the sensor internal variables
+ // it is usually called in motor.loopFOC()
+ // this function reads the sensor hardware and
+ // has to be called before getAngle nad getVelocity
+ sensor.update();
+
+ // keep track of min and max
+ if(sensor.raw_count > max_count) max_count = sensor.raw_count;
+ else if(sensor.raw_count < min_count) min_count = sensor.raw_count;
+
+ // display the raw count, and max and min raw count
+ Serial.print("angle:");
+ Serial.print(sensor.getAngle());
+ Serial.print("\t, raw:");
+ Serial.print(sensor.raw_count);
+ Serial.print("\t, min:");
+ Serial.print(min_count);
+ Serial.print("\t, max:");
+ Serial.println(max_count);
+ delay(100);
+}
\ No newline at end of file
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/utils/sensor_test/magnetic_sensors/magnetic_sensor_analog/magnetic_sensor_analog_example/magnetic_sensor_analog_example.ino b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/utils/sensor_test/magnetic_sensors/magnetic_sensor_analog/magnetic_sensor_analog_example/magnetic_sensor_analog_example.ino
new file mode 100644
index 0000000..2496151
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/utils/sensor_test/magnetic_sensors/magnetic_sensor_analog/magnetic_sensor_analog_example/magnetic_sensor_analog_example.ino
@@ -0,0 +1,37 @@
+#include
+
+
+
+/**
+ * Magnetic sensor reading analog voltage on pin A1. This voltage is proportional to rotation position.
+ * Tested on AS5600 magnetic sensor running in 'analog mode'. Note AS5600 works better in 'i2C mode' (less noise) but only supports one sensor per i2c bus.
+ *
+ * MagneticSensorAnalog(uint8_t _pinAnalog, int _min, int _max)
+ * - pinAnalog - the pin that is reading the pwm from magnetic sensor
+ * - min_raw_count - the smallest expected reading. Whilst you might expect it to be 0 it is often ~15. Getting this wrong results in a small click once per revolution
+ * - max_raw_count - the largest value read. whilst you might expect it to be 2^10 = 1023 it is often ~ 1020. Note ESP32 will be closer to 4096 with its 12bit ADC
+ */
+MagneticSensorAnalog sensor = MagneticSensorAnalog(A1, 14, 1020);
+
+void setup() {
+ // monitoring port
+ Serial.begin(115200);
+
+ // initialise magnetic sensor hardware
+ sensor.init();
+
+ Serial.println("Sensor ready");
+ _delay(1000);
+}
+
+void loop() {
+ // iterative function updating the sensor internal variables
+ // it is usually called in motor.loopFOC()
+ // this function reads the sensor hardware and
+ // has to be called before getAngle nad getVelocity
+ sensor.update();
+ // display the angle and the angular velocity to the terminal
+ Serial.print(sensor.getAngle());
+ Serial.print("\t");
+ Serial.println(sensor.getVelocity());
+}
\ No newline at end of file
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/utils/sensor_test/magnetic_sensors/magnetic_sensor_i2c/magnetic_sensor_i2c_dual_bus_examples/esp32_i2c_dual_bus_example/esp32_i2c_dual_bus_example.ino b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/utils/sensor_test/magnetic_sensors/magnetic_sensor_i2c/magnetic_sensor_i2c_dual_bus_examples/esp32_i2c_dual_bus_example/esp32_i2c_dual_bus_example.ino
new file mode 100644
index 0000000..0516ede
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/utils/sensor_test/magnetic_sensors/magnetic_sensor_i2c/magnetic_sensor_i2c_dual_bus_examples/esp32_i2c_dual_bus_example/esp32_i2c_dual_bus_example.ino
@@ -0,0 +1,40 @@
+#include
+
+/** Annoyingly some i2c sensors (e.g. AS5600) have a fixed chip address. This means only one of these devices can be addressed on a single bus
+ * This example shows how a second i2c bus can be used to communicate with a second sensor.
+ */
+
+MagneticSensorI2C sensor0 = MagneticSensorI2C(AS5600_I2C);
+MagneticSensorI2C sensor1 = MagneticSensorI2C(AS5600_I2C);
+
+
+void setup() {
+
+ Serial.begin(115200);
+ _delay(750);
+
+ Wire.setClock(400000);
+ Wire1.setClock(400000);
+
+ // Normally SimpleFOC will call begin for i2c but with esp32 begin() is the only way to set pins!
+ // It seems safe to call begin multiple times
+ Wire1.begin(19, 23, (uint32_t)400000);
+
+ sensor0.init();
+ sensor1.init(&Wire1);
+}
+
+void loop() {
+ // iterative function updating the sensor internal variables
+ // it is usually called in motor.loopFOC()
+ // this function reads the sensor hardware and
+ // has to be called before getAngle nad getVelocity
+ sensor0.update();
+ sensor1.update();
+
+ _delay(200);
+ Serial.print(sensor0.getAngle());
+ Serial.print(" - ");
+ Serial.print(sensor1.getAngle());
+ Serial.println();
+}
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/utils/sensor_test/magnetic_sensors/magnetic_sensor_i2c/magnetic_sensor_i2c_dual_bus_examples/stm32_i2c_dual_bus_example/stm32_i2c_dual_bus_example.ino b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/utils/sensor_test/magnetic_sensors/magnetic_sensor_i2c/magnetic_sensor_i2c_dual_bus_examples/stm32_i2c_dual_bus_example/stm32_i2c_dual_bus_example.ino
new file mode 100644
index 0000000..08fb145
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/utils/sensor_test/magnetic_sensors/magnetic_sensor_i2c/magnetic_sensor_i2c_dual_bus_examples/stm32_i2c_dual_bus_example/stm32_i2c_dual_bus_example.ino
@@ -0,0 +1,39 @@
+#include
+
+/** Annoyingly some i2c sensors (e.g. AS5600) have a fixed chip address. This means only one of these devices can be addressed on a single bus
+ * This example shows how a second i2c bus can be used to communicate with a second sensor.
+ */
+
+MagneticSensorI2C sensor0 = MagneticSensorI2C(AS5600_I2C);
+MagneticSensorI2C sensor1 = MagneticSensorI2C(AS5600_I2C);
+
+// example of stm32 defining 2nd bus
+TwoWire Wire1(PB11, PB10);
+
+
+void setup() {
+
+ Serial.begin(115200);
+ _delay(750);
+
+ Wire.setClock(400000);
+ Wire1.setClock(400000);
+
+ sensor0.init();
+ sensor1.init(&Wire1);
+}
+
+void loop() {
+ // iterative function updating the sensor internal variables
+ // it is usually called in motor.loopFOC()
+ // this function reads the sensor hardware and
+ // has to be called before getAngle nad getVelocity
+ sensor0.update();
+ sensor1.update();
+
+ _delay(200);
+ Serial.print(sensor0.getAngle());
+ Serial.print(" - ");
+ Serial.print(sensor1.getAngle());
+ Serial.println();
+}
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/utils/sensor_test/magnetic_sensors/magnetic_sensor_i2c/magnetic_sensor_i2c_example/magnetic_sensor_i2c_example.ino b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/utils/sensor_test/magnetic_sensors/magnetic_sensor_i2c/magnetic_sensor_i2c_example/magnetic_sensor_i2c_example.ino
new file mode 100644
index 0000000..4e060c0
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/utils/sensor_test/magnetic_sensors/magnetic_sensor_i2c/magnetic_sensor_i2c_example/magnetic_sensor_i2c_example.ino
@@ -0,0 +1,43 @@
+#include
+
+// MagneticSensorI2C(uint8_t _chip_address, float _cpr, uint8_t _angle_register_msb)
+// chip_address I2C chip address
+// bit_resolution resolution of the sensor
+// angle_register_msb angle read register msb
+// bits_used_msb number of used bits in msb register
+//
+// make sure to read the chip address and the chip angle register msb value from the datasheet
+// also in most cases you will need external pull-ups on SDA and SCL lines!!!!!
+//
+// For AS5058B
+// MagneticSensorI2C sensor = MagneticSensorI2C(0x40, 14, 0xFE, 8);
+
+// Example of AS5600 configuration
+MagneticSensorI2C sensor = MagneticSensorI2C(AS5600_I2C);
+
+
+void setup() {
+ // monitoring port
+ Serial.begin(115200);
+
+ // configure i2C
+ Wire.setClock(400000);
+ // initialise magnetic sensor hardware
+ sensor.init();
+
+ Serial.println("Sensor ready");
+ _delay(1000);
+}
+
+void loop() {
+ // iterative function updating the sensor internal variables
+ // it is usually called in motor.loopFOC()
+ // this function reads the sensor hardware and
+ // has to be called before getAngle nad getVelocity
+ sensor.update();
+
+ // display the angle and the angular velocity to the terminal
+ Serial.print(sensor.getAngle());
+ Serial.print("\t");
+ Serial.println(sensor.getVelocity());
+}
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/utils/sensor_test/magnetic_sensors/magnetic_sensor_pwm/find_raw_min_max/find_raw_min_max.ino b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/utils/sensor_test/magnetic_sensors/magnetic_sensor_pwm/find_raw_min_max/find_raw_min_max.ino
new file mode 100644
index 0000000..ac9bf04
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/utils/sensor_test/magnetic_sensors/magnetic_sensor_pwm/find_raw_min_max/find_raw_min_max.ino
@@ -0,0 +1,49 @@
+#include
+
+
+/**
+ * An example to find out the raw max and min count to be provided to the constructor
+ * SPin your motor/sensor/magnet to see what is the maximum output of the sensor and what is the minimum value
+ * And replace values 4 and 904 with new values. Once when you replace them make sure there is no jump in the angle reading sensor.getAngle().
+ * If there is a jump that means you can still find better values.
+ */
+MagneticSensorPWM sensor = MagneticSensorPWM(2, 4, 904);
+void doPWM(){sensor.handlePWM();}
+
+void setup() {
+ // monitoring port
+ Serial.begin(115200);
+
+ // initialise magnetic sensor hardware
+ sensor.init();
+ // comment out to use sensor in blocking (non-interrupt) way
+ sensor.enableInterrupt(doPWM);
+
+ Serial.println("Sensor ready");
+ _delay(1000);
+}
+
+int max_pulse= 0;
+int min_pulse = 10000;
+
+void loop() {
+ // iterative function updating the sensor internal variables
+ // it is usually called in motor.loopFOC()
+ // this function reads the sensor hardware and
+ // has to be called before getAngle nad getVelocity
+ sensor.update();
+
+ // keep track of min and max
+ if(sensor.pulse_length_us > max_pulse) max_pulse = sensor.pulse_length_us;
+ else if(sensor.pulse_length_us < min_pulse) min_pulse = sensor.pulse_length_us;
+
+ // display the raw count, and max and min raw count
+ Serial.print("angle:");
+ Serial.print(sensor.getAngle());
+ Serial.print("\t, raw:");
+ Serial.print(sensor.pulse_length_us);
+ Serial.print("\t, min:");
+ Serial.print(min_pulse);
+ Serial.print("\t, max:");
+ Serial.println(max_pulse);
+}
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/utils/sensor_test/magnetic_sensors/magnetic_sensor_pwm/magnetic_sensor_pwm_example/magnetic_sensor_pwm_example.ino b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/utils/sensor_test/magnetic_sensors/magnetic_sensor_pwm/magnetic_sensor_pwm_example/magnetic_sensor_pwm_example.ino
new file mode 100644
index 0000000..6ae0a3e
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/utils/sensor_test/magnetic_sensors/magnetic_sensor_pwm/magnetic_sensor_pwm_example/magnetic_sensor_pwm_example.ino
@@ -0,0 +1,38 @@
+#include
+
+
+/**
+ * Magnetic sensor reading pwm signal on pin 2. The pwm duty cycle is proportional to the sensor angle.
+ *
+ * MagneticSensorPWM(uint8_t MagneticSensorPWM, int _min, int _max)
+ * - pinPWM - the pin that is reading the pwm from magnetic sensor
+ * - min_raw_count - the smallest expected reading. Whilst you might expect it to be 0 it is often ~5. Getting this wrong results in a small click once per revolution
+ * - max_raw_count - the largest value read. whilst you might expect it to be 1kHz = 1000 it is often ~910. depending on the exact frequency and saturation
+ */
+MagneticSensorPWM sensor = MagneticSensorPWM(2, 4, 904);
+void doPWM(){sensor.handlePWM();}
+
+void setup() {
+ // monitoring port
+ Serial.begin(115200);
+
+ // initialise magnetic sensor hardware
+ sensor.init();
+ // comment out to use sensor in blocking (non-interrupt) way
+ sensor.enableInterrupt(doPWM);
+
+ Serial.println("Sensor ready");
+ _delay(1000);
+}
+
+void loop() {
+ // iterative function updating the sensor internal variables
+ // it is usually called in motor.loopFOC()
+ // this function reads the sensor hardware and
+ // has to be called before getAngle nad getVelocity
+ sensor.update();
+ // display the angle and the angular velocity to the terminal
+ Serial.print(sensor.getAngle());
+ Serial.print("\t");
+ Serial.println(sensor.getVelocity());
+}
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/utils/sensor_test/magnetic_sensors/magnetic_sensor_pwm/magnetic_sensor_pwm_software_interrupt/magnetic_sensor_pwm_software_interrupt.ino b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/utils/sensor_test/magnetic_sensors/magnetic_sensor_pwm/magnetic_sensor_pwm_software_interrupt/magnetic_sensor_pwm_software_interrupt.ino
new file mode 100644
index 0000000..10dc8a6
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/utils/sensor_test/magnetic_sensors/magnetic_sensor_pwm/magnetic_sensor_pwm_software_interrupt/magnetic_sensor_pwm_software_interrupt.ino
@@ -0,0 +1,44 @@
+#include
+
+// software interrupt library
+#include
+#include
+
+/**
+ * Magnetic sensor reading analog voltage on pin which does not have hardware interrupt support. Such as A0.
+ *
+ * MagneticSensorPWM(uint8_t MagneticSensorPWM, int _min, int _max)
+ * - pinPWM - the pin that is reading the pwm from magnetic sensor
+ * - min_raw_count - the smallest expected reading. Whilst you might expect it to be 0 it is often ~5. Getting this wrong results in a small click once per revolution
+ * - max_raw_count - the largest value read. whilst you might expect it to be 1kHz = 1000 it is often ~910. depending on the exact frequency and saturation
+ */
+MagneticSensorPWM sensor = MagneticSensorPWM(A0, 4, 904);
+void doPWM(){sensor.handlePWM();}
+
+// encoder interrupt init
+PciListenerImp listenerPWM(sensor.pinPWM, doPWM);
+
+void setup() {
+ // monitoring port
+ Serial.begin(115200);
+
+ // initialise magnetic sensor hardware
+ sensor.init();
+ // comment out to use sensor in blocking (non-interrupt) way
+ PciManager.registerListener(&listenerPWM);
+
+ Serial.println("Sensor ready");
+ _delay(1000);
+}
+
+void loop() {
+ // iterative function updating the sensor internal variables
+ // it is usually called in motor.loopFOC()
+ // this function reads the sensor hardware and
+ // has to be called before getAngle nad getVelocity
+ sensor.update();
+ // display the angle and the angular velocity to the terminal
+ Serial.print(sensor.getAngle());
+ Serial.print("\t");
+ Serial.println(sensor.getVelocity());
+}
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/utils/sensor_test/magnetic_sensors/magnetic_sensor_spi/magnetic_sensor_spi_alternative_examples/esp32_spi_alt_example/esp32_spi_alt_example.ino b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/utils/sensor_test/magnetic_sensors/magnetic_sensor_spi/magnetic_sensor_spi_alternative_examples/esp32_spi_alt_example/esp32_spi_alt_example.ino
new file mode 100644
index 0000000..cbb72af
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/utils/sensor_test/magnetic_sensors/magnetic_sensor_spi/magnetic_sensor_spi_alternative_examples/esp32_spi_alt_example/esp32_spi_alt_example.ino
@@ -0,0 +1,41 @@
+#include
+
+// alternative pinout
+#define HSPI_MISO 12
+#define HSPI_MOSI 13
+#define HSPI_SCLK 14
+#define HSPI_SS 15
+
+// MagneticSensorSPI(int cs, float _cpr, int _angle_register)
+// config - SPI config
+// cs - SPI chip select pin
+MagneticSensorSPI sensor = MagneticSensorSPI(AS5147_SPI, HSPI_SS);
+
+// for esp 32, it has 2 spi interfaces VSPI (default) and HPSI as the second one
+// to enable it instatiate the object
+SPIClass SPI_2(HSPI);
+
+void setup() {
+ // monitoring port
+ Serial.begin(115200);
+
+ // start the newly defined spi communication
+ SPI_2.begin(HSPI_SCLK, HSPI_MISO, HSPI_MOSI, HSPI_SS); //SCLK, MISO, MOSI, SS
+ // initialise magnetic sensor hardware
+ sensor.init(&SPI_2);
+
+ Serial.println("Sensor ready");
+ _delay(1000);
+}
+
+void loop() {
+ // iterative function updating the sensor internal variables
+ // it is usually called in motor.loopFOC()
+ // this function reads the sensor hardware and
+ // has to be called before getAngle nad getVelocity
+ sensor.update();
+ // display the angle and the angular velocity to the terminal
+ Serial.print(sensor.getAngle());
+ Serial.print("\t");
+ Serial.println(sensor.getVelocity());
+}
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/utils/sensor_test/magnetic_sensors/magnetic_sensor_spi/magnetic_sensor_spi_alternative_examples/stm32_spi_alt_example/stm32_spi_alt_example.ino b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/utils/sensor_test/magnetic_sensors/magnetic_sensor_spi/magnetic_sensor_spi_alternative_examples/stm32_spi_alt_example/stm32_spi_alt_example.ino
new file mode 100644
index 0000000..713a19b
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/utils/sensor_test/magnetic_sensors/magnetic_sensor_spi/magnetic_sensor_spi_alternative_examples/stm32_spi_alt_example/stm32_spi_alt_example.ino
@@ -0,0 +1,32 @@
+#include
+
+// MagneticSensorSPI(int cs, float _cpr, int _angle_register)
+// config - SPI config
+// cs - SPI chip select pin
+MagneticSensorSPI sensor = MagneticSensorSPI(AS5147_SPI, PA15);
+
+// these are valid pins (mosi, miso, sclk) for 2nd SPI bus on storm32 board (stm32f107rc)
+SPIClass SPI_2(PB15, PB14, PB13);
+
+void setup() {
+ // monitoring port
+ Serial.begin(115200);
+
+ // initialise magnetic sensor hardware
+ sensor.init(&SPI_2);
+
+ Serial.println("Sensor ready");
+ _delay(1000);
+}
+
+void loop() {
+ // iterative function updating the sensor internal variables
+ // it is usually called in motor.loopFOC()
+ // this function reads the sensor hardware and
+ // has to be called before getAngle nad getVelocity
+ sensor.update();
+ // display the angle and the angular velocity to the terminal
+ Serial.print(sensor.getAngle());
+ Serial.print("\t");
+ Serial.println(sensor.getVelocity());
+}
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/utils/sensor_test/magnetic_sensors/magnetic_sensor_spi/magnetic_sensor_spi_example/magnetic_sensor_spi_example.ino b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/utils/sensor_test/magnetic_sensors/magnetic_sensor_spi/magnetic_sensor_spi_example/magnetic_sensor_spi_example.ino
new file mode 100644
index 0000000..048620a
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/examples/utils/sensor_test/magnetic_sensors/magnetic_sensor_spi/magnetic_sensor_spi_example/magnetic_sensor_spi_example.ino
@@ -0,0 +1,32 @@
+#include
+
+// MagneticSensorSPI(MagneticSensorSPIConfig_s config, int cs)
+// config - SPI config
+// cs - SPI chip select pin
+// magnetic sensor instance - SPI
+MagneticSensorSPI sensor = MagneticSensorSPI(AS5147_SPI, 10);
+// alternative constructor (chipselsect, bit_resolution, angle_read_register, )
+// MagneticSensorSPI sensor = MagneticSensorSPI(10, 14, 0x3FFF);
+
+void setup() {
+ // monitoring port
+ Serial.begin(115200);
+
+ // initialise magnetic sensor hardware
+ sensor.init();
+
+ Serial.println("Sensor ready");
+ _delay(1000);
+}
+
+void loop() {
+ // iterative function updating the sensor internal variables
+ // it is usually called in motor.loopFOC()
+ // this function reads the sensor hardware and
+ // has to be called before getAngle nad getVelocity
+ sensor.update();
+ // display the angle and the angular velocity to the terminal
+ Serial.print(sensor.getAngle());
+ Serial.print("\t");
+ Serial.println(sensor.getVelocity());
+}
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/keywords.txt b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/keywords.txt
new file mode 100644
index 0000000..d8fd3e7
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/keywords.txt
@@ -0,0 +1,252 @@
+ArduinoFOC KEYWORD1
+SimpleFOC KEYWORD1
+BLDCMotor KEYWORD1
+FOCMotor KEYWORD1
+StepperMotor KEYWORD1
+Encoder KEYWORD1
+HallSensors KEYWORD1
+MagneticSensorSPI KEYWORD1
+MagneticSensorI2C KEYWORD1
+MagneticSensorAnalog KEYWORD1
+MagneticSensorPWM KEYWORD1
+BLDCDriver3PWM KEYWORD1
+BLDCDriver6PWM KEYWORD1
+BLDCDriver KEYWORD1
+StepperDriver4PWM KEYWORD1
+StepperDriver2PWM KEYWORD1
+StepperDriver KEYWORD1
+PIDController KEYWORD1
+LowPassFilter KEYWORD1
+InlineCurrentSense KEYWORD1
+LowsideCurrentSense KEYWORD1
+CurrentSense KEYWORD1
+Commander KEYWORD1
+StepDirListener KEYWORD1
+GenericCurrentSense KEYWORD1
+GenericSensor KEYWORD1
+SimpleFOCDebug KEYWORD1
+
+initFOC KEYWORD2
+loopFOC KEYWORD2
+disable KEYWORD2
+
+_delay KEYWORD3
+_sqrt KEYWORD3
+_micros KEYWORD3
+_sin KEYWORD3
+_cos KEYWORD3
+_setPwmFrequency KEYWORD3
+_writeDutyCycle KEYWORD3
+_round KEYWORD3
+_sign KEYWORD3
+_constrain KEYWORD3
+monitor KEYWORD3
+command KEYWORD3
+
+PID_velocity KEYWORD2
+PID_current_q KEYWORD2
+PID_current_d KEYWORD2
+LPF_velocity KEYWORD2
+LPF_current_q KEYWORD2
+LPF_current_d KEYWORD2
+P_angle KEYWORD2
+LPF_angle KEYWORD2
+lpf_a KEYWORD2
+lpf_b KEYWORD2
+lpf_c KEYWORD2
+
+MotionControlType KEYWORD1
+TorqueControlType KEYWORD1
+FOCModulationType KEYWORD2
+Quadrature KEYWORD1
+Pullup KEYWORD1
+Direction KEYWORD1
+MagneticSensorI2CConfig_s KEYWORD1
+MagneticSensorSPIConfig_s KEYWORD1
+DQVoltage_s KEYWORD1
+DQCurrent_s KEYWORD1
+PhaseCurrent_s KEYWORD1
+
+linkDriver KEYWORD2
+linkSensor KEYWORD2
+linkCurrentSense KEYWORD2
+handleA KEYWORD2
+handleB KEYWORD2
+handleIndex KEYWORD2
+handleC KEYWORD2
+enableInterrupts KEYWORD2
+ISR KEYWORD2
+getVelocity KEYWORD2
+setPhaseVoltage KEYWORD2
+getAngle KEYWORD2
+getMechanicalAngle KEYWORD2
+getSensorAngle KEYWORD2
+update KEYWORD2
+needsSearch KEYWORD2
+useMonitoring KEYWORD2
+angleOpenloop KEYWORD2
+velocityOpenloop KEYWORD2
+getPhaseCurrents KEYWORD2
+getFOCCurrents KEYWORD2
+getDCCurrent KEYWORD2
+setPwm KEYWORD2
+driverAlign KEYWORD2
+linkDriver KEYWORD2
+add KEYWORD2
+run KEYWORD2
+attach KEYWORD2
+enableInterrupt KEYWORD2
+getValue KEYWORD2
+handle KEYWORD2
+scalar KEYWORD2
+pid KEYWORD2
+lpf KEYWORD2
+motor KEYWORD2
+handlePWM KEYWORD2
+enableInterrupt KEYWORD2
+readCallback KEYWORD2
+initCallback KEYWORD2
+
+
+
+current KEYWORD2
+current_measured KEYWORD2
+shaft_angle_sp KEYWORD2
+electrical_angle KEYWORD2
+shaft_velocity_sp KEYWORD2
+shaft_angle KEYWORD2
+shaft_velocity KEYWORD2
+torque_controller KEYWORD2
+controller KEYWORD2
+pullup KEYWORD2
+quadrature KEYWORD2
+foc_modulation KEYWORD2
+target KEYWORD2
+motion KEYWORD2
+pwm_frequency KEYWORD2
+dead_zone KEYWORD2
+gain_a KEYWORD2
+gain_b KEYWORD2
+gain_c KEYWORD2
+skip_align KEYWORD2
+sensor_direction KEYWORD2
+sensor_offset KEYWORD2
+zero_electric_angle KEYWORD2
+verbose KEYWORD2
+verboseMode KEYWORD1
+decimal_places KEYWORD2
+phase_resistance KEYWORD2
+phase_inductance KEYWORD2
+modulation_centered KEYWORD2
+
+
+
+voltage KEYWORD2
+velocity KEYWORD2
+velocity_openloop KEYWORD2
+angle KEYWORD2
+angle_openloop KEYWORD2
+torque KEYWORD2
+dc_current KEYWORD2
+foc_current KEYWORD2
+
+
+ON KEYWORD2
+OFF KEYWORD2
+CW KEYWORD2
+CCW KEYWORD2
+UNKNOWN KEYWORD2
+
+P KEYWORD2
+I KEYWORD2
+D KEYWORD2
+Tf KEYWORD2
+voltage_limit KEYWORD2
+current_limit KEYWORD2
+output_ramp KEYWORD2
+limit KEYWORD2
+velocity_limit KEYWORD2
+voltage_power_supply KEYWORD2
+voltage_sensor_align KEYWORD2
+velocity_index_search KEYWORD2
+monitor_downsample KEYWORD2
+monitor_start_char KEYWORD2
+monitor_end_char KEYWORD2
+monitor_separator KEYWORD2
+monitor_decimals KEYWORD2
+monitor_variables KEYWORD2
+motion_downsample KEYWORD2
+
+pinA KEYWORD2
+pinB KEYWORD2
+pinC KEYWORD2
+index_pin KEYWORD2
+
+USE_INTERN KEYWORD2
+USE_EXTERN KEYWORD2
+DISABLE KEYWORD2
+ENABLE KEYWORD2
+SpaceVectorPWM KEYWORD2
+SinePWM KEYWORD2
+Trapezoid_120 KEYWORD2
+Trapezoid_150 KEYWORD2
+
+pwmA KEYWORD2
+pwmB KEYWORD2
+pwmC KEYWORD2
+pwm1A KEYWORD2
+pwm1B KEYWORD2
+pwm2A KEYWORD2
+pwm2B KEYWORD2
+Ualpha KEYWORD2
+Ubeta KEYWORD2
+Ua KEYWORD2
+Ub KEYWORD2
+Uc KEYWORD2
+enable_pin KEYWORD2
+enable_pin1 KEYWORD2
+enable_pin2 KEYWORD2
+pole_pairs KEYWORD2
+dc_a KEYWORD2
+dc_b KEYWORD2
+dc_c KEYWORD2
+
+DEF_POWER_SUPPLY LITERAL1
+DEF_PID_VEL_P LITERAL1
+DEF_PID_VEL_I LITERAL1
+DEF_PID_VEL_D LITERAL1
+DEF_PID_VEL_RAMP LITERAL1
+DEF_P_ANGLE_P LITERAL1
+DEF_PID_VEL_LIMIT LITERAL1
+DEF_INDEX_SEARCH_TARGET_VELOCITY LITERAL1
+DEF_VOLTAGE_SENSOR_ALIGN LITERAL1
+DEF_VEL_FILTER_Tf LITERAL1
+DEF_CURRENT_LIM LITERAL1
+DEF_CURR_FILTER_Tf LITERAL1
+DEF_PID_CURR_LIMIT LITERAL1
+DEF_PID_CURR_RAMP LITERAL1
+DEF_PID_CURR_D LITERAL1
+DEF_PID_CURR_I LITERAL1
+DEF_PID_CURR_P LITERAL1
+_2_SQRT3 LITERAL1
+_1_SQRT3 LITERAL1
+_SQRT3_2 LITERAL1
+_SQRT2 LITERAL1
+_120_D2R LITERAL1
+_PI_2 LITERAL1
+_PI_6 LITERAL1
+_2PI LITERAL1
+_3PI_2 LITERAL1
+_PI_3 LITERAL1
+_SQRT3 LITERAL1
+_PI LITERAL1
+_HIGH_Z LITERAL1
+_NC LITERAL1
+
+_MON_TARGET LITERAL1
+_MON_VOLT_Q LITERAL1
+_MON_VOLT_D LITERAL1
+_MON_CURR_Q LITERAL1
+_MON_CURR_D LITERAL1
+_MON_VEL LITERAL1
+_MON_ANGLE LITERAL1
\ No newline at end of file
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/library.properties b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/library.properties
new file mode 100644
index 0000000..5daa49d
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/library.properties
@@ -0,0 +1,10 @@
+name=Simple FOC
+version=2.3.4
+author=Simplefoc
+maintainer=Simplefoc
+sentence=A library demistifying FOC for BLDC motors
+paragraph=Simple library intended for hobby comunity to run the BLDC and Stepper motor using FOC algorithm. It is intended to support as many BLDC/Stepper motor+sensor+driver combinations as possible and in the same time maintain simplicity of usage. Library supports Arudino devices such as Arduino UNO, MEGA, NANO and similar, stm32 boards such as Nucleo and Bluepill, ESP32 and Teensy boards.
+category=Device Control
+url=https://docs.simplefoc.com
+architectures=*
+includes=SimpleFOC.h
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/BLDCMotor.cpp b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/BLDCMotor.cpp
new file mode 100644
index 0000000..501a8bc
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/BLDCMotor.cpp
@@ -0,0 +1,684 @@
+#include "BLDCMotor.h"
+#include "./communication/SimpleFOCDebug.h"
+
+
+// see https://www.youtube.com/watch?v=InzXA7mWBWE Slide 5
+// each is 60 degrees with values for 3 phases of 1=positive -1=negative 0=high-z
+int trap_120_map[6][3] = {
+ {_HIGH_IMPEDANCE,1,-1},
+ {-1,1,_HIGH_IMPEDANCE},
+ {-1,_HIGH_IMPEDANCE,1},
+ {_HIGH_IMPEDANCE,-1,1},
+ {1,-1,_HIGH_IMPEDANCE},
+ {1,_HIGH_IMPEDANCE,-1}
+};
+
+// see https://www.youtube.com/watch?v=InzXA7mWBWE Slide 8
+// each is 30 degrees with values for 3 phases of 1=positive -1=negative 0=high-z
+int trap_150_map[12][3] = {
+ {_HIGH_IMPEDANCE,1,-1},
+ {-1,1,-1},
+ {-1,1,_HIGH_IMPEDANCE},
+ {-1,1,1},
+ {-1,_HIGH_IMPEDANCE,1},
+ {-1,-1,1},
+ {_HIGH_IMPEDANCE,-1,1},
+ {1,-1,1},
+ {1,-1,_HIGH_IMPEDANCE},
+ {1,-1,-1},
+ {1,_HIGH_IMPEDANCE,-1},
+ {1,1,-1}
+};
+
+// BLDCMotor( int pp , float R)
+// - pp - pole pair number
+// - R - motor phase resistance
+// - KV - motor kv rating (rmp/v)
+// - L - motor phase inductance
+BLDCMotor::BLDCMotor(int pp, float _R, float _KV, float _inductance)
+: FOCMotor()
+{
+ // save pole pairs number
+ pole_pairs = pp;
+ // save phase resistance number
+ phase_resistance = _R;
+ // save back emf constant KV = 1/KV
+ // 1/sqrt(2) - rms value
+ KV_rating = NOT_SET;
+ if (_isset(_KV))
+ KV_rating = _KV;
+ // save phase inductance
+ phase_inductance = _inductance;
+
+ // torque control type is voltage by default
+ torque_controller = TorqueControlType::voltage;
+}
+
+
+/**
+ Link the driver which controls the motor
+*/
+void BLDCMotor::linkDriver(BLDCDriver* _driver) {
+ driver = _driver;
+}
+
+// init hardware pins
+int BLDCMotor::init() {
+ if (!driver || !driver->initialized) {
+ motor_status = FOCMotorStatus::motor_init_failed;
+ SIMPLEFOC_DEBUG("MOT: Init not possible, driver not initialized");
+ return 0;
+ }
+ motor_status = FOCMotorStatus::motor_initializing;
+ SIMPLEFOC_DEBUG("MOT: Init");
+
+ // sanity check for the voltage limit configuration
+ if(voltage_limit > driver->voltage_limit) voltage_limit = driver->voltage_limit;
+ // constrain voltage for sensor alignment
+ if(voltage_sensor_align > voltage_limit) voltage_sensor_align = voltage_limit;
+
+ // update the controller limits
+ if(current_sense){
+ // current control loop controls voltage
+ PID_current_q.limit = voltage_limit;
+ PID_current_d.limit = voltage_limit;
+ }
+ if(_isset(phase_resistance) || torque_controller != TorqueControlType::voltage){
+ // velocity control loop controls current
+ PID_velocity.limit = current_limit;
+ }else{
+ // velocity control loop controls the voltage
+ PID_velocity.limit = voltage_limit;
+ }
+ P_angle.limit = velocity_limit;
+
+ // if using open loop control, set a CW as the default direction if not already set
+ if ((controller==MotionControlType::angle_openloop
+ ||controller==MotionControlType::velocity_openloop)
+ && (sensor_direction == Direction::UNKNOWN)) {
+ sensor_direction = Direction::CW;
+ }
+
+ _delay(500);
+ // enable motor
+ SIMPLEFOC_DEBUG("MOT: Enable driver.");
+ enable();
+ _delay(500);
+ motor_status = FOCMotorStatus::motor_uncalibrated;
+ return 1;
+}
+
+
+// disable motor driver
+void BLDCMotor::disable()
+{
+ // disable the current sense
+ if(current_sense) current_sense->disable();
+ // set zero to PWM
+ driver->setPwm(0, 0, 0);
+ // disable the driver
+ driver->disable();
+ // motor status update
+ enabled = 0;
+}
+// enable motor driver
+void BLDCMotor::enable()
+{
+ // enable the driver
+ driver->enable();
+ // set zero to PWM
+ driver->setPwm(0, 0, 0);
+ // enable the current sense
+ if(current_sense) current_sense->enable();
+ // reset the pids
+ PID_velocity.reset();
+ P_angle.reset();
+ PID_current_q.reset();
+ PID_current_d.reset();
+ // motor status update
+ enabled = 1;
+}
+
+/**
+ FOC functions
+*/
+// FOC initialization function
+int BLDCMotor::initFOC() {
+ int exit_flag = 1;
+
+ motor_status = FOCMotorStatus::motor_calibrating;
+
+ // align motor if necessary
+ // alignment necessary for encoders!
+ // sensor and motor alignment - can be skipped
+ // by setting motor.sensor_direction and motor.zero_electric_angle
+ if(sensor){
+ exit_flag *= alignSensor();
+ // added the shaft_angle update
+ sensor->update();
+ shaft_angle = shaftAngle();
+
+ // aligning the current sensor - can be skipped
+ // checks if driver phases are the same as current sense phases
+ // and checks the direction of measuremnt.
+ if(exit_flag){
+ if(current_sense){
+ if (!current_sense->initialized) {
+ motor_status = FOCMotorStatus::motor_calib_failed;
+ SIMPLEFOC_DEBUG("MOT: Init FOC error, current sense not initialized");
+ exit_flag = 0;
+ }else{
+ exit_flag *= alignCurrentSense();
+ }
+ }
+ else { SIMPLEFOC_DEBUG("MOT: No current sense."); }
+ }
+
+ } else {
+ SIMPLEFOC_DEBUG("MOT: No sensor.");
+ if ((controller == MotionControlType::angle_openloop || controller == MotionControlType::velocity_openloop)){
+ exit_flag = 1;
+ SIMPLEFOC_DEBUG("MOT: Openloop only!");
+ }else{
+ exit_flag = 0; // no FOC without sensor
+ }
+ }
+
+ if(exit_flag){
+ SIMPLEFOC_DEBUG("MOT: Ready.");
+ motor_status = FOCMotorStatus::motor_ready;
+ }else{
+ SIMPLEFOC_DEBUG("MOT: Init FOC failed.");
+ motor_status = FOCMotorStatus::motor_calib_failed;
+ disable();
+ }
+
+ return exit_flag;
+}
+
+// Calibarthe the motor and current sense phases
+int BLDCMotor::alignCurrentSense() {
+ int exit_flag = 1; // success
+
+ SIMPLEFOC_DEBUG("MOT: Align current sense.");
+
+ // align current sense and the driver
+ exit_flag = current_sense->driverAlign(voltage_sensor_align, modulation_centered);
+ if(!exit_flag){
+ // error in current sense - phase either not measured or bad connection
+ SIMPLEFOC_DEBUG("MOT: Align error!");
+ exit_flag = 0;
+ }else{
+ // output the alignment status flag
+ SIMPLEFOC_DEBUG("MOT: Success: ", exit_flag);
+ }
+
+ return exit_flag > 0;
+}
+
+// Encoder alignment to electrical 0 angle
+int BLDCMotor::alignSensor() {
+ int exit_flag = 1; //success
+ SIMPLEFOC_DEBUG("MOT: Align sensor.");
+
+ // check if sensor needs zero search
+ if(sensor->needsSearch()) exit_flag = absoluteZeroSearch();
+ // stop init if not found index
+ if(!exit_flag) return exit_flag;
+
+ // v2.3.3 fix for R_AVR_7_PCREL against symbol" bug for AVR boards
+ // TODO figure out why this works
+ float voltage_align = voltage_sensor_align;
+
+ // if unknown natural direction
+ if(sensor_direction==Direction::UNKNOWN){
+
+ // find natural direction
+ // move one electrical revolution forward
+ for (int i = 0; i <=500; i++ ) {
+ float angle = _3PI_2 + _2PI * i / 500.0f;
+ setPhaseVoltage(voltage_align, 0, angle);
+ sensor->update();
+ _delay(2);
+ }
+ // take and angle in the middle
+ sensor->update();
+ float mid_angle = sensor->getAngle();
+ // move one electrical revolution backwards
+ for (int i = 500; i >=0; i-- ) {
+ float angle = _3PI_2 + _2PI * i / 500.0f ;
+ setPhaseVoltage(voltage_align, 0, angle);
+ sensor->update();
+ _delay(2);
+ }
+ sensor->update();
+ float end_angle = sensor->getAngle();
+ // setPhaseVoltage(0, 0, 0);
+ _delay(200);
+ // determine the direction the sensor moved
+ float moved = fabs(mid_angle - end_angle);
+ if (moved 0.5f); // 0.5f is arbitrary number it can be lower or higher!
+ if( pp_check_result==false ) {
+ SIMPLEFOC_DEBUG("MOT: PP check: fail - estimated pp: ", _2PI/moved);
+ } else {
+ SIMPLEFOC_DEBUG("MOT: PP check: OK!");
+ }
+
+ } else { SIMPLEFOC_DEBUG("MOT: Skip dir calib."); }
+
+ // zero electric angle not known
+ if(!_isset(zero_electric_angle)){
+ // align the electrical phases of the motor and sensor
+ // set angle -90(270 = 3PI/2) degrees
+ setPhaseVoltage(voltage_align, 0, _3PI_2);
+ _delay(700);
+ // read the sensor
+ sensor->update();
+ // get the current zero electric angle
+ zero_electric_angle = 0;
+ zero_electric_angle = electricalAngle();
+ //zero_electric_angle = _normalizeAngle(_electricalAngle(sensor_direction*sensor->getAngle(), pole_pairs));
+ _delay(20);
+ if(monitor_port){
+ SIMPLEFOC_DEBUG("MOT: Zero elec. angle: ", zero_electric_angle);
+ }
+ // stop everything
+ setPhaseVoltage(0, 0, 0);
+ _delay(200);
+ } else { SIMPLEFOC_DEBUG("MOT: Skip offset calib."); }
+ return exit_flag;
+}
+
+// Encoder alignment the absolute zero angle
+// - to the index
+int BLDCMotor::absoluteZeroSearch() {
+ // sensor precision: this is all ok, as the search happens near the 0-angle, where the precision
+ // of float is sufficient.
+ SIMPLEFOC_DEBUG("MOT: Index search...");
+ // search the absolute zero with small velocity
+ float limit_vel = velocity_limit;
+ float limit_volt = voltage_limit;
+ velocity_limit = velocity_index_search;
+ voltage_limit = voltage_sensor_align;
+ shaft_angle = 0;
+ while(sensor->needsSearch() && shaft_angle < _2PI){
+ angleOpenloop(1.5f*_2PI);
+ // call important for some sensors not to loose count
+ // not needed for the search
+ sensor->update();
+ }
+ // disable motor
+ setPhaseVoltage(0, 0, 0);
+ // reinit the limits
+ velocity_limit = limit_vel;
+ voltage_limit = limit_volt;
+ // check if the zero found
+ if(monitor_port){
+ if(sensor->needsSearch()) { SIMPLEFOC_DEBUG("MOT: Error: Not found!"); }
+ else { SIMPLEFOC_DEBUG("MOT: Success!"); }
+ }
+ return !sensor->needsSearch();
+}
+
+// Iterative function looping FOC algorithm, setting Uq on the Motor
+// The faster it can be run the better
+void BLDCMotor::loopFOC() {
+ // update sensor - do this even in open-loop mode, as user may be switching between modes and we could lose track
+ // of full rotations otherwise.
+ if (sensor) sensor->update();
+
+ // if open-loop do nothing
+ if( controller==MotionControlType::angle_openloop || controller==MotionControlType::velocity_openloop ) return;
+
+ // if disabled do nothing
+ if(!enabled) return;
+
+ // Needs the update() to be called first
+ // This function will not have numerical issues because it uses Sensor::getMechanicalAngle()
+ // which is in range 0-2PI
+ electrical_angle = electricalAngle();
+ switch (torque_controller) {
+ case TorqueControlType::voltage:
+ // no need to do anything really
+ break;
+ case TorqueControlType::dc_current:
+ if(!current_sense) return;
+ // read overall current magnitude
+ current.q = current_sense->getDCCurrent(electrical_angle);
+ // filter the value values
+ current.q = LPF_current_q(current.q);
+ // calculate the phase voltage
+ voltage.q = PID_current_q(current_sp - current.q);
+ // d voltage - lag compensation
+ if(_isset(phase_inductance)) voltage.d = _constrain( -current_sp*shaft_velocity*pole_pairs*phase_inductance, -voltage_limit, voltage_limit);
+ else voltage.d = 0;
+ break;
+ case TorqueControlType::foc_current:
+ if(!current_sense) return;
+ // read dq currents
+ current = current_sense->getFOCCurrents(electrical_angle);
+ // filter values
+ current.q = LPF_current_q(current.q);
+ current.d = LPF_current_d(current.d);
+ // calculate the phase voltages
+ voltage.q = PID_current_q(current_sp - current.q);
+ voltage.d = PID_current_d(-current.d);
+ // d voltage - lag compensation - TODO verify
+ // if(_isset(phase_inductance)) voltage.d = _constrain( voltage.d - current_sp*shaft_velocity*pole_pairs*phase_inductance, -voltage_limit, voltage_limit);
+ break;
+ default:
+ // no torque control selected
+ SIMPLEFOC_DEBUG("MOT: no torque control selected!");
+ break;
+ }
+
+ // set the phase voltage - FOC heart function :)
+ setPhaseVoltage(voltage.q, voltage.d, electrical_angle);
+}
+
+// Iterative function running outer loop of the FOC algorithm
+// Behavior of this function is determined by the motor.controller variable
+// It runs either angle, velocity or torque loop
+// - needs to be called iteratively it is asynchronous function
+// - if target is not set it uses motor.target value
+void BLDCMotor::move(float new_target) {
+
+ // set internal target variable
+ if(_isset(new_target)) target = new_target;
+
+ // downsampling (optional)
+ if(motion_cnt++ < motion_downsample) return;
+ motion_cnt = 0;
+
+ // shaft angle/velocity need the update() to be called first
+ // get shaft angle
+ // TODO sensor precision: the shaft_angle actually stores the complete position, including full rotations, as a float
+ // For this reason it is NOT precise when the angles become large.
+ // Additionally, the way LPF works on angle is a precision issue, and the angle-LPF is a problem
+ // when switching to a 2-component representation.
+ if( controller!=MotionControlType::angle_openloop && controller!=MotionControlType::velocity_openloop )
+ shaft_angle = shaftAngle(); // read value even if motor is disabled to keep the monitoring updated but not in openloop mode
+ // get angular velocity TODO the velocity reading probably also shouldn't happen in open loop modes?
+ shaft_velocity = shaftVelocity(); // read value even if motor is disabled to keep the monitoring updated
+
+ // if disabled do nothing
+ if(!enabled) return;
+
+ // calculate the back-emf voltage if KV_rating available U_bemf = vel*(1/KV)
+ if (_isset(KV_rating)) voltage_bemf = shaft_velocity/(KV_rating*_SQRT3)/_RPM_TO_RADS;
+ // estimate the motor current if phase reistance available and current_sense not available
+ if(!current_sense && _isset(phase_resistance)) current.q = (voltage.q - voltage_bemf)/phase_resistance;
+
+ // upgrade the current based voltage limit
+ switch (controller) {
+ case MotionControlType::torque:
+ if(torque_controller == TorqueControlType::voltage){ // if voltage torque control
+ if(!_isset(phase_resistance)) voltage.q = target;
+ else voltage.q = target*phase_resistance + voltage_bemf;
+ voltage.q = _constrain(voltage.q, -voltage_limit, voltage_limit);
+ // set d-component (lag compensation if known inductance)
+ if(!_isset(phase_inductance)) voltage.d = 0;
+ else voltage.d = _constrain( -target*shaft_velocity*pole_pairs*phase_inductance, -voltage_limit, voltage_limit);
+ }else{
+ current_sp = target; // if current/foc_current torque control
+ }
+ break;
+ case MotionControlType::angle:
+ // TODO sensor precision: this calculation is not numerically precise. The target value cannot express precise positions when
+ // the angles are large. This results in not being able to command small changes at high position values.
+ // to solve this, the delta-angle has to be calculated in a numerically precise way.
+ // angle set point
+ shaft_angle_sp = target;
+ // calculate velocity set point
+ shaft_velocity_sp = feed_forward_velocity + P_angle( shaft_angle_sp - shaft_angle );
+ shaft_velocity_sp = _constrain(shaft_velocity_sp,-velocity_limit, velocity_limit);
+ // calculate the torque command - sensor precision: this calculation is ok, but based on bad value from previous calculation
+ current_sp = PID_velocity(shaft_velocity_sp - shaft_velocity); // if voltage torque control
+ // if torque controlled through voltage
+ if(torque_controller == TorqueControlType::voltage){
+ // use voltage if phase-resistance not provided
+ if(!_isset(phase_resistance)) voltage.q = current_sp;
+ else voltage.q = _constrain( current_sp*phase_resistance + voltage_bemf , -voltage_limit, voltage_limit);
+ // set d-component (lag compensation if known inductance)
+ if(!_isset(phase_inductance)) voltage.d = 0;
+ else voltage.d = _constrain( -current_sp*shaft_velocity*pole_pairs*phase_inductance, -voltage_limit, voltage_limit);
+ }
+ break;
+ case MotionControlType::velocity:
+ // velocity set point - sensor precision: this calculation is numerically precise.
+ shaft_velocity_sp = target;
+ // calculate the torque command
+ current_sp = PID_velocity(shaft_velocity_sp - shaft_velocity); // if current/foc_current torque control
+ // if torque controlled through voltage control
+ if(torque_controller == TorqueControlType::voltage){
+ // use voltage if phase-resistance not provided
+ if(!_isset(phase_resistance)) voltage.q = current_sp;
+ else voltage.q = _constrain( current_sp*phase_resistance + voltage_bemf , -voltage_limit, voltage_limit);
+ // set d-component (lag compensation if known inductance)
+ if(!_isset(phase_inductance)) voltage.d = 0;
+ else voltage.d = _constrain( -current_sp*shaft_velocity*pole_pairs*phase_inductance, -voltage_limit, voltage_limit);
+ }
+ break;
+ case MotionControlType::velocity_openloop:
+ // velocity control in open loop - sensor precision: this calculation is numerically precise.
+ shaft_velocity_sp = target;
+ voltage.q = velocityOpenloop(shaft_velocity_sp); // returns the voltage that is set to the motor
+ voltage.d = 0;
+ break;
+ case MotionControlType::angle_openloop:
+ // angle control in open loop -
+ // TODO sensor precision: this calculation NOT numerically precise, and subject
+ // to the same problems in small set-point changes at high angles
+ // as the closed loop version.
+ shaft_angle_sp = target;
+ voltage.q = angleOpenloop(shaft_angle_sp); // returns the voltage that is set to the motor
+ voltage.d = 0;
+ break;
+ }
+}
+
+
+// Method using FOC to set Uq and Ud to the motor at the optimal angle
+// Function implementing Space Vector PWM and Sine PWM algorithms
+//
+// Function using sine approximation
+// regular sin + cos ~300us (no memory usage)
+// approx _sin + _cos ~110us (400Byte ~ 20% of memory)
+void BLDCMotor::setPhaseVoltage(float Uq, float Ud, float angle_el) {
+
+ float center;
+ int sector;
+ float _ca,_sa;
+
+ switch (foc_modulation)
+ {
+ case FOCModulationType::Trapezoid_120 :
+ // see https://www.youtube.com/watch?v=InzXA7mWBWE Slide 5
+ // determine the sector
+ sector = 6 * (_normalizeAngle(angle_el + _PI_6 ) / _2PI); // adding PI/6 to align with other modes
+ // centering the voltages around either
+ // modulation_centered == true > driver.voltage_limit/2
+ // modulation_centered == false > or Adaptable centering, all phases drawn to 0 when Uq=0
+ center = modulation_centered ? (driver->voltage_limit)/2 : Uq;
+
+ if(trap_120_map[sector][0] == _HIGH_IMPEDANCE){
+ Ua= center;
+ Ub = trap_120_map[sector][1] * Uq + center;
+ Uc = trap_120_map[sector][2] * Uq + center;
+ driver->setPhaseState(PhaseState::PHASE_OFF, PhaseState::PHASE_ON, PhaseState::PHASE_ON); // disable phase if possible
+ }else if(trap_120_map[sector][1] == _HIGH_IMPEDANCE){
+ Ua = trap_120_map[sector][0] * Uq + center;
+ Ub = center;
+ Uc = trap_120_map[sector][2] * Uq + center;
+ driver->setPhaseState(PhaseState::PHASE_ON, PhaseState::PHASE_OFF, PhaseState::PHASE_ON);// disable phase if possible
+ }else{
+ Ua = trap_120_map[sector][0] * Uq + center;
+ Ub = trap_120_map[sector][1] * Uq + center;
+ Uc = center;
+ driver->setPhaseState(PhaseState::PHASE_ON, PhaseState::PHASE_ON, PhaseState::PHASE_OFF);// disable phase if possible
+ }
+
+ break;
+
+ case FOCModulationType::Trapezoid_150 :
+ // see https://www.youtube.com/watch?v=InzXA7mWBWE Slide 8
+ // determine the sector
+ sector = 12 * (_normalizeAngle(angle_el + _PI_6 ) / _2PI); // adding PI/6 to align with other modes
+ // centering the voltages around either
+ // modulation_centered == true > driver.voltage_limit/2
+ // modulation_centered == false > or Adaptable centering, all phases drawn to 0 when Uq=0
+ center = modulation_centered ? (driver->voltage_limit)/2 : Uq;
+
+ if(trap_150_map[sector][0] == _HIGH_IMPEDANCE){
+ Ua= center;
+ Ub = trap_150_map[sector][1] * Uq + center;
+ Uc = trap_150_map[sector][2] * Uq + center;
+ driver->setPhaseState(PhaseState::PHASE_OFF, PhaseState::PHASE_ON, PhaseState::PHASE_ON); // disable phase if possible
+ }else if(trap_150_map[sector][1] == _HIGH_IMPEDANCE){
+ Ua = trap_150_map[sector][0] * Uq + center;
+ Ub = center;
+ Uc = trap_150_map[sector][2] * Uq + center;
+ driver->setPhaseState(PhaseState::PHASE_ON, PhaseState::PHASE_OFF, PhaseState::PHASE_ON); // disable phase if possible
+ }else if(trap_150_map[sector][2] == _HIGH_IMPEDANCE){
+ Ua = trap_150_map[sector][0] * Uq + center;
+ Ub = trap_150_map[sector][1] * Uq + center;
+ Uc = center;
+ driver->setPhaseState(PhaseState::PHASE_ON, PhaseState::PHASE_ON, PhaseState::PHASE_OFF); // disable phase if possible
+ }else{
+ Ua = trap_150_map[sector][0] * Uq + center;
+ Ub = trap_150_map[sector][1] * Uq + center;
+ Uc = trap_150_map[sector][2] * Uq + center;
+ driver->setPhaseState(PhaseState::PHASE_ON, PhaseState::PHASE_ON, PhaseState::PHASE_ON); // enable all phases
+ }
+
+ break;
+
+ case FOCModulationType::SinePWM :
+ case FOCModulationType::SpaceVectorPWM :
+ // Sinusoidal PWM modulation
+ // Inverse Park + Clarke transformation
+ _sincos(angle_el, &_sa, &_ca);
+
+ // Inverse park transform
+ Ualpha = _ca * Ud - _sa * Uq; // -sin(angle) * Uq;
+ Ubeta = _sa * Ud + _ca * Uq; // cos(angle) * Uq;
+
+ // Clarke transform
+ Ua = Ualpha;
+ Ub = -0.5f * Ualpha + _SQRT3_2 * Ubeta;
+ Uc = -0.5f * Ualpha - _SQRT3_2 * Ubeta;
+
+ center = driver->voltage_limit/2;
+ if (foc_modulation == FOCModulationType::SpaceVectorPWM){
+ // discussed here: https://community.simplefoc.com/t/embedded-world-2023-stm32-cordic-co-processor/3107/165?u=candas1
+ // a bit more info here: https://microchipdeveloper.com/mct5001:which-zsm-is-best
+ // Midpoint Clamp
+ float Umin = min(Ua, min(Ub, Uc));
+ float Umax = max(Ua, max(Ub, Uc));
+ center -= (Umax+Umin) / 2;
+ }
+
+ if (!modulation_centered) {
+ float Umin = min(Ua, min(Ub, Uc));
+ Ua -= Umin;
+ Ub -= Umin;
+ Uc -= Umin;
+ }else{
+ Ua += center;
+ Ub += center;
+ Uc += center;
+ }
+
+ break;
+
+ }
+
+ // set the voltages in driver
+ driver->setPwm(Ua, Ub, Uc);
+}
+
+
+
+// Function (iterative) generating open loop movement for target velocity
+// - target_velocity - rad/s
+// it uses voltage_limit variable
+float BLDCMotor::velocityOpenloop(float target_velocity){
+ // get current timestamp
+ unsigned long now_us = _micros();
+ // calculate the sample time from last call
+ float Ts = (now_us - open_loop_timestamp) * 1e-6f;
+ // quick fix for strange cases (micros overflow + timestamp not defined)
+ if(Ts <= 0 || Ts > 0.5f) Ts = 1e-3f;
+
+ // calculate the necessary angle to achieve target velocity
+ shaft_angle = _normalizeAngle(shaft_angle + target_velocity*Ts);
+ // for display purposes
+ shaft_velocity = target_velocity;
+
+ // use voltage limit or current limit
+ float Uq = voltage_limit;
+ if(_isset(phase_resistance)){
+ Uq = _constrain(current_limit*phase_resistance + fabs(voltage_bemf),-voltage_limit, voltage_limit);
+ // recalculate the current
+ current.q = (Uq - fabs(voltage_bemf))/phase_resistance;
+ }
+ // set the maximal allowed voltage (voltage_limit) with the necessary angle
+ setPhaseVoltage(Uq, 0, _electricalAngle(shaft_angle, pole_pairs));
+
+ // save timestamp for next call
+ open_loop_timestamp = now_us;
+
+ return Uq;
+}
+
+// Function (iterative) generating open loop movement towards the target angle
+// - target_angle - rad
+// it uses voltage_limit and velocity_limit variables
+float BLDCMotor::angleOpenloop(float target_angle){
+ // get current timestamp
+ unsigned long now_us = _micros();
+ // calculate the sample time from last call
+ float Ts = (now_us - open_loop_timestamp) * 1e-6f;
+ // quick fix for strange cases (micros overflow + timestamp not defined)
+ if(Ts <= 0 || Ts > 0.5f) Ts = 1e-3f;
+
+ // calculate the necessary angle to move from current position towards target angle
+ // with maximal velocity (velocity_limit)
+ // TODO sensor precision: this calculation is not numerically precise. The angle can grow to the point
+ // where small position changes are no longer captured by the precision of floats
+ // when the total position is large.
+ if(abs( target_angle - shaft_angle ) > abs(velocity_limit*Ts)){
+ shaft_angle += _sign(target_angle - shaft_angle) * abs( velocity_limit )*Ts;
+ shaft_velocity = velocity_limit;
+ }else{
+ shaft_angle = target_angle;
+ shaft_velocity = 0;
+ }
+
+ // use voltage limit or current limit
+ float Uq = voltage_limit;
+ if(_isset(phase_resistance)){
+ Uq = _constrain(current_limit*phase_resistance + fabs(voltage_bemf),-voltage_limit, voltage_limit);
+ // recalculate the current
+ current.q = (Uq - fabs(voltage_bemf))/phase_resistance;
+ }
+ // set the maximal allowed voltage (voltage_limit) with the necessary angle
+ // sensor precision: this calculation is OK due to the normalisation
+ setPhaseVoltage(Uq, 0, _electricalAngle(_normalizeAngle(shaft_angle), pole_pairs));
+
+ // save timestamp for next call
+ open_loop_timestamp = now_us;
+
+ return Uq;
+}
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/BLDCMotor.h b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/BLDCMotor.h
new file mode 100644
index 0000000..c261e40
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/BLDCMotor.h
@@ -0,0 +1,115 @@
+#ifndef BLDCMotor_h
+#define BLDCMotor_h
+
+#include "Arduino.h"
+#include "common/base_classes/FOCMotor.h"
+#include "common/base_classes/Sensor.h"
+#include "common/base_classes/FOCDriver.h"
+#include "common/base_classes/BLDCDriver.h"
+#include "common/foc_utils.h"
+#include "common/time_utils.h"
+#include "common/defaults.h"
+
+/**
+ BLDC motor class
+*/
+class BLDCMotor: public FOCMotor
+{
+ public:
+ /**
+ BLDCMotor class constructor
+ @param pp pole pairs number
+ @param R motor phase resistance - [Ohm]
+ @param KV motor KV rating (1/K_bemf) - rpm/V
+ @param L motor phase inductance - [H]
+ */
+ BLDCMotor(int pp, float R = NOT_SET, float KV = NOT_SET, float L = NOT_SET);
+
+ /**
+ * Function linking a motor and a foc driver
+ *
+ * @param driver BLDCDriver class implementing all the hardware specific functions necessary PWM setting
+ */
+ virtual void linkDriver(BLDCDriver* driver);
+
+ /**
+ * BLDCDriver link:
+ * - 3PWM
+ * - 6PWM
+ */
+ BLDCDriver* driver;
+
+ /** Motor hardware init function */
+ int init() override;
+ /** Motor disable function */
+ void disable() override;
+ /** Motor enable function */
+ void enable() override;
+
+ /**
+ * Function initializing FOC algorithm
+ * and aligning sensor's and motors' zero position
+ */
+ int initFOC() override;
+ /**
+ * Function running FOC algorithm in real-time
+ * it calculates the gets motor angle and sets the appropriate voltages
+ * to the phase pwm signals
+ * - the faster you can run it the better Arduino UNO ~1ms, Bluepill ~ 100us
+ */
+ void loopFOC() override;
+
+ /**
+ * Function executing the control loops set by the controller parameter of the BLDCMotor.
+ *
+ * @param target Either voltage, angle or velocity based on the motor.controller
+ * If it is not set the motor will use the target set in its variable motor.target
+ *
+ * This function doesn't need to be run upon each loop execution - depends of the use case
+ */
+ void move(float target = NOT_SET) override;
+
+ float Ua, Ub, Uc;//!< Current phase voltages Ua,Ub and Uc set to motor
+
+ /**
+ * Method using FOC to set Uq to the motor at the optimal angle
+ * Heart of the FOC algorithm
+ *
+ * @param Uq Current voltage in q axis to set to the motor
+ * @param Ud Current voltage in d axis to set to the motor
+ * @param angle_el current electrical angle of the motor
+ */
+ void setPhaseVoltage(float Uq, float Ud, float angle_el) override;
+
+ private:
+ // FOC methods
+
+ /** Sensor alignment to electrical 0 angle of the motor */
+ int alignSensor();
+ /** Current sense and motor phase alignment */
+ int alignCurrentSense();
+ /** Motor and sensor alignment to the sensors absolute 0 angle */
+ int absoluteZeroSearch();
+
+
+ // Open loop motion control
+ /**
+ * Function (iterative) generating open loop movement for target velocity
+ * it uses voltage_limit variable
+ *
+ * @param target_velocity - rad/s
+ */
+ float velocityOpenloop(float target_velocity);
+ /**
+ * Function (iterative) generating open loop movement towards the target angle
+ * it uses voltage_limit and velocity_limit variables
+ *
+ * @param target_angle - rad
+ */
+ float angleOpenloop(float target_angle);
+ // open loop variables
+ long open_loop_timestamp;
+};
+
+
+#endif
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/SimpleFOC.h b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/SimpleFOC.h
new file mode 100644
index 0000000..4e6815e
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/SimpleFOC.h
@@ -0,0 +1,119 @@
+/*!
+ * @file SimpleFOC.h
+ *
+ * @mainpage Simple Field Oriented Control BLDC motor control library
+ *
+ * @section intro_sec Introduction
+ *
+ * Proper low-cost and low-power FOC supporting boards are very hard to find these days and even may not exist.
Even harder to find is a stable and simple FOC algorithm code capable of running on Arduino devices. Therefore this is an attempt to:
+ * - Demystify FOC algorithm and make a robust but simple Arduino library: Arduino SimpleFOC library
+ * - Develop a modular BLDC driver board: Arduino SimpleFOC shield.
+ *
+ * @section features Features
+ * - Arduino compatible: Arduino library code
+ * - Easy to setup and configure:
+ * - Easy hardware configuration
+ * - Easy tuning the control loops
+ * - Modular:
+ * - Supports as many sensors , BLDC motors and driver boards as possible
+ * - Supports as many application requirements as possible
+ * - Plug & play: Arduino SimpleFOC shield
+ *
+ * @section dependencies Supported Hardware
+ * - Motors
+ * - BLDC motors
+ * - Stepper motors
+ * - Drivers
+ * - BLDC drivers
+ * - Gimbal drivers
+ * - Stepper drivers
+ * - Position sensors
+ * - Encoders
+ * - Magnetic sensors
+ * - Hall sensors
+ * - Open-loop control
+ * - Microcontrollers
+ * - Arduino
+ * - STM32
+ * - ESP32
+ * - Teensy
+ *
+ * @section example_code Example code
+ * @code
+#include
+
+// BLDCMotor( pole_pairs )
+BLDCMotor motor = BLDCMotor(11);
+// BLDCDriver( pin_pwmA, pin_pwmB, pin_pwmC, enable (optional) )
+BLDCDriver3PWM driver = BLDCDriver3PWM(9, 10, 11, 8);
+// Encoder(pin_A, pin_B, CPR)
+Encoder encoder = Encoder(2, 3, 2048);
+// channel A and B callbacks
+void doA(){encoder.handleA();}
+void doB(){encoder.handleB();}
+
+
+void setup() {
+ // initialize encoder hardware
+ encoder.init();
+ // hardware interrupt enable
+ encoder.enableInterrupts(doA, doB);
+ // link the motor to the sensor
+ motor.linkSensor(&encoder);
+
+ // power supply voltage [V]
+ driver.voltage_power_supply = 12;
+ // initialise driver hardware
+ driver.init();
+ // link driver
+ motor.linkDriver(&driver);
+
+ // set control loop type to be used
+ motor.controller = MotionControlType::velocity;
+ // initialize motor
+ motor.init();
+
+ // align encoder and start FOC
+ motor.initFOC();
+}
+
+void loop() {
+ // FOC algorithm function
+ motor.loopFOC();
+
+ // velocity control loop function
+ // setting the target velocity or 2rad/s
+ motor.move(2);
+}
+ * @endcode
+ *
+ * @section license License
+ *
+ * MIT license, all text here must be included in any redistribution.
+ *
+ */
+
+#ifndef SIMPLEFOC_H
+#define SIMPLEFOC_H
+
+#include "BLDCMotor.h"
+#include "StepperMotor.h"
+#include "sensors/Encoder.h"
+#include "sensors/MagneticSensorSPI.h"
+#include "sensors/MagneticSensorI2C.h"
+#include "sensors/MagneticSensorAnalog.h"
+#include "sensors/MagneticSensorPWM.h"
+#include "sensors/HallSensor.h"
+#include "sensors/GenericSensor.h"
+#include "drivers/BLDCDriver3PWM.h"
+#include "drivers/BLDCDriver6PWM.h"
+#include "drivers/StepperDriver4PWM.h"
+#include "drivers/StepperDriver2PWM.h"
+#include "current_sense/InlineCurrentSense.h"
+#include "current_sense/LowsideCurrentSense.h"
+#include "current_sense/GenericCurrentSense.h"
+#include "communication/Commander.h"
+#include "communication/StepDirListener.h"
+#include "communication/SimpleFOCDebug.h"
+
+#endif
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/StepperMotor.cpp b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/StepperMotor.cpp
new file mode 100644
index 0000000..1d8f314
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/StepperMotor.cpp
@@ -0,0 +1,539 @@
+#include "StepperMotor.h"
+#include "./communication/SimpleFOCDebug.h"
+
+
+// StepperMotor(int pp)
+// - pp - pole pair number
+// - R - motor phase resistance
+// - KV - motor kv rating (rmp/v)
+// - L - motor phase inductance [H]
+StepperMotor::StepperMotor(int pp, float _R, float _KV, float _inductance)
+: FOCMotor()
+{
+ // number od pole pairs
+ pole_pairs = pp;
+ // save phase resistance number
+ phase_resistance = _R;
+ // save back emf constant KV = 1/K_bemf
+ // usually used rms
+ KV_rating = _KV;
+ // save phase inductance
+ phase_inductance = _inductance;
+
+ // torque control type is voltage by default
+ // current and foc_current not supported yet
+ torque_controller = TorqueControlType::voltage;
+}
+
+/**
+ Link the driver which controls the motor
+*/
+void StepperMotor::linkDriver(StepperDriver* _driver) {
+ driver = _driver;
+}
+
+// init hardware pins
+int StepperMotor::init() {
+ if (!driver || !driver->initialized) {
+ motor_status = FOCMotorStatus::motor_init_failed;
+ SIMPLEFOC_DEBUG("MOT: Init not possible, driver not initialized");
+ return 0;
+ }
+ motor_status = FOCMotorStatus::motor_initializing;
+ SIMPLEFOC_DEBUG("MOT: Init");
+
+ // sanity check for the voltage limit configuration
+ if(voltage_limit > driver->voltage_limit) voltage_limit = driver->voltage_limit;
+ // constrain voltage for sensor alignment
+ if(voltage_sensor_align > voltage_limit) voltage_sensor_align = voltage_limit;
+
+ // update the controller limits
+ if(_isset(phase_resistance)){
+ // velocity control loop controls current
+ PID_velocity.limit = current_limit;
+ }else{
+ PID_velocity.limit = voltage_limit;
+ }
+ P_angle.limit = velocity_limit;
+
+ // if using open loop control, set a CW as the default direction if not already set
+ if ((controller==MotionControlType::angle_openloop
+ ||controller==MotionControlType::velocity_openloop)
+ && (sensor_direction == Direction::UNKNOWN)) {
+ sensor_direction = Direction::CW;
+ }
+
+ _delay(500);
+ // enable motor
+ SIMPLEFOC_DEBUG("MOT: Enable driver.");
+ enable();
+ _delay(500);
+
+ motor_status = FOCMotorStatus::motor_uncalibrated;
+ return 1;
+}
+
+
+// disable motor driver
+void StepperMotor::disable()
+{
+ // set zero to PWM
+ driver->setPwm(0, 0);
+ // disable driver
+ driver->disable();
+ // motor status update
+ enabled = 0;
+}
+// enable motor driver
+void StepperMotor::enable()
+{
+ // disable enable
+ driver->enable();
+ // set zero to PWM
+ driver->setPwm(0, 0);
+ // motor status update
+ enabled = 1;
+}
+
+
+/**
+ FOC functions
+*/
+// FOC initialization function
+int StepperMotor::initFOC() {
+ int exit_flag = 1;
+
+ motor_status = FOCMotorStatus::motor_calibrating;
+
+ // align motor if necessary
+ // alignment necessary for encoders!
+ // sensor and motor alignment - can be skipped
+ // by setting motor.sensor_direction and motor.zero_electric_angle
+ if(sensor){
+ exit_flag *= alignSensor();
+ // added the shaft_angle update
+ sensor->update();
+ shaft_angle = shaftAngle();
+
+ // aligning the current sensor - can be skipped
+ // checks if driver phases are the same as current sense phases
+ // and checks the direction of measuremnt.
+ if(exit_flag){
+ if(current_sense){
+ if (!current_sense->initialized) {
+ motor_status = FOCMotorStatus::motor_calib_failed;
+ SIMPLEFOC_DEBUG("MOT: Init FOC error, current sense not initialized");
+ exit_flag = 0;
+ }else{
+ exit_flag *= alignCurrentSense();
+ }
+ }
+ else { SIMPLEFOC_DEBUG("MOT: No current sense."); }
+ }
+
+ } else {
+ SIMPLEFOC_DEBUG("MOT: No sensor.");
+ if ((controller == MotionControlType::angle_openloop || controller == MotionControlType::velocity_openloop)){
+ exit_flag = 1;
+ SIMPLEFOC_DEBUG("MOT: Openloop only!");
+ }else{
+ exit_flag = 0; // no FOC without sensor
+ }
+ }
+
+ if(exit_flag){
+ SIMPLEFOC_DEBUG("MOT: Ready.");
+ motor_status = FOCMotorStatus::motor_ready;
+ }else{
+ SIMPLEFOC_DEBUG("MOT: Init FOC failed.");
+ motor_status = FOCMotorStatus::motor_calib_failed;
+ disable();
+ }
+
+ return exit_flag;
+}
+
+// Calibrate the motor and current sense phases
+int StepperMotor::alignCurrentSense() {
+ int exit_flag = 1; // success
+
+ SIMPLEFOC_DEBUG("MOT: Align current sense.");
+
+ // align current sense and the driver
+ exit_flag = current_sense->driverAlign(voltage_sensor_align, modulation_centered);
+ if(!exit_flag){
+ // error in current sense - phase either not measured or bad connection
+ SIMPLEFOC_DEBUG("MOT: Align error!");
+ exit_flag = 0;
+ }else{
+ // output the alignment status flag
+ SIMPLEFOC_DEBUG("MOT: Success: ", exit_flag);
+ }
+
+ return exit_flag > 0;
+}
+
+// Encoder alignment to electrical 0 angle
+int StepperMotor::alignSensor() {
+ int exit_flag = 1; //success
+ SIMPLEFOC_DEBUG("MOT: Align sensor.");
+
+ // v2.3.3 fix for R_AVR_7_PCREL against symbol" bug for AVR boards
+ // TODO figure out why this works
+ float voltage_align = voltage_sensor_align;
+
+ // if unknown natural direction
+ if(sensor_direction == Direction::UNKNOWN){
+ // check if sensor needs zero search
+ if(sensor->needsSearch()) exit_flag = absoluteZeroSearch();
+ // stop init if not found index
+ if(!exit_flag) return exit_flag;
+
+ // find natural direction
+ // move one electrical revolution forward
+ for (int i = 0; i <=500; i++ ) {
+ float angle = _3PI_2 + _2PI * i / 500.0f;
+ setPhaseVoltage(voltage_align, 0, angle);
+ sensor->update();
+ _delay(2);
+ }
+ // take and angle in the middle
+ sensor->update();
+ float mid_angle = sensor->getAngle();
+ // move one electrical revolution backwards
+ for (int i = 500; i >=0; i-- ) {
+ float angle = _3PI_2 + _2PI * i / 500.0f ;
+ setPhaseVoltage(voltage_align, 0, angle);
+ sensor->update();
+ _delay(2);
+ }
+ sensor->update();
+ float end_angle = sensor->getAngle();
+ setPhaseVoltage(0, 0, 0);
+ _delay(200);
+ // determine the direction the sensor moved
+ if (mid_angle == end_angle) {
+ SIMPLEFOC_DEBUG("MOT: Failed to notice movement");
+ return 0; // failed calibration
+ } else if (mid_angle < end_angle) {
+ SIMPLEFOC_DEBUG("MOT: sensor_direction==CCW");
+ sensor_direction = Direction::CCW;
+ } else{
+ SIMPLEFOC_DEBUG("MOT: sensor_direction==CW");
+ sensor_direction = Direction::CW;
+ }
+ // check pole pair number
+ float moved = fabs(mid_angle - end_angle);
+ pp_check_result = !(fabs(moved*pole_pairs - _2PI) > 0.5f); // 0.5f is arbitrary number it can be lower or higher!
+ if( pp_check_result==false ) {
+ SIMPLEFOC_DEBUG("MOT: PP check: fail - estimated pp: ", _2PI/moved);
+ } else {
+ SIMPLEFOC_DEBUG("MOT: PP check: OK!");
+ }
+
+ } else {
+ SIMPLEFOC_DEBUG("MOT: Skip dir calib.");
+ }
+
+ // zero electric angle not known
+ if(!_isset(zero_electric_angle)){
+ // align the electrical phases of the motor and sensor
+ // set angle -90(270 = 3PI/2) degrees
+ setPhaseVoltage(voltage_align, 0, _3PI_2);
+ _delay(700);
+ // read the sensor
+ sensor->update();
+ // get the current zero electric angle
+ zero_electric_angle = 0;
+ zero_electric_angle = electricalAngle();
+ _delay(20);
+ if(monitor_port){
+ SIMPLEFOC_DEBUG("MOT: Zero elec. angle: ", zero_electric_angle);
+ }
+ // stop everything
+ setPhaseVoltage(0, 0, 0);
+ _delay(200);
+ } else { SIMPLEFOC_DEBUG("MOT: Skip offset calib."); }
+ return exit_flag;
+}
+
+// Encoder alignment the absolute zero angle
+// - to the index
+int StepperMotor::absoluteZeroSearch() {
+
+ SIMPLEFOC_DEBUG("MOT: Index search...");
+ // search the absolute zero with small velocity
+ float limit_vel = velocity_limit;
+ float limit_volt = voltage_limit;
+ velocity_limit = velocity_index_search;
+ voltage_limit = voltage_sensor_align;
+ shaft_angle = 0;
+ while(sensor->needsSearch() && shaft_angle < _2PI){
+ angleOpenloop(1.5f*_2PI);
+ // call important for some sensors not to loose count
+ // not needed for the search
+ sensor->update();
+ }
+ // disable motor
+ setPhaseVoltage(0, 0, 0);
+ // reinit the limits
+ velocity_limit = limit_vel;
+ voltage_limit = limit_volt;
+ // check if the zero found
+ if(monitor_port){
+ if(sensor->needsSearch()) SIMPLEFOC_DEBUG("MOT: Error: Not found!");
+ else { SIMPLEFOC_DEBUG("MOT: Success!"); }
+ }
+ return !sensor->needsSearch();
+}
+
+
+// Iterative function looping FOC algorithm, setting Uq on the Motor
+// The faster it can be run the better
+void StepperMotor::loopFOC() {
+
+ // update sensor - do this even in open-loop mode, as user may be switching between modes and we could lose track
+ // of full rotations otherwise.
+ if (sensor) sensor->update();
+
+ // if open-loop do nothing
+ if( controller==MotionControlType::angle_openloop || controller==MotionControlType::velocity_openloop ) return;
+
+ // if disabled do nothing
+ if(!enabled) return;
+
+ // Needs the update() to be called first
+ // This function will not have numerical issues because it uses Sensor::getMechanicalAngle()
+ // which is in range 0-2PI
+ electrical_angle = electricalAngle();
+ switch (torque_controller) {
+ case TorqueControlType::voltage:
+ // no need to do anything really
+ break;
+ case TorqueControlType::dc_current:
+ if(!current_sense) return;
+ // read overall current magnitude
+ current.q = current_sense->getDCCurrent(electrical_angle);
+ // filter the value values
+ current.q = LPF_current_q(current.q);
+ // calculate the phase voltage
+ voltage.q = PID_current_q(current_sp - current.q);
+ // d voltage - lag compensation
+ if(_isset(phase_inductance)) voltage.d = _constrain( -current_sp*shaft_velocity*pole_pairs*phase_inductance, -voltage_limit, voltage_limit);
+ else voltage.d = 0;
+ break;
+ case TorqueControlType::foc_current:
+ if(!current_sense) return;
+ // read dq currents
+ current = current_sense->getFOCCurrents(electrical_angle);
+ // filter values
+ current.q = LPF_current_q(current.q);
+ current.d = LPF_current_d(current.d);
+ // calculate the phase voltages
+ voltage.q = PID_current_q(current_sp - current.q);
+ voltage.d = PID_current_d(-current.d);
+ // d voltage - lag compensation - TODO verify
+ // if(_isset(phase_inductance)) voltage.d = _constrain( voltage.d - current_sp*shaft_velocity*pole_pairs*phase_inductance, -voltage_limit, voltage_limit);
+ break;
+ default:
+ // no torque control selected
+ SIMPLEFOC_DEBUG("MOT: no torque control selected!");
+ break;
+ }
+ // set the phase voltage - FOC heart function :)
+ setPhaseVoltage(voltage.q, voltage.d, electrical_angle);
+}
+
+// Iterative function running outer loop of the FOC algorithm
+// Behavior of this function is determined by the motor.controller variable
+// It runs either angle, velocity or voltage loop
+// - needs to be called iteratively it is asynchronous function
+// - if target is not set it uses motor.target value
+void StepperMotor::move(float new_target) {
+
+ // set internal target variable
+ if(_isset(new_target) ) target = new_target;
+
+ // downsampling (optional)
+ if(motion_cnt++ < motion_downsample) return;
+ motion_cnt = 0;
+
+ // shaft angle/velocity need the update() to be called first
+ // get shaft angle
+ // TODO sensor precision: the shaft_angle actually stores the complete position, including full rotations, as a float
+ // For this reason it is NOT precise when the angles become large.
+ // Additionally, the way LPF works on angle is a precision issue, and the angle-LPF is a problem
+ // when switching to a 2-component representation.
+ if( controller!=MotionControlType::angle_openloop && controller!=MotionControlType::velocity_openloop )
+ shaft_angle = shaftAngle(); // read value even if motor is disabled to keep the monitoring updated but not in openloop mode
+ // get angular velocity
+ shaft_velocity = shaftVelocity(); // read value even if motor is disabled to keep the monitoring updated
+
+ // if disabled do nothing
+ if(!enabled) return;
+
+
+ // calculate the back-emf voltage if KV_rating available U_bemf = vel*(1/KV)
+ if (_isset(KV_rating)) voltage_bemf = shaft_velocity/(KV_rating*_SQRT3)/_RPM_TO_RADS;
+ // estimate the motor current if phase reistance available and current_sense not available
+ if(!current_sense && _isset(phase_resistance)) current.q = (voltage.q - voltage_bemf)/phase_resistance;
+
+ // upgrade the current based voltage limit
+ switch (controller) {
+ case MotionControlType::torque:
+ if(torque_controller == TorqueControlType::voltage){ // if voltage torque control
+ if(!_isset(phase_resistance)) voltage.q = target;
+ else voltage.q = target*phase_resistance + voltage_bemf;
+ voltage.q = _constrain(voltage.q, -voltage_limit, voltage_limit);
+ // set d-component (lag compensation if known inductance)
+ if(!_isset(phase_inductance)) voltage.d = 0;
+ else voltage.d = _constrain( -target*shaft_velocity*pole_pairs*phase_inductance, -voltage_limit, voltage_limit);
+ }else{
+ current_sp = target; // if current/foc_current torque control
+ }
+ break;
+ case MotionControlType::angle:
+ // TODO sensor precision: this calculation is not numerically precise. The target value cannot express precise positions when
+ // the angles are large. This results in not being able to command small changes at high position values.
+ // to solve this, the delta-angle has to be calculated in a numerically precise way.
+ // angle set point
+ shaft_angle_sp = target;
+ // calculate velocity set point
+ shaft_velocity_sp = feed_forward_velocity + P_angle( shaft_angle_sp - shaft_angle );
+ shaft_velocity_sp = _constrain(shaft_velocity_sp,-velocity_limit, velocity_limit);
+ // calculate the torque command - sensor precision: this calculation is ok, but based on bad value from previous calculation
+ current_sp = PID_velocity(shaft_velocity_sp - shaft_velocity); // if voltage torque control
+ // if torque controlled through voltage
+ if(torque_controller == TorqueControlType::voltage){
+ // use voltage if phase-resistance not provided
+ if(!_isset(phase_resistance)) voltage.q = current_sp;
+ else voltage.q = _constrain( current_sp*phase_resistance + voltage_bemf , -voltage_limit, voltage_limit);
+ // set d-component (lag compensation if known inductance)
+ if(!_isset(phase_inductance)) voltage.d = 0;
+ else voltage.d = _constrain( -current_sp*shaft_velocity*pole_pairs*phase_inductance, -voltage_limit, voltage_limit);
+ }
+ break;
+ case MotionControlType::velocity:
+ // velocity set point - sensor precision: this calculation is numerically precise.
+ shaft_velocity_sp = target;
+ // calculate the torque command
+ current_sp = PID_velocity(shaft_velocity_sp - shaft_velocity); // if current/foc_current torque control
+ // if torque controlled through voltage control
+ if(torque_controller == TorqueControlType::voltage){
+ // use voltage if phase-resistance not provided
+ if(!_isset(phase_resistance)) voltage.q = current_sp;
+ else voltage.q = _constrain( current_sp*phase_resistance + voltage_bemf , -voltage_limit, voltage_limit);
+ // set d-component (lag compensation if known inductance)
+ if(!_isset(phase_inductance)) voltage.d = 0;
+ else voltage.d = _constrain( -current_sp*shaft_velocity*pole_pairs*phase_inductance, -voltage_limit, voltage_limit);
+ }
+ break;
+ case MotionControlType::velocity_openloop:
+ // velocity control in open loop - sensor precision: this calculation is numerically precise.
+ shaft_velocity_sp = target;
+ voltage.q = velocityOpenloop(shaft_velocity_sp); // returns the voltage that is set to the motor
+ voltage.d = 0;
+ break;
+ case MotionControlType::angle_openloop:
+ // angle control in open loop -
+ // TODO sensor precision: this calculation NOT numerically precise, and subject
+ // to the same problems in small set-point changes at high angles
+ // as the closed loop version.
+ shaft_angle_sp = target;
+ voltage.q = angleOpenloop(shaft_angle_sp); // returns the voltage that is set to the motor
+ voltage.d = 0;
+ break;
+ }
+}
+
+
+// Method using FOC to set Uq and Ud to the motor at the optimal angle
+// Function implementing Sine PWM algorithms
+// - space vector not implemented yet
+//
+// Function using sine approximation
+// regular sin + cos ~300us (no memory usaage)
+// approx _sin + _cos ~110us (400Byte ~ 20% of memory)
+void StepperMotor::setPhaseVoltage(float Uq, float Ud, float angle_el) {
+ // Sinusoidal PWM modulation
+ // Inverse Park transformation
+ float _sa, _ca;
+ _sincos(angle_el, &_sa, &_ca);
+
+ // Inverse park transform
+ Ualpha = _ca * Ud - _sa * Uq; // -sin(angle) * Uq;
+ Ubeta = _sa * Ud + _ca * Uq; // cos(angle) * Uq;
+
+ // set the voltages in hardware
+ driver->setPwm(Ualpha, Ubeta);
+}
+
+// Function (iterative) generating open loop movement for target velocity
+// - target_velocity - rad/s
+// it uses voltage_limit variable
+float StepperMotor::velocityOpenloop(float target_velocity){
+ // get current timestamp
+ unsigned long now_us = _micros();
+ // calculate the sample time from last call
+ float Ts = (now_us - open_loop_timestamp) * 1e-6f;
+ // quick fix for strange cases (micros overflow + timestamp not defined)
+ if(Ts <= 0 || Ts > 0.5f) Ts = 1e-3f;
+
+ // calculate the necessary angle to achieve target velocity
+ shaft_angle = _normalizeAngle(shaft_angle + target_velocity*Ts);
+ // for display purposes
+ shaft_velocity = target_velocity;
+
+ // use voltage limit or current limit
+ float Uq = voltage_limit;
+ if(_isset(phase_resistance)){
+ Uq = _constrain(current_limit*phase_resistance + fabs(voltage_bemf),-voltage_limit, voltage_limit);
+ // recalculate the current
+ current.q = (Uq - fabs(voltage_bemf))/phase_resistance;
+ }
+
+ // set the maximal allowed voltage (voltage_limit) with the necessary angle
+ setPhaseVoltage(Uq, 0, _electricalAngle(shaft_angle, pole_pairs));
+
+ // save timestamp for next call
+ open_loop_timestamp = now_us;
+
+ return Uq;
+}
+
+// Function (iterative) generating open loop movement towards the target angle
+// - target_angle - rad
+// it uses voltage_limit and velocity_limit variables
+float StepperMotor::angleOpenloop(float target_angle){
+ // get current timestamp
+ unsigned long now_us = _micros();
+ // calculate the sample time from last call
+ float Ts = (now_us - open_loop_timestamp) * 1e-6f;
+ // quick fix for strange cases (micros overflow + timestamp not defined)
+ if(Ts <= 0 || Ts > 0.5f) Ts = 1e-3f;
+
+ // calculate the necessary angle to move from current position towards target angle
+ // with maximal velocity (velocity_limit)
+ if(abs( target_angle - shaft_angle ) > abs(velocity_limit*Ts)){
+ shaft_angle += _sign(target_angle - shaft_angle) * abs( velocity_limit )*Ts;
+ shaft_velocity = velocity_limit;
+ }else{
+ shaft_angle = target_angle;
+ shaft_velocity = 0;
+ }
+
+ // use voltage limit or current limit
+ float Uq = voltage_limit;
+ if(_isset(phase_resistance)){
+ Uq = _constrain(current_limit*phase_resistance + fabs(voltage_bemf),-voltage_limit, voltage_limit);
+ // recalculate the current
+ current.q = (Uq - fabs(voltage_bemf))/phase_resistance;
+ }
+ // set the maximal allowed voltage (voltage_limit) with the necessary angle
+ setPhaseVoltage(Uq, 0, _electricalAngle((shaft_angle), pole_pairs));
+
+ // save timestamp for next call
+ open_loop_timestamp = now_us;
+
+ return Uq;
+}
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/StepperMotor.h b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/StepperMotor.h
new file mode 100644
index 0000000..7e7810d
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/StepperMotor.h
@@ -0,0 +1,115 @@
+/**
+ * @file StepperMotor.h
+ *
+ */
+
+#ifndef StepperMotor_h
+#define StepperMotor_h
+
+#include "Arduino.h"
+#include "common/base_classes/FOCMotor.h"
+#include "common/base_classes/StepperDriver.h"
+#include "common/base_classes/Sensor.h"
+#include "common/foc_utils.h"
+#include "common/time_utils.h"
+#include "common/defaults.h"
+
+/**
+ Stepper Motor class
+*/
+class StepperMotor: public FOCMotor
+{
+ public:
+ /**
+ StepperMotor class constructor
+ @param pp pole pair number
+ @param R motor phase resistance - [Ohm]
+ @param KV motor KV rating (1/K_bemf) - rpm/V
+ @param L motor phase inductance - [H]
+ */
+ StepperMotor(int pp, float R = NOT_SET, float KV = NOT_SET, float L = NOT_SET);
+
+ /**
+ * Function linking a motor and a foc driver
+ *
+ * @param driver StepperDriver class implementing all the hardware specific functions necessary PWM setting
+ */
+ void linkDriver(StepperDriver* driver);
+
+ /**
+ * StepperDriver link:
+ * - 4PWM - L298N for example
+ */
+ StepperDriver* driver;
+
+ /** Motor hardware init function */
+ int init() override;
+ /** Motor disable function */
+ void disable() override;
+ /** Motor enable function */
+ void enable() override;
+
+ /**
+ * Function initializing FOC algorithm
+ * and aligning sensor's and motors' zero position
+ *
+ * - If zero_electric_offset parameter is set the alignment procedure is skipped
+ */
+ int initFOC() override;
+ /**
+ * Function running FOC algorithm in real-time
+ * it calculates the gets motor angle and sets the appropriate voltages
+ * to the phase pwm signals
+ * - the faster you can run it the better Arduino UNO ~1ms, Bluepill ~ 100us
+ */
+ void loopFOC() override;
+ /**
+ * Function executing the control loops set by the controller parameter of the StepperMotor.
+ *
+ * @param target Either voltage, angle or velocity based on the motor.controller
+ * If it is not set the motor will use the target set in its variable motor.target
+ *
+ * This function doesn't need to be run upon each loop execution - depends of the use case
+ */
+ void move(float target = NOT_SET) override;
+
+ /**
+ * Method using FOC to set Uq to the motor at the optimal angle
+ * Heart of the FOC algorithm
+ *
+ * @param Uq Current voltage in q axis to set to the motor
+ * @param Ud Current voltage in d axis to set to the motor
+ * @param angle_el current electrical angle of the motor
+ */
+ void setPhaseVoltage(float Uq, float Ud, float angle_el) override;
+
+ private:
+
+ /** Sensor alignment to electrical 0 angle of the motor */
+ int alignSensor();
+ /** Motor and sensor alignment to the sensors absolute 0 angle */
+ int absoluteZeroSearch();
+ /** Current sense and motor phase alignment */
+ int alignCurrentSense();
+
+ // Open loop motion control
+ /**
+ * Function (iterative) generating open loop movement for target velocity
+ * it uses voltage_limit variable
+ *
+ * @param target_velocity - rad/s
+ */
+ float velocityOpenloop(float target_velocity);
+ /**
+ * Function (iterative) generating open loop movement towards the target angle
+ * it uses voltage_limit and velocity_limit variables
+ *
+ * @param target_angle - rad
+ */
+ float angleOpenloop(float target_angle);
+ // open loop variables
+ long open_loop_timestamp;
+};
+
+
+#endif
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/common/base_classes/BLDCDriver.h b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/common/base_classes/BLDCDriver.h
new file mode 100644
index 0000000..6ae8186
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/common/base_classes/BLDCDriver.h
@@ -0,0 +1,36 @@
+#ifndef BLDCDRIVER_H
+#define BLDCDRIVER_H
+
+#include "Arduino.h"
+#include "FOCDriver.h"
+
+class BLDCDriver: public FOCDriver{
+ public:
+
+ float dc_a; //!< currently set duty cycle on phaseA
+ float dc_b; //!< currently set duty cycle on phaseB
+ float dc_c; //!< currently set duty cycle on phaseC
+
+ /**
+ * Set phase voltages to the hardware
+ *
+ * @param Ua - phase A voltage
+ * @param Ub - phase B voltage
+ * @param Uc - phase C voltage
+ */
+ virtual void setPwm(float Ua, float Ub, float Uc) = 0;
+
+ /**
+ * Set phase state, enable/disable
+ *
+ * @param sc - phase A state : active / disabled ( high impedance )
+ * @param sb - phase B state : active / disabled ( high impedance )
+ * @param sa - phase C state : active / disabled ( high impedance )
+ */
+ virtual void setPhaseState(PhaseState sa, PhaseState sb, PhaseState sc) = 0;
+
+ /** driver type getter function */
+ virtual DriverType type() override { return DriverType::BLDC; };
+};
+
+#endif
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/common/base_classes/CurrentSense.cpp b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/common/base_classes/CurrentSense.cpp
new file mode 100644
index 0000000..4813dc3
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/common/base_classes/CurrentSense.cpp
@@ -0,0 +1,475 @@
+#include "CurrentSense.h"
+#include "../../communication/SimpleFOCDebug.h"
+
+
+// get current magnitude
+// - absolute - if no electrical_angle provided
+// - signed - if angle provided
+float CurrentSense::getDCCurrent(float motor_electrical_angle){
+ // read current phase currents
+ PhaseCurrent_s current = getPhaseCurrents();
+
+ // calculate clarke transform
+ ABCurrent_s ABcurrent = getABCurrents(current);
+
+ // current sign - if motor angle not provided the magnitude is always positive
+ float sign = 1;
+
+ // if motor angle provided function returns signed value of the current
+ // determine the sign of the current
+ // sign(atan2(current.q, current.d)) is the same as c.q > 0 ? 1 : -1
+ if(motor_electrical_angle) {
+ float ct;
+ float st;
+ _sincos(motor_electrical_angle, &st, &ct);
+ sign = (ABcurrent.beta*ct - ABcurrent.alpha*st) > 0 ? 1 : -1;
+ }
+ // return current magnitude
+ return sign*_sqrt(ABcurrent.alpha*ABcurrent.alpha + ABcurrent.beta*ABcurrent.beta);
+}
+
+// function used with the foc algorithm
+// calculating DQ currents from phase currents
+// - function calculating park and clarke transform of the phase currents
+// - using getPhaseCurrents and getABCurrents internally
+DQCurrent_s CurrentSense::getFOCCurrents(float angle_el){
+ // read current phase currents
+ PhaseCurrent_s current = getPhaseCurrents();
+
+ // calculate clarke transform
+ ABCurrent_s ABcurrent = getABCurrents(current);
+
+ // calculate park transform
+ DQCurrent_s return_current = getDQCurrents(ABcurrent,angle_el);
+
+ return return_current;
+}
+
+// function used with the foc algorithm
+// calculating Alpha Beta currents from phase currents
+// - function calculating Clarke transform of the phase currents
+ABCurrent_s CurrentSense::getABCurrents(PhaseCurrent_s current){
+
+ // check if driver is an instance of StepperDriver
+ // if so there is no need to Clarke transform
+ if (driver_type == DriverType::Stepper){
+ ABCurrent_s return_ABcurrent;
+ return_ABcurrent.alpha = current.a;
+ return_ABcurrent.beta = current.b;
+ return return_ABcurrent;
+ }
+
+ // otherwise it's a BLDC motor and
+ // calculate clarke transform
+ float i_alpha, i_beta;
+ if(!current.c){
+ // if only two measured currents
+ i_alpha = current.a;
+ i_beta = _1_SQRT3 * current.a + _2_SQRT3 * current.b;
+ }else if(!current.a){
+ // if only two measured currents
+ float a = -current.c - current.b;
+ i_alpha = a;
+ i_beta = _1_SQRT3 * a + _2_SQRT3 * current.b;
+ }else if(!current.b){
+ // if only two measured currents
+ float b = -current.a - current.c;
+ i_alpha = current.a;
+ i_beta = _1_SQRT3 * current.a + _2_SQRT3 * b;
+ } else {
+ // signal filtering using identity a + b + c = 0. Assumes measurement error is normally distributed.
+ float mid = (1.f/3) * (current.a + current.b + current.c);
+ float a = current.a - mid;
+ float b = current.b - mid;
+ i_alpha = a;
+ i_beta = _1_SQRT3 * a + _2_SQRT3 * b;
+ }
+
+ ABCurrent_s return_ABcurrent;
+ return_ABcurrent.alpha = i_alpha;
+ return_ABcurrent.beta = i_beta;
+ return return_ABcurrent;
+}
+
+// function used with the foc algorithm
+// calculating D and Q currents from Alpha Beta currents and electrical angle
+// - function calculating Clarke transform of the phase currents
+DQCurrent_s CurrentSense::getDQCurrents(ABCurrent_s current, float angle_el){
+ // calculate park transform
+ float ct;
+ float st;
+ _sincos(angle_el, &st, &ct);
+ DQCurrent_s return_current;
+ return_current.d = current.alpha * ct + current.beta * st;
+ return_current.q = current.beta * ct - current.alpha * st;
+ return return_current;
+}
+
+/**
+ Driver linking to the current sense
+*/
+void CurrentSense::linkDriver(FOCDriver* _driver) {
+ driver = _driver;
+ // save the driver type for easier access
+ driver_type = driver->type();
+}
+
+
+void CurrentSense::enable(){
+ // nothing is done here, but you can override this function
+};
+
+void CurrentSense::disable(){
+ // nothing is done here, but you can override this function
+};
+
+
+// Function aligning the current sense with motor driver
+// if all pins are connected well none of this is really necessary! - can be avoided
+// returns flag
+// 0 - fail
+// 1 - success and nothing changed
+// 2 - success but pins reconfigured
+// 3 - success but gains inverted
+// 4 - success but pins reconfigured and gains inverted
+// IMPORTANT, this function can be overriden in the child class
+int CurrentSense::driverAlign(float voltage, bool modulation_centered){
+
+ int exit_flag = 1;
+ if(skip_align) return exit_flag;
+
+ if (!initialized) return 0;
+
+ // check if stepper or BLDC
+ if(driver_type == DriverType::Stepper)
+ return alignStepperDriver(voltage, (StepperDriver*)driver, modulation_centered);
+ else
+ return alignBLDCDriver(voltage, (BLDCDriver*)driver, modulation_centered);
+}
+
+
+
+// Helper function to read and average phase currents
+PhaseCurrent_s CurrentSense::readAverageCurrents(int N) {
+ PhaseCurrent_s c = getPhaseCurrents();
+ for (int i = 0; i < N; i++) {
+ PhaseCurrent_s c1 = getPhaseCurrents();
+ c.a = c.a * 0.6f + 0.4f * c1.a;
+ c.b = c.b * 0.6f + 0.4f * c1.b;
+ c.c = c.c * 0.6f + 0.4f * c1.c;
+ _delay(3);
+ }
+ return c;
+};
+
+
+
+// Function aligning the current sense with motor driver
+// if all pins are connected well none of this is really necessary! - can be avoided
+// returns flag
+// 0 - fail
+// 1 - success and nothing changed
+// 2 - success but pins reconfigured
+// 3 - success but gains inverted
+// 4 - success but pins reconfigured and gains inverted
+int CurrentSense::alignBLDCDriver(float voltage, BLDCDriver* bldc_driver, bool modulation_centered){
+
+ bool phases_switched = 0;
+ bool phases_inverted = 0;
+
+ float zero = 0;
+ if(modulation_centered) zero = driver->voltage_limit/2.0;
+
+ // set phase A active and phases B and C down
+ // 300 ms of ramping
+ for(int i=0; i < 100; i++){
+ bldc_driver->setPwm(voltage/100.0*((float)i)+zero , zero, zero);
+ _delay(3);
+ }
+ _delay(500);
+ PhaseCurrent_s c_a = readAverageCurrents();
+ bldc_driver->setPwm(zero, zero, zero);
+ // check if currents are to low (lower than 100mA)
+ // TODO calculate the 100mA threshold from the ADC resolution
+ // if yes throw an error and return 0
+ // either the current sense is not connected or the current is
+ // too low for calibration purposes (one should raise the motor.voltage_sensor_align)
+ if((fabs(c_a.a) < 0.1f) && (fabs(c_a.b) < 0.1f) && (fabs(c_a.c) < 0.1f)){
+ SIMPLEFOC_DEBUG("CS: Err too low current, rise voltage!");
+ return 0; // measurement current too low
+ }
+
+
+ // now we have to determine
+ // 1) which pin correspond to which phase of the bldc driver
+ // 2) if the currents measured have good polarity
+ //
+ // > when we apply a voltage to a phase A of the driver what we expect to measure is the current I on the phase A
+ // and -I/2 on the phase B and I/2 on the phase C
+
+ // find the highest magnitude in c_a
+ // and make sure it's around 2 (1.5 at least) times higher than the other two
+ float ca[3] = {fabs(c_a.a), fabs(c_a.b), fabs(c_a.c)};
+ uint8_t max_i = -1; // max index
+ float max_c = 0; // max current
+ float max_c_ratio = 0; // max current ratio
+ for(int i = 0; i < 3; i++){
+ if(!ca[i]) continue; // current not measured
+ if(ca[i] > max_c){
+ max_c = ca[i];
+ max_i = i;
+ for(int j = 0; j < 3; j++){
+ if(i == j) continue;
+ if(!ca[j]) continue; // current not measured
+ float ratio = max_c / ca[j];
+ if(ratio > max_c_ratio) max_c_ratio = ratio;
+ }
+ }
+ }
+
+ // check the current magnitude ratios
+ // 1) if there is one current that is approximately 2 times higher than the other two
+ // this is the A current
+ // 2) if the max current is not at least 1.5 times higher than the other two
+ // we have two cases:
+ // - either we only measure two currents and the third one is not measured - then phase A is not measured
+ // - or the current sense is not connected properly
+
+ if(max_c_ratio >=1.5f){
+ switch (max_i){
+ case 1: // phase B is the max current
+ SIMPLEFOC_DEBUG("CS: Switch A-B");
+ // switch phase A and B
+ _swap(pinA, pinB);
+ _swap(offset_ia, offset_ib);
+ _swap(gain_a, gain_b);
+ _swap(c_a.b, c_a.b);
+ phases_switched = true; // signal that pins have been switched
+ break;
+ case 2: // phase C is the max current
+ SIMPLEFOC_DEBUG("CS: Switch A-C");
+ // switch phase A and C
+ _swap(pinA, pinC);
+ _swap(offset_ia, offset_ic);
+ _swap(gain_a, gain_c);
+ _swap(c_a.a, c_a.c);
+ phases_switched = true;// signal that pins have been switched
+ break;
+ }
+ // check if the current is negative and invert the gain if so
+ if( _sign(c_a.a) < 0 ){
+ SIMPLEFOC_DEBUG("CS: Inv A");
+ gain_a *= -1;
+ phases_inverted = true; // signal that pins have been inverted
+ }
+ }else if(_isset(pinA) && _isset(pinB) && _isset(pinC)){
+ // if all three currents are measured and none of them is significantly higher
+ // we have a problem with the current sense
+ SIMPLEFOC_DEBUG("CS: Err A - all currents same magnitude!");
+ return 0;
+ }else{ //phase A is not measured so put the _NC to the phase A
+ if(_isset(pinA) && !_isset(pinB)){
+ SIMPLEFOC_DEBUG("CS: Switch A-(B)NC");
+ _swap(pinA, pinB);
+ _swap(offset_ia, offset_ib);
+ _swap(gain_a, gain_b);
+ _swap(c_a.b, c_a.b);
+ phases_switched = true; // signal that pins have been switched
+ }else if(_isset(pinA) && !_isset(pinC)){
+ SIMPLEFOC_DEBUG("CS: Switch A-(C)NC");
+ _swap(pinA, pinC);
+ _swap(offset_ia, offset_ic);
+ _swap(gain_a, gain_c);
+ _swap(c_a.b, c_a.c);
+ phases_switched = true; // signal that pins have been switched
+ }
+ }
+ // at this point the current sensing on phase A can be either:
+ // - aligned with the driver phase A
+ // - or the phase A is not measured and the _NC is connected to the phase A
+ //
+ // In either case A is done, now we have to check the phase B and C
+
+
+ // set phase B active and phases A and C down
+ // 300 ms of ramping
+ for(int i=0; i < 100; i++){
+ bldc_driver->setPwm(zero, voltage/100.0*((float)i)+zero, zero);
+ _delay(3);
+ }
+ _delay(500);
+ PhaseCurrent_s c_b = readAverageCurrents();
+ bldc_driver->setPwm(zero, zero, zero);
+
+ // check the phase B
+ // find the highest magnitude in c_b
+ // and make sure it's around 2 (1.5 at least) times higher than the other two
+ float cb[3] = {fabs(c_b.a), fabs(c_b.b), fabs(c_b.c)};
+ max_i = -1; // max index
+ max_c = 0; // max current
+ max_c_ratio = 0; // max current ratio
+ for(int i = 0; i < 3; i++){
+ if(!cb[i]) continue; // current not measured
+ if(cb[i] > max_c){
+ max_c = cb[i];
+ max_i = i;
+ for(int j = 0; j < 3; j++){
+ if(i == j) continue;
+ if(!cb[j]) continue; // current not measured
+ float ratio = max_c / cb[j];
+ if(ratio > max_c_ratio) max_c_ratio = ratio;
+ }
+ }
+ }
+ if(max_c_ratio >= 1.5f){
+ switch (max_i){
+ case 0: // phase A is the max current
+ // this is an error as phase A is already aligned
+ SIMPLEFOC_DEBUG("CS: Err align B");
+ return 0;
+ case 2: // phase C is the max current
+ SIMPLEFOC_DEBUG("CS: Switch B-C");
+ _swap(pinB, pinC);
+ _swap(offset_ib, offset_ic);
+ _swap(gain_b, gain_c);
+ _swap(c_b.b, c_b.c);
+ phases_switched = true; // signal that pins have been switched
+ break;
+ }
+ // check if the current is negative and invert the gain if so
+ if( _sign(c_b.b) < 0 ){
+ SIMPLEFOC_DEBUG("CS: Inv B");
+ gain_b *= -1;
+ phases_inverted = true; // signal that pins have been inverted
+ }
+ }else if(_isset(pinB) && _isset(pinC)){
+ // if all three currents are measured and none of them is significantly higher
+ // we have a problem with the current sense
+ SIMPLEFOC_DEBUG("CS: Err B - all currents same magnitude!");
+ return 0;
+ }else{ //phase B is not measured so put the _NC to the phase B
+ if(_isset(pinB) && !_isset(pinC)){
+ SIMPLEFOC_DEBUG("CS: Switch B-(C)NC");
+ _swap(pinB, pinC);
+ _swap(offset_ib, offset_ic);
+ _swap(gain_b, gain_c);
+ _swap(c_b.b, c_b.c);
+ phases_switched = true; // signal that pins have been switched
+ }
+ }
+ // at this point the current sensing on phase A and B can be either:
+ // - aligned with the driver phase A and B
+ // - or the phase A and B are not measured and the _NC is connected to the phase A and B
+ //
+ // In either case A and B is done, now we have to check the phase C
+ // phase C is also aligned if it is measured (not _NC)
+ // we have to check if the current is negative and invert the gain if so
+ if(_isset(pinC)){
+ if( _sign(c_b.c) > 0 ){ // the expected current is -I/2 (if the phase A and B are aligned and C has correct polarity)
+ SIMPLEFOC_DEBUG("CS: Inv C");
+ gain_c *= -1;
+ phases_inverted = true; // signal that pins have been inverted
+ }
+ }
+
+ // construct the return flag
+ // if the phases have been switched return 2
+ // if the gains have been inverted return 3
+ // if both return 4
+ uint8_t exit_flag = 1;
+ if(phases_switched) exit_flag += 1;
+ if(phases_inverted) exit_flag += 2;
+ return exit_flag;
+}
+
+
+// Function aligning the current sense with motor driver
+// if all pins are connected well none of this is really necessary! - can be avoided
+// returns flag
+// 0 - fail
+// 1 - success and nothing changed
+// 2 - success but pins reconfigured
+// 3 - success but gains inverted
+// 4 - success but pins reconfigured and gains inverted
+int CurrentSense::alignStepperDriver(float voltage, StepperDriver* stepper_driver, bool modulation_centered){
+
+ _UNUSED(modulation_centered);
+
+ bool phases_switched = 0;
+ bool phases_inverted = 0;
+
+ if(!_isset(pinA) || !_isset(pinB)){
+ SIMPLEFOC_DEBUG("CS: Pins A & B not specified!");
+ return 0;
+ }
+
+ // set phase A active and phases B down
+ // ramp 300ms
+ for(int i=0; i < 100; i++){
+ stepper_driver->setPwm(voltage/100.0*((float)i), 0);
+ _delay(3);
+ }
+ _delay(500);
+ PhaseCurrent_s c = readAverageCurrents();
+ // disable the phases
+ stepper_driver->setPwm(0, 0);
+ if (fabs(c.a) < 0.1f && fabs(c.b) < 0.1f ){
+ SIMPLEFOC_DEBUG("CS: Err too low current!");
+ return 0; // measurement current too low
+ }
+ // align phase A
+ // 1) only one phase can be measured so we first measure which ADC pin corresponds
+ // to the phase A by comparing the magnitude
+ if (fabs(c.a) < fabs(c.b)){
+ SIMPLEFOC_DEBUG("CS: Switch A-B");
+ // switch phase A and B
+ _swap(pinA, pinB);
+ _swap(offset_ia, offset_ib);
+ _swap(gain_a, gain_b);
+ phases_switched = true; // signal that pins have been switched
+ }
+ // 2) check if measured current a is positive and invert if not
+ if (c.a < 0){
+ SIMPLEFOC_DEBUG("CS: Inv A");
+ gain_a *= -1;
+ phases_inverted = true; // signal that pins have been inverted
+ }
+
+ // at this point the driver's phase A is aligned with the ADC pinA
+ // and the pin B should be the phase B
+
+ // set phase B active and phases A down
+ // ramp 300ms
+ for(int i=0; i < 100; i++){
+ stepper_driver->setPwm(0, voltage/100.0*((float)i));
+ _delay(3);
+ }
+ _delay(500);
+ c = readAverageCurrents();
+ stepper_driver->setPwm(0, 0);
+
+ // phase B should be aligned
+ // 1) we just need to verify that it has been measured
+ if (fabs(c.b) < 0.1f ){
+ SIMPLEFOC_DEBUG("CS: Err too low current on B!");
+ return 0; // measurement current too low
+ }
+ // 2) check if measured current a is positive and invert if not
+ if (c.b < 0){
+ SIMPLEFOC_DEBUG("CS: Inv B");
+ gain_b *= -1;
+ phases_inverted = true; // signal that pins have been inverted
+ }
+
+ // construct the return flag
+ // if success and nothing changed return 1
+ // if the phases have been switched return 2
+ // if the gains have been inverted return 3
+ // if both return 4
+ uint8_t exit_flag = 1;
+ if(phases_switched) exit_flag += 1;
+ if(phases_inverted) exit_flag += 2;
+ return exit_flag;
+}
+
+
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/common/base_classes/CurrentSense.h b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/common/base_classes/CurrentSense.h
new file mode 100644
index 0000000..d3f7f8e
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/common/base_classes/CurrentSense.h
@@ -0,0 +1,145 @@
+#ifndef CURRENTSENSE_H
+#define CURRENTSENSE_H
+
+#include "FOCDriver.h"
+#include "../foc_utils.h"
+#include "../time_utils.h"
+#include "StepperDriver.h"
+#include "BLDCDriver.h"
+
+/**
+ * Current sensing abstract class defintion
+ * Each current sensing implementation needs to extend this interface
+ */
+class CurrentSense{
+ public:
+
+ /**
+ * Function intialising the CurrentSense class
+ * - All the necessary intialisations of adc and sync should be implemented here
+ *
+ * @returns - 0 - for failure & 1 - for success
+ */
+ virtual int init() = 0;
+
+ /**
+ * Linking the current sense with the motor driver
+ * Only necessary if synchronisation in between the two is required
+ */
+ void linkDriver(FOCDriver *driver);
+
+ // variables
+ bool skip_align = false; //!< variable signaling that the phase current direction should be verified during initFOC()
+
+ FOCDriver* driver = nullptr; //!< driver link
+ bool initialized = false; // true if current sense was successfully initialized
+ void* params = 0; //!< pointer to hardware specific parameters of current sensing
+ DriverType driver_type = DriverType::Unknown; //!< driver type (BLDC or Stepper)
+
+
+ // ADC measurement gain for each phase
+ // support for different gains for different phases of more commonly - inverted phase currents
+ // this should be automated later
+ float gain_a; //!< phase A gain
+ float gain_b; //!< phase B gain
+ float gain_c; //!< phase C gain
+
+ float offset_ia; //!< zero current A voltage value (center of the adc reading)
+ float offset_ib; //!< zero current B voltage value (center of the adc reading)
+ float offset_ic; //!< zero current C voltage value (center of the adc reading)
+
+ // hardware variables
+ int pinA; //!< pin A analog pin for current measurement
+ int pinB; //!< pin B analog pin for current measurement
+ int pinC; //!< pin C analog pin for current measurement
+
+ /**
+ * Function intended to verify if:
+ * - phase current are oriented properly
+ * - if their order is the same as driver phases
+ *
+ * This function corrects the alignment errors if possible ans if no such thing is needed it can be left empty (return 1)
+ * @returns -
+ 0 - failure
+ 1 - success and nothing changed
+ 2 - success but pins reconfigured
+ 3 - success but gains inverted
+ 4 - success but pins reconfigured and gains inverted
+ *
+ * IMPORTANT: Default implementation provided in the CurrentSense class, but can be overriden in the child classes
+ */
+ virtual int driverAlign(float align_voltage, bool modulation_centered = false);
+
+ /**
+ * Function rading the phase currents a, b and c
+ * This function will be used with the foc control throught the function
+ * CurrentSense::getFOCCurrents(electrical_angle)
+ * - it returns current c equal to 0 if only two phase measurements available
+ *
+ * @return PhaseCurrent_s current values
+ */
+ virtual PhaseCurrent_s getPhaseCurrents() = 0;
+ /**
+ * Function reading the magnitude of the current set to the motor
+ * It returns the absolute or signed magnitude if possible
+ * It can receive the motor electrical angle to help with calculation
+ * This function is used with the current control (not foc)
+ *
+ * @param angle_el - electrical angle of the motor (optional)
+ */
+ virtual float getDCCurrent(float angle_el = 0);
+
+ /**
+ * Function used for FOC control, it reads the DQ currents of the motor
+ * It uses the function getPhaseCurrents internally
+ *
+ * @param angle_el - motor electrical angle
+ */
+ DQCurrent_s getFOCCurrents(float angle_el);
+
+ /**
+ * Function used for Clarke transform in FOC control
+ * It reads the phase currents of the motor
+ * It returns the alpha and beta currents
+ *
+ * @param current - phase current
+ */
+ ABCurrent_s getABCurrents(PhaseCurrent_s current);
+
+ /**
+ * Function used for Park transform in FOC control
+ * It reads the Alpha Beta currents and electrical angle of the motor
+ * It returns the D and Q currents
+ *
+ * @param current - phase current
+ */
+ DQCurrent_s getDQCurrents(ABCurrent_s current,float angle_el);
+
+ /**
+ * enable the current sense. default implementation does nothing, but you can
+ * override it to do something useful.
+ */
+ virtual void enable();
+
+ /**
+ * disable the current sense. default implementation does nothing, but you can
+ * override it to do something useful.
+ */
+ virtual void disable();
+
+ /**
+ * Function used to align the current sense with the BLDC motor driver
+ */
+ int alignBLDCDriver(float align_voltage, BLDCDriver* driver, bool modulation_centered);
+ /**
+ * Function used to align the current sense with the Stepper motor driver
+ */
+ int alignStepperDriver(float align_voltage, StepperDriver* driver, bool modulation_centered);
+ /**
+ * Function used to read the average current values over N samples
+ */
+ PhaseCurrent_s readAverageCurrents(int N=100);
+
+};
+
+#endif
\ No newline at end of file
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/common/base_classes/FOCDriver.h b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/common/base_classes/FOCDriver.h
new file mode 100644
index 0000000..944251a
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/common/base_classes/FOCDriver.h
@@ -0,0 +1,47 @@
+#ifndef FOCDRIVER_H
+#define FOCDRIVER_H
+
+#include "Arduino.h"
+
+
+enum PhaseState : uint8_t {
+ PHASE_OFF = 0, // both sides of the phase are off
+ PHASE_ON = 1, // both sides of the phase are driven with PWM, dead time is applied in 6-PWM mode
+ PHASE_HI = 2, // only the high side of the phase is driven with PWM (6-PWM mode only)
+ PHASE_LO = 3, // only the low side of the phase is driven with PWM (6-PWM mode only)
+};
+
+
+enum DriverType{
+ Unknown=0,
+ BLDC=1,
+ Stepper=2
+};
+
+/**
+ * FOC driver class
+ */
+class FOCDriver{
+ public:
+
+ /** Initialise hardware */
+ virtual int init() = 0;
+ /** Enable hardware */
+ virtual void enable() = 0;
+ /** Disable hardware */
+ virtual void disable() = 0;
+
+ long pwm_frequency; //!< pwm frequency value in hertz
+ float voltage_power_supply; //!< power supply voltage
+ float voltage_limit; //!< limiting voltage set to the motor
+
+ bool initialized = false; //!< true if driver was successfully initialized
+ void* params = 0; //!< pointer to hardware specific parameters of driver
+
+ bool enable_active_high = true; //!< enable pin should be set to high to enable the driver (default is HIGH)
+
+ /** get the driver type*/
+ virtual DriverType type() = 0;
+};
+
+#endif
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/common/base_classes/FOCMotor.cpp b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/common/base_classes/FOCMotor.cpp
new file mode 100644
index 0000000..5d8f812
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/common/base_classes/FOCMotor.cpp
@@ -0,0 +1,159 @@
+#include "FOCMotor.h"
+#include "../../communication/SimpleFOCDebug.h"
+
+/**
+ * Default constructor - setting all variabels to default values
+ */
+FOCMotor::FOCMotor()
+{
+ // maximum angular velocity to be used for positioning
+ velocity_limit = DEF_VEL_LIM;
+ // maximum voltage to be set to the motor
+ voltage_limit = DEF_POWER_SUPPLY;
+ // not set on the begining
+ current_limit = DEF_CURRENT_LIM;
+
+ // index search velocity
+ velocity_index_search = DEF_INDEX_SEARCH_TARGET_VELOCITY;
+ // sensor and motor align voltage
+ voltage_sensor_align = DEF_VOLTAGE_SENSOR_ALIGN;
+
+ // default modulation is SinePWM
+ foc_modulation = FOCModulationType::SinePWM;
+
+ // default target value
+ target = 0;
+ voltage.d = 0;
+ voltage.q = 0;
+ // current target values
+ current_sp = 0;
+ current.q = 0;
+ current.d = 0;
+
+ // voltage bemf
+ voltage_bemf = 0;
+
+ // Initialize phase voltages U alpha and U beta used for inverse Park and Clarke transform
+ Ualpha = 0;
+ Ubeta = 0;
+
+ //monitor_port
+ monitor_port = nullptr;
+ //sensor
+ sensor_offset = 0.0f;
+ sensor = nullptr;
+ //current sensor
+ current_sense = nullptr;
+}
+
+
+/**
+ Sensor linking method
+*/
+void FOCMotor::linkSensor(Sensor* _sensor) {
+ sensor = _sensor;
+}
+
+/**
+ CurrentSense linking method
+*/
+void FOCMotor::linkCurrentSense(CurrentSense* _current_sense) {
+ current_sense = _current_sense;
+}
+
+// shaft angle calculation
+float FOCMotor::shaftAngle() {
+ // if no sensor linked return previous value ( for open loop )
+ if(!sensor) return shaft_angle;
+ return sensor_direction*LPF_angle(sensor->getAngle()) - sensor_offset;
+}
+// shaft velocity calculation
+float FOCMotor::shaftVelocity() {
+ // if no sensor linked return previous value ( for open loop )
+ if(!sensor) return shaft_velocity;
+ return sensor_direction*LPF_velocity(sensor->getVelocity());
+}
+
+float FOCMotor::electricalAngle(){
+ // if no sensor linked return previous value ( for open loop )
+ if(!sensor) return electrical_angle;
+ return _normalizeAngle( (float)(sensor_direction * pole_pairs) * sensor->getMechanicalAngle() - zero_electric_angle );
+}
+
+/**
+ * Monitoring functions
+ */
+// function implementing the monitor_port setter
+void FOCMotor::useMonitoring(Print &print){
+ monitor_port = &print; //operate on the address of print
+ #ifndef SIMPLEFOC_DISABLE_DEBUG
+ SimpleFOCDebug::enable(&print);
+ SIMPLEFOC_DEBUG("MOT: Monitor enabled!");
+ #endif
+}
+
+// utility function intended to be used with serial plotter to monitor motor variables
+// significantly slowing the execution down!!!!
+void FOCMotor::monitor() {
+ if( !monitor_downsample || monitor_cnt++ < (monitor_downsample-1) ) return;
+ monitor_cnt = 0;
+ if(!monitor_port) return;
+ bool printed = 0;
+
+ if(monitor_variables & _MON_TARGET){
+ if(!printed && monitor_start_char) monitor_port->print(monitor_start_char);
+ monitor_port->print(target,monitor_decimals);
+ printed= true;
+ }
+ if(monitor_variables & _MON_VOLT_Q) {
+ if(!printed && monitor_start_char) monitor_port->print(monitor_start_char);
+ else if(printed) monitor_port->print(monitor_separator);
+ monitor_port->print(voltage.q,monitor_decimals);
+ printed= true;
+ }
+ if(monitor_variables & _MON_VOLT_D) {
+ if(!printed && monitor_start_char) monitor_port->print(monitor_start_char);
+ else if(printed) monitor_port->print(monitor_separator);
+ monitor_port->print(voltage.d,monitor_decimals);
+ printed= true;
+ }
+ // read currents if possible - even in voltage mode (if current_sense available)
+ if(monitor_variables & _MON_CURR_Q || monitor_variables & _MON_CURR_D) {
+ DQCurrent_s c = current;
+ if( current_sense && torque_controller != TorqueControlType::foc_current ){
+ c = current_sense->getFOCCurrents(electrical_angle);
+ c.q = LPF_current_q(c.q);
+ c.d = LPF_current_d(c.d);
+ }
+ if(monitor_variables & _MON_CURR_Q) {
+ if(!printed && monitor_start_char) monitor_port->print(monitor_start_char);
+ else if(printed) monitor_port->print(monitor_separator);
+ monitor_port->print(c.q*1000, monitor_decimals); // mAmps
+ printed= true;
+ }
+ if(monitor_variables & _MON_CURR_D) {
+ if(!printed && monitor_start_char) monitor_port->print(monitor_start_char);
+ else if(printed) monitor_port->print(monitor_separator);
+ monitor_port->print(c.d*1000, monitor_decimals); // mAmps
+ printed= true;
+ }
+ }
+
+ if(monitor_variables & _MON_VEL) {
+ if(!printed && monitor_start_char) monitor_port->print(monitor_start_char);
+ else if(printed) monitor_port->print(monitor_separator);
+ monitor_port->print(shaft_velocity,monitor_decimals);
+ printed= true;
+ }
+ if(monitor_variables & _MON_ANGLE) {
+ if(!printed && monitor_start_char) monitor_port->print(monitor_start_char);
+ else if(printed) monitor_port->print(monitor_separator);
+ monitor_port->print(shaft_angle,monitor_decimals);
+ printed= true;
+ }
+ if(printed){
+ if(monitor_end_char) monitor_port->println(monitor_end_char);
+ else monitor_port->println("");
+ }
+}
+
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/common/base_classes/FOCMotor.h b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/common/base_classes/FOCMotor.h
new file mode 100644
index 0000000..8ae0e8a
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/common/base_classes/FOCMotor.h
@@ -0,0 +1,254 @@
+#ifndef FOCMOTOR_H
+#define FOCMOTOR_H
+
+#include "Arduino.h"
+#include "Sensor.h"
+#include "CurrentSense.h"
+
+#include "../time_utils.h"
+#include "../foc_utils.h"
+#include "../defaults.h"
+#include "../pid.h"
+#include "../lowpass_filter.h"
+
+
+// monitoring bitmap
+#define _MON_TARGET 0b1000000 // monitor target value
+#define _MON_VOLT_Q 0b0100000 // monitor voltage q value
+#define _MON_VOLT_D 0b0010000 // monitor voltage d value
+#define _MON_CURR_Q 0b0001000 // monitor current q value - if measured
+#define _MON_CURR_D 0b0000100 // monitor current d value - if measured
+#define _MON_VEL 0b0000010 // monitor velocity value
+#define _MON_ANGLE 0b0000001 // monitor angle value
+
+/**
+ * Motiron control type
+ */
+enum MotionControlType : uint8_t {
+ torque = 0x00, //!< Torque control
+ velocity = 0x01, //!< Velocity motion control
+ angle = 0x02, //!< Position/angle motion control
+ velocity_openloop = 0x03,
+ angle_openloop = 0x04
+};
+
+/**
+ * Motiron control type
+ */
+enum TorqueControlType : uint8_t {
+ voltage = 0x00, //!< Torque control using voltage
+ dc_current = 0x01, //!< Torque control using DC current (one current magnitude)
+ foc_current = 0x02, //!< torque control using dq currents
+};
+
+/**
+ * FOC modulation type
+ */
+enum FOCModulationType : uint8_t {
+ SinePWM = 0x00, //!< Sinusoidal PWM modulation
+ SpaceVectorPWM = 0x01, //!< Space vector modulation method
+ Trapezoid_120 = 0x02,
+ Trapezoid_150 = 0x03,
+};
+
+
+
+enum FOCMotorStatus : uint8_t {
+ motor_uninitialized = 0x00, //!< Motor is not yet initialized
+ motor_initializing = 0x01, //!< Motor intiialization is in progress
+ motor_uncalibrated = 0x02, //!< Motor is initialized, but not calibrated (open loop possible)
+ motor_calibrating = 0x03, //!< Motor calibration in progress
+ motor_ready = 0x04, //!< Motor is initialized and calibrated (closed loop possible)
+ motor_error = 0x08, //!< Motor is in error state (recoverable, e.g. overcurrent protection active)
+ motor_calib_failed = 0x0E, //!< Motor calibration failed (possibly recoverable)
+ motor_init_failed = 0x0F, //!< Motor initialization failed (not recoverable)
+};
+
+
+
+/**
+ Generic motor class
+*/
+class FOCMotor
+{
+ public:
+ /**
+ * Default constructor - setting all variabels to default values
+ */
+ FOCMotor();
+
+ /** Motor hardware init function */
+ virtual int init()=0;
+ /** Motor disable function */
+ virtual void disable()=0;
+ /** Motor enable function */
+ virtual void enable()=0;
+
+ /**
+ * Function linking a motor and a sensor
+ *
+ * @param sensor Sensor class wrapper for the FOC algorihtm to read the motor angle and velocity
+ */
+ void linkSensor(Sensor* sensor);
+
+ /**
+ * Function linking a motor and current sensing
+ *
+ * @param current_sense CurrentSense class wrapper for the FOC algorihtm to read the motor current measurements
+ */
+ void linkCurrentSense(CurrentSense* current_sense);
+
+
+ /**
+ * Function initializing FOC algorithm
+ * and aligning sensor's and motors' zero position
+ *
+ * - If zero_electric_offset parameter is set the alignment procedure is skipped
+ */
+ virtual int initFOC()=0;
+ /**
+ * Function running FOC algorithm in real-time
+ * it calculates the gets motor angle and sets the appropriate voltages
+ * to the phase pwm signals
+ * - the faster you can run it the better Arduino UNO ~1ms, Bluepill ~ 100us
+ */
+ virtual void loopFOC()=0;
+ /**
+ * Function executing the control loops set by the controller parameter of the BLDCMotor.
+ *
+ * @param target Either voltage, angle or velocity based on the motor.controller
+ * If it is not set the motor will use the target set in its variable motor.target
+ *
+ * This function doesn't need to be run upon each loop execution - depends of the use case
+ */
+ virtual void move(float target = NOT_SET)=0;
+
+ /**
+ * Method using FOC to set Uq to the motor at the optimal angle
+ * Heart of the FOC algorithm
+ *
+ * @param Uq Current voltage in q axis to set to the motor
+ * @param Ud Current voltage in d axis to set to the motor
+ * @param angle_el current electrical angle of the motor
+ */
+ virtual void setPhaseVoltage(float Uq, float Ud, float angle_el)=0;
+
+ // State calculation methods
+ /** Shaft angle calculation in radians [rad] */
+ float shaftAngle();
+ /**
+ * Shaft angle calculation function in radian per second [rad/s]
+ * It implements low pass filtering
+ */
+ float shaftVelocity();
+
+
+
+ /**
+ * Electrical angle calculation
+ */
+ float electricalAngle();
+
+ // state variables
+ float target; //!< current target value - depends of the controller
+ float feed_forward_velocity = 0.0f; //!< current feed forward velocity
+ float shaft_angle;//!< current motor angle
+ float electrical_angle;//!< current electrical angle
+ float shaft_velocity;//!< current motor velocity
+ float current_sp;//!< target current ( q current )
+ float shaft_velocity_sp;//!< current target velocity
+ float shaft_angle_sp;//!< current target angle
+ DQVoltage_s voltage;//!< current d and q voltage set to the motor
+ DQCurrent_s current;//!< current d and q current measured
+ float voltage_bemf; //!< estimated backemf voltage (if provided KV constant)
+ float Ualpha, Ubeta; //!< Phase voltages U alpha and U beta used for inverse Park and Clarke transform
+
+
+ // motor configuration parameters
+ float voltage_sensor_align;//!< sensor and motor align voltage parameter
+ float velocity_index_search;//!< target velocity for index search
+
+ // motor physical parameters
+ float phase_resistance; //!< motor phase resistance
+ int pole_pairs;//!< motor pole pairs number
+ float KV_rating; //!< motor KV rating
+ float phase_inductance; //!< motor phase inductance
+
+ // limiting variables
+ float voltage_limit; //!< Voltage limiting variable - global limit
+ float current_limit; //!< Current limiting variable - global limit
+ float velocity_limit; //!< Velocity limiting variable - global limit
+
+ // motor status vairables
+ int8_t enabled = 0;//!< enabled or disabled motor flag
+ FOCMotorStatus motor_status = FOCMotorStatus::motor_uninitialized; //!< motor status
+
+ // pwm modulation related variables
+ FOCModulationType foc_modulation;//!< parameter determining modulation algorithm
+ int8_t modulation_centered = 1;//!< flag (1) centered modulation around driver limit /2 or (0) pulled to 0
+
+
+ // configuration structures
+ TorqueControlType torque_controller; //!< parameter determining the torque control type
+ MotionControlType controller; //!< parameter determining the control loop to be used
+
+ // controllers and low pass filters
+ PIDController PID_current_q{DEF_PID_CURR_P,DEF_PID_CURR_I,DEF_PID_CURR_D,DEF_PID_CURR_RAMP, DEF_POWER_SUPPLY};//!< parameter determining the q current PID config
+ PIDController PID_current_d{DEF_PID_CURR_P,DEF_PID_CURR_I,DEF_PID_CURR_D,DEF_PID_CURR_RAMP, DEF_POWER_SUPPLY};//!< parameter determining the d current PID config
+ LowPassFilter LPF_current_q{DEF_CURR_FILTER_Tf};//!< parameter determining the current Low pass filter configuration
+ LowPassFilter LPF_current_d{DEF_CURR_FILTER_Tf};//!< parameter determining the current Low pass filter configuration
+ PIDController PID_velocity{DEF_PID_VEL_P,DEF_PID_VEL_I,DEF_PID_VEL_D,DEF_PID_VEL_RAMP,DEF_PID_VEL_LIMIT};//!< parameter determining the velocity PID configuration
+ PIDController P_angle{DEF_P_ANGLE_P,0,0,0,DEF_VEL_LIM}; //!< parameter determining the position PID configuration
+ LowPassFilter LPF_velocity{DEF_VEL_FILTER_Tf};//!< parameter determining the velocity Low pass filter configuration
+ LowPassFilter LPF_angle{0.0};//!< parameter determining the angle low pass filter configuration
+ unsigned int motion_downsample = DEF_MOTION_DOWNSMAPLE; //!< parameter defining the ratio of downsampling for move commad
+ unsigned int motion_cnt = 0; //!< counting variable for downsampling for move commad
+
+ // sensor related variabels
+ float sensor_offset; //!< user defined sensor zero offset
+ float zero_electric_angle = NOT_SET;//!< absolute zero electric angle - if available
+ Direction sensor_direction = Direction::UNKNOWN; //!< default is CW. if sensor_direction == Direction::CCW then direction will be flipped compared to CW. Set to UNKNOWN to set by calibration
+ bool pp_check_result = false; //!< the result of the PP check, if run during loopFOC
+
+ /**
+ * Function providing BLDCMotor class with the
+ * Serial interface and enabling monitoring mode
+ *
+ * @param serial Monitoring Serial class reference
+ */
+ void useMonitoring(Print &serial);
+
+ /**
+ * Utility function intended to be used with serial plotter to monitor motor variables
+ * significantly slowing the execution down!!!!
+ */
+ void monitor();
+ unsigned int monitor_downsample = DEF_MON_DOWNSMAPLE; //!< show monitor outputs each monitor_downsample calls
+ char monitor_start_char = '\0'; //!< monitor starting character
+ char monitor_end_char = '\0'; //!< monitor outputs ending character
+ char monitor_separator = '\t'; //!< monitor outputs separation character
+ unsigned int monitor_decimals = 4; //!< monitor outputs decimal places
+ // initial monitoring will display target, voltage, velocity and angle
+ uint8_t monitor_variables = _MON_TARGET | _MON_VOLT_Q | _MON_VEL | _MON_ANGLE; //!< Bit array holding the map of variables the user wants to monitor
+
+ /**
+ * Sensor link:
+ * - Encoder
+ * - MagneticSensor*
+ * - HallSensor
+ */
+ Sensor* sensor;
+ /**
+ * CurrentSense link
+ */
+ CurrentSense* current_sense;
+
+ // monitoring functions
+ Print* monitor_port; //!< Serial terminal variable if provided
+ private:
+ // monitor counting variable
+ unsigned int monitor_cnt = 0 ; //!< counting variable
+};
+
+
+#endif
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/common/base_classes/Sensor.cpp b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/common/base_classes/Sensor.cpp
new file mode 100644
index 0000000..db17e92
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/common/base_classes/Sensor.cpp
@@ -0,0 +1,80 @@
+#include "Sensor.h"
+#include "../foc_utils.h"
+#include "../time_utils.h"
+
+
+
+void Sensor::update() {
+ float val = getSensorAngle();
+ if (val<0) // sensor angles are strictly non-negative. Negative values are used to signal errors.
+ return; // TODO signal error, e.g. via a flag and counter
+ angle_prev_ts = _micros();
+ float d_angle = val - angle_prev;
+ // if overflow happened track it as full rotation
+ if(abs(d_angle) > (0.8f*_2PI) ) full_rotations += ( d_angle > 0 ) ? -1 : 1;
+ angle_prev = val;
+}
+
+
+ /** get current angular velocity (rad/s) */
+float Sensor::getVelocity() {
+ // calculate sample time
+ float Ts = (angle_prev_ts - vel_angle_prev_ts)*1e-6f;
+ if (Ts < 0.0f) { // handle micros() overflow - we need to reset vel_angle_prev_ts
+ vel_angle_prev = angle_prev;
+ vel_full_rotations = full_rotations;
+ vel_angle_prev_ts = angle_prev_ts;
+ return velocity;
+ }
+ if (Ts < min_elapsed_time) return velocity; // don't update velocity if deltaT is too small
+
+ velocity = ( (float)(full_rotations - vel_full_rotations)*_2PI + (angle_prev - vel_angle_prev) ) / Ts;
+ vel_angle_prev = angle_prev;
+ vel_full_rotations = full_rotations;
+ vel_angle_prev_ts = angle_prev_ts;
+ return velocity;
+}
+
+
+
+void Sensor::init() {
+ // initialize all the internal variables of Sensor to ensure a "smooth" startup (without a 'jump' from zero)
+ getSensorAngle(); // call once
+ delayMicroseconds(1);
+ vel_angle_prev = getSensorAngle(); // call again
+ vel_angle_prev_ts = _micros();
+ delay(1);
+ getSensorAngle(); // call once
+ delayMicroseconds(1);
+ angle_prev = getSensorAngle(); // call again
+ angle_prev_ts = _micros();
+}
+
+
+float Sensor::getMechanicalAngle() {
+ return angle_prev;
+}
+
+
+
+float Sensor::getAngle(){
+ return (float)full_rotations * _2PI + angle_prev;
+}
+
+
+
+double Sensor::getPreciseAngle() {
+ return (double)full_rotations * (double)_2PI + (double)angle_prev;
+}
+
+
+
+int32_t Sensor::getFullRotations() {
+ return full_rotations;
+}
+
+
+
+int Sensor::needsSearch() {
+ return 0; // default false
+}
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/common/base_classes/Sensor.h b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/common/base_classes/Sensor.h
new file mode 100644
index 0000000..c77eb91
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/common/base_classes/Sensor.h
@@ -0,0 +1,139 @@
+#ifndef SENSOR_H
+#define SENSOR_H
+
+#include
+
+/**
+ * Direction structure
+ */
+enum Direction : int8_t {
+ CW = 1, // clockwise
+ CCW = -1, // counter clockwise
+ UNKNOWN = 0 // not yet known or invalid state
+};
+
+
+/**
+ * Pullup configuration structure
+ */
+enum Pullup : uint8_t {
+ USE_INTERN = 0x00, //!< Use internal pullups
+ USE_EXTERN = 0x01 //!< Use external pullups
+};
+
+/**
+ * Sensor abstract class defintion
+ *
+ * This class is purposefully kept simple, as a base for all kinds of sensors. Currently we have
+ * Encoders, Magnetic Encoders and Hall Sensor implementations. This base class extracts the
+ * most basic common features so that a FOC driver can obtain the data it needs for operation.
+ *
+ * To implement your own sensors, create a sub-class of this class, and implement the getSensorAngle()
+ * method. getSensorAngle() returns a float value, in radians, representing the current shaft angle in the
+ * range 0 to 2*PI (one full turn).
+ *
+ * To function correctly, the sensor class update() method has to be called sufficiently quickly. Normally,
+ * the BLDCMotor's loopFOC() function calls it once per iteration, so you must ensure to call loopFOC() quickly
+ * enough, both for correct motor and sensor operation.
+ *
+ * The Sensor base class provides an implementation of getVelocity(), and takes care of counting full
+ * revolutions in a precise way, but if you wish you can additionally override these methods to provide more
+ * optimal implementations for your hardware.
+ *
+ */
+class Sensor{
+ friend class SmoothingSensor;
+ public:
+ /**
+ * Get mechanical shaft angle in the range 0 to 2PI. This value will be as precise as possible with
+ * the hardware. Base implementation uses the values returned by update() so that
+ * the same values are returned until update() is called again.
+ */
+ virtual float getMechanicalAngle();
+
+ /**
+ * Get current position (in rad) including full rotations and shaft angle.
+ * Base implementation uses the values returned by update() so that the same
+ * values are returned until update() is called again.
+ * Note that this value has limited precision as the number of rotations increases,
+ * because the limited precision of float can't capture the large angle of the full
+ * rotations and the small angle of the shaft angle at the same time.
+ */
+ virtual float getAngle();
+
+ /**
+ * On architectures supporting it, this will return a double precision position value,
+ * which should have improved precision for large position values.
+ * Base implementation uses the values returned by update() so that the same
+ * values are returned until update() is called again.
+ */
+ virtual double getPreciseAngle();
+
+ /**
+ * Get current angular velocity (rad/s)
+ * Can be overridden in subclasses. Base implementation uses the values
+ * returned by update() so that it only makes sense to call this if update()
+ * has been called in the meantime.
+ */
+ virtual float getVelocity();
+
+ /**
+ * Get the number of full rotations
+ * Base implementation uses the values returned by update() so that the same
+ * values are returned until update() is called again.
+ */
+ virtual int32_t getFullRotations();
+
+ /**
+ * Updates the sensor values by reading the hardware sensor.
+ * Some implementations may work with interrupts, and not need this.
+ * The base implementation calls getSensorAngle(), and updates internal
+ * fields for angle, timestamp and full rotations.
+ * This method must be called frequently enough to guarantee that full
+ * rotations are not "missed" due to infrequent polling.
+ * Override in subclasses if alternative behaviours are required for your
+ * sensor hardware.
+ */
+ virtual void update();
+
+ /**
+ * returns 0 if it does need search for absolute zero
+ * 0 - magnetic sensor (& encoder with index which is found)
+ * 1 - ecoder with index (with index not found yet)
+ */
+ virtual int needsSearch();
+
+ /**
+ * Minimum time between updates to velocity. If time elapsed is lower than this, the velocity is not updated.
+ */
+ float min_elapsed_time = 0.000100; // default is 100 microseconds, or 10kHz
+
+ protected:
+ /**
+ * Get current shaft angle from the sensor hardware, and
+ * return it as a float in radians, in the range 0 to 2PI.
+ *
+ * This method is pure virtual and must be implemented in subclasses.
+ * Calling this method directly does not update the base-class internal fields.
+ * Use update() when calling from outside code.
+ */
+ virtual float getSensorAngle()=0;
+ /**
+ * Call Sensor::init() from your sensor subclass's init method if you want smoother startup
+ * The base class init() method calls getSensorAngle() several times to initialize the internal fields
+ * to current values, ensuring there is no discontinuity ("jump from zero") during the first calls
+ * to sensor.getAngle() and sensor.getVelocity()
+ */
+ virtual void init();
+
+ // velocity calculation variables
+ float velocity=0.0f;
+ float angle_prev=0.0f; // result of last call to getSensorAngle(), used for full rotations and velocity
+ long angle_prev_ts=0; // timestamp of last call to getAngle, used for velocity
+ float vel_angle_prev=0.0f; // angle at last call to getVelocity, used for velocity
+ long vel_angle_prev_ts=0; // last velocity calculation timestamp
+ int32_t full_rotations=0; // full rotation tracking
+ int32_t vel_full_rotations=0; // previous full rotation value for velocity calculation
+};
+
+#endif
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/common/base_classes/StepperDriver.h b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/common/base_classes/StepperDriver.h
new file mode 100644
index 0000000..9864b23
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/common/base_classes/StepperDriver.h
@@ -0,0 +1,30 @@
+#ifndef STEPPERDRIVER_H
+#define STEPPERDRIVER_H
+
+#include "Arduino.h"
+#include "FOCDriver.h"
+
+class StepperDriver: public FOCDriver{
+ public:
+
+ /**
+ * Set phase voltages to the hardware
+ *
+ * @param Ua phase A voltage
+ * @param Ub phase B voltage
+ */
+ virtual void setPwm(float Ua, float Ub) = 0;
+
+ /**
+ * Set phase state, enable/disable
+ *
+ * @param sc - phase A state : active / disabled ( high impedance )
+ * @param sb - phase B state : active / disabled ( high impedance )
+ */
+ virtual void setPhaseState(PhaseState sa, PhaseState sb) = 0;
+
+ /** driver type getter function */
+ virtual DriverType type() override { return DriverType::Stepper; } ;
+};
+
+#endif
\ No newline at end of file
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/common/defaults.h b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/common/defaults.h
new file mode 100644
index 0000000..ac57daa
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/common/defaults.h
@@ -0,0 +1,49 @@
+// default configuration values
+// change this file to optimal values for your application
+
+#define DEF_POWER_SUPPLY 12.0f //!< default power supply voltage
+// velocity PI controller params
+#define DEF_PID_VEL_P 0.5f //!< default PID controller P value
+#define DEF_PID_VEL_I 10.0f //!< default PID controller I value
+#define DEF_PID_VEL_D 0.0f //!< default PID controller D value
+#define DEF_PID_VEL_RAMP 1000.0f //!< default PID controller voltage ramp value
+#define DEF_PID_VEL_LIMIT (DEF_POWER_SUPPLY) //!< default PID controller voltage limit
+
+// current sensing PID values
+#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) || defined(__AVR_ATmega328PB__) || defined(__AVR_ATmega2560__)
+// for 16Mhz controllers like Arduino uno and mega
+#define DEF_PID_CURR_P 2 //!< default PID controller P value
+#define DEF_PID_CURR_I 100 //!< default PID controller I value
+#define DEF_PID_CURR_D 0.0f //!< default PID controller D value
+#define DEF_PID_CURR_RAMP 1000.0f //!< default PID controller voltage ramp value
+#define DEF_PID_CURR_LIMIT (DEF_POWER_SUPPLY) //!< default PID controller voltage limit
+#define DEF_CURR_FILTER_Tf 0.01f //!< default velocity filter time constant
+#else
+// for stm32, due, teensy, esp32 and similar
+#define DEF_PID_CURR_P 3 //!< default PID controller P value
+#define DEF_PID_CURR_I 300.0f //!< default PID controller I value
+#define DEF_PID_CURR_D 0.0f //!< default PID controller D value
+#define DEF_PID_CURR_RAMP 0 //!< default PID controller voltage ramp value
+#define DEF_PID_CURR_LIMIT (DEF_POWER_SUPPLY) //!< default PID controller voltage limit
+#define DEF_CURR_FILTER_Tf 0.005f //!< default currnet filter time constant
+#endif
+// default current limit values
+#define DEF_CURRENT_LIM 2.0f //!< 2Amps current limit by default
+
+// default monitor downsample
+#define DEF_MON_DOWNSMAPLE 100 //!< default monitor downsample
+#define DEF_MOTION_DOWNSMAPLE 0 //!< default motion downsample - disable
+
+// angle P params
+#define DEF_P_ANGLE_P 20.0f //!< default P controller P value
+#define DEF_VEL_LIM 20.0f //!< angle velocity limit default
+
+// index search
+#define DEF_INDEX_SEARCH_TARGET_VELOCITY 1.0f //!< default index search velocity
+// align voltage
+#define DEF_VOLTAGE_SENSOR_ALIGN 3.0f //!< default voltage for sensor and motor zero alignemt
+// low pass filter velocity
+#define DEF_VEL_FILTER_Tf 0.005f //!< default velocity filter time constant
+
+// current sense default parameters
+#define DEF_LPF_PER_PHASE_CURRENT_SENSE_Tf 0.0f //!< default currnet sense per phase low pass filter time constant
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/common/foc_utils.cpp b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/common/foc_utils.cpp
new file mode 100644
index 0000000..7ae372f
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/common/foc_utils.cpp
@@ -0,0 +1,97 @@
+#include "foc_utils.h"
+
+
+// function approximating the sine calculation by using fixed size array
+// uses a 65 element lookup table and interpolation
+// thanks to @dekutree for his work on optimizing this
+__attribute__((weak)) float _sin(float a){
+ // 16bit integer array for sine lookup. interpolation is used for better precision
+ // 16 bit precision on sine value, 8 bit fractional value for interpolation, 6bit LUT size
+ // resulting precision compared to stdlib sine is 0.00006480 (RMS difference in range -PI,PI for 3217 steps)
+ static uint16_t sine_array[65] = {0,804,1608,2411,3212,4011,4808,5602,6393,7180,7962,8740,9512,10279,11039,11793,12540,13279,14010,14733,15447,16151,16846,17531,18205,18868,19520,20160,20788,21403,22006,22595,23170,23732,24279,24812,25330,25833,26320,26791,27246,27684,28106,28511,28899,29269,29622,29957,30274,30572,30853,31114,31357,31581,31786,31972,32138,32286,32413,32522,32610,32679,32729,32758,32768};
+ int32_t t1, t2;
+ unsigned int i = (unsigned int)(a * (64*4*256.0f/_2PI));
+ int frac = i & 0xff;
+ i = (i >> 8) & 0xff;
+ if (i < 64) {
+ t1 = (int32_t)sine_array[i]; t2 = (int32_t)sine_array[i+1];
+ }
+ else if(i < 128) {
+ t1 = (int32_t)sine_array[128 - i]; t2 = (int32_t)sine_array[127 - i];
+ }
+ else if(i < 192) {
+ t1 = -(int32_t)sine_array[-128 + i]; t2 = -(int32_t)sine_array[-127 + i];
+ }
+ else {
+ t1 = -(int32_t)sine_array[256 - i]; t2 = -(int32_t)sine_array[255 - i];
+ }
+ return (1.0f/32768.0f) * (t1 + (((t2 - t1) * frac) >> 8));
+}
+
+// function approximating cosine calculation by using fixed size array
+// ~55us (float array)
+// ~56us (int array)
+// precision +-0.005
+// it has to receive an angle in between 0 and 2PI
+__attribute__((weak)) float _cos(float a){
+ float a_sin = a + _PI_2;
+ a_sin = a_sin > _2PI ? a_sin - _2PI : a_sin;
+ return _sin(a_sin);
+}
+
+
+__attribute__((weak)) void _sincos(float a, float* s, float* c){
+ *s = _sin(a);
+ *c = _cos(a);
+}
+
+// fast_atan2 based on https://math.stackexchange.com/a/1105038/81278
+// Via Odrive project
+// https://github.com/odriverobotics/ODrive/blob/master/Firmware/MotorControl/utils.cpp
+// This function is MIT licenced, copyright Oskar Weigl/Odrive Robotics
+// The origin for Odrive atan2 is public domain. Thanks to Odrive for making
+// it easy to borrow.
+__attribute__((weak)) float _atan2(float y, float x) {
+ // a := min (|x|, |y|) / max (|x|, |y|)
+ float abs_y = fabsf(y);
+ float abs_x = fabsf(x);
+ // inject FLT_MIN in denominator to avoid division by zero
+ float a = min(abs_x, abs_y) / (max(abs_x, abs_y));
+ // s := a * a
+ float s = a * a;
+ // r := ((-0.0464964749 * s + 0.15931422) * s - 0.327622764) * s * a + a
+ float r =
+ ((-0.0464964749f * s + 0.15931422f) * s - 0.327622764f) * s * a + a;
+ // if |y| > |x| then r := 1.57079637 - r
+ if (abs_y > abs_x) r = 1.57079637f - r;
+ // if x < 0 then r := 3.14159274 - r
+ if (x < 0.0f) r = 3.14159274f - r;
+ // if y < 0 then r := -r
+ if (y < 0.0f) r = -r;
+
+ return r;
+ }
+
+
+// normalizing radian angle to [0,2PI]
+__attribute__((weak)) float _normalizeAngle(float angle){
+ float a = fmod(angle, _2PI);
+ return a >= 0 ? a : (a + _2PI);
+}
+
+// Electrical angle calculation
+float _electricalAngle(float shaft_angle, int pole_pairs) {
+ return (shaft_angle * pole_pairs);
+}
+
+// square root approximation function using
+// https://reprap.org/forum/read.php?147,219210
+// https://en.wikipedia.org/wiki/Fast_inverse_square_root
+__attribute__((weak)) float _sqrtApprox(float number) {//low in fat
+ union {
+ float f;
+ uint32_t i;
+ } y = { .f = number };
+ y.i = 0x5f375a86 - ( y.i >> 1 );
+ return number * y.f;
+}
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/common/foc_utils.h b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/common/foc_utils.h
new file mode 100644
index 0000000..2094ab2
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/common/foc_utils.h
@@ -0,0 +1,119 @@
+#ifndef FOCUTILS_LIB_H
+#define FOCUTILS_LIB_H
+
+#include "Arduino.h"
+
+// sign function
+#define _sign(a) ( ( (a) < 0 ) ? -1 : ( (a) > 0 ) )
+#ifndef _round
+#define _round(x) ((x)>=0?(long)((x)+0.5f):(long)((x)-0.5f))
+#endif
+#define _constrain(amt,low,high) ((amt)<(low)?(low):((amt)>(high)?(high):(amt)))
+#define _sqrt(a) (_sqrtApprox(a))
+#define _isset(a) ( (a) != (NOT_SET) )
+#define _UNUSED(v) (void) (v)
+#define _powtwo(x) (1 << (x))
+
+#define _swap(a, b) { auto temp = a; a = b; b = temp; }
+
+// utility defines
+#define _2_SQRT3 1.15470053838f
+#define _SQRT3 1.73205080757f
+#define _1_SQRT3 0.57735026919f
+#define _SQRT3_2 0.86602540378f
+#define _SQRT2 1.41421356237f
+#define _120_D2R 2.09439510239f
+#define _PI 3.14159265359f
+#define _PI_2 1.57079632679f
+#define _PI_3 1.0471975512f
+#define _2PI 6.28318530718f
+#define _3PI_2 4.71238898038f
+#define _PI_6 0.52359877559f
+#define _RPM_TO_RADS 0.10471975512f
+
+#define NOT_SET -12345.0f
+#define _HIGH_IMPEDANCE 0
+#define _HIGH_Z _HIGH_IMPEDANCE
+#define _ACTIVE 1
+#define _NC ((int) NOT_SET)
+
+#define MIN_ANGLE_DETECT_MOVEMENT (_2PI/101.0f)
+
+// dq current structure
+struct DQCurrent_s
+{
+ float d;
+ float q;
+};
+// phase current structure
+struct PhaseCurrent_s
+{
+ float a;
+ float b;
+ float c;
+};
+// dq voltage structs
+struct DQVoltage_s
+{
+ float d;
+ float q;
+};
+// alpha beta current structure
+struct ABCurrent_s
+{
+ float alpha;
+ float beta;
+};
+
+
+/**
+ * Function approximating the sine calculation by using fixed size array
+ * - execution time ~40us (Arduino UNO)
+ *
+ * @param a angle in between 0 and 2PI
+ */
+float _sin(float a);
+/**
+ * Function approximating cosine calculation by using fixed size array
+ * - execution time ~50us (Arduino UNO)
+ *
+ * @param a angle in between 0 and 2PI
+ */
+float _cos(float a);
+/**
+ * Function returning both sine and cosine of the angle in one call.
+ * Internally it uses the _sin and _cos functions, but you may wish to
+ * provide your own implementation which is more optimized.
+ */
+void _sincos(float a, float* s, float* c);
+
+/**
+ * Function approximating atan2
+ *
+ */
+float _atan2(float y, float x);
+
+/**
+ * normalizing radian angle to [0,2PI]
+ * @param angle - angle to be normalized
+ */
+float _normalizeAngle(float angle);
+
+
+/**
+ * Electrical angle calculation
+ *
+ * @param shaft_angle - shaft angle of the motor
+ * @param pole_pairs - number of pole pairs
+ */
+float _electricalAngle(float shaft_angle, int pole_pairs);
+
+/**
+ * Function approximating square root function
+ * - using fast inverse square root
+ *
+ * @param value - number
+ */
+float _sqrtApprox(float value);
+
+#endif
\ No newline at end of file
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/common/lowpass_filter.cpp b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/common/lowpass_filter.cpp
new file mode 100644
index 0000000..ffb15cf
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/common/lowpass_filter.cpp
@@ -0,0 +1,28 @@
+#include "lowpass_filter.h"
+
+LowPassFilter::LowPassFilter(float time_constant)
+ : Tf(time_constant)
+ , y_prev(0.0f)
+{
+ timestamp_prev = _micros();
+}
+
+
+float LowPassFilter::operator() (float x)
+{
+ unsigned long timestamp = _micros();
+ float dt = (timestamp - timestamp_prev)*1e-6f;
+
+ if (dt < 0.0f ) dt = 1e-3f;
+ else if(dt > 0.3f) {
+ y_prev = x;
+ timestamp_prev = timestamp;
+ return x;
+ }
+
+ float alpha = Tf/(Tf + dt);
+ float y = alpha*y_prev + (1.0f - alpha)*x;
+ y_prev = y;
+ timestamp_prev = timestamp;
+ return y;
+}
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/common/lowpass_filter.h b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/common/lowpass_filter.h
new file mode 100644
index 0000000..1f24e80
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/common/lowpass_filter.h
@@ -0,0 +1,28 @@
+#ifndef LOWPASS_FILTER_H
+#define LOWPASS_FILTER_H
+
+
+#include "time_utils.h"
+#include "foc_utils.h"
+
+/**
+ * Low pass filter class
+ */
+class LowPassFilter
+{
+public:
+ /**
+ * @param Tf - Low pass filter time constant
+ */
+ LowPassFilter(float Tf);
+ ~LowPassFilter() = default;
+
+ float operator() (float x);
+ float Tf; //!< Low pass filter time constant
+
+protected:
+ unsigned long timestamp_prev; //!< Last execution timestamp
+ float y_prev; //!< filtered value in previous execution step
+};
+
+#endif // LOWPASS_FILTER_H
\ No newline at end of file
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/common/pid.cpp b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/common/pid.cpp
new file mode 100644
index 0000000..da1bee1
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/common/pid.cpp
@@ -0,0 +1,64 @@
+#include "pid.h"
+
+PIDController::PIDController(float P, float I, float D, float ramp, float limit)
+ : P(P)
+ , I(I)
+ , D(D)
+ , output_ramp(ramp) // output derivative limit [volts/second]
+ , limit(limit) // output supply limit [volts]
+ , error_prev(0.0f)
+ , output_prev(0.0f)
+ , integral_prev(0.0f)
+{
+ timestamp_prev = _micros();
+}
+
+// PID controller function
+float PIDController::operator() (float error){
+ // calculate the time from the last call
+ unsigned long timestamp_now = _micros();
+ float Ts = (timestamp_now - timestamp_prev) * 1e-6f;
+ // quick fix for strange cases (micros overflow)
+ if(Ts <= 0 || Ts > 0.5f) Ts = 1e-3f;
+
+ // u(s) = (P + I/s + Ds)e(s)
+ // Discrete implementations
+ // proportional part
+ // u_p = P *e(k)
+ float proportional = P * error;
+ // Tustin transform of the integral part
+ // u_ik = u_ik_1 + I*Ts/2*(ek + ek_1)
+ float integral = integral_prev + I*Ts*0.5f*(error + error_prev);
+ // antiwindup - limit the output
+ integral = _constrain(integral, -limit, limit);
+ // Discrete derivation
+ // u_dk = D(ek - ek_1)/Ts
+ float derivative = D*(error - error_prev)/Ts;
+
+ // sum all the components
+ float output = proportional + integral + derivative;
+ // antiwindup - limit the output variable
+ output = _constrain(output, -limit, limit);
+
+ // if output ramp defined
+ if(output_ramp > 0){
+ // limit the acceleration by ramping the output
+ float output_rate = (output - output_prev)/Ts;
+ if (output_rate > output_ramp)
+ output = output_prev + output_ramp*Ts;
+ else if (output_rate < -output_ramp)
+ output = output_prev - output_ramp*Ts;
+ }
+ // saving for the next pass
+ integral_prev = integral;
+ output_prev = output;
+ error_prev = error;
+ timestamp_prev = timestamp_now;
+ return output;
+}
+
+void PIDController::reset(){
+ integral_prev = 0.0f;
+ output_prev = 0.0f;
+ error_prev = 0.0f;
+}
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/common/pid.h b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/common/pid.h
new file mode 100644
index 0000000..acd68d6
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/common/pid.h
@@ -0,0 +1,41 @@
+#ifndef PID_H
+#define PID_H
+
+
+#include "time_utils.h"
+#include "foc_utils.h"
+
+/**
+ * PID controller class
+ */
+class PIDController
+{
+public:
+ /**
+ *
+ * @param P - Proportional gain
+ * @param I - Integral gain
+ * @param D - Derivative gain
+ * @param ramp - Maximum speed of change of the output value
+ * @param limit - Maximum output value
+ */
+ PIDController(float P, float I, float D, float ramp, float limit);
+ ~PIDController() = default;
+
+ float operator() (float error);
+ void reset();
+
+ float P; //!< Proportional gain
+ float I; //!< Integral gain
+ float D; //!< Derivative gain
+ float output_ramp; //!< Maximum speed of change of the output value
+ float limit; //!< Maximum output value
+
+protected:
+ float error_prev; //!< last tracking error value
+ float output_prev; //!< last pid output value
+ float integral_prev; //!< last integral component value
+ unsigned long timestamp_prev; //!< Last execution timestamp
+};
+
+#endif // PID_H
\ No newline at end of file
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/common/time_utils.cpp b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/common/time_utils.cpp
new file mode 100644
index 0000000..2acb47a
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/common/time_utils.cpp
@@ -0,0 +1,31 @@
+#include "time_utils.h"
+
+// function buffering delay()
+// arduino uno function doesn't work well with interrupts
+void _delay(unsigned long ms){
+#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) || defined(__AVR_ATmega328PB__) || defined(__AVR_ATmega2560__) || defined(__AVR_ATmega32U4__)
+ // if arduino uno and other atmega328p chips
+ // use while instad of delay,
+ // due to wrong measurement based on changed timer0
+ unsigned long t = _micros() + ms*1000;
+ while( _micros() < t ){};
+#else
+ // regular micros
+ delay(ms);
+#endif
+}
+
+
+// function buffering _micros()
+// arduino function doesn't work well with interrupts
+unsigned long _micros(){
+#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) || defined(__AVR_ATmega328PB__) || defined(__AVR_ATmega2560__) || defined(__AVR_ATmega32U4__)
+// if arduino uno and other atmega328p chips
+ //return the value based on the prescaler
+ if((TCCR0B & 0b00000111) == 0x01) return (micros()/32);
+ else return (micros());
+#else
+ // regular micros
+ return micros();
+#endif
+}
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/common/time_utils.h b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/common/time_utils.h
new file mode 100644
index 0000000..143d485
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/common/time_utils.h
@@ -0,0 +1,22 @@
+#ifndef TIME_UTILS_H
+#define TIME_UTILS_H
+
+#include "foc_utils.h"
+
+/**
+ * Function implementing delay() function in milliseconds
+ * - blocking function
+ * - hardware specific
+
+ * @param ms number of milliseconds to wait
+ */
+void _delay(unsigned long ms);
+
+/**
+ * Function implementing timestamp getting function in microseconds
+ * hardware specific
+ */
+unsigned long _micros();
+
+
+#endif
\ No newline at end of file
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/communication/Commander.cpp b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/communication/Commander.cpp
new file mode 100644
index 0000000..d2822b0
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/communication/Commander.cpp
@@ -0,0 +1,685 @@
+#include "Commander.h"
+
+Commander::Commander(Stream& serial, char eol, bool echo){
+ com_port = &serial;
+ this->eol = eol;
+ this->echo = echo;
+}
+Commander::Commander(char eol, bool echo){
+ this->eol = eol;
+ this->echo = echo;
+}
+
+
+void Commander::add(char id, CommandCallback onCommand, const char* label ){
+ call_list[call_count] = onCommand;
+ call_ids[call_count] = id;
+ call_label[call_count] = (char*)label;
+ call_count++;
+}
+
+
+void Commander::run(){
+ if(!com_port) return;
+ run(*com_port, eol);
+}
+
+void Commander::run(Stream& serial, char eol){
+ Stream* tmp = com_port; // save the serial instance
+ char eol_tmp = this->eol;
+ this->eol = eol;
+ com_port = &serial;
+
+ // a string to hold incoming data
+ while (serial.available()) {
+ // get the new byte:
+ int ch = serial.read();
+ received_chars[rec_cnt++] = (char)ch;
+ // end of user input
+ if(echo)
+ print((char)ch);
+ if (isSentinel(ch)) {
+ // execute the user command
+ run(received_chars);
+
+ // reset the command buffer
+ received_chars[0] = 0;
+ rec_cnt=0;
+ }
+ if (rec_cnt>=MAX_COMMAND_LENGTH) { // prevent buffer overrun if message is too long
+ received_chars[0] = 0;
+ rec_cnt=0;
+ }
+ }
+
+ com_port = tmp; // reset the instance to the internal value
+ this->eol = eol_tmp;
+}
+
+void Commander::run(char* user_input){
+ // execute the user command
+ char id = user_input[0];
+ switch(id){
+ case CMD_SCAN:
+ for(int i=0; i < call_count; i++){
+ printMachineReadable(CMD_SCAN);
+ print(call_ids[i]);
+ print(":");
+ if(call_label[i]) println(call_label[i]);
+ else println("");
+ }
+ break;
+ case CMD_VERBOSE:
+ if(!isSentinel(user_input[1])) verbose = (VerboseMode)atoi(&user_input[1]);
+ printVerbose(F("Verb:"));
+ printMachineReadable(CMD_VERBOSE);
+ switch (verbose){
+ case VerboseMode::nothing:
+ println(F("off!"));
+ break;
+ case VerboseMode::on_request:
+ case VerboseMode::user_friendly:
+ println(F("on!"));
+ break;
+ case VerboseMode::machine_readable:
+ printlnMachineReadable(F("machine"));
+ break;
+ }
+ break;
+ case CMD_DECIMAL:
+ if(!isSentinel(user_input[1])) decimal_places = atoi(&user_input[1]);
+ printVerbose(F("Decimal:"));
+ printMachineReadable(CMD_DECIMAL);
+ println(decimal_places);
+ break;
+ default:
+ for(int i=0; i < call_count; i++){
+ if(id == call_ids[i]){
+ printMachineReadable(user_input[0]);
+ call_list[i](&user_input[1]);
+ break;
+ }
+ }
+ break;
+ }
+}
+
+void Commander::motor(FOCMotor* motor, char* user_command) {
+
+ // if target setting
+ if(isDigit(user_command[0]) || user_command[0] == '-' || user_command[0] == '+' || isSentinel(user_command[0])){
+ target(motor, user_command);
+ return;
+ }
+
+ // parse command letter
+ char cmd = user_command[0];
+ char sub_cmd = user_command[1];
+ // check if there is a subcommand or not
+ int value_index = (sub_cmd >= 'A' && sub_cmd <= 'Z') || (sub_cmd == '#') ? 2 : 1;
+ // check if get command
+ bool GET = isSentinel(user_command[value_index]);
+ // parse command values
+ float value = atof(&user_command[value_index]);
+ printMachineReadable(cmd);
+ if (sub_cmd >= 'A' && sub_cmd <= 'Z') {
+ printMachineReadable(sub_cmd);
+ }
+
+ // a bit of optimisation of variable memory for Arduino UNO (atmega328)
+ switch(cmd){
+ case CMD_C_Q_PID: //
+ printVerbose(F("PID curr q| "));
+ if(sub_cmd == SCMD_LPF_TF) lpf(&motor->LPF_current_q, &user_command[1]);
+ else pid(&motor->PID_current_q,&user_command[1]);
+ break;
+ case CMD_C_D_PID: //
+ printVerbose(F("PID curr d| "));
+ if(sub_cmd == SCMD_LPF_TF) lpf(&motor->LPF_current_d, &user_command[1]);
+ else pid(&motor->PID_current_d, &user_command[1]);
+ break;
+ case CMD_V_PID: //
+ printVerbose(F("PID vel| "));
+ if(sub_cmd == SCMD_LPF_TF) lpf(&motor->LPF_velocity, &user_command[1]);
+ else pid(&motor->PID_velocity, &user_command[1]);
+ break;
+ case CMD_A_PID: //
+ printVerbose(F("PID angle| "));
+ if(sub_cmd == SCMD_LPF_TF) lpf(&motor->LPF_angle, &user_command[1]);
+ else pid(&motor->P_angle, &user_command[1]);
+ break;
+ case CMD_LIMITS: //
+ printVerbose(F("Limits| "));
+ switch (sub_cmd){
+ case SCMD_LIM_VOLT: // voltage limit change
+ printVerbose(F("volt: "));
+ if(!GET) {
+ motor->voltage_limit = value;
+ motor->PID_current_d.limit = value;
+ motor->PID_current_q.limit = value;
+ // change velocity pid limit if in voltage mode and no phase resistance set
+ if( !_isset(motor->phase_resistance) && motor->torque_controller==TorqueControlType::voltage) motor->PID_velocity.limit = value;
+ }
+ println(motor->voltage_limit);
+ break;
+ case SCMD_LIM_CURR: // current limit
+ printVerbose(F("curr: "));
+ if(!GET){
+ motor->current_limit = value;
+ // if phase resistance specified or the current control is on set the current limit to the velocity PID
+ if(_isset(motor->phase_resistance) || motor->torque_controller != TorqueControlType::voltage ) motor->PID_velocity.limit = value;
+ }
+ println(motor->current_limit);
+ break;
+ case SCMD_LIM_VEL: // velocity limit
+ printVerbose(F("vel: "));
+ if(!GET){
+ motor->velocity_limit = value;
+ motor->P_angle.limit = value;
+ }
+ println(motor->velocity_limit);
+ break;
+ default:
+ printError();
+ break;
+ }
+ break;
+ case CMD_MOTION_TYPE:
+ case CMD_TORQUE_TYPE:
+ case CMD_STATUS:
+ motion(motor, &user_command[0]);
+ break;
+ case CMD_PWMMOD:
+ // PWM modulation change
+ printVerbose(F("PWM Mod | "));
+ switch (sub_cmd){
+ case SCMD_PWMMOD_TYPE: // zero offset
+ printVerbose(F("type: "));
+ if(!GET) motor->foc_modulation = (FOCModulationType)value;
+ switch(motor->foc_modulation){
+ case FOCModulationType::SinePWM:
+ println(F("SinePWM"));
+ break;
+ case FOCModulationType::SpaceVectorPWM:
+ println(F("SVPWM"));
+ break;
+ case FOCModulationType::Trapezoid_120:
+ println(F("Trap 120"));
+ break;
+ case FOCModulationType::Trapezoid_150:
+ println(F("Trap 150"));
+ break;
+ }
+ break;
+ case SCMD_PWMMOD_CENTER: // centered modulation
+ printVerbose(F("center: "));
+ if(!GET) motor->modulation_centered = value;
+ println(motor->modulation_centered);
+ break;
+ default:
+ printError();
+ break;
+ }
+ break;
+ case CMD_RESIST:
+ printVerbose(F("R phase: "));
+ if(!GET){
+ motor->phase_resistance = value;
+ if(motor->torque_controller==TorqueControlType::voltage)
+ motor->PID_velocity.limit= motor->current_limit;
+ }
+ if(_isset(motor->phase_resistance)) println(motor->phase_resistance);
+ else println(0);
+ break;
+ case CMD_INDUCTANCE:
+ printVerbose(F("L phase: "));
+ if(!GET){
+ motor->phase_inductance = value;
+ }
+ if(_isset(motor->phase_inductance)) println(motor->phase_inductance);
+ else println(0);
+ break;
+ case CMD_KV_RATING:
+ printVerbose(F("Motor KV: "));
+ if(!GET){
+ motor->KV_rating = value;
+ }
+ if(_isset(motor->KV_rating)) println(motor->KV_rating);
+ else println(0);
+ break;
+ case CMD_SENSOR:
+ // Sensor zero offset
+ printVerbose(F("Sensor | "));
+ switch (sub_cmd){
+ case SCMD_SENS_MECH_OFFSET: // zero offset
+ printVerbose(F("offset: "));
+ if(!GET) motor->sensor_offset = value;
+ println(motor->sensor_offset);
+ break;
+ case SCMD_SENS_ELEC_OFFSET: // electrical zero offset - not suggested to touch
+ printVerbose(F("el. offset: "));
+ if(!GET) motor->zero_electric_angle = value;
+ println(motor->zero_electric_angle);
+ break;
+ default:
+ printError();
+ break;
+ }
+ break;
+ case CMD_MONITOR: // get current values of the state variables
+ printVerbose(F("Monitor | "));
+ switch (sub_cmd){
+ case SCMD_GET: // get command
+ switch((uint8_t)value){
+ case 0: // get target
+ printVerbose(F("target: "));
+ println(motor->target);
+ break;
+ case 1: // get voltage q
+ printVerbose(F("Vq: "));
+ println(motor->voltage.q);
+ break;
+ case 2: // get voltage d
+ printVerbose(F("Vd: "));
+ println(motor->voltage.d);
+ break;
+ case 3: // get current q
+ printVerbose(F("Cq: "));
+ println(motor->current.q);
+ break;
+ case 4: // get current d
+ printVerbose(F("Cd: "));
+ println(motor->current.d);
+ break;
+ case 5: // get velocity
+ printVerbose(F("vel: "));
+ println(motor->shaft_velocity);
+ break;
+ case 6: // get angle
+ printVerbose(F("angle: "));
+ println(motor->shaft_angle);
+ break;
+ case 7: // get all states
+ printVerbose(F("all: "));
+ print(motor->target);
+ print(";");
+ print(motor->voltage.q);
+ print(";");
+ print(motor->voltage.d);
+ print(";");
+ print(motor->current.q);
+ print(";");
+ print(motor->current.d);
+ print(";");
+ print(motor->shaft_velocity);
+ print(";");
+ println(motor->shaft_angle);
+ break;
+ default:
+ printError();
+ break;
+ }
+ break;
+ case SCMD_DOWNSAMPLE:
+ printVerbose(F("downsample: "));
+ if(!GET) motor->monitor_downsample = value;
+ println((int)motor->monitor_downsample);
+ break;
+ case SCMD_CLEAR:
+ motor->monitor_variables = (uint8_t) 0;
+ println(F("clear"));
+ break;
+ case CMD_DECIMAL:
+ printVerbose(F("decimal: "));
+ motor->monitor_decimals = value;
+ println((int)motor->monitor_decimals);
+ break;
+ case SCMD_SET:
+ if(!GET){
+ // set the variables
+ motor->monitor_variables = (uint8_t) 0;
+ for(int i = 0; i < 7; i++){
+ if(isSentinel(user_command[value_index+i])) break;
+ motor->monitor_variables |= (user_command[value_index+i] - '0') << (6-i);
+ }
+ }
+ // print the variables
+ for(int i = 0; i < 7; i++){
+ print( (motor->monitor_variables & (1 << (6-i))) >> (6-i));
+ }
+ println("");
+ break;
+ default:
+ printError();
+ break;
+ }
+ break;
+ default: // unknown cmd
+ printVerbose(F("unknown cmd "));
+ printError();
+ }
+}
+
+void Commander::motion(FOCMotor* motor, char* user_cmd, char* separator){
+ char cmd = user_cmd[0];
+ char sub_cmd = user_cmd[1];
+ bool GET = isSentinel(user_cmd[1]);
+ float value = atof(&user_cmd[(sub_cmd >= 'A' && sub_cmd <= 'Z') ? 2 : 1]);
+
+ switch(cmd){
+ case CMD_MOTION_TYPE:
+ printVerbose(F("Motion:"));
+ switch(sub_cmd){
+ case SCMD_DOWNSAMPLE:
+ printVerbose(F(" downsample: "));
+ if(!GET) motor->motion_downsample = value;
+ println((int)motor->motion_downsample);
+ break;
+ default:
+ // change control type
+ if(!GET && value >= 0 && (int)value < 5) // if set command
+ motor->controller = (MotionControlType)value;
+ switch(motor->controller){
+ case MotionControlType::torque:
+ println(F("torque"));
+ break;
+ case MotionControlType::velocity:
+ println(F("vel"));
+ break;
+ case MotionControlType::angle:
+ println(F("angle"));
+ break;
+ case MotionControlType::velocity_openloop:
+ println(F("vel open"));
+ break;
+ case MotionControlType::angle_openloop:
+ println(F("angle open"));
+ break;
+ }
+ break;
+ }
+ break;
+ case CMD_TORQUE_TYPE:
+ // change control type
+ printVerbose(F("Torque: "));
+ if(!GET && (int8_t)value >= 0 && (int8_t)value < 3)// if set command
+ motor->torque_controller = (TorqueControlType)value;
+ switch(motor->torque_controller){
+ case TorqueControlType::voltage:
+ println(F("volt"));
+ // change the velocity control limits if necessary
+ if( !_isset(motor->phase_resistance) ) motor->PID_velocity.limit = motor->voltage_limit;
+ break;
+ case TorqueControlType::dc_current:
+ println(F("dc curr"));
+ // change the velocity control limits if necessary
+ motor->PID_velocity.limit = motor->current_limit;
+ break;
+ case TorqueControlType::foc_current:
+ println(F("foc curr"));
+ // change the velocity control limits if necessary
+ motor->PID_velocity.limit = motor->current_limit;
+ break;
+ }
+ break;
+ case CMD_STATUS:
+ // enable/disable
+ printVerbose(F("Status: "));
+ if(!GET) (bool)value ? motor->enable() : motor->disable();
+ println(motor->enabled);
+ break;
+ default:
+ target(motor, user_cmd, separator);
+ break;
+ }
+}
+
+void Commander::pid(PIDController* pid, char* user_cmd){
+ char cmd = user_cmd[0];
+ bool GET = isSentinel(user_cmd[1]);
+ float value = atof(&user_cmd[1]);
+
+ switch (cmd){
+ case SCMD_PID_P: // P gain change
+ printVerbose("P: ");
+ if(!GET) pid->P = value;
+ println(pid->P);
+ break;
+ case SCMD_PID_I: // I gain change
+ printVerbose("I: ");
+ if(!GET) pid->I = value;
+ println(pid->I);
+ break;
+ case SCMD_PID_D: // D gain change
+ printVerbose("D: ");
+ if(!GET) pid->D = value;
+ println(pid->D);
+ break;
+ case SCMD_PID_RAMP: // ramp change
+ printVerbose("ramp: ");
+ if(!GET) pid->output_ramp = value;
+ println(pid->output_ramp);
+ break;
+ case SCMD_PID_LIM: // limit change
+ printVerbose("limit: ");
+ if(!GET) pid->limit = value;
+ println(pid->limit);
+ break;
+ default:
+ printError();
+ break;
+ }
+}
+
+void Commander::lpf(LowPassFilter* lpf, char* user_cmd){
+ char cmd = user_cmd[0];
+ bool GET = isSentinel(user_cmd[1]);
+ float value = atof(&user_cmd[1]);
+
+ switch (cmd){
+ case SCMD_LPF_TF: // Tf value change
+ printVerbose(F("Tf: "));
+ if(!GET) lpf->Tf = value;
+ println(lpf->Tf);
+ break;
+ default:
+ printError();
+ break;
+ }
+}
+
+void Commander::scalar(float* value, char* user_cmd){
+ bool GET = isSentinel(user_cmd[0]);
+ if(!GET) *value = atof(user_cmd);
+ println(*value);
+}
+
+
+void Commander::target(FOCMotor* motor, char* user_cmd, char* separator){
+ // if no values sent
+ if(isSentinel(user_cmd[0])) {
+ printlnMachineReadable(motor->target);
+ return;
+ };
+
+ float pos, vel, torque;
+ char* next_value;
+ switch(motor->controller){
+ case MotionControlType::torque: // setting torque target
+ torque = atof(strtok (user_cmd, separator));
+ motor->target = torque;
+ break;
+ case MotionControlType::velocity: // setting velocity target + torque limit
+ // set the target
+ vel= atof(strtok (user_cmd, separator));
+ motor->target = vel;
+
+ // allow for setting only the target velocity without chaning the torque limit
+ next_value = strtok (NULL, separator);
+ if (next_value){
+ torque = atof(next_value);
+ motor->PID_velocity.limit = torque;
+ // torque command can be voltage or current
+ if(!_isset(motor->phase_resistance) && motor->torque_controller == TorqueControlType::voltage) motor->voltage_limit = torque;
+ else motor->current_limit = torque;
+ }
+ break;
+ case MotionControlType::angle: // setting angle target + torque, velocity limit
+ // setting the target position
+ pos= atof(strtok (user_cmd, separator));
+ motor->target = pos;
+
+ // allow for setting only the target position without chaning the velocity/torque limits
+ next_value = strtok (NULL, separator);
+ if( next_value ){
+ vel = atof(next_value);
+ motor->velocity_limit = vel;
+ motor->P_angle.limit = vel;
+
+ // allow for setting only the target position and velocity limit without the torque limit
+ next_value = strtok (NULL, separator);
+ if( next_value ){
+ torque= atof(next_value);
+ motor->PID_velocity.limit = torque;
+ // torque command can be voltage or current
+ if(!_isset(motor->phase_resistance) && motor->torque_controller == TorqueControlType::voltage) motor->voltage_limit = torque;
+ else motor->current_limit = torque;
+ }
+ }
+ break;
+ case MotionControlType::velocity_openloop: // setting velocity target + torque limit
+ // set the target
+ vel= atof(strtok (user_cmd, separator));
+ motor->target = vel;
+ // allow for setting only the target velocity without chaning the torque limit
+ next_value = strtok (NULL, separator);
+ if (next_value ){
+ torque = atof(next_value);
+ // torque command can be voltage or current
+ if(!_isset(motor->phase_resistance)) motor->voltage_limit = torque;
+ else motor->current_limit = torque;
+ }
+ break;
+ case MotionControlType::angle_openloop: // setting angle target + torque, velocity limit
+ // set the target
+ pos= atof(strtok (user_cmd, separator));
+ motor->target = pos;
+
+ // allow for setting only the target position without chaning the velocity/torque limits
+ next_value = strtok (NULL, separator);
+ if( next_value ){
+ vel = atof(next_value);
+ motor->velocity_limit = vel;
+ // allow for setting only the target velocity without chaning the torque limit
+ next_value = strtok (NULL, separator);
+ if (next_value ){
+ torque = atof(next_value);
+ // torque command can be voltage or current
+ if(!_isset(motor->phase_resistance)) motor->voltage_limit = torque;
+ else motor->current_limit = torque;
+ }
+ }
+ break;
+ }
+ printVerbose(F("Target: "));
+ println(motor->target);
+}
+
+
+bool Commander::isSentinel(char ch)
+{
+ if(ch == eol)
+ return true;
+ else if (ch == '\r')
+ {
+ printVerbose(F("Warn: \\r detected! \n"));
+ return true; // lets still consider it to end the line...
+ }
+ return false;
+}
+
+void Commander::print(const int number){
+ if( !com_port || verbose == VerboseMode::nothing ) return;
+ com_port->print(number);
+}
+void Commander::print(const float number){
+ if(!com_port || verbose == VerboseMode::nothing ) return;
+ com_port->print((float)number,(int)decimal_places);
+}
+void Commander::print(const char* message){
+ if(!com_port || verbose == VerboseMode::nothing ) return;
+ com_port->print(message);
+}
+void Commander::print(const __FlashStringHelper *message){
+ if(!com_port || verbose == VerboseMode::nothing ) return;
+ com_port->print(message);
+}
+void Commander::print(const char message){
+ if(!com_port || verbose == VerboseMode::nothing ) return;
+ com_port->print(message);
+}
+
+void Commander::println(const int number){
+ if(!com_port || verbose == VerboseMode::nothing ) return;
+ com_port->println(number);
+}
+void Commander::println(const float number){
+ if(!com_port || verbose == VerboseMode::nothing ) return;
+ com_port->println((float)number, (int)decimal_places);
+}
+void Commander::println(const char* message){
+ if(!com_port || verbose == VerboseMode::nothing ) return;
+ com_port->println(message);
+}
+void Commander::println(const __FlashStringHelper *message){
+ if(!com_port || verbose == VerboseMode::nothing ) return;
+ com_port->println(message);
+}
+void Commander::println(const char message){
+ if(!com_port || verbose == VerboseMode::nothing ) return;
+ com_port->println(message);
+}
+
+
+void Commander::printVerbose(const char* message){
+ if(verbose == VerboseMode::user_friendly) print(message);
+}
+void Commander::printVerbose(const __FlashStringHelper *message){
+ if(verbose == VerboseMode::user_friendly) print(message);
+}
+
+void Commander::printMachineReadable(const int number){
+ if(verbose == VerboseMode::machine_readable) print(number);
+}
+void Commander::printMachineReadable(const float number){
+ if(verbose == VerboseMode::machine_readable) print(number);
+}
+void Commander::printMachineReadable(const char* message){
+ if(verbose == VerboseMode::machine_readable) print(message);
+}
+void Commander::printMachineReadable(const __FlashStringHelper *message){
+ if(verbose == VerboseMode::machine_readable) print(message);
+}
+void Commander::printMachineReadable(const char message){
+ if(verbose == VerboseMode::machine_readable) print(message);
+}
+
+void Commander::printlnMachineReadable(const int number){
+ if(verbose == VerboseMode::machine_readable) println(number);
+}
+void Commander::printlnMachineReadable(const float number){
+ if(verbose == VerboseMode::machine_readable) println(number);
+}
+void Commander::printlnMachineReadable(const char* message){
+ if(verbose == VerboseMode::machine_readable) println(message);
+}
+void Commander::printlnMachineReadable(const __FlashStringHelper *message){
+ if(verbose == VerboseMode::machine_readable) println(message);
+}
+void Commander::printlnMachineReadable(const char message){
+ if(verbose == VerboseMode::machine_readable) println(message);
+}
+
+void Commander::printError(){
+ println(F("err"));
+}
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/communication/Commander.h b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/communication/Commander.h
new file mode 100644
index 0000000..4ec2b28
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/communication/Commander.h
@@ -0,0 +1,301 @@
+#ifndef COMMANDS_H
+#define COMMANDS_H
+
+#include "Arduino.h"
+#include "../common/base_classes/FOCMotor.h"
+#include "../common/pid.h"
+#include "../common/lowpass_filter.h"
+#include "commands.h"
+
+
+#define MAX_COMMAND_LENGTH 20
+
+
+// Commander verbose display to the user type
+enum VerboseMode : uint8_t {
+ nothing = 0x00, // display nothing - good for monitoring
+ on_request = 0x01, // display only on user request
+ user_friendly = 0x02, // display textual messages to the user
+ machine_readable = 0x03 // display machine readable commands, matching commands to set each settings
+};
+
+
+// callback function pointer definiton
+typedef void (* CommandCallback)(char*); //!< command callback function pointer
+
+/**
+ * Commander class implementing string communication protocol based on IDvalue (ex AB5.321 - command id `A`, sub-command id `B`,value `5.321`)
+ *
+ * - This class can be used in combination with HardwareSerial instance which it would read and write
+ * or it can be used to parse strings that have been received from the user outside this library
+ * - Commander class implements command protocol for few standard components of the SimpleFOC library
+ * - FOCMotor
+ * - PIDController
+ * - LowPassFilter
+ * - Commander also provides a very simple command > callback interface that enables user to
+ * attach a callback function to certain command id - see function add()
+ */
+class Commander
+{
+ public:
+ /**
+ * Default constructor receiving a serial interface that it uses to output the values to
+ * Also if the function run() is used it uses this serial instance to read the serial for user commands
+ *
+ * @param serial - Serial com port instance
+ * @param eol - the end of line sentinel character
+ * @param echo - echo last typed character (for command line feedback)
+ */
+ Commander(Stream &serial, char eol = '\n', bool echo = false);
+ Commander(char eol = '\n', bool echo = false);
+
+ /**
+ * Function reading the serial port and firing callbacks that have been added to the commander
+ * once the user has requested them - when he sends the command
+ *
+ * - It has default commands (the letters can be changed in the commands.h file)
+ * '@' - Verbose mode
+ * '#' - Number of decimal places
+ * '?' - Scan command - displays all the labels of attached nodes
+ */
+ void run();
+ /**
+ * Function reading the string of user input and firing callbacks that have been added to the commander
+ * once the user has requested them - when he sends the command
+ *
+ * - It has default commands (the letters can be changed in the commands.h file)
+ * '@' - Verbose mode
+ * '#' - Number of decimal places
+ * '?' - Scan command - displays all the labels of attached nodes
+ *
+ * @param reader - temporary stream to read user input
+ * @param eol - temporary end of line sentinel
+ */
+ void run(Stream &reader, char eol = '\n');
+ /**
+ * Function reading the string of user input and firing callbacks that have been added to the commander
+ * once the user has requested them - when he sends the command
+ *
+ * - It has default commands (the letters can be changed in the commands.h file)
+ * '@' - Verbose mode
+ * '#' - Number of decimal places
+ * '?' - Scan command - displays all the labels of attached nodes
+ *
+ * @param user_input - string of user inputs
+ */
+ void run(char* user_input);
+
+ /**
+ * Function adding a callback to the coomander withe the command id
+ * @param id - char command letter
+ * @param onCommand - function pointer void function(char*)
+ * @param label - string label to be displayed when scan command sent
+ */
+ void add(char id , CommandCallback onCommand, const char* label = nullptr);
+
+ // printing variables
+ VerboseMode verbose = VerboseMode::user_friendly; //!< flag signaling that the commands should output user understanable text
+ uint8_t decimal_places = 3; //!< number of decimal places to be used when displaying numbers
+
+ // monitoring functions
+ Stream* com_port = nullptr; //!< Serial terminal variable if provided
+ char eol = '\n'; //!< end of line sentinel character
+ bool echo = false; //!< echo last typed character (for command line feedback)
+
+ /**
+ *
+ * FOC motor (StepperMotor and BLDCMotor) command interface
+ * @param motor - FOCMotor (BLDCMotor or StepperMotor) instance
+ * @param user_cmd - the string command
+ *
+ * - It has several paramters (the letters can be changed in the commands.h file)
+ * 'Q' - Q current PID controller & LPF (see function pid and lpf for commands)
+ * 'D' - D current PID controller & LPF (see function pid and lpf for commands)
+ * 'V' - Velocity PID controller & LPF (see function pid and lpf for commands)
+ * 'A' - Angle PID controller & LPF (see function pid and lpf for commands)
+ * 'L' - Limits
+ * sub-commands:
+ * 'C' - Current
+ * 'U' - Voltage
+ * 'V' - Velocity
+ * 'C' - Motion control type config
+ * sub-commands:
+ * 'D' - downsample motiron loop
+ * '0' - torque
+ * '1' - velocity
+ * '2' - angle
+ * 'T' - Torque control type
+ * sub-commands:
+ * '0' - voltage
+ * '1' - current
+ * '2' - foc_current
+ * 'E' - Motor status (enable/disable)
+ * sub-commands:
+ * '0' - enable
+ * '1' - disable
+ * 'R' - Motor resistance
+ * 'S' - Sensor offsets
+ * sub-commands:
+ * 'M' - sensor offset
+ * 'E' - sensor electrical zero
+ * 'M' - Monitoring control
+ * sub-commands:
+ * 'D' - downsample monitoring
+ * 'C' - clear monitor
+ * 'S' - set monitoring variables
+ * 'G' - get variable value
+ * '' - Target setting interface
+ * Depends of the motion control mode:
+ * - torque : torque (ex. M2.5)
+ * - velocity (open and closed loop) : velocity torque (ex.M10 2.5 or M10 to only chanage the target witout limits)
+ * - angle (open and closed loop) : angle velocity torque (ex.M3.5 10 2.5 or M3.5 to only chanage the target witout limits)
+ *
+ * - Each of them can be get by sening the command letter -(ex. 'R' - to get the phase resistance)
+ * - Each of them can be set by sending 'IdSubidValue' - (ex. SM1.5 for setting sensor zero offset to 1.5f)
+ *
+ */
+ void motor(FOCMotor* motor, char* user_cmd);
+
+ /**
+ * Low pass fileter command interface
+ * @param lpf - LowPassFilter instance
+ * @param user_cmd - the string command
+ *
+ * - It only has one property - filtering time constant Tf
+ * - It can be get by sending 'F'
+ * - It can be set by sending 'Fvalue' - (ex. F0.01 for settin Tf=0.01)
+ */
+ void lpf(LowPassFilter* lpf, char* user_cmd);
+ /**
+ * PID controller command interface
+ * @param pid - PIDController instance
+ * @param user_cmd - the string command
+ *
+ * - It has several paramters (the letters can be changed in the commands.h file)
+ * - P gain - 'P'
+ * - I gain - 'I'
+ * - D gain - 'D'
+ * - output ramp - 'R'
+ * - output limit - 'L'
+ * - Each of them can be get by sening the command letter -(ex. 'D' - to get the D gain)
+ * - Each of them can be set by sending 'IDvalue' - (ex. I1.5 for setting I=1.5)
+ */
+ void pid(PIDController* pid, char* user_cmd);
+ /**
+ * Float variable scalar command interface
+ * @param value - float variable pointer
+ * @param user_cmd - the string command
+ *
+ * - It only has one property - one float value
+ * - It can be get by sending an empty string '\n'
+ * - It can be set by sending 'value' - (ex. 0.01f for settin *value=0.01)
+ */
+ void scalar(float* value, char* user_cmd);
+ /**
+ * Target setting interface, enables setting the target and limiting variables at once.
+ * The values are sent separated by a separator specified as the third argument. The default separator is the space.
+ *
+ * @param motor - FOCMotor (BLDCMotor or StepperMotor) instance
+ * @param user_cmd - the string command
+ * @param separator - the string separator in between target and limit values, default is space - " "
+ *
+ * Example: P2.34 70 2
+ * `P` is the user defined command, `2.34` is the target angle `70` is the target
+ * velocity and `2` is the desired max current.
+ *
+ * It depends of the motion control mode:
+ * - torque : torque (ex. P2.5)
+ * - velocity : velocity torque (ex.P10 2.5 or P10 to only chanage the target witout limits)
+ * - angle : angle velocity torque (ex.P3.5 10 2.5 or P3.5 to only chanage the target witout limits)
+ */
+ void target(FOCMotor* motor, char* user_cmd, char* separator = (char *)" ");
+
+ /**
+ * FOC motor (StepperMotor and BLDCMotor) motion control interfaces
+ * @param motor - FOCMotor (BLDCMotor or StepperMotor) instance
+ * @param user_cmd - the string command
+ * @param separator - the string separator in between target and limit values, default is space - " "
+ *
+ * Commands:
+ * 'C' - Motion control type config
+ * sub-commands:
+ * 'D' - downsample motiron loop
+ * '0' - torque
+ * '1' - velocity
+ * '2' - angle
+ * 'T' - Torque control type
+ * sub-commands:
+ * '0' - voltage
+ * '1' - current
+ * '2' - foc_current
+ * 'E' - Motor status (enable/disable)
+ * sub-commands:
+ * '0' - enable
+ * '1' - disable
+ * '' - Target setting interface
+ * Depends of the motion control mode:
+ * - torque : torque (ex. M2.5)
+ * - velocity (open and closed loop) : velocity torque (ex.M10 2.5 or M10 to only chanage the target witout limits)
+ * - angle (open and closed loop) : angle velocity torque (ex.M3.5 10 2.5 or M3.5 to only chanage the target witout limits)
+ */
+ void motion(FOCMotor* motor, char* user_cmd, char* separator = (char *)" ");
+
+ bool isSentinel(char ch);
+ private:
+ // Subscribed command callback variables
+ CommandCallback call_list[20];//!< array of command callback pointers - 20 is an arbitrary number
+ char call_ids[20]; //!< added callback commands
+ char* call_label[20]; //!< added callback labels
+ int call_count = 0;//!< number callbacks that are subscribed
+
+ // helping variable for serial communication reading
+ char received_chars[MAX_COMMAND_LENGTH] = {0}; //!< so far received user message - waiting for newline
+ int rec_cnt = 0; //!< number of characters receives
+
+ // serial printing functions
+ /**
+ * print the string message only if verbose mode on
+ * @param message - message to be printed
+ */
+ void printVerbose(const char* message);
+ /**
+ * Print the string message only if verbose mode on
+ * - Function handling the case for strings defined by F macro
+ * @param message - message to be printed
+ */
+ void printVerbose(const __FlashStringHelper *message);
+ /**
+ * print the numbers to the serial with desired decimal point number
+ * @param message - number to be printed
+ * @param newline - if needs lewline (1) otherwise (0)
+ */
+
+ void print(const float number);
+ void print(const int number);
+ void print(const char* message);
+ void print(const __FlashStringHelper *message);
+ void print(const char message);
+ void println(const float number);
+ void println(const int number);
+ void println(const char* message);
+ void println(const __FlashStringHelper *message);
+ void println(const char message);
+
+ void printMachineReadable(const float number);
+ void printMachineReadable(const int number);
+ void printMachineReadable(const char* message);
+ void printMachineReadable(const __FlashStringHelper *message);
+ void printMachineReadable(const char message);
+
+ void printlnMachineReadable(const float number);
+ void printlnMachineReadable(const int number);
+ void printlnMachineReadable(const char* message);
+ void printlnMachineReadable(const __FlashStringHelper *message);
+ void printlnMachineReadable(const char message);
+
+
+ void printError();
+};
+
+
+#endif
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/communication/SimpleFOCDebug.cpp b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/communication/SimpleFOCDebug.cpp
new file mode 100644
index 0000000..4d50b87
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/communication/SimpleFOCDebug.cpp
@@ -0,0 +1,125 @@
+
+#include "SimpleFOCDebug.h"
+
+#ifndef SIMPLEFOC_DISABLE_DEBUG
+
+
+Print* SimpleFOCDebug::_debugPrint = NULL;
+
+
+void SimpleFOCDebug::enable(Print* debugPrint) {
+ _debugPrint = debugPrint;
+}
+
+
+void SimpleFOCDebug::println(int val) {
+ if (_debugPrint != NULL) {
+ _debugPrint->println(val);
+ }
+}
+
+void SimpleFOCDebug::println(float val) {
+ if (_debugPrint != NULL) {
+ _debugPrint->println(val);
+ }
+}
+
+
+
+void SimpleFOCDebug::println(const char* str) {
+ if (_debugPrint != NULL) {
+ _debugPrint->println(str);
+ }
+}
+
+void SimpleFOCDebug::println(const __FlashStringHelper* str) {
+ if (_debugPrint != NULL) {
+ _debugPrint->println(str);
+ }
+}
+
+
+void SimpleFOCDebug::println(const char* str, float val) {
+ if (_debugPrint != NULL) {
+ _debugPrint->print(str);
+ _debugPrint->println(val);
+ }
+}
+
+void SimpleFOCDebug::println(const __FlashStringHelper* str, float val) {
+ if (_debugPrint != NULL) {
+ _debugPrint->print(str);
+ _debugPrint->println(val);
+ }
+}
+
+void SimpleFOCDebug::println(const char* str, int val) {
+ if (_debugPrint != NULL) {
+ _debugPrint->print(str);
+ _debugPrint->println(val);
+ }
+}
+void SimpleFOCDebug::println(const char* str, char val) {
+ if (_debugPrint != NULL) {
+ _debugPrint->print(str);
+ _debugPrint->println(val);
+ }
+}
+
+void SimpleFOCDebug::println(const __FlashStringHelper* str, int val) {
+ if (_debugPrint != NULL) {
+ _debugPrint->print(str);
+ _debugPrint->println(val);
+ }
+}
+
+
+void SimpleFOCDebug::print(const char* str) {
+ if (_debugPrint != NULL) {
+ _debugPrint->print(str);
+ }
+}
+
+
+void SimpleFOCDebug::print(const __FlashStringHelper* str) {
+ if (_debugPrint != NULL) {
+ _debugPrint->print(str);
+ }
+}
+
+void SimpleFOCDebug::print(const StringSumHelper str) {
+ if (_debugPrint != NULL) {
+ _debugPrint->print(str.c_str());
+ }
+}
+
+
+void SimpleFOCDebug::println(const StringSumHelper str) {
+ if (_debugPrint != NULL) {
+ _debugPrint->println(str.c_str());
+ }
+}
+
+
+
+void SimpleFOCDebug::print(int val) {
+ if (_debugPrint != NULL) {
+ _debugPrint->print(val);
+ }
+}
+
+
+void SimpleFOCDebug::print(float val) {
+ if (_debugPrint != NULL) {
+ _debugPrint->print(val);
+ }
+}
+
+
+void SimpleFOCDebug::println() {
+ if (_debugPrint != NULL) {
+ _debugPrint->println();
+ }
+}
+
+#endif
\ No newline at end of file
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/communication/SimpleFOCDebug.h b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/communication/SimpleFOCDebug.h
new file mode 100644
index 0000000..d0ff611
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/communication/SimpleFOCDebug.h
@@ -0,0 +1,79 @@
+
+#ifndef __SIMPLEFOCDEBUG_H__
+#define __SIMPLEFOCDEBUG_H__
+
+#include "Arduino.h"
+
+
+/**
+ * SimpleFOCDebug class
+ *
+ * This class is used to print debug messages to a chosen output.
+ * Currently, Print instances are supported as targets, e.g. serial port.
+ *
+ * Activate debug output globally by calling enable(), optionally passing
+ * in a Print instance. If none is provided "Serial" is used by default.
+ *
+ * To produce debug output, use the macro SIMPLEFOC_DEBUG:
+ * SIMPLEFOC_DEBUG("Debug message!");
+ * SIMPLEFOC_DEBUG("a float value:", 123.456f);
+ * SIMPLEFOC_DEBUG("an integer value: ", 123);
+ *
+ * Keep debugging output short and simple. Some of our MCUs have limited
+ * RAM and limited serial output capabilities.
+ *
+ * By default, the SIMPLEFOC_DEBUG macro uses the flash string helper to
+ * help preserve memory on Arduino boards.
+ *
+ * You can also disable debug output completely. In this case all debug output
+ * and the SimpleFOCDebug class is removed from the compiled code.
+ * Add -DSIMPLEFOC_DISABLE_DEBUG to your compiler flags to disable debug in
+ * this way.
+ *
+ **/
+
+// #define SIMPLEFOC_DISABLE_DEBUG
+
+#ifndef SIMPLEFOC_DISABLE_DEBUG
+
+class SimpleFOCDebug {
+public:
+ static void enable(Print* debugPrint = &Serial);
+
+ static void println(const __FlashStringHelper* msg);
+ static void println(const StringSumHelper msg);
+ static void println(const char* msg);
+ static void println(const __FlashStringHelper* msg, float val);
+ static void println(const char* msg, float val);
+ static void println(const __FlashStringHelper* msg, int val);
+ static void println(const char* msg, int val);
+ static void println(const char* msg, char val);
+ static void println();
+ static void println(int val);
+ static void println(float val);
+
+ static void print(const char* msg);
+ static void print(const __FlashStringHelper* msg);
+ static void print(const StringSumHelper msg);
+ static void print(int val);
+ static void print(float val);
+
+protected:
+ static Print* _debugPrint;
+};
+
+
+#define SIMPLEFOC_DEBUG(msg, ...) \
+ SimpleFOCDebug::println(F(msg), ##__VA_ARGS__)
+
+#else //ifndef SIMPLEFOC_DISABLE_DEBUG
+
+
+
+#define SIMPLEFOC_DEBUG(msg, ...)
+
+
+
+#endif //ifndef SIMPLEFOC_DISABLE_DEBUG
+#endif
+
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/communication/StepDirListener.cpp b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/communication/StepDirListener.cpp
new file mode 100644
index 0000000..ee4f69e
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/communication/StepDirListener.cpp
@@ -0,0 +1,40 @@
+#include "StepDirListener.h"
+
+StepDirListener::StepDirListener(int _pinStep, int _pinDir, float _counter_to_value){
+ pin_step = _pinStep;
+ pin_dir = _pinDir;
+ counter_to_value = _counter_to_value;
+}
+
+void StepDirListener::init(){
+ pinMode(pin_dir, INPUT);
+ pinMode(pin_step, INPUT_PULLUP);
+ count = 0;
+}
+
+void StepDirListener::enableInterrupt(void (*doA)()){
+ attachInterrupt(digitalPinToInterrupt(pin_step), doA, polarity);
+}
+
+void StepDirListener::attach(float* variable){
+ attached_variable = variable;
+}
+
+void StepDirListener::handle(){
+ // read step status
+ //bool step = digitalRead(pin_step);
+ // update counter only on rising edge
+ //if(step && step != step_active){
+ if(digitalRead(pin_dir))
+ count++;
+ else
+ count--;
+ //}
+ //step_active = step;
+ // if attached variable update it
+ if(attached_variable) *attached_variable = getValue();
+}
+// calculate the position from counter
+float StepDirListener::getValue(){
+ return (float) count * counter_to_value;
+}
\ No newline at end of file
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/communication/StepDirListener.h b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/communication/StepDirListener.h
new file mode 100644
index 0000000..3627b5e
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/communication/StepDirListener.h
@@ -0,0 +1,60 @@
+#ifndef STEPDIR_H
+#define STEPDIR_H
+
+#include "Arduino.h"
+#include "../common/foc_utils.h"
+
+
+/**
+ * Step/Dir listenner class for easier interraction with this communication interface.
+ */
+class StepDirListener
+{
+ public:
+
+ /**
+ * Constructor for step/direction interface
+ * @param step - pin
+ * @param direction - pin
+ * @param counter_to_value - step counter to value
+ */
+ StepDirListener(int pinStep, int pinDir, float counter_to_value = 1);
+ /**
+ * Start listenning for step commands
+ *
+ * @param handleStep - on step received handler
+ */
+ void enableInterrupt(void (*handleStep)());
+
+ /**
+ * Initialise dir and step commands
+ */
+ void init();
+ /**
+ * step handler
+ */
+ void handle();
+ /**
+ * Get so far received valued
+ */
+ float getValue();
+ /**
+ * Attach the value to be updated on each step receive
+ * - no need to call getValue function
+ */
+ void attach(float* variable);
+
+ // variables
+ int pin_step; //!< step pin
+ int pin_dir; //!< direction pin
+ long count; //!< current counter value - should be set to 0 for homing
+ decltype(RISING) polarity = RISING; //!< polarity of the step pin
+
+ private:
+ float* attached_variable = nullptr; //!< pointer to the attached variable
+ float counter_to_value; //!< step counter to value
+ //bool step_active = 0; //!< current step pin status (HIGH/LOW) - debouncing variable
+
+};
+
+#endif
\ No newline at end of file
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/communication/commands.h b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/communication/commands.h
new file mode 100644
index 0000000..323a8e7
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/communication/commands.h
@@ -0,0 +1,52 @@
+#ifndef COMMANDS_h
+#define COMMANDS_h
+
+// see docs.simplefoc.com for in depth explanation of the commands
+
+// list of commands
+ #define CMD_C_D_PID 'D' //!< current d PID & LPF
+ #define CMD_C_Q_PID 'Q' //!< current d PID & LPF
+ #define CMD_V_PID 'V' //!< velocity PID & LPF
+ #define CMD_A_PID 'A' //!< angle PID & LPF
+ #define CMD_STATUS 'E' //!< motor status enable/disable
+ #define CMD_LIMITS 'L' //!< limits current/voltage/velocity
+ #define CMD_MOTION_TYPE 'C' //!< motion control type
+ #define CMD_TORQUE_TYPE 'T' //!< torque control type
+ #define CMD_SENSOR 'S' //!< sensor offsets
+ #define CMD_MONITOR 'M' //!< monitoring
+ #define CMD_RESIST 'R' //!< motor phase resistance
+ #define CMD_INDUCTANCE 'I' //!< motor phase inductance
+ #define CMD_KV_RATING 'K' //!< motor kv rating
+ #define CMD_PWMMOD 'W' //!< pwm modulation
+
+ // commander configuration
+ #define CMD_SCAN '?' //!< command scaning the network - only for commander
+ #define CMD_VERBOSE '@' //!< command setting output mode - only for commander
+ #define CMD_DECIMAL '#' //!< command setting decimal places - only for commander
+
+ // subcomands
+ //pid - lpf
+ #define SCMD_PID_P 'P' //!< PID gain P
+ #define SCMD_PID_I 'I' //!< PID gain I
+ #define SCMD_PID_D 'D' //!< PID gain D
+ #define SCMD_PID_RAMP 'R' //!< PID ramp
+ #define SCMD_PID_LIM 'L' //!< PID limit
+ #define SCMD_LPF_TF 'F' //!< LPF time constant
+ // limits
+ #define SCMD_LIM_CURR 'C' //!< Limit current
+ #define SCMD_LIM_VOLT 'U' //!< Limit voltage
+ #define SCMD_LIM_VEL 'V' //!< Limit velocity
+ //sensor
+ #define SCMD_SENS_MECH_OFFSET 'M' //!< Sensor offset
+ #define SCMD_SENS_ELEC_OFFSET 'E' //!< Sensor electrical zero offset
+ // monitoring
+ #define SCMD_DOWNSAMPLE 'D' //!< Monitoring downsample value
+ #define SCMD_CLEAR 'C' //!< Clear all monitored variables
+ #define SCMD_GET 'G' //!< Get variable only one value
+ #define SCMD_SET 'S' //!< Set variables to be monitored
+
+ #define SCMD_PWMMOD_TYPE 'T' //!<< Pwm modulation type
+ #define SCMD_PWMMOD_CENTER 'C' //!<< Pwm modulation center flag
+
+
+#endif
\ No newline at end of file
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/GenericCurrentSense.cpp b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/GenericCurrentSense.cpp
new file mode 100644
index 0000000..54c4f12
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/GenericCurrentSense.cpp
@@ -0,0 +1,63 @@
+#include "GenericCurrentSense.h"
+
+// GenericCurrentSense constructor
+GenericCurrentSense::GenericCurrentSense(PhaseCurrent_s (*readCallback)(), void (*initCallback)()){
+ // if function provided add it to the
+ if(readCallback != nullptr) this->readCallback = readCallback;
+ if(initCallback != nullptr) this->initCallback = initCallback;
+}
+
+// Inline sensor init function
+int GenericCurrentSense::init(){
+ // configure ADC variables
+ if(initCallback != nullptr) initCallback();
+ // calibrate zero offsets
+ calibrateOffsets();
+ // set the initialized flag
+ initialized = (params!=SIMPLEFOC_CURRENT_SENSE_INIT_FAILED);
+ // return success
+ return 1;
+}
+// Function finding zero offsets of the ADC
+void GenericCurrentSense::calibrateOffsets(){
+ const int calibration_rounds = 1000;
+
+ // find adc offset = zero current voltage
+ offset_ia = 0;
+ offset_ib = 0;
+ offset_ic = 0;
+ // read the adc voltage 1000 times ( arbitrary number )
+ for (int i = 0; i < calibration_rounds; i++) {
+ PhaseCurrent_s current = readCallback();
+ offset_ia += current.a;
+ offset_ib += current.b;
+ offset_ic += current.c;
+ _delay(1);
+ }
+ // calculate the mean offsets
+ offset_ia = offset_ia / calibration_rounds;
+ offset_ib = offset_ib / calibration_rounds;
+ offset_ic = offset_ic / calibration_rounds;
+}
+
+// read all three phase currents (if possible 2 or 3)
+PhaseCurrent_s GenericCurrentSense::getPhaseCurrents(){
+ PhaseCurrent_s current = readCallback();
+ current.a = (current.a - offset_ia); // amps
+ current.b = (current.b - offset_ib); // amps
+ current.c = (current.c - offset_ic); // amps
+ return current;
+}
+
+// Function aligning the current sense with motor driver
+// if all pins are connected well none of this is really necessary! - can be avoided
+// returns flag
+// 0 - fail
+// 1 - success and nothing changed
+int GenericCurrentSense::driverAlign(float voltage, bool modulation_centered){
+ _UNUSED(voltage) ; // remove unused parameter warning
+ int exit_flag = 1;
+ if(skip_align) return exit_flag;
+ if (!initialized) return 0;
+ return exit_flag;
+}
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/GenericCurrentSense.h b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/GenericCurrentSense.h
new file mode 100644
index 0000000..02bf8fa
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/GenericCurrentSense.h
@@ -0,0 +1,40 @@
+#ifndef GENERIC_CS_LIB_H
+#define GENERIC_CS_LIB_H
+
+#include "Arduino.h"
+#include "../common/foc_utils.h"
+#include "../common/time_utils.h"
+#include "../common/defaults.h"
+#include "../common/base_classes/CurrentSense.h"
+#include "../common/lowpass_filter.h"
+#include "hardware_api.h"
+
+
+class GenericCurrentSense: public CurrentSense{
+ public:
+ /**
+ GenericCurrentSense class constructor
+ */
+ GenericCurrentSense(PhaseCurrent_s (*readCallback)() = nullptr, void (*initCallback)() = nullptr);
+
+ // CurrentSense interface implementing functions
+ int init() override;
+ PhaseCurrent_s getPhaseCurrents() override;
+ int driverAlign(float align_voltage, bool modulation_centered) override;
+
+
+ PhaseCurrent_s (*readCallback)() = nullptr; //!< function pointer to sensor reading
+ void (*initCallback)() = nullptr; //!< function pointer to sensor initialisation
+
+ private:
+ /**
+ * Function finding zero offsets of the ADC
+ */
+ void calibrateOffsets();
+ float offset_ia; //!< zero current A voltage value (center of the adc reading)
+ float offset_ib; //!< zero current B voltage value (center of the adc reading)
+ float offset_ic; //!< zero current C voltage value (center of the adc reading)
+
+};
+
+#endif
\ No newline at end of file
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/InlineCurrentSense.cpp b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/InlineCurrentSense.cpp
new file mode 100644
index 0000000..35c9776
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/InlineCurrentSense.cpp
@@ -0,0 +1,88 @@
+#include "InlineCurrentSense.h"
+#include "communication/SimpleFOCDebug.h"
+// InlineCurrentSensor constructor
+// - shunt_resistor - shunt resistor value
+// - gain - current-sense op-amp gain
+// - phA - A phase adc pin
+// - phB - B phase adc pin
+// - phC - C phase adc pin (optional)
+InlineCurrentSense::InlineCurrentSense(float _shunt_resistor, float _gain, int _pinA, int _pinB, int _pinC){
+ pinA = _pinA;
+ pinB = _pinB;
+ pinC = _pinC;
+
+ shunt_resistor = _shunt_resistor;
+ amp_gain = _gain;
+ volts_to_amps_ratio = 1.0f /_shunt_resistor / _gain; // volts to amps
+ // gains for each phase
+ gain_a = volts_to_amps_ratio;
+ gain_b = volts_to_amps_ratio;
+ gain_c = volts_to_amps_ratio;
+};
+
+
+InlineCurrentSense::InlineCurrentSense(float _mVpA, int _pinA, int _pinB, int _pinC){
+ pinA = _pinA;
+ pinB = _pinB;
+ pinC = _pinC;
+
+ volts_to_amps_ratio = 1000.0f / _mVpA; // mV to amps
+ // gains for each phase
+ gain_a = volts_to_amps_ratio;
+ gain_b = volts_to_amps_ratio;
+ gain_c = volts_to_amps_ratio;
+};
+
+
+
+// Inline sensor init function
+int InlineCurrentSense::init(){
+ // if no linked driver its fine in this case
+ // at least for init()
+ void* drv_params = driver ? driver->params : nullptr;
+ // configure ADC variables
+ params = _configureADCInline(drv_params,pinA,pinB,pinC);
+ // if init failed return fail
+ if (params == SIMPLEFOC_CURRENT_SENSE_INIT_FAILED) return 0;
+ // set the center pwm (0 voltage vector)
+ if(driver_type==DriverType::BLDC)
+ static_cast(driver)->setPwm(driver->voltage_limit/2, driver->voltage_limit/2, driver->voltage_limit/2);
+ // calibrate zero offsets
+ calibrateOffsets();
+ // set zero voltage to all phases
+ if(driver_type==DriverType::BLDC)
+ static_cast(driver)->setPwm(0,0,0);
+ // set the initialized flag
+ initialized = (params!=SIMPLEFOC_CURRENT_SENSE_INIT_FAILED);
+ // return success
+ return 1;
+}
+// Function finding zero offsets of the ADC
+void InlineCurrentSense::calibrateOffsets(){
+ const int calibration_rounds = 1000;
+
+ // find adc offset = zero current voltage
+ offset_ia = 0;
+ offset_ib = 0;
+ offset_ic = 0;
+ // read the adc voltage 1000 times ( arbitrary number )
+ for (int i = 0; i < calibration_rounds; i++) {
+ if(_isset(pinA)) offset_ia += _readADCVoltageInline(pinA, params);
+ if(_isset(pinB)) offset_ib += _readADCVoltageInline(pinB, params);
+ if(_isset(pinC)) offset_ic += _readADCVoltageInline(pinC, params);
+ _delay(1);
+ }
+ // calculate the mean offsets
+ if(_isset(pinA)) offset_ia = offset_ia / calibration_rounds;
+ if(_isset(pinB)) offset_ib = offset_ib / calibration_rounds;
+ if(_isset(pinC)) offset_ic = offset_ic / calibration_rounds;
+}
+
+// read all three phase currents (if possible 2 or 3)
+PhaseCurrent_s InlineCurrentSense::getPhaseCurrents(){
+ PhaseCurrent_s current;
+ current.a = (!_isset(pinA)) ? 0 : (_readADCVoltageInline(pinA, params) - offset_ia)*gain_a;// amps
+ current.b = (!_isset(pinB)) ? 0 : (_readADCVoltageInline(pinB, params) - offset_ib)*gain_b;// amps
+ current.c = (!_isset(pinC)) ? 0 : (_readADCVoltageInline(pinC, params) - offset_ic)*gain_c; // amps
+ return current;
+}
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/InlineCurrentSense.h b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/InlineCurrentSense.h
new file mode 100644
index 0000000..94be0f7
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/InlineCurrentSense.h
@@ -0,0 +1,54 @@
+#ifndef INLINE_CS_LIB_H
+#define INLINE_CS_LIB_H
+
+#include "Arduino.h"
+#include "../common/foc_utils.h"
+#include "../common/time_utils.h"
+#include "../common/defaults.h"
+#include "../common/base_classes/CurrentSense.h"
+#include "../common/base_classes/StepperDriver.h"
+#include "../common/base_classes/BLDCDriver.h"
+#include "../common/lowpass_filter.h"
+#include "hardware_api.h"
+
+
+
+class InlineCurrentSense: public CurrentSense{
+ public:
+ /**
+ InlineCurrentSense class constructor
+ @param shunt_resistor shunt resistor value
+ @param gain current-sense op-amp gain
+ @param phA A phase adc pin
+ @param phB B phase adc pin
+ @param phC C phase adc pin (optional)
+ */
+ InlineCurrentSense(float shunt_resistor, float gain, int pinA, int pinB, int pinC = NOT_SET);
+ /**
+ InlineCurrentSense class constructor
+ @param mVpA mV per Amp ratio
+ @param phA A phase adc pin
+ @param phB B phase adc pin
+ @param phC C phase adc pin (optional)
+ */
+ InlineCurrentSense(float mVpA, int pinA, int pinB, int pinC = NOT_SET);
+
+ // CurrentSense interface implementing functions
+ int init() override;
+ PhaseCurrent_s getPhaseCurrents() override;
+
+ private:
+
+ // gain variables
+ float shunt_resistor; //!< Shunt resistor value
+ float amp_gain; //!< amp gain value
+ float volts_to_amps_ratio; //!< Volts to amps ratio
+
+ /**
+ * Function finding zero offsets of the ADC
+ */
+ void calibrateOffsets();
+
+};
+
+#endif
\ No newline at end of file
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/LowsideCurrentSense.cpp b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/LowsideCurrentSense.cpp
new file mode 100644
index 0000000..a0026ae
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/LowsideCurrentSense.cpp
@@ -0,0 +1,95 @@
+#include "LowsideCurrentSense.h"
+#include "communication/SimpleFOCDebug.h"
+// LowsideCurrentSensor constructor
+// - shunt_resistor - shunt resistor value
+// - gain - current-sense op-amp gain
+// - phA - A phase adc pin
+// - phB - B phase adc pin
+// - phC - C phase adc pin (optional)
+LowsideCurrentSense::LowsideCurrentSense(float _shunt_resistor, float _gain, int _pinA, int _pinB, int _pinC){
+ pinA = _pinA;
+ pinB = _pinB;
+ pinC = _pinC;
+
+ shunt_resistor = _shunt_resistor;
+ amp_gain = _gain;
+ volts_to_amps_ratio = 1.0f /_shunt_resistor / _gain; // volts to amps
+ // gains for each phase
+ gain_a = volts_to_amps_ratio;
+ gain_b = volts_to_amps_ratio;
+ gain_c = volts_to_amps_ratio;
+}
+
+
+LowsideCurrentSense::LowsideCurrentSense(float _mVpA, int _pinA, int _pinB, int _pinC){
+ pinA = _pinA;
+ pinB = _pinB;
+ pinC = _pinC;
+
+ volts_to_amps_ratio = 1000.0f / _mVpA; // mV to amps
+ // gains for each phase
+ gain_a = volts_to_amps_ratio;
+ gain_b = volts_to_amps_ratio;
+ gain_c = volts_to_amps_ratio;
+}
+
+
+// Lowside sensor init function
+int LowsideCurrentSense::init(){
+
+ if (driver==nullptr) {
+ SIMPLEFOC_DEBUG("CUR: Driver not linked!");
+ return 0;
+ }
+
+ // configure ADC variables
+ params = _configureADCLowSide(driver->params,pinA,pinB,pinC);
+ // if init failed return fail
+ if (params == SIMPLEFOC_CURRENT_SENSE_INIT_FAILED) return 0;
+ // sync the driver
+ void* r = _driverSyncLowSide(driver->params, params);
+ if(r == SIMPLEFOC_CURRENT_SENSE_INIT_FAILED) return 0;
+ // set the center pwm (0 voltage vector)
+ if(driver_type==DriverType::BLDC)
+ static_cast(driver)->setPwm(driver->voltage_limit/2, driver->voltage_limit/2, driver->voltage_limit/2);
+ // calibrate zero offsets
+ calibrateOffsets();
+ // set zero voltage to all phases
+ if(driver_type==DriverType::BLDC)
+ static_cast(driver)->setPwm(0,0,0);
+ // set the initialized flag
+ initialized = (params!=SIMPLEFOC_CURRENT_SENSE_INIT_FAILED);
+ // return success
+ return 1;
+}
+// Function finding zero offsets of the ADC
+void LowsideCurrentSense::calibrateOffsets(){
+ const int calibration_rounds = 2000;
+
+ // find adc offset = zero current voltage
+ offset_ia = 0;
+ offset_ib = 0;
+ offset_ic = 0;
+ // read the adc voltage 1000 times ( arbitrary number )
+ for (int i = 0; i < calibration_rounds; i++) {
+ _startADC3PinConversionLowSide();
+ if(_isset(pinA)) offset_ia += (_readADCVoltageLowSide(pinA, params));
+ if(_isset(pinB)) offset_ib += (_readADCVoltageLowSide(pinB, params));
+ if(_isset(pinC)) offset_ic += (_readADCVoltageLowSide(pinC, params));
+ _delay(1);
+ }
+ // calculate the mean offsets
+ if(_isset(pinA)) offset_ia = offset_ia / calibration_rounds;
+ if(_isset(pinB)) offset_ib = offset_ib / calibration_rounds;
+ if(_isset(pinC)) offset_ic = offset_ic / calibration_rounds;
+}
+
+// read all three phase currents (if possible 2 or 3)
+PhaseCurrent_s LowsideCurrentSense::getPhaseCurrents(){
+ PhaseCurrent_s current;
+ _startADC3PinConversionLowSide();
+ current.a = (!_isset(pinA)) ? 0 : (_readADCVoltageLowSide(pinA, params) - offset_ia)*gain_a;// amps
+ current.b = (!_isset(pinB)) ? 0 : (_readADCVoltageLowSide(pinB, params) - offset_ib)*gain_b;// amps
+ current.c = (!_isset(pinC)) ? 0 : (_readADCVoltageLowSide(pinC, params) - offset_ic)*gain_c; // amps
+ return current;
+}
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/LowsideCurrentSense.h b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/LowsideCurrentSense.h
new file mode 100644
index 0000000..6651bcd
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/LowsideCurrentSense.h
@@ -0,0 +1,54 @@
+#ifndef LOWSIDE_CS_LIB_H
+#define LOWSIDE_CS_LIB_H
+
+#include "Arduino.h"
+#include "../common/foc_utils.h"
+#include "../common/time_utils.h"
+#include "../common/defaults.h"
+#include "../common/base_classes/CurrentSense.h"
+#include "../common/base_classes/FOCMotor.h"
+#include "../common/base_classes/StepperDriver.h"
+#include "../common/base_classes/BLDCDriver.h"
+#include "../common/lowpass_filter.h"
+#include "hardware_api.h"
+
+
+class LowsideCurrentSense: public CurrentSense{
+ public:
+ /**
+ LowsideCurrentSense class constructor
+ @param shunt_resistor shunt resistor value
+ @param gain current-sense op-amp gain
+ @param phA A phase adc pin
+ @param phB B phase adc pin
+ @param phC C phase adc pin (optional)
+ */
+ LowsideCurrentSense(float shunt_resistor, float gain, int pinA, int pinB, int pinC = _NC);
+ /**
+ LowsideCurrentSense class constructor
+ @param mVpA mV per Amp ratio
+ @param phA A phase adc pin
+ @param phB B phase adc pin
+ @param phC C phase adc pin (optional)
+ */
+ LowsideCurrentSense(float mVpA, int pinA, int pinB, int pinC = _NC);
+
+ // CurrentSense interface implementing functions
+ int init() override;
+ PhaseCurrent_s getPhaseCurrents() override;
+
+ private:
+
+ // gain variables
+ float shunt_resistor; //!< Shunt resistor value
+ float amp_gain; //!< amp gain value
+ float volts_to_amps_ratio; //!< Volts to amps ratio
+
+ /**
+ * Function finding zero offsets of the ADC
+ */
+ void calibrateOffsets();
+
+};
+
+#endif
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/hardware_api.h b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/hardware_api.h
new file mode 100644
index 0000000..d1f5f16
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/hardware_api.h
@@ -0,0 +1,68 @@
+#ifndef HARDWARE_UTILS_CURRENT_H
+#define HARDWARE_UTILS_CURRENT_H
+
+#include "../common/foc_utils.h"
+#include "../common/time_utils.h"
+
+// flag returned if current sense init fails
+#define SIMPLEFOC_CURRENT_SENSE_INIT_FAILED ((void*)-1)
+
+// generic implementation of the hardware specific structure
+// containing all the necessary current sense parameters
+// will be returned as a void pointer from the _configureADCx functions
+// will be provided to the _readADCVoltageX() as a void pointer
+typedef struct GenericCurrentSenseParams {
+ int pins[3];
+ float adc_voltage_conv;
+} GenericCurrentSenseParams;
+
+
+/**
+ * function reading an ADC value and returning the read voltage
+ *
+ * @param pinA - the arduino pin to be read (it has to be ADC pin)
+ * @param cs_params -current sense parameter structure - hardware specific
+ */
+float _readADCVoltageInline(const int pinA, const void* cs_params);
+
+/**
+ * function reading an ADC value and returning the read voltage
+ *
+ * @param driver_params - driver parameter structure - hardware specific
+ * @param pinA - adc pin A
+ * @param pinB - adc pin B
+ * @param pinC - adc pin C
+ */
+void* _configureADCInline(const void *driver_params, const int pinA,const int pinB,const int pinC = NOT_SET);
+
+/**
+ * function reading an ADC value and returning the read voltage
+ *
+ * @param driver_params - driver parameter structure - hardware specific
+ * @param pinA - adc pin A
+ * @param pinB - adc pin B
+ * @param pinC - adc pin C
+ */
+void* _configureADCLowSide(const void *driver_params, const int pinA,const int pinB,const int pinC = NOT_SET);
+
+void _startADC3PinConversionLowSide();
+
+/**
+ * function reading an ADC value and returning the read voltage
+ *
+ * @param pinA - the arduino pin to be read (it has to be ADC pin)
+ * @param cs_params -current sense parameter structure - hardware specific
+ */
+float _readADCVoltageLowSide(const int pinA, const void* cs_params);
+
+/**
+ * function syncing the Driver with the ADC for the LowSide Sensing
+ * @param driver_params - driver parameter structure - hardware specific
+ * @param cs_params - current sense parameter structure - hardware specific
+ *
+ * @return void* - returns the pointer to the current sense parameter structure (unchanged)
+ * - returns SIMPLEFOC_CURRENT_SENSE_INIT_FAILED if the init fails
+ */
+void* _driverSyncLowSide(void* driver_params, void* cs_params);
+
+#endif
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/hardware_specific/atmega_mcu.cpp b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/hardware_specific/atmega_mcu.cpp
new file mode 100644
index 0000000..50ae596
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/hardware_specific/atmega_mcu.cpp
@@ -0,0 +1,40 @@
+#include "../hardware_api.h"
+
+#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) || defined(__AVR_ATmega328PB__)
+
+#define _ADC_VOLTAGE 5.0f
+#define _ADC_RESOLUTION 1024.0f
+
+#ifndef cbi
+ #define cbi(sfr, bit) (_SFR_BYTE(sfr) &= ~_BV(bit))
+#endif
+#ifndef sbi
+ #define sbi(sfr, bit) (_SFR_BYTE(sfr) |= _BV(bit))
+#endif
+
+// function reading an ADC value and returning the read voltage
+void* _configureADCInline(const void* driver_params, const int pinA,const int pinB,const int pinC){
+ _UNUSED(driver_params);
+
+ if( _isset(pinA) ) pinMode(pinA, INPUT);
+ if( _isset(pinB) ) pinMode(pinB, INPUT);
+ if( _isset(pinC) ) pinMode(pinC, INPUT);
+
+
+ GenericCurrentSenseParams* params = new GenericCurrentSenseParams {
+ .pins = { pinA, pinB, pinC },
+ .adc_voltage_conv = (_ADC_VOLTAGE)/(_ADC_RESOLUTION)
+ };
+
+ // set hight frequency adc - ADPS2,ADPS1,ADPS0 | 001 (16mhz/2) | 010 ( 16mhz/4 ) | 011 (16mhz/8) | 100(16mhz/16) | 101 (16mhz/32) | 110 (16mhz/64) | 111 (16mhz/128 default)
+ // set divisor to 8 - adc frequency 16mhz/8 = 2 mhz
+ // arduino takes 25 conversions per sample so - 2mhz/25 = 80k samples per second - 12.5us per sample
+ cbi(ADCSRA, ADPS2);
+ sbi(ADCSRA, ADPS1);
+ sbi(ADCSRA, ADPS0);
+
+ return params;
+}
+
+
+#endif
\ No newline at end of file
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/hardware_specific/due_mcu.cpp b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/hardware_specific/due_mcu.cpp
new file mode 100644
index 0000000..ce58cd9
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/hardware_specific/due_mcu.cpp
@@ -0,0 +1,27 @@
+#include "../hardware_api.h"
+
+#if defined(__arm__) && defined(__SAM3X8E__)
+
+#define _ADC_VOLTAGE 3.3f
+#define _ADC_RESOLUTION 1024.0f
+
+
+// function reading an ADC value and returning the read voltage
+void* _configureADCInline(const void* driver_params, const int pinA,const int pinB,const int pinC){
+ _UNUSED(driver_params);
+
+ if( _isset(pinA) ) pinMode(pinA, INPUT);
+ if( _isset(pinB) ) pinMode(pinB, INPUT);
+ if( _isset(pinC) ) pinMode(pinC, INPUT);
+
+ GenericCurrentSenseParams* params = new GenericCurrentSenseParams {
+ .pins = { pinA, pinB, pinC },
+ .adc_voltage_conv = (_ADC_VOLTAGE)/(_ADC_RESOLUTION)
+ };
+
+ return params;
+}
+
+
+
+#endif
\ No newline at end of file
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/hardware_specific/esp32/esp32_adc_driver.cpp b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/hardware_specific/esp32/esp32_adc_driver.cpp
new file mode 100644
index 0000000..caf29c1
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/hardware_specific/esp32/esp32_adc_driver.cpp
@@ -0,0 +1,176 @@
+
+#include "esp32_mcu.h"
+#include "esp32_adc_driver.h"
+
+#if defined(ESP_H) && defined(ARDUINO_ARCH_ESP32)
+#define SIMPLEFOC_ADC_ATTEN ADC_11db
+#define SIMPLEFOC_ADC_RES 12
+
+
+#if CONFIG_IDF_TARGET_ESP32 // if esp32 variant
+
+#include "soc/sens_reg.h"
+
+// configure the ADCs in RTC mode
+// saves about 3us per call
+// going from 12us to 9us
+void __configFastADCs(){
+
+ // configure both ADCs in RTC mode
+ SET_PERI_REG_MASK(SENS_SAR_READ_CTRL_REG, SENS_SAR1_DATA_INV);
+ SET_PERI_REG_MASK(SENS_SAR_READ_CTRL2_REG, SENS_SAR2_DATA_INV);
+
+ SET_PERI_REG_MASK(SENS_SAR_MEAS_START1_REG, SENS_MEAS1_START_FORCE_M); //SAR ADC1 controller (in RTC) is started by SW
+ SET_PERI_REG_MASK(SENS_SAR_MEAS_START1_REG, SENS_SAR1_EN_PAD_FORCE_M); //SAR ADC1 pad enable bitmap is controlled by SW
+ SET_PERI_REG_MASK(SENS_SAR_MEAS_START2_REG, SENS_MEAS2_START_FORCE_M); //SAR ADC2 controller (in RTC) is started by SW
+ SET_PERI_REG_MASK(SENS_SAR_MEAS_START2_REG, SENS_SAR2_EN_PAD_FORCE_M); //SAR ADC2 pad enable bitmap is controlled by SW
+
+ CLEAR_PERI_REG_MASK(SENS_SAR_MEAS_WAIT2_REG, SENS_FORCE_XPD_SAR_M); //force XPD_SAR=0, use XPD_FSM
+ SET_PERI_REG_BITS(SENS_SAR_MEAS_WAIT2_REG, SENS_FORCE_XPD_AMP, 0x2, SENS_FORCE_XPD_AMP_S); //force XPD_AMP=0
+
+ CLEAR_PERI_REG_MASK(SENS_SAR_MEAS_CTRL_REG, 0xfff << SENS_AMP_RST_FB_FSM_S); //clear FSM
+ SET_PERI_REG_BITS(SENS_SAR_MEAS_WAIT1_REG, SENS_SAR_AMP_WAIT1, 0x1, SENS_SAR_AMP_WAIT1_S);
+ SET_PERI_REG_BITS(SENS_SAR_MEAS_WAIT1_REG, SENS_SAR_AMP_WAIT2, 0x1, SENS_SAR_AMP_WAIT2_S);
+ SET_PERI_REG_BITS(SENS_SAR_MEAS_WAIT2_REG, SENS_SAR_AMP_WAIT3, 0x1, SENS_SAR_AMP_WAIT3_S);
+ while (GET_PERI_REG_BITS2(SENS_SAR_SLAVE_ADDR1_REG, 0x7, SENS_MEAS_STATUS_S) != 0); //wait det_fsm==
+}
+
+
+uint16_t IRAM_ATTR adcRead(uint8_t pin)
+{
+ int8_t channel = digitalPinToAnalogChannel(pin);
+ if(channel < 0){
+ SIMPLEFOC_ESP32_CS_DEBUG("ERROR: Not ADC pin: "+String(pin));
+ return false;//not adc pin
+ }
+
+ // start teh ADC conversion
+ if(channel > 9){
+ CLEAR_PERI_REG_MASK(SENS_SAR_MEAS_START2_REG, SENS_MEAS2_START_SAR_M);
+ SET_PERI_REG_BITS(SENS_SAR_MEAS_START2_REG, SENS_SAR2_EN_PAD, (1 << (channel - 10)), SENS_SAR2_EN_PAD_S);
+ SET_PERI_REG_MASK(SENS_SAR_MEAS_START2_REG, SENS_MEAS2_START_SAR_M);
+ } else {
+ CLEAR_PERI_REG_MASK(SENS_SAR_MEAS_START1_REG, SENS_MEAS1_START_SAR_M);
+ SET_PERI_REG_BITS(SENS_SAR_MEAS_START1_REG, SENS_SAR1_EN_PAD, (1 << channel), SENS_SAR1_EN_PAD_S);
+ SET_PERI_REG_MASK(SENS_SAR_MEAS_START1_REG, SENS_MEAS1_START_SAR_M);
+ }
+
+ uint16_t value = 0;
+
+ if(channel > 7){
+ //wait for conversion
+ while (GET_PERI_REG_MASK(SENS_SAR_MEAS_START2_REG, SENS_MEAS2_DONE_SAR) == 0);
+ // read the value
+ value = GET_PERI_REG_BITS2(SENS_SAR_MEAS_START2_REG, SENS_MEAS2_DATA_SAR, SENS_MEAS2_DATA_SAR_S);
+ } else {
+ //wait for conversion
+ while (GET_PERI_REG_MASK(SENS_SAR_MEAS_START1_REG, SENS_MEAS1_DONE_SAR) == 0);
+ // read the value
+ value = GET_PERI_REG_BITS2(SENS_SAR_MEAS_START1_REG, SENS_MEAS1_DATA_SAR, SENS_MEAS1_DATA_SAR_S);
+ }
+
+ // return value
+ return value;
+}
+
+#elif CONFIG_IDF_TARGET_ESP32S2 || CONFIG_IDF_TARGET_ESP32S3 // if esp32 s2 or s3 variants
+
+#include "soc/sens_reg.h"
+
+
+// configure the ADCs in RTC mode
+// no real gain - see if we do something with it later
+// void __configFastADCs(){
+
+// SET_PERI_REG_MASK(SENS_SAR_READER1_CTRL_REG, SENS_SAR1_DATA_INV);
+// SET_PERI_REG_MASK(SENS_SAR_READER2_CTRL_REG, SENS_SAR2_DATA_INV);
+
+// SET_PERI_REG_MASK(SENS_SAR_MEAS1_CTRL2_REG, SENS_MEAS1_START_FORCE_M); //SAR ADC1 controller (in RTC) is started by SW
+// SET_PERI_REG_MASK(SENS_SAR_MEAS1_CTRL2_REG, SENS_SAR1_EN_PAD_FORCE_M); //SAR ADC1 pad enable bitmap is controlled by SW
+// SET_PERI_REG_MASK(SENS_SAR_MEAS2_CTRL2_REG, SENS_MEAS2_START_FORCE_M); //SAR ADC2 controller (in RTC) is started by SW
+// SET_PERI_REG_MASK(SENS_SAR_MEAS2_CTRL2_REG, SENS_SAR2_EN_PAD_FORCE_M); //SAR ADC2 pad enable bitmap is controlled by SW
+
+// CLEAR_PERI_REG_MASK(SENS_SAR_POWER_XPD_SAR_REG, SENS_FORCE_XPD_SAR_M); //force XPD_SAR=0, use XPD_FSM
+// SET_PERI_REG_BITS(SENS_SAR_POWER_XPD_SAR_REG, SENS_FORCE_XPD_AMP, 0x2, SENS_FORCE_XPD_AMP_S); //force XPD_AMP=0
+
+// CLEAR_PERI_REG_MASK(SENS_SAR_AMP_CTRL3_REG, 0xfff << SENS_AMP_RST_FB_FSM_S); //clear FSM
+// SET_PERI_REG_BITS(SENS_SAR_AMP_CTRL1_REG, SENS_SAR_AMP_WAIT1, 0x1, SENS_SAR_AMP_WAIT1_S);
+// SET_PERI_REG_BITS(SENS_SAR_AMP_CTRL1_REG, SENS_SAR_AMP_WAIT2, 0x1, SENS_SAR_AMP_WAIT2_S);
+// SET_PERI_REG_BITS(SENS_SAR_POWER_XPD_SAR_REG, SENS_SAR_AMP_WAIT3, 0x1, SENS_SAR_AMP_WAIT3_S);
+// while (GET_PERI_REG_BITS2(SENS_SAR_SLAVE_ADDR1_REG, 0x7, SENS_SARADC_MEAS_STATUS_S) != 0); //wait det_fsm==
+// }
+
+uint16_t IRAM_ATTR adcRead(uint8_t pin)
+{
+ int8_t channel = digitalPinToAnalogChannel(pin);
+ if(channel < 0){
+ SIMPLEFOC_ESP32_CS_DEBUG("ERROR: Not ADC pin: "+String(pin));
+ return false;//not adc pin
+ }
+
+ // start the ADC conversion
+ if(channel > 9){
+ CLEAR_PERI_REG_MASK(SENS_SAR_MEAS2_CTRL2_REG, SENS_MEAS2_START_SAR_M);
+ SET_PERI_REG_BITS(SENS_SAR_MEAS2_CTRL2_REG, SENS_SAR2_EN_PAD, (1 << (channel - 10)), SENS_SAR2_EN_PAD_S);
+ SET_PERI_REG_MASK(SENS_SAR_MEAS2_CTRL2_REG, SENS_MEAS2_START_SAR_M);
+ } else {
+ CLEAR_PERI_REG_MASK(SENS_SAR_MEAS1_CTRL2_REG, SENS_MEAS1_START_SAR_M);
+ SET_PERI_REG_BITS(SENS_SAR_MEAS1_CTRL2_REG, SENS_SAR1_EN_PAD, (1 << channel), SENS_SAR1_EN_PAD_S);
+ SET_PERI_REG_MASK(SENS_SAR_MEAS1_CTRL2_REG, SENS_MEAS1_START_SAR_M);
+ }
+
+ uint16_t value = 0;
+
+ if(channel > 9){
+ //wait for conversion
+ while (GET_PERI_REG_MASK(SENS_SAR_MEAS2_CTRL2_REG, SENS_MEAS2_DONE_SAR) == 0);
+ // read the value
+ value = GET_PERI_REG_BITS2(SENS_SAR_MEAS2_CTRL2_REG, SENS_MEAS2_DATA_SAR, SENS_MEAS2_DATA_SAR_S);
+ } else {
+ //wait for conversion
+ while (GET_PERI_REG_MASK(SENS_SAR_MEAS1_CTRL2_REG, SENS_MEAS1_DONE_SAR) == 0);
+ // read teh value
+ value = GET_PERI_REG_BITS2(SENS_SAR_MEAS1_CTRL2_REG, SENS_MEAS1_DATA_SAR, SENS_MEAS1_DATA_SAR_S);
+ }
+
+ return value;
+}
+
+#else // if others just use analogRead
+
+#pragma message("SimpleFOC: Using analogRead for ADC reading, no fast ADC configuration available!")
+
+uint16_t IRAM_ATTR adcRead(uint8_t pin){
+ return analogRead(pin);
+}
+
+#endif
+
+
+// configure the ADC for the pin
+bool IRAM_ATTR adcInit(uint8_t pin){
+ static bool initialized = false;
+
+ int8_t channel = digitalPinToAnalogChannel(pin);
+ if(channel < 0){
+ SIMPLEFOC_ESP32_CS_DEBUG("ERROR: Not ADC pin: "+String(pin));
+ return false;//not adc pin
+ }
+
+ if(! initialized){
+ analogSetAttenuation(SIMPLEFOC_ADC_ATTEN);
+ analogReadResolution(SIMPLEFOC_ADC_RES);
+ }
+ pinMode(pin, ANALOG);
+ analogSetPinAttenuation(pin, SIMPLEFOC_ADC_ATTEN);
+ analogRead(pin);
+
+#if CONFIG_IDF_TARGET_ESP32 // if esp32 variant
+ __configFastADCs();
+#endif
+
+ initialized = true;
+ return true;
+}
+
+#endif
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/hardware_specific/esp32/esp32_adc_driver.h b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/hardware_specific/esp32/esp32_adc_driver.h
new file mode 100644
index 0000000..cad441f
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/hardware_specific/esp32/esp32_adc_driver.h
@@ -0,0 +1,24 @@
+#ifndef SIMPLEFOC_ESP32_HAL_ADC_DRIVER_H_
+#define SIMPLEFOC_ESP32_HAL_ADC_DRIVER_H_
+
+#if defined(ESP_H) && defined(ARDUINO_ARCH_ESP32)
+
+/**
+ * Get ADC value for pin
+ * @param pin - pin number
+ * @return ADC value (0 - 4095)
+ * */
+uint16_t adcRead(uint8_t pin);
+
+/**
+ * Initialize ADC pin
+ * @param pin - pin number
+ *
+ * @return true if success
+ * false if pin is not an ADC pin
+ */
+bool adcInit(uint8_t pin);
+
+
+#endif /* SIMPLEFOC_ESP32_HAL_ADC_DRIVER_H_ */
+#endif /* ESP32 */
\ No newline at end of file
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/hardware_specific/esp32/esp32_mcpwm_mcu.cpp b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/hardware_specific/esp32/esp32_mcpwm_mcu.cpp
new file mode 100644
index 0000000..33d547d
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/hardware_specific/esp32/esp32_mcpwm_mcu.cpp
@@ -0,0 +1,158 @@
+#include "esp32_mcu.h"
+
+#if defined(ESP_H) && defined(ARDUINO_ARCH_ESP32) && defined(SOC_MCPWM_SUPPORTED) && !defined(SIMPLEFOC_ESP32_USELEDC)
+
+// check the version of the ESP-IDF
+#include "esp_idf_version.h"
+
+#if ESP_IDF_VERSION < ESP_IDF_VERSION_VAL(5, 0, 0)
+#error SimpleFOC: ESP-IDF version 4 or lower detected. Please update to ESP-IDF 5.x and Arduino-esp32 3.0 (or higher)
+#endif
+
+#include "../../../drivers/hardware_specific/esp32/esp32_driver_mcpwm.h"
+#include "../../../drivers/hardware_specific/esp32/mcpwm_private.h"
+
+#include "driver/mcpwm_prelude.h"
+#include "soc/mcpwm_reg.h"
+#include "soc/mcpwm_struct.h"
+
+
+
+// adding a debug toggle pin to measure the time of the interrupt with oscilloscope
+
+// #define SIMPLEFOC_ESP32_INTERRUPT_DEBUG
+
+#ifdef SIMPLEFOC_ESP32_INTERRUPT_DEBUG
+#include "driver/gpio.h"
+
+#ifdef CONFIG_IDF_TARGET_ESP32S3
+#define DEBUGPIN 16
+#define GPIO_NUM GPIO_NUM_16
+#else
+#define DEBUGPIN 19
+#define GPIO_NUM GPIO_NUM_19
+#endif
+
+#endif
+
+
+
+/**
+ * Low side adc reading implementation
+*/
+
+
+// function reading an ADC value and returning the read voltage
+float _readADCVoltageLowSide(const int pin, const void* cs_params){
+ ESP32CurrentSenseParams* p = (ESP32CurrentSenseParams*)cs_params;
+ int no_channel = 0;
+ for(int i=0; i < 3; i++){
+ if(!_isset(p->pins[i])) continue;
+ if(pin == p->pins[i]) // found in the buffer
+ return p->adc_buffer[no_channel] * p->adc_voltage_conv;
+ else no_channel++;
+ }
+ SIMPLEFOC_DEBUG("ERROR: ADC pin not found in the buffer!");
+ // not found
+ return 0;
+}
+
+
+// function configuring low-side current sensing
+void* _configureADCLowSide(const void* driver_params, const int pinA,const int pinB,const int pinC){
+ // check if driver timer is already running
+ // fail if it is
+ // the easiest way that I've found to check if timer is running
+ // is to start it and stop it
+ ESP32MCPWMDriverParams *p = (ESP32MCPWMDriverParams*)driver_params;
+ mcpwm_timer_t* t = (mcpwm_timer_t*) p->timers[0];
+
+ // check if low side callback is already set
+ // if it is, return error
+ if(t->on_full != nullptr){
+ SIMPLEFOC_ESP32_CS_DEBUG("ERROR: Low side callback is already set. Cannot set it again for timer: "+String(t->timer_id)+", group: "+String(t->group->group_id));
+ return SIMPLEFOC_CURRENT_SENSE_INIT_FAILED;
+ }
+
+
+ ESP32CurrentSenseParams* params = new ESP32CurrentSenseParams{};
+ int no_adc_channels = 0;
+
+ // initialize the ADC pins
+ // fail if the pin is not an ADC pin
+ int adc_pins[3] = {pinA, pinB, pinC};
+ for (int i = 0; i < 3; i++){
+ if(_isset(adc_pins[i])){
+ if(!adcInit(adc_pins[i])){
+ SIMPLEFOC_ESP32_CS_DEBUG("ERROR: Failed to initialise ADC pin: "+String(adc_pins[i]) + String(", maybe not an ADC pin?"));
+ return SIMPLEFOC_CURRENT_SENSE_INIT_FAILED;
+ }
+ params->pins[no_adc_channels++] = adc_pins[i];
+ }
+ }
+
+ t->user_data = params;
+ params->adc_voltage_conv = (_ADC_VOLTAGE)/(_ADC_RESOLUTION);
+ params->no_adc_channels = no_adc_channels;
+ return params;
+}
+
+
+
+void* _driverSyncLowSide(void* driver_params, void* cs_params){
+#ifdef SIMPLEFOC_ESP32_INTERRUPT_DEBUG
+ pinMode(DEBUGPIN, OUTPUT);
+#endif
+ ESP32MCPWMDriverParams *p = (ESP32MCPWMDriverParams*)driver_params;
+ mcpwm_timer_t* t = (mcpwm_timer_t*) p->timers[0];
+
+ // check if low side callback is already set
+ // if it is, return error
+ if(t->on_full != nullptr){
+ SIMPLEFOC_ESP32_CS_DEBUG("ERROR: Low side callback is already set. Cannot set it again for timer: "+String(t->timer_id)+", group: "+String(t->group->group_id));
+ return SIMPLEFOC_CURRENT_SENSE_INIT_FAILED;
+ }
+
+ // set the callback for the low side current sensing
+ // mcpwm_timer_event_callbacks_t can be used to set the callback
+ // for three timer events
+ // - on_full - low-side
+ // - on_empty - high-side
+ // - on_sync - sync event (not used with simplefoc)
+ auto cbs = mcpwm_timer_event_callbacks_t{
+ .on_full = [](mcpwm_timer_handle_t tim, const mcpwm_timer_event_data_t* edata, void* user_data){
+ ESP32CurrentSenseParams *p = (ESP32CurrentSenseParams*)user_data;
+#ifdef SIMPLEFOC_ESP32_INTERRUPT_DEBUG // debugging toggle pin to measure the time of the interrupt with oscilloscope
+ gpio_set_level(GPIO_NUM,1); //cca 250ns for on+off
+#endif
+
+ // sample the phase currents one at a time
+ // ESP's adc read takes around 10us which is very long
+ // increment buffer index
+ p->buffer_index = (p->buffer_index + 1) % p->no_adc_channels;
+ // so we are sampling one phase per call
+ p->adc_buffer[p->buffer_index] = adcRead(p->pins[p->buffer_index]);
+
+#ifdef SIMPLEFOC_ESP32_INTERRUPT_DEBUG // debugging toggle pin to measure the time of the interrupt with oscilloscope
+ gpio_set_level(GPIO_NUM,0); //cca 250ns for on+off
+#endif
+ return true;
+ },
+ };
+ SIMPLEFOC_ESP32_CS_DEBUG("Timer "+String(t->timer_id)+" enable interrupt callback.");
+ // set the timer state to init (so that we can call the `mcpwm_timer_register_event_callbacks` )
+ // this is a hack, as this function is not supposed to be called when the timer is running
+ // the timer does not really go to the init state!
+ t->fsm = MCPWM_TIMER_FSM_INIT;
+ // set the callback
+ CHECK_CS_ERR(mcpwm_timer_register_event_callbacks(t, &cbs, cs_params), "Failed to set low side callback");
+ // set the timer state to enabled again
+ t->fsm = MCPWM_TIMER_FSM_ENABLE;
+ SIMPLEFOC_ESP32_CS_DEBUG("Timer "+String(t->timer_id)+" enable interrupts.");
+ CHECK_CS_ERR(esp_intr_enable(t->intr), "Failed to enable low-side interrupts!");
+
+ return cs_params;
+}
+
+
+#endif
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/hardware_specific/esp32/esp32_mcu.cpp b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/hardware_specific/esp32/esp32_mcu.cpp
new file mode 100644
index 0000000..e5ed3fb
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/hardware_specific/esp32/esp32_mcu.cpp
@@ -0,0 +1,38 @@
+#include "esp32_mcu.h"
+
+#if defined(ESP_H) && defined(ARDUINO_ARCH_ESP32)
+
+/**
+ * Inline adc reading implementation
+*/
+// function reading an ADC value and returning the read voltage
+float _readADCVoltageInline(const int pinA, const void* cs_params){
+ uint32_t raw_adc = adcRead(pinA);
+ return raw_adc * ((ESP32CurrentSenseParams*)cs_params)->adc_voltage_conv;
+}
+
+// function reading an ADC value and returning the read voltage
+void* _configureADCInline(const void* driver_params, const int pinA, const int pinB, const int pinC){
+
+ ESP32CurrentSenseParams* params = new ESP32CurrentSenseParams {
+ .pins = { pinA, pinB, pinC },
+ .adc_voltage_conv = (_ADC_VOLTAGE)/(_ADC_RESOLUTION)
+ };
+
+ // initialize the ADC pins
+ // fail if the pin is not an ADC pin
+ for (int i = 0; i < 3; i++){
+ if(_isset(params->pins[i])){
+ pinMode(params->pins[i], ANALOG);
+ if(!adcInit(params->pins[i])) {
+ SIMPLEFOC_ESP32_CS_DEBUG("ERROR: Failed to initialise ADC pin: "+String(params->pins[i]) + String(", maybe not an ADC pin?"));
+ return SIMPLEFOC_CURRENT_SENSE_INIT_FAILED;
+ }
+ }
+ }
+
+ return params;
+}
+
+
+#endif
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/hardware_specific/esp32/esp32_mcu.h b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/hardware_specific/esp32/esp32_mcu.h
new file mode 100644
index 0000000..9207fb6
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/hardware_specific/esp32/esp32_mcu.h
@@ -0,0 +1,37 @@
+#ifndef ESP32_MCU_CURRENT_SENSING_H
+#define ESP32_MCU_CURRENT_SENSING_H
+
+#include "../../hardware_api.h"
+
+#if defined(ESP_H) && defined(ARDUINO_ARCH_ESP32)
+
+
+#include "../../../drivers/hardware_api.h"
+#include "esp32_adc_driver.h"
+
+
+// esp32 current sense parameters
+typedef struct ESP32CurrentSenseParams {
+ int pins[3];
+ float adc_voltage_conv;
+ int adc_buffer[3] = {};
+ int buffer_index = 0;
+ int no_adc_channels = 0;
+} ESP32CurrentSenseParams;
+
+// macros for debugging wuing the simplefoc debug system
+#define SIMPLEFOC_ESP32_CS_DEBUG(str)\
+ SimpleFOCDebug::println( "ESP32-CS: "+ String(str));\
+
+#define CHECK_CS_ERR(func_call, message) \
+ if ((func_call) != ESP_OK) { \
+ SIMPLEFOC_ESP32_CS_DEBUG("ERROR - " + String(message)); \
+ return SIMPLEFOC_CURRENT_SENSE_INIT_FAILED; \
+ }
+
+
+#define _ADC_VOLTAGE 3.3f
+#define _ADC_RESOLUTION 4095.0f
+
+#endif // ESP_H && ARDUINO_ARCH_ESP32
+#endif
\ No newline at end of file
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/hardware_specific/generic_mcu.cpp b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/hardware_specific/generic_mcu.cpp
new file mode 100644
index 0000000..ff8c467
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/hardware_specific/generic_mcu.cpp
@@ -0,0 +1,47 @@
+#include "../hardware_api.h"
+#include "../../communication/SimpleFOCDebug.h"
+
+// function reading an ADC value and returning the read voltage
+__attribute__((weak)) float _readADCVoltageInline(const int pinA, const void* cs_params){
+ uint32_t raw_adc = analogRead(pinA);
+ return raw_adc * ((GenericCurrentSenseParams*)cs_params)->adc_voltage_conv;
+}
+
+// function reading an ADC value and returning the read voltage
+__attribute__((weak)) void* _configureADCInline(const void* driver_params, const int pinA,const int pinB,const int pinC){
+ _UNUSED(driver_params);
+
+ if( _isset(pinA) ) pinMode(pinA, INPUT);
+ if( _isset(pinB) ) pinMode(pinB, INPUT);
+ if( _isset(pinC) ) pinMode(pinC, INPUT);
+
+ GenericCurrentSenseParams* params = new GenericCurrentSenseParams {
+ .pins = { pinA, pinB, pinC },
+ .adc_voltage_conv = (5.0f)/(1024.0f)
+ };
+
+ return params;
+}
+
+// function reading an ADC value and returning the read voltage
+__attribute__((weak)) float _readADCVoltageLowSide(const int pinA, const void* cs_params){
+ SIMPLEFOC_DEBUG("ERR: Low-side cs not supported!");
+ return 0.0;
+}
+
+// Configure low side for generic mcu
+// cannot do much but
+__attribute__((weak)) void* _configureADCLowSide(const void* driver_params, const int pinA,const int pinB,const int pinC){
+ SIMPLEFOC_DEBUG("ERR: Low-side cs not supported!");
+ return SIMPLEFOC_CURRENT_SENSE_INIT_FAILED;
+}
+
+// sync driver and the adc
+__attribute__((weak)) void* _driverSyncLowSide(void* driver_params, void* cs_params){
+ _UNUSED(driver_params);
+ return cs_params;
+}
+
+// function starting the ADC conversion for the high side current sensing
+// only necessary for certain types of MCUs
+__attribute__((weak)) void _startADC3PinConversionLowSide(){ }
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/hardware_specific/rp2040/rp2040_mcu.cpp b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/hardware_specific/rp2040/rp2040_mcu.cpp
new file mode 100644
index 0000000..d2ed881
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/hardware_specific/rp2040/rp2040_mcu.cpp
@@ -0,0 +1,265 @@
+
+#if defined(TARGET_RP2040)
+
+
+#include "../../hardware_api.h"
+#include "./rp2040_mcu.h"
+#include "../../../drivers/hardware_specific/rp2040/rp2040_mcu.h"
+#include "communication/SimpleFOCDebug.h"
+
+#include "hardware/dma.h"
+#include "hardware/irq.h"
+#include "hardware/pwm.h"
+#include "hardware/adc.h"
+
+
+/* Singleton instance of the ADC engine */
+RP2040ADCEngine engine;
+
+alignas(32) const uint32_t trigger_value = ADC_CS_START_ONCE_BITS; // start once
+
+/* Hardware API implementation */
+
+float _readADCVoltageInline(const int pinA, const void* cs_params) {
+ // not super-happy with this. Here we have to return 1 phase current at a time, when actually we want to
+ // return readings from the same ADC conversion run. The ADC on RP2040 is anyway in round robin mode :-(
+ // like this we either have to block interrupts, or of course have the chance of reading across
+ // new ADC conversions, which probably won't improve the accuracy.
+ _UNUSED(cs_params);
+
+ if (pinA>=26 && pinA<=29 && engine.channelsEnabled[pinA-26]) {
+ return engine.lastResults.raw[pinA-26]*engine.adc_conv;
+ }
+
+ // otherwise return NaN
+ return NAN;
+};
+
+
+void* _configureADCInline(const void *driver_params, const int pinA, const int pinB, const int pinC) {
+ _UNUSED(driver_params);
+
+ if( _isset(pinA) )
+ engine.addPin(pinA);
+ if( _isset(pinB) )
+ engine.addPin(pinB);
+ if( _isset(pinC) )
+ engine.addPin(pinC);
+ engine.init(); // TODO this has to happen later if we want to support more than one motor...
+ engine.start();
+ return &engine;
+};
+
+
+// not supported at the moment
+// void* _configureADCLowSide(const void *driver_params, const int pinA, const int pinB, const int pinC) {
+// if( _isset(pinA) )
+// engine.addPin(pinA);
+// if( _isset(pinB) )
+// engine.addPin(pinB);
+// if( _isset(pinC) )
+// engine.addPin(pinC);
+// engine.setPWMTrigger(((RP2040DriverParams*)driver_params)->slice[0]);
+// engine.init();
+// engine.start();
+// return &engine;
+// };
+
+
+// void _startADC3PinConversionLowSide() {
+// // what is this for?
+// };
+
+
+// float _readADCVoltageLowSide(const int pinA, const void* cs_params) {
+// // not super-happy with this. Here we have to return 1 phase current at a time, when actually we want to
+// // return readings from the same ADC conversion run. The ADC on RP2040 is anyway in round robin mode :-(
+// // like this we have block interrupts 3x instead of just once, and of course have the chance of reading across
+// // new ADC conversions, which probably won't improve the accuracy.
+
+// if (pinA>=26 && pinA<=29 && engine.channelsEnabled[pinA-26]) {
+// return engine.lastResults[pinA-26]*engine.adc_conv;
+// }
+
+// // otherwise return NaN
+// return NAN;
+// };
+
+
+// void* _driverSyncLowSide(void* driver_params, void* cs_params) {
+// // nothing to do
+// };
+
+
+
+volatile int rp2040_intcount = 0;
+
+void _adcConversionFinishedHandler() {
+ // conversion of all channels finished. copy results.
+ volatile uint8_t* from = engine.samples;
+ if (engine.channelsEnabled[0])
+ engine.lastResults.raw[0] = (*from++);
+ if (engine.channelsEnabled[1])
+ engine.lastResults.raw[1] = (*from++);
+ if (engine.channelsEnabled[2])
+ engine.lastResults.raw[2] = (*from++);
+ if (engine.channelsEnabled[3])
+ engine.lastResults.raw[3] = (*from++);
+ //dma_channel_acknowledge_irq0(engine.readDMAChannel);
+ dma_hw->ints0 = 1u << engine.readDMAChannel;
+ //dma_start_channel_mask( (1u << engine.readDMAChannel) );
+ dma_channel_set_write_addr(engine.readDMAChannel, engine.samples, true);
+ // if (engine.triggerPWMSlice>=0)
+ // dma_channel_set_trans_count(engine.triggerDMAChannel, 1, true);
+ rp2040_intcount++;
+};
+
+
+
+/* ADC engine implementation */
+
+
+RP2040ADCEngine::RP2040ADCEngine() {
+ channelsEnabled[0] = false;
+ channelsEnabled[1] = false;
+ channelsEnabled[2] = false;
+ channelsEnabled[3] = false;
+ initialized = false;
+};
+
+
+
+void RP2040ADCEngine::addPin(int pin) {
+ if (pin>=26 && pin<=29)
+ channelsEnabled[pin-26] = true;
+ else
+ SIMPLEFOC_DEBUG("RP2040-CUR: ERR: Not an ADC pin: ", pin);
+};
+
+
+
+// void RP2040ADCEngine::setPWMTrigger(uint slice){
+// triggerPWMSlice = slice;
+// };
+
+
+
+
+bool RP2040ADCEngine::init() {
+ if (initialized)
+ return true;
+
+ adc_init();
+ int enableMask = 0x00;
+ int channelCount = 0;
+ for (int i = 3; i>=0; i--) {
+ if (channelsEnabled[i]){
+ adc_gpio_init(i+26);
+ enableMask |= (0x01<=500000) {
+ samples_per_second = 0;
+ adc_set_clkdiv(0);
+ }
+ else
+ adc_set_clkdiv(48000000/samples_per_second);
+ SIMPLEFOC_DEBUG("RP2040-CUR: ADC init");
+
+ readDMAChannel = dma_claim_unused_channel(true);
+ dma_channel_config cc1 = dma_channel_get_default_config(readDMAChannel);
+ channel_config_set_transfer_data_size(&cc1, DMA_SIZE_8);
+ channel_config_set_read_increment(&cc1, false);
+ channel_config_set_write_increment(&cc1, true);
+ channel_config_set_dreq(&cc1, DREQ_ADC);
+ channel_config_set_irq_quiet(&cc1, false);
+ dma_channel_configure(readDMAChannel,
+ &cc1,
+ samples, // dest
+ &adc_hw->fifo, // source
+ channelCount, // count
+ false // defer start
+ );
+ dma_channel_set_irq0_enabled(readDMAChannel, true);
+ irq_add_shared_handler(DMA_IRQ_0, _adcConversionFinishedHandler, PICO_SHARED_IRQ_HANDLER_DEFAULT_ORDER_PRIORITY);
+
+ SIMPLEFOC_DEBUG("RP2040-CUR: DMA init");
+
+ // if (triggerPWMSlice>=0) { // if we have a trigger
+ // triggerDMAChannel = dma_claim_unused_channel(true);
+ // dma_channel_config cc3 = dma_channel_get_default_config(triggerDMAChannel);
+ // channel_config_set_transfer_data_size(&cc3, DMA_SIZE_32);
+ // channel_config_set_read_increment(&cc3, false);
+ // channel_config_set_write_increment(&cc3, false);
+ // channel_config_set_irq_quiet(&cc3, true);
+ // channel_config_set_dreq(&cc3, DREQ_PWM_WRAP0+triggerPWMSlice); //pwm_get_dreq(triggerPWMSlice));
+ // pwm_set_irq_enabled(triggerPWMSlice, true);
+ // dma_channel_configure(triggerDMAChannel,
+ // &cc3,
+ // hw_set_alias_untyped(&adc_hw->cs), // dest
+ // &trigger_value, // source
+ // 1, // count
+ // true // defer start
+ // );
+ // SIMPLEFOC_DEBUG("RP2040-CUR: PWM trigger init slice ", triggerPWMSlice);
+ // }
+
+ initialized = true;
+ return initialized;
+};
+
+
+
+
+void RP2040ADCEngine::start() {
+ SIMPLEFOC_DEBUG("RP2040-CUR: ADC engine starting");
+ irq_set_enabled(DMA_IRQ_0, true);
+ dma_start_channel_mask( (1u << readDMAChannel) );
+ for (int i=0;i<4;i++) {
+ if (channelsEnabled[i]) {
+ adc_select_input(i); // set input to first enabled channel
+ break;
+ }
+ }
+ // if (triggerPWMSlice>=0) {
+ // dma_start_channel_mask( (1u << triggerDMAChannel) );
+ // //hw_set_bits(&adc_hw->cs, trigger_value);
+ // }
+ // else
+ adc_run(true);
+ SIMPLEFOC_DEBUG("RP2040-CUR: ADC engine started");
+};
+
+
+
+
+void RP2040ADCEngine::stop() {
+ adc_run(false);
+ irq_set_enabled(DMA_IRQ_0, false);
+ dma_channel_abort(readDMAChannel);
+ // if (triggerPWMSlice>=0)
+ // dma_channel_abort(triggerDMAChannel);
+ adc_fifo_drain();
+ SIMPLEFOC_DEBUG("RP2040-CUR: ADC engine stopped");
+};
+
+
+
+ADCResults RP2040ADCEngine::getLastResults() {
+ ADCResults r;
+ r.value = lastResults.value;
+ return r;
+};
+
+
+
+#endif
\ No newline at end of file
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/hardware_specific/rp2040/rp2040_mcu.h b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/hardware_specific/rp2040/rp2040_mcu.h
new file mode 100644
index 0000000..ae28bb2
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/hardware_specific/rp2040/rp2040_mcu.h
@@ -0,0 +1,93 @@
+
+
+#pragma once
+
+/*
+ * RP2040 ADC features are very weak :-(
+ * - only 4 inputs
+ * - only 9 bit effective resolution
+ * - read only 1 input at a time
+ * - 2 microseconds conversion time!
+ * - no triggers from PWM / events, only DMA
+ *
+ * So to read 3 phases takes 6 microseconds. :-(
+ *
+ * The RP2040 ADC engine takes over the control of the MCU's ADC. Parallel ADC access is not permitted, as this would
+ * cause conflicts with the engine's DMA based access and cause crashes.
+ * To use the other ADC channels, use them via this engine. Use addPin() to add them to the conversion, and getLastResult()
+ * to retrieve their value at any time.
+ *
+ * For motor current sensing, the engine supports inline sensing only.
+ *
+ * Inline sensing is supported by offering a user-selectable fixed ADC sampling rate, which can be set between 500kHz and 1Hz.
+ * After starting the engine it will continuously sample and provide new values at the configured rate.
+ *
+ * The default sampling rate is 20kHz, which is suitable for 2 channels assuming you a 5kHz main loop speed (a new measurement is used per
+ * main loop iteration).
+ *
+ * Low-side sensing is currently not supported.
+ *
+ * The SimpleFOC PWM driver for RP2040 syncs all the slices, so the PWM trigger is applied to the first used slice. For current
+ * sensing to work correctly, all PWM slices have to be set to the same PWM frequency.
+ * In theory, two motors could be sensed using 2 shunts on each motor.
+ *
+ * Note that if using other ADC channels along with the motor current sensing, those channels will be subject to the same conversion schedule as the motor's ADC channels, i.e. convert at the same fixed rate in case
+ * of inline sensing.
+ *
+ * Solution to trigger ADC conversion from PWM via DMA:
+ * use the PWM wrap as a DREQ to a DMA channel, and have the DMA channel write to the ADC's CS register to trigger an ADC sample.
+ * Unfortunately, I could not get this to work, so no low side sensing for the moment.
+ *
+ * Solution for ADC conversion:
+ * ADC converts all channels in round-robin mode, and writes to FIFO. FIFO is emptied by a DMA which triggers after N conversions,
+ * where N is the number of ADC channels used. So this DMA copies all the values from one round-robin conversion.
+ *
+ *
+ */
+
+
+#define SIMPLEFOC_RP2040_ADC_RESOLUTION 256
+#ifndef SIMPLEFOC_RP2040_ADC_VDDA
+#define SIMPLEFOC_RP2040_ADC_VDDA 3.3f
+#endif
+
+
+union ADCResults {
+ uint32_t value;
+ uint8_t raw[4];
+ struct {
+ uint8_t ch0;
+ uint8_t ch1;
+ uint8_t ch2;
+ uint8_t ch3;
+ };
+};
+
+
+class RP2040ADCEngine {
+
+public:
+ RP2040ADCEngine();
+ void addPin(int pin);
+ //void setPWMTrigger(uint slice);
+
+ bool init();
+ void start();
+ void stop();
+
+ ADCResults getLastResults(); // TODO find a better API and representation for this
+
+ int samples_per_second = 20000; // 20kHz default (assuming 2 shunts and 5kHz loop speed), set to 0 to convert in tight loop
+ float adc_conv = (SIMPLEFOC_RP2040_ADC_VDDA / SIMPLEFOC_RP2040_ADC_RESOLUTION); // conversion from raw ADC to float
+
+ //int triggerPWMSlice = -1;
+ bool initialized;
+ uint readDMAChannel;
+ //uint copyDMAChannel;
+ //uint triggerDMAChannel;
+
+ bool channelsEnabled[4];
+ volatile uint8_t samples[4];
+ volatile ADCResults lastResults;
+ //alignas(32) volatile uint8_t nextResults[4];
+};
\ No newline at end of file
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/hardware_specific/samd/samd21_mcu.cpp b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/hardware_specific/samd/samd21_mcu.cpp
new file mode 100644
index 0000000..046f3db
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/hardware_specific/samd/samd21_mcu.cpp
@@ -0,0 +1,319 @@
+#ifdef _SAMD21_
+
+#include "samd21_mcu.h"
+#include "../../hardware_api.h"
+
+
+static bool freeRunning = false;
+static int _pinA, _pinB, _pinC;
+static uint16_t a = 0xFFFF, b = 0xFFFF, c = 0xFFFF; // updated by adcStopWithDMA when configured in freerunning mode
+static SAMDCurrentSenseADCDMA instance;
+
+// function configuring low-side current sensing
+void* _configureADCLowSide(const void* driver_params, const int pinA,const int pinB,const int pinC)
+{
+ _UNUSED(driver_params);
+
+ _pinA = pinA;
+ _pinB = pinB;
+ _pinC = pinC;
+ freeRunning = true;
+ instance.init(pinA, pinB, pinC);
+
+ GenericCurrentSenseParams* params = new GenericCurrentSenseParams {
+ .pins = { pinA, pinB, pinC }
+ };
+
+ return params;
+}
+void _startADC3PinConversionLowSide()
+{
+ instance.startADCScan();
+}
+/**
+ * function reading an ADC value and returning the read voltage
+ *
+ * @param pinA - the arduino pin to be read (it has to be ADC pin)
+ */
+float _readADCVoltageLowSide(const int pinA, const void* cs_params)
+{
+ _UNUSED(cs_params);
+
+ instance.readResults(a, b, c);
+
+ if(pinA == _pinA)
+ return instance.toVolts(a);
+ if(pinA == _pinB)
+ return instance.toVolts(b);
+ if(pinA == _pinC)
+ return instance.toVolts(c);
+
+ return NAN;
+}
+
+/**
+ * function syncing the Driver with the ADC for the LowSide Sensing
+ */
+void* _driverSyncLowSide(void* driver_params, void* cs_params)
+{
+ _UNUSED(driver_params);
+
+ SIMPLEFOC_SAMD_DEBUG_SERIAL.println(F("TODO! _driverSyncLowSide() is not implemented"));
+ instance.startADCScan();
+ //TODO: hook with PWM interrupts
+
+ return cs_params;
+}
+
+
+
+
+
+
+
+
+
+
+ // Credit: significant portions of this code were pulled from Paul Gould's git https://github.com/gouldpa/FOC-Arduino-Brushless
+
+static void adcStopWithDMA(void);
+static void adcStartWithDMA(void);
+
+/**
+ * @brief ADC sync wait
+ * @retval void
+ */
+static __inline__ void ADCsync() __attribute__((always_inline, unused));
+static void ADCsync() {
+ while (ADC->STATUS.bit.SYNCBUSY == 1); //Just wait till the ADC is free
+}
+
+// ADC DMA sequential free running (6) with Interrupts /////////////////
+
+SAMDCurrentSenseADCDMA * SAMDCurrentSenseADCDMA::getHardwareAPIInstance()
+{
+
+ return &instance;
+}
+
+SAMDCurrentSenseADCDMA::SAMDCurrentSenseADCDMA()
+{
+}
+
+void SAMDCurrentSenseADCDMA::init(int pinA, int pinB, int pinC, int pinAREF, float voltageAREF, uint32_t adcBits, uint32_t channelDMA)
+{
+ this->pinA = pinA;
+ this->pinB = pinB;
+ this->pinC = pinC;
+ this->pinAREF = pinAREF;
+ this->channelDMA = channelDMA;
+ this->voltageAREF = voltageAREF;
+ this->maxCountsADC = 1 << adcBits;
+ countsToVolts = ( voltageAREF / maxCountsADC );
+
+ initPins();
+ initADC();
+ initDMA();
+ startADCScan(); //so we have something to read next time we call readResults()
+}
+
+
+void SAMDCurrentSenseADCDMA::startADCScan(){
+ adcToDMATransfer(adcBuffer + oneBeforeFirstAIN, BufferSize);
+ adcStartWithDMA();
+}
+
+bool SAMDCurrentSenseADCDMA::readResults(uint16_t & a, uint16_t & b, uint16_t & c){
+ if(ADC->CTRLA.bit.ENABLE)
+ return false;
+ uint32_t ainA = g_APinDescription[pinA].ulADCChannelNumber;
+ uint32_t ainB = g_APinDescription[pinB].ulADCChannelNumber;
+ a = adcBuffer[ainA];
+ b = adcBuffer[ainB];
+ if(_isset(pinC))
+ {
+ uint32_t ainC = g_APinDescription[pinC].ulADCChannelNumber;
+ c = adcBuffer[ainC];
+ }
+ return true;
+}
+
+
+float SAMDCurrentSenseADCDMA::toVolts(uint16_t counts) {
+ return counts * countsToVolts;
+}
+
+void SAMDCurrentSenseADCDMA::initPins(){
+
+ if (pinAREF>=0)
+ pinMode(pinAREF, INPUT);
+ pinMode(pinA, INPUT);
+ pinMode(pinB, INPUT);
+
+ uint32_t ainA = g_APinDescription[pinA].ulADCChannelNumber;
+ uint32_t ainB = g_APinDescription[pinB].ulADCChannelNumber;
+ firstAIN = min(ainA, ainB);
+ lastAIN = max(ainA, ainB);
+ if( _isset(pinC) )
+ {
+ uint32_t ainC = g_APinDescription[pinC].ulADCChannelNumber;
+ pinMode(pinC, INPUT);
+ firstAIN = min(firstAIN, ainC);
+ lastAIN = max(lastAIN, ainC);
+ }
+
+ oneBeforeFirstAIN = firstAIN - 1; //hack to discard noisy first readout
+ BufferSize = lastAIN - oneBeforeFirstAIN + 1;
+
+}
+
+void SAMDCurrentSenseADCDMA::initADC(){
+
+ analogRead(pinA); // do some pin init pinPeripheral()
+ analogRead(pinB); // do some pin init pinPeripheral()
+ analogRead(pinC); // do some pin init pinPeripheral()
+
+ ADC->CTRLA.bit.ENABLE = 0x00; // Disable ADC
+ ADCsync();
+ //ADC->REFCTRL.bit.REFSEL = ADC_REFCTRL_REFSEL_INTVCC0_Val; // 2.2297 V Supply VDDANA
+ ADC->INPUTCTRL.bit.GAIN = ADC_INPUTCTRL_GAIN_1X_Val; // Gain select as 1X
+ // ADC->INPUTCTRL.bit.GAIN = ADC_INPUTCTRL_GAIN_DIV2_Val; // default
+ if (pinAREF>=0)
+ ADC->REFCTRL.bit.REFSEL = ADC_REFCTRL_REFSEL_AREFA;
+ else
+ ADC->REFCTRL.bit.REFSEL = ADC_REFCTRL_REFSEL_INTVCC0;
+ ADCsync(); // ref 31.6.16
+
+ /*
+ Bits 19:16 – INPUTSCAN[3:0]: Number of Input Channels Included in Scan
+ This register gives the number of input sources included in the pin scan. The number of input sources included is
+ INPUTSCAN + 1. The input channels included are in the range from MUXPOS + INPUTOFFSET to MUXPOS +
+ INPUTOFFSET + INPUTSCAN.
+ The range of the scan mode must not exceed the number of input channels available on the device.
+ Bits 4:0 – MUXPOS[4:0]: Positive Mux Input Selection
+ These bits define the Mux selection for the positive ADC input. Table 32-14 shows the possible input selections. If
+ the internal bandgap voltage or temperature sensor input channel is selected, then the Sampling Time Length bit
+ group in the SamplingControl register must be written.
+ Table 32-14. Positive Mux Input Selection
+ MUXPOS[4:0] Group configuration Description
+ 0x00 PIN0 ADC AIN0 pin
+ 0x01 PIN1 ADC AIN1 pin
+ 0x02 PIN2 ADC AIN2 pin
+ 0x03 PIN3 ADC AIN3 pin
+ 0x04 PIN4 ADC AIN4 pin
+ 0x05 PIN5 ADC AIN5 pin
+ 0x06 PIN6 ADC AIN6 pin
+ 0x07 PIN7 ADC AIN7 pin
+ 0x08 PIN8 ADC AIN8 pin
+ 0x09 PIN9 ADC AIN9 pin
+ 0x0A PIN10 ADC AIN10 pin
+ 0x0B PIN11 ADC AIN11 pin
+ 0x0C PIN12 ADC AIN12 pin
+ 0x0D PIN13 ADC AIN13 pin
+ 0x0E PIN14 ADC AIN14 pin
+ 0x0F PIN15 ADC AIN15 pin
+ 0x10 PIN16 ADC AIN16 pin
+ 0x11 PIN17 ADC AIN17 pin
+ 0x12 PIN18 ADC AIN18 pin
+ 0x13 PIN19 ADC AIN19 pin
+ 0x14-0x17 Reserved
+ 0x18 TEMP Temperature reference
+ 0x19 BANDGAP Bandgap voltage
+ 0x1A SCALEDCOREVCC 1/4 scaled core supply
+ 0x1B SCALEDIOVCC 1/4 scaled I/O supply
+ 0x1C DAC DAC output
+ 0x1D-0x1F Reserved
+ */
+ ADC->INPUTCTRL.bit.MUXPOS = oneBeforeFirstAIN;
+ ADCsync();
+ ADC->INPUTCTRL.bit.INPUTSCAN = lastAIN; // so the adc will scan from oneBeforeFirstAIN to lastAIN (inclusive)
+ ADCsync();
+ ADC->INPUTCTRL.bit.INPUTOFFSET = 0; //input scan cursor
+ ADCsync();
+ ADC->AVGCTRL.reg = 0x00 ; //no averaging
+ ADC->SAMPCTRL.reg = 0x05; ; //sample length in 1/2 CLK_ADC cycles, see GCLK_ADC and ADC_CTRLB_PRESCALER_DIV16
+ // according to the specsheet: f_GCLK_ADC ADC input clock frequency 48 MHz, so same as fCPU
+ ADCsync();
+ ADC->CTRLB.reg = ADC_CTRLB_PRESCALER_DIV16 | ADC_CTRLB_FREERUN | ADC_CTRLB_RESSEL_12BIT;
+ ADCsync();
+}
+
+volatile dmacdescriptor wrb[12] __attribute__ ((aligned (16)));
+
+void SAMDCurrentSenseADCDMA::initDMA() {
+ // probably on by default
+ PM->AHBMASK.reg |= PM_AHBMASK_DMAC ;
+ PM->APBBMASK.reg |= PM_APBBMASK_DMAC ;
+ NVIC_EnableIRQ( DMAC_IRQn ) ;
+ DMAC->BASEADDR.reg = (uint32_t)descriptor_section;
+ DMAC->WRBADDR.reg = (uint32_t)wrb;
+ DMAC->CTRL.reg = DMAC_CTRL_DMAENABLE | DMAC_CTRL_LVLEN(0xf);
+}
+
+
+void SAMDCurrentSenseADCDMA::adcToDMATransfer(void *rxdata, uint32_t hwords) {
+
+ DMAC->CHID.reg = DMAC_CHID_ID(channelDMA);
+ DMAC->CHCTRLA.reg &= ~DMAC_CHCTRLA_ENABLE;
+ DMAC->CHCTRLA.reg = DMAC_CHCTRLA_SWRST;
+ DMAC->SWTRIGCTRL.reg &= (uint32_t)(~(1 << channelDMA));
+
+ DMAC->CHCTRLB.reg = DMAC_CHCTRLB_LVL(0)
+ | DMAC_CHCTRLB_TRIGSRC(ADC_DMAC_ID_RESRDY)
+ | DMAC_CHCTRLB_TRIGACT_BEAT;
+ DMAC->CHINTENSET.reg = DMAC_CHINTENSET_MASK ; // enable all 3 interrupts
+ descriptor.descaddr = 0;
+ descriptor.srcaddr = (uint32_t) &ADC->RESULT.reg;
+ descriptor.btcnt = hwords;
+ descriptor.dstaddr = (uint32_t)rxdata + hwords*2; // end address
+ descriptor.btctrl = DMAC_BTCTRL_BEATSIZE_HWORD | DMAC_BTCTRL_DSTINC | DMAC_BTCTRL_VALID;
+ memcpy(&descriptor_section[channelDMA],&descriptor, sizeof(dmacdescriptor));
+
+ // start channel
+ DMAC->CHID.reg = DMAC_CHID_ID(channelDMA);
+ DMAC->CHCTRLA.reg |= DMAC_CHCTRLA_ENABLE;
+}
+
+
+int iii = 0;
+
+void adcStopWithDMA(void){
+ ADCsync();
+ ADC->CTRLA.bit.ENABLE = 0x00;
+ // ADCsync();
+ // if(iii++ % 1000 == 0)
+ // {
+ // SIMPLEFOC_SAMD_DEBUG_SERIAL.print(a);
+ // SIMPLEFOC_SAMD_DEBUG_SERIAL.print(" :: ");
+ // SIMPLEFOC_SAMD_DEBUG_SERIAL.print(b);
+ // SIMPLEFOC_SAMD_DEBUG_SERIAL.print(" :: ");
+ // SIMPLEFOC_SAMD_DEBUG_SERIAL.print(c);
+ // SIMPLEFOC_SAMD_DEBUG_SERIAL.println("yo!");
+ // }
+
+
+}
+
+void adcStartWithDMA(void){
+ ADCsync();
+ ADC->INPUTCTRL.bit.INPUTOFFSET = 0;
+ ADCsync();
+ ADC->SWTRIG.bit.FLUSH = 1;
+ ADCsync();
+ ADC->CTRLA.bit.ENABLE = 0x01;
+ ADCsync();
+}
+
+void DMAC_Handler() {
+ uint8_t active_channel;
+ active_channel = DMAC->INTPEND.reg & DMAC_INTPEND_ID_Msk; // get channel number
+ DMAC->CHID.reg = DMAC_CHID_ID(active_channel);
+ adcStopWithDMA();
+ DMAC->CHINTFLAG.reg = DMAC_CHINTENCLR_TCMPL; // clear
+ DMAC->CHINTFLAG.reg = DMAC_CHINTENCLR_TERR;
+ DMAC->CHINTFLAG.reg = DMAC_CHINTENCLR_SUSP;
+
+}
+
+
+#endif
\ No newline at end of file
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/hardware_specific/samd/samd21_mcu.h b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/hardware_specific/samd/samd21_mcu.h
new file mode 100644
index 0000000..e7d7442
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/hardware_specific/samd/samd21_mcu.h
@@ -0,0 +1,69 @@
+#ifdef _SAMD21_
+
+#ifndef CURRENT_SENSE_SAMD21_H
+#define CURRENT_SENSE_SAMD21_H
+
+#define SIMPLEFOC_SAMD_DEBUG
+#if !defined(SIMPLEFOC_SAMD_DEBUG_SERIAL)
+#define SIMPLEFOC_SAMD_DEBUG_SERIAL Serial
+#endif
+
+#include
+ typedef struct {
+ uint16_t btctrl;
+ uint16_t btcnt;
+ uint32_t srcaddr;
+ uint32_t dstaddr;
+ uint32_t descaddr;
+ } dmacdescriptor ;
+
+
+// AREF pin is 42
+
+class SAMDCurrentSenseADCDMA
+{
+
+public:
+ static SAMDCurrentSenseADCDMA * getHardwareAPIInstance();
+ SAMDCurrentSenseADCDMA();
+ void init(int pinA, int pinB, int pinC, int pinAREF = 42, float voltageAREF = 3.3, uint32_t adcBits = 12, uint32_t channelDMA = 3);
+ void startADCScan();
+ bool readResults(uint16_t & a, uint16_t & b, uint16_t & c);
+ float toVolts(uint16_t counts);
+private:
+
+ void adcToDMATransfer(void *rxdata, uint32_t hwords);
+
+ void initPins();
+ void initADC();
+ void initDMA();
+
+ uint32_t oneBeforeFirstAIN; // hack to discard first noisy readout
+ uint32_t firstAIN;
+ uint32_t lastAIN;
+ uint32_t BufferSize = 0;
+
+ uint16_t adcBuffer[20];
+
+
+ uint32_t pinA;
+ uint32_t pinB;
+ uint32_t pinC;
+ uint32_t pinAREF;
+ uint32_t channelDMA; // DMA channel
+ bool freeRunning;
+
+ float voltageAREF;
+ float maxCountsADC;
+ float countsToVolts;
+
+ dmacdescriptor descriptor_section[12] __attribute__ ((aligned (16)));
+ dmacdescriptor descriptor __attribute__ ((aligned (16)));
+
+};
+
+#endif
+
+
+
+#endif
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/hardware_specific/samd/samd_mcu.cpp b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/hardware_specific/samd/samd_mcu.cpp
new file mode 100644
index 0000000..2ec47c0
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/hardware_specific/samd/samd_mcu.cpp
@@ -0,0 +1,23 @@
+#include "../../hardware_api.h"
+
+#if defined(_SAMD21_)|| defined(_SAMD51_) || defined(_SAME51_)
+
+#define _ADC_VOLTAGE 3.3f
+#define _ADC_RESOLUTION 1024.0f
+
+// function reading an ADC value and returning the read voltage
+void* _configureADCInline(const void* driver_params, const int pinA,const int pinB,const int pinC){
+ _UNUSED(driver_params);
+
+ if( _isset(pinA) ) pinMode(pinA, INPUT);
+ if( _isset(pinB) ) pinMode(pinB, INPUT);
+ if( _isset(pinC) ) pinMode(pinC, INPUT);
+
+ GenericCurrentSenseParams* params = new GenericCurrentSenseParams {
+ .pins = { pinA, pinB, pinC },
+ .adc_voltage_conv = (_ADC_VOLTAGE)/(_ADC_RESOLUTION)
+ };
+
+ return params;
+}
+#endif
\ No newline at end of file
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/hardware_specific/stm32/b_g431/b_g431_hal.cpp b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/hardware_specific/stm32/b_g431/b_g431_hal.cpp
new file mode 100644
index 0000000..dc505d6
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/hardware_specific/stm32/b_g431/b_g431_hal.cpp
@@ -0,0 +1,377 @@
+#include "../../../hardware_api.h"
+#if defined(ARDUINO_B_G431B_ESC1)
+
+#include "communication/SimpleFOCDebug.h"
+
+#include "stm32g4xx_hal.h"
+#include "stm32g4xx_ll_pwr.h"
+#include "stm32g4xx_hal_adc.h"
+#include "b_g431_hal.h"
+
+// From STM32 cube IDE
+/**
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2020 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software component is licensed by ST under BSD 3-Clause license,
+ * the "License"; You may not use this file except in compliance with the
+ * License. You may obtain a copy of the License at:
+ * opensource.org/licenses/BSD-3-Clause
+ *
+ ******************************************************************************
+ */
+
+
+/**
+ * @brief GPIO Initialization Function
+ * @param None
+ * @retval None
+ */
+void MX_GPIO_Init(void)
+{
+ /* GPIO Ports Clock Enable */
+ __HAL_RCC_GPIOC_CLK_ENABLE();
+ __HAL_RCC_GPIOF_CLK_ENABLE();
+ __HAL_RCC_GPIOA_CLK_ENABLE();
+ __HAL_RCC_GPIOB_CLK_ENABLE();
+
+ __HAL_RCC_ADC12_CLK_ENABLE();
+}
+
+/**
+ * Enable DMA controller clock
+ */
+void MX_DMA_Init(void)
+{
+ /* DMA controller clock enable */
+ __HAL_RCC_DMAMUX1_CLK_ENABLE();
+ __HAL_RCC_DMA1_CLK_ENABLE();
+ __HAL_RCC_DMA2_CLK_ENABLE();
+
+ /* DMA interrupt init */
+ /* DMA1_Channel1_IRQn interrupt configuration */
+ HAL_NVIC_SetPriority(DMA1_Channel1_IRQn, 0, 0);
+ HAL_NVIC_EnableIRQ(DMA1_Channel1_IRQn);
+ /* DMA1_Channel2_IRQn interrupt configuration */
+ HAL_NVIC_SetPriority(DMA1_Channel2_IRQn, 0, 0);
+ HAL_NVIC_EnableIRQ(DMA1_Channel2_IRQn);
+
+ // Enable external clock for ADC
+ RCC_PeriphCLKInitTypeDef PeriphClkInit;
+ PeriphClkInit.PeriphClockSelection = RCC_PERIPHCLK_ADC12;
+ PeriphClkInit.Adc12ClockSelection = RCC_ADC12CLKSOURCE_PLL;
+ HAL_RCCEx_PeriphCLKConfig(&PeriphClkInit);
+}
+
+
+/**
+ * @brief ADC1 Initialization Function
+ * @param None
+ * @retval None
+ */
+void MX_ADC1_Init(ADC_HandleTypeDef* hadc1)
+{
+ /* USER CODE BEGIN ADC1_Init 0 */
+
+ /* USER CODE END ADC1_Init 0 */
+
+ ADC_MultiModeTypeDef multimode = {0};
+ ADC_ChannelConfTypeDef sConfig = {0};
+
+ /* USER CODE BEGIN ADC1_Init 1 */
+
+ /* USER CODE END ADC1_Init 1 */
+ /** Common config
+ */
+ hadc1->Instance = ADC1;
+ hadc1->Init.ClockPrescaler = ADC_CLOCK_ASYNC_DIV16;
+ hadc1->Init.Resolution = ADC_RESOLUTION_12B;
+ hadc1->Init.DataAlign = ADC_DATAALIGN_RIGHT;
+ hadc1->Init.GainCompensation = 0;
+ hadc1->Init.ScanConvMode = ADC_SCAN_ENABLE;
+ hadc1->Init.EOCSelection = ADC_EOC_SINGLE_CONV;
+ hadc1->Init.LowPowerAutoWait = DISABLE;
+ hadc1->Init.ContinuousConvMode = DISABLE;
+ hadc1->Init.NbrOfConversion = 5;
+ hadc1->Init.DiscontinuousConvMode = DISABLE;
+ hadc1->Init.ExternalTrigConv = ADC_EXTERNALTRIG_T1_TRGO;
+ hadc1->Init.ExternalTrigConvEdge = ADC_EXTERNALTRIGCONVEDGE_RISING;
+ hadc1->Init.DMAContinuousRequests = ENABLE;
+ hadc1->Init.Overrun = ADC_OVR_DATA_PRESERVED;
+
+ if (HAL_ADC_Init(hadc1) != HAL_OK)
+ {
+ SIMPLEFOC_DEBUG("HAL_ADC_Init failed!");
+ }
+
+ /** Configure the ADC multi-mode
+ */
+ multimode.Mode = ADC_MODE_INDEPENDENT;
+ if (HAL_ADCEx_MultiModeConfigChannel(hadc1, &multimode) != HAL_OK)
+ {
+ SIMPLEFOC_DEBUG("HAL_ADCEx_MultiModeConfigChannel failed!");
+ }
+ /** Configure Regular Channel
+ */
+ sConfig.Channel = ADC_CHANNEL_12; // ADC1_IN12 = PB1 = OP3_OUT
+ sConfig.Rank = ADC_REGULAR_RANK_1;
+ sConfig.SamplingTime = ADC_SAMPLETIME_2CYCLES_5;
+ sConfig.SingleDiff = ADC_SINGLE_ENDED;
+ sConfig.OffsetNumber = ADC_OFFSET_NONE;
+ sConfig.Offset = 0;
+ if (HAL_ADC_ConfigChannel(hadc1, &sConfig) != HAL_OK)
+ {
+ SIMPLEFOC_DEBUG("HAL_ADC_ConfigChannel failed!");
+ }
+ /** Configure Regular Channel
+ */
+ sConfig.Channel = ADC_CHANNEL_3; // ADC1_IN3 = PA2 = OP1_OUT
+ sConfig.Rank = ADC_REGULAR_RANK_2;
+ if (HAL_ADC_ConfigChannel(hadc1, &sConfig) != HAL_OK)
+ {
+ SIMPLEFOC_DEBUG("HAL_ADC_ConfigChannel failed!");
+ }
+
+ //******************************************************************
+ // Temp, Poti ....
+ /* Configure Regular Channel (PB12, Potentiometer)
+ */
+ sConfig.Channel = ADC_CHANNEL_11;
+ sConfig.Rank = ADC_REGULAR_RANK_3;
+ sConfig.SamplingTime = ADC_SAMPLETIME_47CYCLES_5;
+ sConfig.SingleDiff = ADC_SINGLE_ENDED;
+ sConfig.OffsetNumber = ADC_OFFSET_NONE;
+ sConfig.Offset = 0;
+ if (HAL_ADC_ConfigChannel(hadc1, &sConfig) != HAL_OK)
+ {
+ SIMPLEFOC_DEBUG("HAL_ADC_ConfigChannel failed!");
+ }
+
+ /** Configure Regular Channel (PB14, Temperature)
+ */
+ sConfig.Channel = ADC_CHANNEL_5;
+ sConfig.Rank = ADC_REGULAR_RANK_4;
+ sConfig.SamplingTime = ADC_SAMPLETIME_47CYCLES_5;
+ sConfig.SingleDiff = ADC_SINGLE_ENDED;
+ sConfig.OffsetNumber = ADC_OFFSET_NONE;
+ sConfig.Offset = 0;
+ if (HAL_ADC_ConfigChannel(hadc1, &sConfig) != HAL_OK)
+ {
+ SIMPLEFOC_DEBUG("HAL_ADC_ConfigChannel failed!");
+ }
+
+ /** Configure Regular Channel (PB14, Temperature)
+ */
+ sConfig.Channel = ADC_CHANNEL_1;
+ sConfig.Rank = ADC_REGULAR_RANK_5;
+ sConfig.SamplingTime = ADC_SAMPLETIME_47CYCLES_5;
+ sConfig.SingleDiff = ADC_SINGLE_ENDED;
+ sConfig.OffsetNumber = ADC_OFFSET_NONE;
+ sConfig.Offset = 0;
+ if (HAL_ADC_ConfigChannel(hadc1, &sConfig) != HAL_OK)
+ {
+ SIMPLEFOC_DEBUG("HAL_ADC_ConfigChannel failed!");
+ }
+ /* USER CODE BEGIN ADC1_Init 2 */
+
+ /* USER CODE END ADC1_Init 2 */
+
+}
+
+/**
+ * @brief ADC2 Initialization Function
+ * @param None
+ * @retval None
+ */
+void MX_ADC2_Init(ADC_HandleTypeDef* hadc2)
+{
+ /* USER CODE BEGIN ADC2_Init 0 */
+
+ /* USER CODE END ADC2_Init 0 */
+
+ ADC_ChannelConfTypeDef sConfig = {0};
+
+ /* USER CODE BEGIN ADC2_Init 1 */
+
+ /* USER CODE END ADC2_Init 1 */
+ /** Common config
+ */
+ hadc2->Instance = ADC2;
+ hadc2->Init.ClockPrescaler = ADC_CLOCK_ASYNC_DIV16;
+ hadc2->Init.Resolution = ADC_RESOLUTION_12B;
+ hadc2->Init.DataAlign = ADC_DATAALIGN_RIGHT;
+ hadc2->Init.GainCompensation = 0;
+ hadc2->Init.ScanConvMode = ADC_SCAN_ENABLE;
+ hadc2->Init.EOCSelection = ADC_EOC_SINGLE_CONV;
+ hadc2->Init.LowPowerAutoWait = DISABLE;
+ hadc2->Init.ContinuousConvMode = DISABLE;
+ hadc2->Init.NbrOfConversion = 1;
+ hadc2->Init.DiscontinuousConvMode = DISABLE;
+ hadc2->Init.ExternalTrigConv = ADC_EXTERNALTRIG_T1_TRGO;
+ hadc2->Init.ExternalTrigConvEdge = ADC_EXTERNALTRIGCONVEDGE_RISING;
+ hadc2->Init.DMAContinuousRequests = ENABLE;
+ hadc2->Init.Overrun = ADC_OVR_DATA_PRESERVED;
+
+ if (HAL_ADC_Init(hadc2) != HAL_OK)
+ {
+ SIMPLEFOC_DEBUG("HAL_ADC_Init failed!");
+ }
+ /** Configure Regular Channel
+ */
+ sConfig.Channel = ADC_CHANNEL_3; // ADC2_IN3 = PA6
+ sConfig.Rank = ADC_REGULAR_RANK_1;
+ sConfig.SamplingTime = ADC_SAMPLETIME_2CYCLES_5;
+ sConfig.SingleDiff = ADC_SINGLE_ENDED;
+ sConfig.OffsetNumber = ADC_OFFSET_NONE;
+ sConfig.Offset = 0;
+ if (HAL_ADC_ConfigChannel(hadc2, &sConfig) != HAL_OK)
+ {
+ SIMPLEFOC_DEBUG("HAL_ADC_ConfigChannel failed!");
+ }
+ /* USER CODE BEGIN ADC2_Init 2 */
+
+ /* USER CODE END ADC2_Init 2 */
+
+}
+
+/**
+* @brief OPAMP MSP Initialization
+* This function configures the hardware resources used in this example
+* @param hopamp-> OPAMP handle pointer
+* @retval None
+*/
+void HAL_OPAMP_MspInit(OPAMP_HandleTypeDef* hopamp)
+{
+ GPIO_InitTypeDef GPIO_InitStruct = {0};
+ if(hopamp->Instance==OPAMP1)
+ {
+ /* USER CODE BEGIN OPAMP1_MspInit 0 */
+
+ /* USER CODE END OPAMP1_MspInit 0 */
+
+ __HAL_RCC_GPIOA_CLK_ENABLE();
+ /**OPAMP1 GPIO Configuration
+ PA1 ------> OPAMP1_VINP
+ PA2 ------> OPAMP1_VOUT
+ PA3 ------> OPAMP1_VINM
+ */
+ GPIO_InitStruct.Pin = GPIO_PIN_1|GPIO_PIN_2|GPIO_PIN_3;
+ GPIO_InitStruct.Mode = GPIO_MODE_ANALOG;
+ GPIO_InitStruct.Pull = GPIO_NOPULL;
+ HAL_GPIO_Init(GPIOA, &GPIO_InitStruct);
+
+ /* USER CODE BEGIN OPAMP1_MspInit 1 */
+
+ /* USER CODE END OPAMP1_MspInit 1 */
+ }
+ else if(hopamp->Instance==OPAMP2)
+ {
+ /* USER CODE BEGIN OPAMP2_MspInit 0 */
+
+ /* USER CODE END OPAMP2_MspInit 0 */
+
+ __HAL_RCC_GPIOA_CLK_ENABLE();
+ /**OPAMP2 GPIO Configuration
+ PA5 ------> OPAMP2_VINM
+ PA6 ------> OPAMP2_VOUT
+ PA7 ------> OPAMP2_VINP
+ */
+ GPIO_InitStruct.Pin = GPIO_PIN_5|GPIO_PIN_6|GPIO_PIN_7;
+ GPIO_InitStruct.Mode = GPIO_MODE_ANALOG;
+ GPIO_InitStruct.Pull = GPIO_NOPULL;
+ HAL_GPIO_Init(GPIOA, &GPIO_InitStruct);
+
+ /* USER CODE BEGIN OPAMP2_MspInit 1 */
+
+ /* USER CODE END OPAMP2_MspInit 1 */
+ }
+ else if(hopamp->Instance==OPAMP3)
+ {
+ /* USER CODE BEGIN OPAMP3_MspInit 0 */
+
+ /* USER CODE END OPAMP3_MspInit 0 */
+
+ __HAL_RCC_GPIOB_CLK_ENABLE();
+ /**OPAMP3 GPIO Configuration
+ PB0 ------> OPAMP3_VINP
+ PB1 ------> OPAMP3_VOUT
+ PB2 ------> OPAMP3_VINM
+ */
+ GPIO_InitStruct.Pin = GPIO_PIN_0|GPIO_PIN_1|GPIO_PIN_2;
+ GPIO_InitStruct.Mode = GPIO_MODE_ANALOG;
+ GPIO_InitStruct.Pull = GPIO_NOPULL;
+ HAL_GPIO_Init(GPIOB, &GPIO_InitStruct);
+
+ /* USER CODE BEGIN OPAMP3_MspInit 1 */
+
+ /* USER CODE END OPAMP3_MspInit 1 */
+ }
+
+}
+
+/**
+* @brief OPAMP MSP De-Initialization
+* This function freeze the hardware resources used in this example
+* @param hopamp-> OPAMP handle pointer
+* @retval None
+*/
+void HAL_OPAMP_MspDeInit(OPAMP_HandleTypeDef* hopamp)
+{
+ if(hopamp->Instance==OPAMP1)
+ {
+ /* USER CODE BEGIN OPAMP1_MspDeInit 0 */
+
+ /* USER CODE END OPAMP1_MspDeInit 0 */
+
+ /**OPAMP1 GPIO Configuration
+ PA1 ------> OPAMP1_VINP
+ PA2 ------> OPAMP1_VOUT
+ PA3 ------> OPAMP1_VINM
+ */
+ HAL_GPIO_DeInit(GPIOA, GPIO_PIN_1|GPIO_PIN_2|GPIO_PIN_3);
+
+ /* USER CODE BEGIN OPAMP1_MspDeInit 1 */
+
+ /* USER CODE END OPAMP1_MspDeInit 1 */
+ }
+ else if(hopamp->Instance==OPAMP2)
+ {
+ /* USER CODE BEGIN OPAMP2_MspDeInit 0 */
+
+ /* USER CODE END OPAMP2_MspDeInit 0 */
+
+ /**OPAMP2 GPIO Configuration
+ PA5 ------> OPAMP2_VINM
+ PA6 ------> OPAMP2_VOUT
+ PA7 ------> OPAMP2_VINP
+ */
+ HAL_GPIO_DeInit(GPIOA, GPIO_PIN_5|GPIO_PIN_6|GPIO_PIN_7);
+
+ /* USER CODE BEGIN OPAMP2_MspDeInit 1 */
+
+ /* USER CODE END OPAMP2_MspDeInit 1 */
+ }
+ else if(hopamp->Instance==OPAMP3)
+ {
+ /* USER CODE BEGIN OPAMP3_MspDeInit 0 */
+
+ /* USER CODE END OPAMP3_MspDeInit 0 */
+
+ /**OPAMP3 GPIO Configuration
+ PB0 ------> OPAMP3_VINP
+ PB1 ------> OPAMP3_VOUT
+ PB2 ------> OPAMP3_VINM
+ */
+ HAL_GPIO_DeInit(GPIOB, GPIO_PIN_0|GPIO_PIN_1|GPIO_PIN_2);
+
+ /* USER CODE BEGIN OPAMP3_MspDeInit 1 */
+
+ /* USER CODE END OPAMP3_MspDeInit 1 */
+ }
+
+}
+
+#endif
\ No newline at end of file
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/hardware_specific/stm32/b_g431/b_g431_hal.h b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/hardware_specific/stm32/b_g431/b_g431_hal.h
new file mode 100644
index 0000000..2d6a1f0
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/hardware_specific/stm32/b_g431/b_g431_hal.h
@@ -0,0 +1,18 @@
+#ifndef B_G431_ESC1_HAL
+#define B_G431_ESC1_HAL
+
+#if defined(ARDUINO_B_G431B_ESC1)
+
+#include
+#include
+
+void MX_GPIO_Init(void);
+void MX_DMA_Init(void);
+void MX_ADC1_Init(ADC_HandleTypeDef* hadc1);
+void MX_ADC2_Init(ADC_HandleTypeDef* hadc2);
+void MX_OPAMP1_Init(OPAMP_HandleTypeDef* hopamp);
+void MX_OPAMP2_Init(OPAMP_HandleTypeDef* hopamp);
+void MX_OPAMP3_Init(OPAMP_HandleTypeDef* hopamp);
+#endif
+
+#endif
\ No newline at end of file
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/hardware_specific/stm32/b_g431/b_g431_mcu.cpp b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/hardware_specific/stm32/b_g431/b_g431_mcu.cpp
new file mode 100644
index 0000000..46cb20b
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/hardware_specific/stm32/b_g431/b_g431_mcu.cpp
@@ -0,0 +1,178 @@
+#include "../../../hardware_api.h"
+
+#if defined(ARDUINO_B_G431B_ESC1)
+
+#include "b_g431_hal.h"
+#include "Arduino.h"
+#include "../stm32_mcu.h"
+#include "../../../../drivers/hardware_specific/stm32/stm32_mcu.h"
+#include "communication/SimpleFOCDebug.h"
+
+#define _ADC_VOLTAGE 3.3f
+#define _ADC_RESOLUTION 4096.0f
+#define ADC_BUF_LEN_1 5
+#define ADC_BUF_LEN_2 1
+
+static ADC_HandleTypeDef hadc1;
+static ADC_HandleTypeDef hadc2;
+static OPAMP_HandleTypeDef hopamp1;
+static OPAMP_HandleTypeDef hopamp2;
+static OPAMP_HandleTypeDef hopamp3;
+
+static DMA_HandleTypeDef hdma_adc1;
+static DMA_HandleTypeDef hdma_adc2;
+
+volatile uint16_t adcBuffer1[ADC_BUF_LEN_1] = {0}; // Buffer for store the results of the ADC conversion
+volatile uint16_t adcBuffer2[ADC_BUF_LEN_2] = {0}; // Buffer for store the results of the ADC conversion
+
+// function reading an ADC value and returning the read voltage
+// As DMA is being used just return the DMA result
+float _readADCVoltageLowSide(const int pin, const void* cs_params){
+ uint32_t raw_adc = 0;
+ if(pin == PA2) // = ADC1_IN3 = phase U (OP1_OUT) on B-G431B-ESC1
+ raw_adc = adcBuffer1[1];
+ else if(pin == PA6) // = ADC2_IN3 = phase V (OP2_OUT) on B-G431B-ESC1
+ raw_adc = adcBuffer2[0];
+#ifdef PB1
+ else if(pin == PB1) // = ADC1_IN12 = phase W (OP3_OUT) on B-G431B-ESC1
+ raw_adc = adcBuffer1[0];
+#endif
+
+ else if (pin == A_POTENTIOMETER)
+ raw_adc = adcBuffer1[2];
+ else if (pin == A_TEMPERATURE)
+ raw_adc = adcBuffer1[3];
+ else if (pin == A_VBUS)
+ raw_adc = adcBuffer1[4];
+
+ return raw_adc * ((Stm32CurrentSenseParams*)cs_params)->adc_voltage_conv;
+}
+
+void _configureOPAMP(OPAMP_HandleTypeDef *hopamp, OPAMP_TypeDef *OPAMPx_Def){
+ // could this be replaced with LL_OPAMP calls??
+ hopamp->Instance = OPAMPx_Def;
+ hopamp->Init.PowerMode = OPAMP_POWERMODE_HIGHSPEED;
+ hopamp->Init.Mode = OPAMP_PGA_MODE;
+ hopamp->Init.NonInvertingInput = OPAMP_NONINVERTINGINPUT_IO0;
+ hopamp->Init.InternalOutput = DISABLE;
+ hopamp->Init.TimerControlledMuxmode = OPAMP_TIMERCONTROLLEDMUXMODE_DISABLE;
+ hopamp->Init.PgaConnect = OPAMP_PGA_CONNECT_INVERTINGINPUT_IO0_BIAS;
+ hopamp->Init.PgaGain = OPAMP_PGA_GAIN_16_OR_MINUS_15;
+ hopamp->Init.UserTrimming = OPAMP_TRIMMING_FACTORY;
+ if (HAL_OPAMP_Init(hopamp) != HAL_OK)
+ {
+ SIMPLEFOC_DEBUG("HAL_OPAMP_Init failed!");
+ }
+}
+void _configureOPAMPs(OPAMP_HandleTypeDef *OPAMPA, OPAMP_HandleTypeDef *OPAMPB, OPAMP_HandleTypeDef *OPAMPC){
+ // Configure the opamps
+ _configureOPAMP(OPAMPA, OPAMP1);
+ _configureOPAMP(OPAMPB, OPAMP2);
+ _configureOPAMP(OPAMPC, OPAMP3);
+}
+
+void MX_DMA1_Init(ADC_HandleTypeDef *hadc, DMA_HandleTypeDef *hdma_adc, DMA_Channel_TypeDef* channel, uint32_t request) {
+ hdma_adc->Instance = channel;
+ hdma_adc->Init.Request = request;
+ hdma_adc->Init.Direction = DMA_PERIPH_TO_MEMORY;
+ hdma_adc->Init.PeriphInc = DMA_PINC_DISABLE;
+ hdma_adc->Init.MemInc = DMA_MINC_ENABLE;
+ hdma_adc->Init.PeriphDataAlignment = DMA_PDATAALIGN_HALFWORD;
+ hdma_adc->Init.MemDataAlignment = DMA_MDATAALIGN_HALFWORD;
+ hdma_adc->Init.Mode = DMA_CIRCULAR;
+ hdma_adc->Init.Priority = DMA_PRIORITY_LOW;
+ HAL_DMA_DeInit(hdma_adc);
+ if (HAL_DMA_Init(hdma_adc) != HAL_OK)
+ {
+ SIMPLEFOC_DEBUG("HAL_DMA_Init failed!");
+ }
+ __HAL_LINKDMA(hadc, DMA_Handle, *hdma_adc);
+}
+
+void* _configureADCInline(const void* driver_params, const int pinA,const int pinB,const int pinC){
+ _UNUSED(driver_params);
+ _UNUSED(pinA);
+ _UNUSED(pinB);
+ _UNUSED(pinC);
+
+ SIMPLEFOC_DEBUG("B-G431B does not implement inline current sense. Use low-side current sense instead.");
+ return SIMPLEFOC_CURRENT_SENSE_INIT_FAILED;
+}
+
+
+void* _configureADCLowSide(const void* driver_params, const int pinA,const int pinB,const int pinC){
+ _UNUSED(driver_params);
+
+ HAL_Init();
+ MX_GPIO_Init();
+ MX_DMA_Init();
+ _configureOPAMPs(&hopamp1, &hopamp3, &hopamp2);
+ MX_ADC1_Init(&hadc1);
+ MX_ADC2_Init(&hadc2);
+
+ HAL_ADCEx_Calibration_Start(&hadc1,ADC_SINGLE_ENDED);
+ HAL_ADCEx_Calibration_Start(&hadc2,ADC_SINGLE_ENDED);
+
+ MX_DMA1_Init(&hadc1, &hdma_adc1, DMA1_Channel1, DMA_REQUEST_ADC1);
+ MX_DMA1_Init(&hadc2, &hdma_adc2, DMA1_Channel2, DMA_REQUEST_ADC2);
+
+ if (HAL_ADC_Start_DMA(&hadc1, (uint32_t*)adcBuffer1, ADC_BUF_LEN_1) != HAL_OK)
+ {
+ SIMPLEFOC_DEBUG("DMA read init failed");
+ }
+ if (HAL_ADC_Start_DMA(&hadc2, (uint32_t*)adcBuffer2, ADC_BUF_LEN_2) != HAL_OK)
+ {
+ SIMPLEFOC_DEBUG("DMA read init failed");
+ }
+
+ HAL_OPAMP_Start(&hopamp1);
+ HAL_OPAMP_Start(&hopamp2);
+ HAL_OPAMP_Start(&hopamp3);
+
+ Stm32CurrentSenseParams* params = new Stm32CurrentSenseParams {
+ .pins = { pinA, pinB, pinC },
+ .adc_voltage_conv = (_ADC_VOLTAGE) / (_ADC_RESOLUTION),
+ .timer_handle = (HardwareTimer *)(HardwareTimer_Handle[get_timer_index(TIM1)]->__this)
+ };
+
+ return params;
+}
+
+extern "C" {
+void DMA1_Channel1_IRQHandler(void) {
+ HAL_DMA_IRQHandler(&hdma_adc1);
+}
+
+void DMA1_Channel2_IRQHandler(void) {
+ HAL_DMA_IRQHandler(&hdma_adc2);
+}
+}
+
+void* _driverSyncLowSide(void* _driver_params, void* _cs_params){
+ STM32DriverParams* driver_params = (STM32DriverParams*)_driver_params;
+ Stm32CurrentSenseParams* cs_params = (Stm32CurrentSenseParams*)_cs_params;
+
+ // stop all the timers for the driver
+ _stopTimers(driver_params->timers, 6);
+
+ // if timer has repetition counter - it will downsample using it
+ // and it does not need the software downsample
+ if( IS_TIM_REPETITION_COUNTER_INSTANCE(cs_params->timer_handle->getHandle()->Instance) ){
+ // adjust the initial timer state such that the trigger for DMA transfer aligns with the pwm peaks instead of throughs.
+ // only necessary for the timers that have repetition counters
+ cs_params->timer_handle->getHandle()->Instance->CR1 |= TIM_CR1_DIR;
+ cs_params->timer_handle->getHandle()->Instance->CNT = cs_params->timer_handle->getHandle()->Instance->ARR;
+ }
+ // set the trigger output event
+ LL_TIM_SetTriggerOutput(cs_params->timer_handle->getHandle()->Instance, LL_TIM_TRGO_UPDATE);
+
+ // restart all the timers of the driver
+ _startTimers(driver_params->timers, 6);
+
+ // return the cs parameters
+ // successfully initialized
+ // TODO verify if success in future
+ return _cs_params;
+}
+
+#endif
\ No newline at end of file
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/hardware_specific/stm32/stm32_mcu.cpp b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/hardware_specific/stm32/stm32_mcu.cpp
new file mode 100644
index 0000000..94253d7
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/hardware_specific/stm32/stm32_mcu.cpp
@@ -0,0 +1,33 @@
+
+#include "../../hardware_api.h"
+
+#if defined(_STM32_DEF_) and !defined(ARDUINO_B_G431B_ESC1)
+
+#include "stm32_mcu.h"
+
+#define _ADC_VOLTAGE 3.3f
+#define _ADC_RESOLUTION 1024.0f
+
+// function reading an ADC value and returning the read voltage
+void* _configureADCInline(const void* driver_params, const int pinA,const int pinB,const int pinC){
+ _UNUSED(driver_params);
+
+ if( _isset(pinA) ) pinMode(pinA, INPUT);
+ if( _isset(pinB) ) pinMode(pinB, INPUT);
+ if( _isset(pinC) ) pinMode(pinC, INPUT);
+
+ Stm32CurrentSenseParams* params = new Stm32CurrentSenseParams {
+ .pins = { pinA, pinB, pinC },
+ .adc_voltage_conv = (_ADC_VOLTAGE)/(_ADC_RESOLUTION)
+ };
+
+ return params;
+}
+
+// function reading an ADC value and returning the read voltage
+__attribute__((weak)) float _readADCVoltageInline(const int pinA, const void* cs_params){
+ uint32_t raw_adc = analogRead(pinA);
+ return raw_adc * ((Stm32CurrentSenseParams*)cs_params)->adc_voltage_conv;
+}
+
+#endif
\ No newline at end of file
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/hardware_specific/stm32/stm32_mcu.h b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/hardware_specific/stm32/stm32_mcu.h
new file mode 100644
index 0000000..6e23817
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/hardware_specific/stm32/stm32_mcu.h
@@ -0,0 +1,21 @@
+
+#ifndef STM32_CURRENTSENSE_MCU_DEF
+#define STM32_CURRENTSENSE_MCU_DEF
+#include "../../hardware_api.h"
+#include "../../../common/foc_utils.h"
+
+#if defined(_STM32_DEF_)
+
+// generic implementation of the hardware specific structure
+// containing all the necessary current sense parameters
+// will be returned as a void pointer from the _configureADCx functions
+// will be provided to the _readADCVoltageX() as a void pointer
+typedef struct Stm32CurrentSenseParams {
+ int pins[3] = {(int)NOT_SET};
+ float adc_voltage_conv;
+ ADC_HandleTypeDef* adc_handle = NP;
+ HardwareTimer* timer_handle = NP;
+} Stm32CurrentSenseParams;
+
+#endif
+#endif
\ No newline at end of file
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/hardware_specific/stm32/stm32f1/stm32f1_hal.cpp b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/hardware_specific/stm32/stm32f1/stm32f1_hal.cpp
new file mode 100644
index 0000000..d3bea81
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/hardware_specific/stm32/stm32f1/stm32f1_hal.cpp
@@ -0,0 +1,157 @@
+#include "stm32f1_hal.h"
+
+#if defined(STM32F1xx)
+
+#include "../../../../communication/SimpleFOCDebug.h"
+#define _TRGO_NOT_AVAILABLE 12345
+
+// timer to injected TRGO
+// https://github.com/stm32duino/Arduino_Core_STM32/blob/e156c32db24d69cb4818208ccc28894e2f427cfa/system/Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_adc_ex.h#L215
+uint32_t _timerToInjectedTRGO(HardwareTimer* timer){
+ if(timer->getHandle()->Instance == TIM1)
+ return ADC_EXTERNALTRIGINJECCONV_T1_TRGO;
+#ifdef TIM2 // if defined timer 2
+ else if(timer->getHandle()->Instance == TIM2)
+ return ADC_EXTERNALTRIGINJECCONV_T2_TRGO;
+#endif
+#ifdef TIM4 // if defined timer 4
+ else if(timer->getHandle()->Instance == TIM4)
+ return ADC_EXTERNALTRIGINJECCONV_T4_TRGO;
+#endif
+#ifdef TIM5 // if defined timer 5
+ else if(timer->getHandle()->Instance == TIM5)
+ return ADC_EXTERNALTRIGINJECCONV_T5_TRGO;
+#endif
+ else
+ return _TRGO_NOT_AVAILABLE;
+}
+
+// timer to regular TRGO
+// https://github.com/stm32duino/Arduino_Core_STM32/blob/e156c32db24d69cb4818208ccc28894e2f427cfa/system/Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_adc_ex.h#L215
+uint32_t _timerToRegularTRGO(HardwareTimer* timer){
+ if(timer->getHandle()->Instance == TIM3)
+ return ADC_EXTERNALTRIGCONV_T3_TRGO;
+#ifdef TIM8 // if defined timer 8
+ else if(timer->getHandle()->Instance == TIM8)
+ return ADC_EXTERNALTRIGCONV_T8_TRGO;
+#endif
+ else
+ return _TRGO_NOT_AVAILABLE;
+}
+
+ADC_HandleTypeDef hadc;
+
+int _adc_init(Stm32CurrentSenseParams* cs_params, const STM32DriverParams* driver_params)
+{
+ ADC_InjectionConfTypeDef sConfigInjected;
+
+ /**Configure the global features of the ADC (Clock, Resolution, Data Alignment and number of conversion)
+ */
+ hadc.Instance = (ADC_TypeDef *)pinmap_peripheral(analogInputToPinName(cs_params->pins[0]), PinMap_ADC);
+ if(hadc.Instance == ADC1) __HAL_RCC_ADC1_CLK_ENABLE();
+#ifdef ADC2 // if defined ADC2
+ else if(hadc.Instance == ADC2) __HAL_RCC_ADC2_CLK_ENABLE();
+#endif
+#ifdef ADC3 // if defined ADC3
+ else if(hadc.Instance == ADC3) __HAL_RCC_ADC3_CLK_ENABLE();
+#endif
+ else{
+#ifdef SIMPLEFOC_STM32_DEBUG
+ SIMPLEFOC_DEBUG("STM32-CS: ERR: Pin does not belong to any ADC!");
+#endif
+ return -1; // error not a valid ADC instance
+ }
+
+ hadc.Init.ScanConvMode = ADC_SCAN_ENABLE;
+ hadc.Init.ContinuousConvMode = ENABLE;
+ hadc.Init.DiscontinuousConvMode = DISABLE;
+ hadc.Init.ExternalTrigConv = ADC_SOFTWARE_START;
+ hadc.Init.DataAlign = ADC_DATAALIGN_RIGHT;
+ hadc.Init.NbrOfConversion = 1;
+ HAL_ADC_Init(&hadc);
+ /**Configure for the selected ADC regular channel to be converted.
+ */
+
+ /**Configures for the selected ADC injected channel its corresponding rank in the sequencer and its sample time
+ */
+ sConfigInjected.InjectedNbrOfConversion = _isset(cs_params->pins[2]) ? 3 : 2;
+ sConfigInjected.InjectedSamplingTime = ADC_SAMPLETIME_1CYCLE_5;
+ sConfigInjected.AutoInjectedConv = DISABLE;
+ sConfigInjected.InjectedDiscontinuousConvMode = DISABLE;
+ sConfigInjected.InjectedOffset = 0;
+
+ // automating TRGO flag finding - hardware specific
+ uint8_t tim_num = 0;
+ while(driver_params->timers[tim_num] != NP && tim_num < 6){
+ uint32_t trigger_flag = _timerToInjectedTRGO(driver_params->timers[tim_num++]);
+ if(trigger_flag == _TRGO_NOT_AVAILABLE) continue; // timer does not have valid trgo for injected channels
+
+ // if the code comes here, it has found the timer available
+ // timer does have trgo flag for injected channels
+ sConfigInjected.ExternalTrigInjecConv = trigger_flag;
+
+ // this will be the timer with which the ADC will sync
+ cs_params->timer_handle = driver_params->timers[tim_num-1];
+ // done
+ break;
+ }
+ if( cs_params->timer_handle == NP ){
+ // not possible to use these timers for low-side current sense
+ #ifdef SIMPLEFOC_STM32_DEBUG
+ SIMPLEFOC_DEBUG("STM32-CS: ERR: cannot sync any timer to injected channels!");
+ #endif
+ return -1;
+ }
+ // display which timer is being used
+ #ifdef SIMPLEFOC_STM32_DEBUG
+ // it would be better to use the getTimerNumber from driver
+ SIMPLEFOC_DEBUG("STM32-CS: injected trigger for timer index: ", get_timer_index(cs_params->timer_handle->getHandle()->Instance) + 1);
+ #endif
+
+ // first channel
+ sConfigInjected.InjectedRank = ADC_REGULAR_RANK_1;
+ sConfigInjected.InjectedChannel = STM_PIN_CHANNEL(pinmap_function(analogInputToPinName(cs_params->pins[0]), PinMap_ADC));
+ HAL_ADCEx_InjectedConfigChannel(&hadc, &sConfigInjected);
+ // second channel
+ sConfigInjected.InjectedRank = ADC_REGULAR_RANK_2;
+ sConfigInjected.InjectedChannel = STM_PIN_CHANNEL(pinmap_function(analogInputToPinName(cs_params->pins[1]), PinMap_ADC));
+ HAL_ADCEx_InjectedConfigChannel(&hadc, &sConfigInjected);
+
+ // third channel - if exists
+ if(_isset(cs_params->pins[2])){
+ sConfigInjected.InjectedRank = ADC_REGULAR_RANK_3;
+ sConfigInjected.InjectedChannel = STM_PIN_CHANNEL(pinmap_function(analogInputToPinName(cs_params->pins[2]), PinMap_ADC));
+ HAL_ADCEx_InjectedConfigChannel(&hadc, &sConfigInjected);
+ }
+
+ cs_params->adc_handle = &hadc;
+
+ return 0;
+}
+
+void _adc_gpio_init(Stm32CurrentSenseParams* cs_params, const int pinA, const int pinB, const int pinC)
+{
+ uint8_t cnt = 0;
+ if(_isset(pinA)){
+ pinmap_pinout(analogInputToPinName(pinA), PinMap_ADC);
+ cs_params->pins[cnt++] = pinA;
+ }
+ if(_isset(pinB)){
+ pinmap_pinout(analogInputToPinName(pinB), PinMap_ADC);
+ cs_params->pins[cnt++] = pinB;
+ }
+ if(_isset(pinC)){
+ pinmap_pinout(analogInputToPinName(pinC), PinMap_ADC);
+ cs_params->pins[cnt] = pinC;
+ }
+
+}
+
+extern "C" {
+ void ADC1_2_IRQHandler(void)
+ {
+ HAL_ADC_IRQHandler(&hadc);
+ }
+}
+
+#endif
\ No newline at end of file
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/hardware_specific/stm32/stm32f1/stm32f1_hal.h b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/hardware_specific/stm32/stm32f1/stm32f1_hal.h
new file mode 100644
index 0000000..b0f4f83
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/hardware_specific/stm32/stm32f1/stm32f1_hal.h
@@ -0,0 +1,17 @@
+#ifndef STM32F1_LOWSIDE_HAL
+#define STM32F1_LOWSIDE_HAL
+
+#include "Arduino.h"
+
+#if defined(STM32F1xx)
+#include "stm32f1xx_hal.h"
+#include "../../../../common/foc_utils.h"
+#include "../../../../drivers/hardware_specific/stm32/stm32_mcu.h"
+#include "../stm32_mcu.h"
+
+int _adc_init(Stm32CurrentSenseParams* cs_params, const STM32DriverParams* driver_params);
+void _adc_gpio_init(Stm32CurrentSenseParams* cs_params, const int pinA, const int pinB, const int pinC);
+
+#endif
+
+#endif
\ No newline at end of file
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/hardware_specific/stm32/stm32f1/stm32f1_mcu.cpp b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/hardware_specific/stm32/stm32f1/stm32f1_mcu.cpp
new file mode 100644
index 0000000..49f2f3d
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/hardware_specific/stm32/stm32f1/stm32f1_mcu.cpp
@@ -0,0 +1,141 @@
+#include "../../../hardware_api.h"
+
+#if defined(STM32F1xx)
+#include "../../../../common/foc_utils.h"
+#include "../../../../drivers/hardware_api.h"
+#include "../../../../drivers/hardware_specific/stm32/stm32_mcu.h"
+#include "../../../hardware_api.h"
+#include "../stm32_mcu.h"
+#include "stm32f1_hal.h"
+#include "Arduino.h"
+
+#define _ADC_VOLTAGE_F1 3.3f
+#define _ADC_RESOLUTION_F1 4096.0f
+
+// array of values of 4 injected channels per adc instance (3)
+uint32_t adc_val[3][4]={0};
+// does adc interrupt need a downsample - per adc (3)
+bool needs_downsample[3] = {1};
+// downsampling variable - per adc (3)
+uint8_t tim_downsample[3] = {0};
+
+#ifdef SIMPLEFOC_STM32_ADC_INTERRUPT
+uint8_t use_adc_interrupt = 1;
+#else
+uint8_t use_adc_interrupt = 0;
+#endif
+
+int _adcToIndex(ADC_HandleTypeDef *AdcHandle){
+ if(AdcHandle->Instance == ADC1) return 0;
+#ifdef ADC2 // if ADC2 exists
+ else if(AdcHandle->Instance == ADC2) return 1;
+#endif
+#ifdef ADC3 // if ADC3 exists
+ else if(AdcHandle->Instance == ADC3) return 2;
+#endif
+ return 0;
+}
+
+void* _configureADCLowSide(const void* driver_params, const int pinA, const int pinB, const int pinC){
+
+ Stm32CurrentSenseParams* cs_params= new Stm32CurrentSenseParams {
+ .pins={(int)NOT_SET,(int)NOT_SET,(int)NOT_SET},
+ .adc_voltage_conv = (_ADC_VOLTAGE_F1) / (_ADC_RESOLUTION_F1)
+ };
+ _adc_gpio_init(cs_params, pinA,pinB,pinC);
+ if(_adc_init(cs_params, (STM32DriverParams*)driver_params) != 0) return SIMPLEFOC_CURRENT_SENSE_INIT_FAILED;
+ return cs_params;
+}
+
+
+void* _driverSyncLowSide(void* _driver_params, void* _cs_params){
+ STM32DriverParams* driver_params = (STM32DriverParams*)_driver_params;
+ Stm32CurrentSenseParams* cs_params = (Stm32CurrentSenseParams*)_cs_params;
+
+ // if compatible timer has not been found
+ if (cs_params->timer_handle == NULL) return SIMPLEFOC_CURRENT_SENSE_INIT_FAILED;
+
+ // stop all the timers for the driver
+ _stopTimers(driver_params->timers, 6);
+
+ // if timer has repetition counter - it will downsample using it
+ // and it does not need the software downsample
+ if( IS_TIM_REPETITION_COUNTER_INSTANCE(cs_params->timer_handle->getHandle()->Instance) ){
+ // adjust the initial timer state such that the trigger
+ // - for DMA transfer aligns with the pwm peaks instead of throughs.
+ // - for interrupt based ADC transfer
+ // - only necessary for the timers that have repetition counters
+ cs_params->timer_handle->getHandle()->Instance->CR1 |= TIM_CR1_DIR;
+ cs_params->timer_handle->getHandle()->Instance->CNT = cs_params->timer_handle->getHandle()->Instance->ARR;
+ // remember that this timer has repetition counter - no need to downasmple
+ needs_downsample[_adcToIndex(cs_params->adc_handle)] = 0;
+ }else{
+ if(!use_adc_interrupt){
+ // If the timer has no repetition counter, it needs to use the interrupt to downsample for low side sensing
+ use_adc_interrupt = 1;
+ #ifdef SIMPLEFOC_STM32_DEBUG
+ SIMPLEFOC_DEBUG("STM32-CS: timer has no repetition counter, ADC interrupt has to be used");
+ #endif
+ }
+ }
+ // set the trigger output event
+ LL_TIM_SetTriggerOutput(cs_params->timer_handle->getHandle()->Instance, LL_TIM_TRGO_UPDATE);
+
+ // Start the adc calibration
+ HAL_ADCEx_Calibration_Start(cs_params->adc_handle);
+
+ // start the adc
+ if(use_adc_interrupt){
+ HAL_NVIC_SetPriority(ADC1_2_IRQn, 0, 0);
+ HAL_NVIC_EnableIRQ(ADC1_2_IRQn);
+
+ HAL_ADCEx_InjectedStart_IT(cs_params->adc_handle);
+ }else{
+ HAL_ADCEx_InjectedStart(cs_params->adc_handle);
+ }
+
+
+ // restart all the timers of the driver
+ _startTimers(driver_params->timers, 6);
+
+ // return the cs parameters
+ // successfully initialized
+ // TODO verify if success in future
+ return _cs_params;
+}
+
+
+// function reading an ADC value and returning the read voltage
+float _readADCVoltageLowSide(const int pin, const void* cs_params){
+ for(int i=0; i < 3; i++){
+ if( pin == ((Stm32CurrentSenseParams*)cs_params)->pins[i]){ // found in the buffer
+ if (use_adc_interrupt){
+ return adc_val[_adcToIndex(((Stm32CurrentSenseParams*)cs_params)->adc_handle)][i] * ((Stm32CurrentSenseParams*)cs_params)->adc_voltage_conv;
+ }else{
+ // an optimized way to go from i to the channel i=0 -> channel 1, i=1 -> channel 2, i=2 -> channel 3
+ uint32_t channel = (i == 0) ? ADC_INJECTED_RANK_1 : (i == 1) ? ADC_INJECTED_RANK_2 : ADC_INJECTED_RANK_3;;
+ return HAL_ADCEx_InjectedGetValue(((Stm32CurrentSenseParams*)cs_params)->adc_handle, channel) * ((Stm32CurrentSenseParams*)cs_params)->adc_voltage_conv;
+ }
+ }
+ }
+ return 0;
+}
+
+extern "C" {
+ void HAL_ADCEx_InjectedConvCpltCallback(ADC_HandleTypeDef *AdcHandle){
+ // calculate the instance
+ int adc_index = _adcToIndex(AdcHandle);
+
+ // if the timer han't repetition counter - downsample two times
+ if( needs_downsample[adc_index] && tim_downsample[adc_index]++ > 0) {
+ tim_downsample[adc_index] = 0;
+ return;
+ }
+
+ adc_val[adc_index][0]=HAL_ADCEx_InjectedGetValue(AdcHandle, ADC_INJECTED_RANK_1);
+ adc_val[adc_index][1]=HAL_ADCEx_InjectedGetValue(AdcHandle, ADC_INJECTED_RANK_2);
+ adc_val[adc_index][2]=HAL_ADCEx_InjectedGetValue(AdcHandle, ADC_INJECTED_RANK_3);
+ }
+}
+
+#endif
\ No newline at end of file
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/hardware_specific/stm32/stm32f4/stm32f4_hal.cpp b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/hardware_specific/stm32/stm32f4/stm32f4_hal.cpp
new file mode 100644
index 0000000..bd0df4b
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/hardware_specific/stm32/stm32f4/stm32f4_hal.cpp
@@ -0,0 +1,166 @@
+#include "stm32f4_hal.h"
+
+#if defined(STM32F4xx)
+
+//#define SIMPLEFOC_STM32_DEBUG
+
+#include "../../../../communication/SimpleFOCDebug.h"
+#define _TRGO_NOT_AVAILABLE 12345
+
+ADC_HandleTypeDef hadc;
+
+int _adc_init(Stm32CurrentSenseParams* cs_params, const STM32DriverParams* driver_params)
+{
+ ADC_InjectionConfTypeDef sConfigInjected;
+
+ // check if all pins belong to the same ADC
+ ADC_TypeDef* adc_pin1 = (ADC_TypeDef*)pinmap_peripheral(analogInputToPinName(cs_params->pins[0]), PinMap_ADC);
+ ADC_TypeDef* adc_pin2 = (ADC_TypeDef*)pinmap_peripheral(analogInputToPinName(cs_params->pins[1]), PinMap_ADC);
+ ADC_TypeDef* adc_pin3 = _isset(cs_params->pins[2]) ? (ADC_TypeDef*)pinmap_peripheral(analogInputToPinName(cs_params->pins[2]), PinMap_ADC) : nullptr;
+ if ( (adc_pin1 != adc_pin2) || ( (adc_pin3) && (adc_pin1 != adc_pin3) )){
+#ifdef SIMPLEFOC_STM32_DEBUG
+ SIMPLEFOC_DEBUG("STM32-CS: ERR: Analog pins dont belong to the same ADC!");
+#endif
+ return -1;
+ }
+
+
+ /**Configure the global features of the ADC (Clock, Resolution, Data Alignment and number of conversion)
+ */
+ hadc.Instance = (ADC_TypeDef *)pinmap_peripheral(analogInputToPinName(cs_params->pins[0]), PinMap_ADC);
+
+ if(hadc.Instance == ADC1) __HAL_RCC_ADC1_CLK_ENABLE();
+#ifdef ADC2 // if defined ADC2
+ else if(hadc.Instance == ADC2) __HAL_RCC_ADC2_CLK_ENABLE();
+#endif
+#ifdef ADC3 // if defined ADC3
+ else if(hadc.Instance == ADC3) __HAL_RCC_ADC3_CLK_ENABLE();
+#endif
+ else{
+#ifdef SIMPLEFOC_STM32_DEBUG
+ SIMPLEFOC_DEBUG("STM32-CS: ERR: Pin does not belong to any ADC!");
+#endif
+ return -1; // error not a valid ADC instance
+ }
+
+#ifdef SIMPLEFOC_STM32_DEBUG
+ SIMPLEFOC_DEBUG("STM32-CS: Using ADC: ", _adcToIndex(&hadc)+1);
+#endif
+
+ hadc.Init.ClockPrescaler = ADC_CLOCK_SYNC_PCLK_DIV4;
+ hadc.Init.Resolution = ADC_RESOLUTION_12B;
+ hadc.Init.ScanConvMode = ENABLE;
+ hadc.Init.ContinuousConvMode = ENABLE;
+ hadc.Init.DiscontinuousConvMode = DISABLE;
+ hadc.Init.ExternalTrigConvEdge = ADC_EXTERNALTRIGCONVEDGE_NONE;
+ hadc.Init.ExternalTrigConv = ADC_SOFTWARE_START; // for now
+ hadc.Init.DataAlign = ADC_DATAALIGN_RIGHT;
+ hadc.Init.NbrOfConversion = 1;
+ hadc.Init.DMAContinuousRequests = DISABLE;
+ hadc.Init.EOCSelection = ADC_EOC_SINGLE_CONV;
+ if ( HAL_ADC_Init(&hadc) != HAL_OK){
+#ifdef SIMPLEFOC_STM32_DEBUG
+ SIMPLEFOC_DEBUG("STM32-CS: ERR: cannot init ADC!");
+#endif
+ return -1;
+ }
+
+ /**Configures for the selected ADC injected channel its corresponding rank in the sequencer and its sample time
+ */
+ sConfigInjected.InjectedNbrOfConversion = _isset(cs_params->pins[2]) ? 3 : 2;
+ sConfigInjected.InjectedSamplingTime = ADC_SAMPLETIME_3CYCLES;
+ sConfigInjected.ExternalTrigInjecConvEdge = ADC_EXTERNALTRIGINJECCONVEDGE_RISING;
+ sConfigInjected.AutoInjectedConv = DISABLE;
+ sConfigInjected.InjectedDiscontinuousConvMode = DISABLE;
+ sConfigInjected.InjectedOffset = 0;
+
+ // automating TRGO flag finding - hardware specific
+ uint8_t tim_num = 0;
+ while(driver_params->timers[tim_num] != NP && tim_num < 6){
+ uint32_t trigger_flag = _timerToInjectedTRGO(driver_params->timers[tim_num++]);
+ if(trigger_flag == _TRGO_NOT_AVAILABLE) continue; // timer does not have valid trgo for injected channels
+
+ // if the code comes here, it has found the timer available
+ // timer does have trgo flag for injected channels
+ sConfigInjected.ExternalTrigInjecConv = trigger_flag;
+
+ // this will be the timer with which the ADC will sync
+ cs_params->timer_handle = driver_params->timers[tim_num-1];
+ // done
+ break;
+ }
+ if( cs_params->timer_handle == NP ){
+ // not possible to use these timers for low-side current sense
+ #ifdef SIMPLEFOC_STM32_DEBUG
+ SIMPLEFOC_DEBUG("STM32-CS: ERR: cannot sync any timer to injected channels!");
+ #endif
+ return -1;
+ }
+ // display which timer is being used
+ #ifdef SIMPLEFOC_STM32_DEBUG
+ // it would be better to use the getTimerNumber from driver
+ SIMPLEFOC_DEBUG("STM32-CS: injected trigger for timer index: ", get_timer_index(cs_params->timer_handle->getHandle()->Instance) + 1);
+ #endif
+
+
+ // first channel
+ sConfigInjected.InjectedRank = ADC_INJECTED_RANK_1;
+ sConfigInjected.InjectedChannel = _getADCChannel(analogInputToPinName(cs_params->pins[0]));
+ if (HAL_ADCEx_InjectedConfigChannel(&hadc, &sConfigInjected) != HAL_OK){
+#ifdef SIMPLEFOC_STM32_DEBUG
+ SIMPLEFOC_DEBUG("STM32-CS: ERR: cannot init injected channel: ", (int)_getADCChannel(analogInputToPinName(cs_params->pins[0])) );
+#endif
+ return -1;
+ }
+
+ // second channel
+ sConfigInjected.InjectedRank = ADC_INJECTED_RANK_2;
+ sConfigInjected.InjectedChannel = _getADCChannel(analogInputToPinName(cs_params->pins[1]));
+ if (HAL_ADCEx_InjectedConfigChannel(&hadc, &sConfigInjected) != HAL_OK){
+#ifdef SIMPLEFOC_STM32_DEBUG
+ SIMPLEFOC_DEBUG("STM32-CS: ERR: cannot init injected channel: ", (int)_getADCChannel(analogInputToPinName(cs_params->pins[1]))) ;
+#endif
+ return -1;
+ }
+
+ // third channel - if exists
+ if(_isset(cs_params->pins[2])){
+ sConfigInjected.InjectedRank = ADC_INJECTED_RANK_3;
+ sConfigInjected.InjectedChannel = _getADCChannel(analogInputToPinName(cs_params->pins[2]));
+ if (HAL_ADCEx_InjectedConfigChannel(&hadc, &sConfigInjected) != HAL_OK){
+#ifdef SIMPLEFOC_STM32_DEBUG
+ SIMPLEFOC_DEBUG("STM32-CS: ERR: cannot init injected channel: ", (int)_getADCChannel(analogInputToPinName(cs_params->pins[2]))) ;
+#endif
+ return -1;
+ }
+ }
+
+ cs_params->adc_handle = &hadc;
+ return 0;
+}
+
+void _adc_gpio_init(Stm32CurrentSenseParams* cs_params, const int pinA, const int pinB, const int pinC)
+{
+ uint8_t cnt = 0;
+ if(_isset(pinA)){
+ pinmap_pinout(analogInputToPinName(pinA), PinMap_ADC);
+ cs_params->pins[cnt++] = pinA;
+ }
+ if(_isset(pinB)){
+ pinmap_pinout(analogInputToPinName(pinB), PinMap_ADC);
+ cs_params->pins[cnt++] = pinB;
+ }
+ if(_isset(pinC)){
+ pinmap_pinout(analogInputToPinName(pinC), PinMap_ADC);
+ cs_params->pins[cnt] = pinC;
+ }
+}
+
+extern "C" {
+ void ADC_IRQHandler(void)
+ {
+ HAL_ADC_IRQHandler(&hadc);
+ }
+}
+
+#endif
\ No newline at end of file
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/hardware_specific/stm32/stm32f4/stm32f4_hal.h b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/hardware_specific/stm32/stm32f4/stm32f4_hal.h
new file mode 100644
index 0000000..71071a5
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/hardware_specific/stm32/stm32f4/stm32f4_hal.h
@@ -0,0 +1,18 @@
+#ifndef STM32F4_LOWSIDE_HAL
+#define STM32F4_LOWSIDE_HAL
+
+#include "Arduino.h"
+
+#if defined(STM32F4xx)
+#include "stm32f4xx_hal.h"
+#include "../../../../common/foc_utils.h"
+#include "../../../../drivers/hardware_specific/stm32/stm32_mcu.h"
+#include "../stm32_mcu.h"
+#include "stm32f4_utils.h"
+
+int _adc_init(Stm32CurrentSenseParams* cs_params, const STM32DriverParams* driver_params);
+void _adc_gpio_init(Stm32CurrentSenseParams* cs_params, const int pinA, const int pinB, const int pinC);
+
+#endif
+
+#endif
\ No newline at end of file
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/hardware_specific/stm32/stm32f4/stm32f4_mcu.cpp b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/hardware_specific/stm32/stm32f4/stm32f4_mcu.cpp
new file mode 100644
index 0000000..6b597d4
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/hardware_specific/stm32/stm32f4/stm32f4_mcu.cpp
@@ -0,0 +1,130 @@
+#include "../../../hardware_api.h"
+
+#if defined(STM32F4xx)
+#include "../../../../common/foc_utils.h"
+#include "../../../../drivers/hardware_api.h"
+#include "../../../../drivers/hardware_specific/stm32/stm32_mcu.h"
+#include "../../../hardware_api.h"
+#include "../stm32_mcu.h"
+#include "stm32f4_hal.h"
+#include "stm32f4_utils.h"
+#include "Arduino.h"
+
+
+#define _ADC_VOLTAGE_F4 3.3f
+#define _ADC_RESOLUTION_F4 4096.0f
+
+
+// array of values of 4 injected channels per adc instance (3)
+uint32_t adc_val[3][4]={0};
+// does adc interrupt need a downsample - per adc (3)
+bool needs_downsample[3] = {1};
+// downsampling variable - per adc (3)
+uint8_t tim_downsample[3] = {0};
+
+#ifdef SIMPLEFOC_STM32_ADC_INTERRUPT
+uint8_t use_adc_interrupt = 1;
+#else
+uint8_t use_adc_interrupt = 0;
+#endif
+
+void* _configureADCLowSide(const void* driver_params, const int pinA, const int pinB, const int pinC){
+
+ Stm32CurrentSenseParams* cs_params= new Stm32CurrentSenseParams {
+ .pins={(int)NOT_SET,(int)NOT_SET,(int)NOT_SET},
+ .adc_voltage_conv = (_ADC_VOLTAGE_F4) / (_ADC_RESOLUTION_F4)
+ };
+ _adc_gpio_init(cs_params, pinA,pinB,pinC);
+ if(_adc_init(cs_params, (STM32DriverParams*)driver_params) != 0) return SIMPLEFOC_CURRENT_SENSE_INIT_FAILED;
+ return cs_params;
+}
+
+
+void* _driverSyncLowSide(void* _driver_params, void* _cs_params){
+ STM32DriverParams* driver_params = (STM32DriverParams*)_driver_params;
+ Stm32CurrentSenseParams* cs_params = (Stm32CurrentSenseParams*)_cs_params;
+
+ // if compatible timer has not been found
+ if (cs_params->timer_handle == NULL) return SIMPLEFOC_CURRENT_SENSE_INIT_FAILED;
+
+ // stop all the timers for the driver
+ _stopTimers(driver_params->timers, 6);
+
+ // if timer has repetition counter - it will downsample using it
+ // and it does not need the software downsample
+ if( IS_TIM_REPETITION_COUNTER_INSTANCE(cs_params->timer_handle->getHandle()->Instance) ){
+ // adjust the initial timer state such that the trigger
+ // - for DMA transfer aligns with the pwm peaks instead of throughs.
+ // - for interrupt based ADC transfer
+ // - only necessary for the timers that have repetition counters
+ cs_params->timer_handle->getHandle()->Instance->CR1 |= TIM_CR1_DIR;
+ cs_params->timer_handle->getHandle()->Instance->CNT = cs_params->timer_handle->getHandle()->Instance->ARR;
+ // remember that this timer has repetition counter - no need to downasmple
+ needs_downsample[_adcToIndex(cs_params->adc_handle)] = 0;
+ }else{
+ if(!use_adc_interrupt){
+ // If the timer has no repetition counter, it needs to use the interrupt to downsample for low side sensing
+ use_adc_interrupt = 1;
+ #ifdef SIMPLEFOC_STM32_DEBUG
+ SIMPLEFOC_DEBUG("STM32-CS: timer has no repetition counter, ADC interrupt has to be used");
+ #endif
+ }
+ }
+ // set the trigger output event
+ LL_TIM_SetTriggerOutput(cs_params->timer_handle->getHandle()->Instance, LL_TIM_TRGO_UPDATE);
+
+ // start the adc
+ if (use_adc_interrupt){
+ // enable interrupt
+ HAL_NVIC_SetPriority(ADC_IRQn, 0, 0);
+ HAL_NVIC_EnableIRQ(ADC_IRQn);
+
+ HAL_ADCEx_InjectedStart_IT(cs_params->adc_handle);
+ }else{
+ HAL_ADCEx_InjectedStart(cs_params->adc_handle);
+ }
+
+ // restart all the timers of the driver
+ _startTimers(driver_params->timers, 6);
+
+ // return the cs parameters
+ // successfully initialized
+ // TODO verify if success in future
+ return _cs_params;
+}
+
+
+// function reading an ADC value and returning the read voltage
+float _readADCVoltageLowSide(const int pin, const void* cs_params){
+ for(int i=0; i < 3; i++){
+ if( pin == ((Stm32CurrentSenseParams*)cs_params)->pins[i]){ // found in the buffer
+ if (use_adc_interrupt){
+ return adc_val[_adcToIndex(((Stm32CurrentSenseParams*)cs_params)->adc_handle)][i] * ((Stm32CurrentSenseParams*)cs_params)->adc_voltage_conv;
+ }else{
+ // an optimized way to go from i to the channel i=0 -> channel 1, i=1 -> channel 2, i=2 -> channel 3
+ uint32_t channel = (i == 0) ? ADC_INJECTED_RANK_1 : (i == 1) ? ADC_INJECTED_RANK_2 : ADC_INJECTED_RANK_3;
+ return HAL_ADCEx_InjectedGetValue(((Stm32CurrentSenseParams*)cs_params)->adc_handle, channel) * ((Stm32CurrentSenseParams*)cs_params)->adc_voltage_conv;
+ }
+ }
+ }
+ return 0;
+}
+
+extern "C" {
+ void HAL_ADCEx_InjectedConvCpltCallback(ADC_HandleTypeDef *AdcHandle){
+ // calculate the instance
+ int adc_index = _adcToIndex(AdcHandle);
+
+ // if the timer han't repetition counter - downsample two times
+ if( needs_downsample[adc_index] && tim_downsample[adc_index]++ > 0) {
+ tim_downsample[adc_index] = 0;
+ return;
+ }
+
+ adc_val[adc_index][0]=HAL_ADCEx_InjectedGetValue(AdcHandle, ADC_INJECTED_RANK_1);
+ adc_val[adc_index][1]=HAL_ADCEx_InjectedGetValue(AdcHandle, ADC_INJECTED_RANK_2);
+ adc_val[adc_index][2]=HAL_ADCEx_InjectedGetValue(AdcHandle, ADC_INJECTED_RANK_3);
+ }
+}
+
+#endif
\ No newline at end of file
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/hardware_specific/stm32/stm32f4/stm32f4_utils.cpp b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/hardware_specific/stm32/stm32f4/stm32f4_utils.cpp
new file mode 100644
index 0000000..20793d8
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/hardware_specific/stm32/stm32f4/stm32f4_utils.cpp
@@ -0,0 +1,193 @@
+#include "stm32f4_utils.h"
+
+#if defined(STM32F4xx)
+
+/* Exported Functions */
+/**
+ * @brief Return ADC HAL channel linked to a PinName
+ * @param pin: PinName
+ * @retval Valid HAL channel
+ */
+uint32_t _getADCChannel(PinName pin)
+{
+ uint32_t function = pinmap_function(pin, PinMap_ADC);
+ uint32_t channel = 0;
+ switch (STM_PIN_CHANNEL(function)) {
+#ifdef ADC_CHANNEL_0
+ case 0:
+ channel = ADC_CHANNEL_0;
+ break;
+#endif
+ case 1:
+ channel = ADC_CHANNEL_1;
+ break;
+ case 2:
+ channel = ADC_CHANNEL_2;
+ break;
+ case 3:
+ channel = ADC_CHANNEL_3;
+ break;
+ case 4:
+ channel = ADC_CHANNEL_4;
+ break;
+ case 5:
+ channel = ADC_CHANNEL_5;
+ break;
+ case 6:
+ channel = ADC_CHANNEL_6;
+ break;
+ case 7:
+ channel = ADC_CHANNEL_7;
+ break;
+ case 8:
+ channel = ADC_CHANNEL_8;
+ break;
+ case 9:
+ channel = ADC_CHANNEL_9;
+ break;
+ case 10:
+ channel = ADC_CHANNEL_10;
+ break;
+ case 11:
+ channel = ADC_CHANNEL_11;
+ break;
+ case 12:
+ channel = ADC_CHANNEL_12;
+ break;
+ case 13:
+ channel = ADC_CHANNEL_13;
+ break;
+ case 14:
+ channel = ADC_CHANNEL_14;
+ break;
+ case 15:
+ channel = ADC_CHANNEL_15;
+ break;
+#ifdef ADC_CHANNEL_16
+ case 16:
+ channel = ADC_CHANNEL_16;
+ break;
+#endif
+ case 17:
+ channel = ADC_CHANNEL_17;
+ break;
+#ifdef ADC_CHANNEL_18
+ case 18:
+ channel = ADC_CHANNEL_18;
+ break;
+#endif
+#ifdef ADC_CHANNEL_19
+ case 19:
+ channel = ADC_CHANNEL_19;
+ break;
+#endif
+#ifdef ADC_CHANNEL_20
+ case 20:
+ channel = ADC_CHANNEL_20;
+ break;
+ case 21:
+ channel = ADC_CHANNEL_21;
+ break;
+ case 22:
+ channel = ADC_CHANNEL_22;
+ break;
+ case 23:
+ channel = ADC_CHANNEL_23;
+ break;
+#ifdef ADC_CHANNEL_24
+ case 24:
+ channel = ADC_CHANNEL_24;
+ break;
+ case 25:
+ channel = ADC_CHANNEL_25;
+ break;
+ case 26:
+ channel = ADC_CHANNEL_26;
+ break;
+#ifdef ADC_CHANNEL_27
+ case 27:
+ channel = ADC_CHANNEL_27;
+ break;
+ case 28:
+ channel = ADC_CHANNEL_28;
+ break;
+ case 29:
+ channel = ADC_CHANNEL_29;
+ break;
+ case 30:
+ channel = ADC_CHANNEL_30;
+ break;
+ case 31:
+ channel = ADC_CHANNEL_31;
+ break;
+#endif
+#endif
+#endif
+ default:
+ _Error_Handler("ADC: Unknown adc channel", (int)(STM_PIN_CHANNEL(function)));
+ break;
+ }
+ return channel;
+}
+
+
+// timer to injected TRGO
+// https://github.com/stm32duino/Arduino_Core_STM32/blob/e156c32db24d69cb4818208ccc28894e2f427cfa/system/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_adc_ex.h#L179
+uint32_t _timerToInjectedTRGO(HardwareTimer* timer){
+ if(timer->getHandle()->Instance == TIM1)
+ return ADC_EXTERNALTRIGINJECCONV_T1_TRGO;
+#ifdef TIM2 // if defined timer 2
+ else if(timer->getHandle()->Instance == TIM2)
+ return ADC_EXTERNALTRIGINJECCONV_T2_TRGO;
+#endif
+#ifdef TIM4 // if defined timer 4
+ else if(timer->getHandle()->Instance == TIM4)
+ return ADC_EXTERNALTRIGINJECCONV_T4_TRGO;
+#endif
+#ifdef TIM5 // if defined timer 5
+ else if(timer->getHandle()->Instance == TIM5)
+ return ADC_EXTERNALTRIGINJECCONV_T5_TRGO;
+#endif
+ else
+ return _TRGO_NOT_AVAILABLE;
+}
+
+// timer to regular TRGO
+// https://github.com/stm32duino/Arduino_Core_STM32/blob/e156c32db24d69cb4818208ccc28894e2f427cfa/system/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_adc.h#L331
+uint32_t _timerToRegularTRGO(HardwareTimer* timer){
+ if(timer->getHandle()->Instance == TIM2)
+ return ADC_EXTERNALTRIGCONV_T2_TRGO;
+#ifdef TIM3 // if defined timer 3
+ else if(timer->getHandle()->Instance == TIM3)
+ return ADC_EXTERNALTRIGCONV_T3_TRGO;
+#endif
+#ifdef TIM8 // if defined timer 8
+ else if(timer->getHandle()->Instance == TIM8)
+ return ADC_EXTERNALTRIGCONV_T8_TRGO;
+#endif
+ else
+ return _TRGO_NOT_AVAILABLE;
+}
+
+
+int _adcToIndex(ADC_TypeDef *AdcHandle){
+ if(AdcHandle == ADC1) return 0;
+#ifdef ADC2 // if ADC2 exists
+ else if(AdcHandle == ADC2) return 1;
+#endif
+#ifdef ADC3 // if ADC3 exists
+ else if(AdcHandle == ADC3) return 2;
+#endif
+#ifdef ADC4 // if ADC4 exists
+ else if(AdcHandle == ADC4) return 3;
+#endif
+#ifdef ADC5 // if ADC5 exists
+ else if(AdcHandle == ADC5) return 4;
+#endif
+ return 0;
+}
+int _adcToIndex(ADC_HandleTypeDef *AdcHandle){
+ return _adcToIndex(AdcHandle->Instance);
+}
+
+#endif
\ No newline at end of file
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/hardware_specific/stm32/stm32f4/stm32f4_utils.h b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/hardware_specific/stm32/stm32f4/stm32f4_utils.h
new file mode 100644
index 0000000..b4549ba
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/hardware_specific/stm32/stm32f4/stm32f4_utils.h
@@ -0,0 +1,34 @@
+
+#ifndef STM32F4_UTILS_HAL
+#define STM32F4_UTILS_HAL
+
+#include "Arduino.h"
+
+#if defined(STM32F4xx)
+
+#define _TRGO_NOT_AVAILABLE 12345
+
+
+/* Exported Functions */
+/**
+ * @brief Return ADC HAL channel linked to a PinName
+ * @param pin: PinName
+ * @retval Valid HAL channel
+ */
+uint32_t _getADCChannel(PinName pin);
+
+// timer to injected TRGO
+// https://github.com/stm32duino/Arduino_Core_STM32/blob/e156c32db24d69cb4818208ccc28894e2f427cfa/system/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_adc_ex.h#L179
+uint32_t _timerToInjectedTRGO(HardwareTimer* timer);
+
+// timer to regular TRGO
+// https://github.com/stm32duino/Arduino_Core_STM32/blob/e156c32db24d69cb4818208ccc28894e2f427cfa/system/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_adc.h#L331
+uint32_t _timerToRegularTRGO(HardwareTimer* timer);
+
+// function returning index of the ADC instance
+int _adcToIndex(ADC_HandleTypeDef *AdcHandle);
+int _adcToIndex(ADC_TypeDef *AdcHandle);
+
+#endif
+
+#endif
\ No newline at end of file
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/hardware_specific/stm32/stm32f7/stm32f7_hal.cpp b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/hardware_specific/stm32/stm32f7/stm32f7_hal.cpp
new file mode 100644
index 0000000..d4cffec
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/hardware_specific/stm32/stm32f7/stm32f7_hal.cpp
@@ -0,0 +1,185 @@
+#include "stm32f7_hal.h"
+
+#if defined(STM32F7xx)
+
+//#define SIMPLEFOC_STM32_DEBUG
+
+#include "../../../../communication/SimpleFOCDebug.h"
+#define _TRGO_NOT_AVAILABLE 12345
+
+ADC_HandleTypeDef hadc;
+
+int _adc_init(Stm32CurrentSenseParams* cs_params, const STM32DriverParams* driver_params)
+{
+ ADC_InjectionConfTypeDef sConfigInjected;
+
+ // check if all pins belong to the same ADC
+ ADC_TypeDef* adc_pin1 = (ADC_TypeDef*)pinmap_peripheral(analogInputToPinName(cs_params->pins[0]), PinMap_ADC);
+ ADC_TypeDef* adc_pin2 = (ADC_TypeDef*)pinmap_peripheral(analogInputToPinName(cs_params->pins[1]), PinMap_ADC);
+ ADC_TypeDef* adc_pin3 = _isset(cs_params->pins[2]) ? (ADC_TypeDef*)pinmap_peripheral(analogInputToPinName(cs_params->pins[2]), PinMap_ADC) : nullptr;
+ if ( (adc_pin1 != adc_pin2) || ( (adc_pin3) && (adc_pin1 != adc_pin3) )){
+#ifdef SIMPLEFOC_STM32_DEBUG
+ SIMPLEFOC_DEBUG("STM32-CS: ERR: Analog pins dont belong to the same ADC!");
+#endif
+ return -1;
+ }
+
+
+ /**Configure the global features of the ADC (Clock, Resolution, Data Alignment and number of conversion)
+ */
+ hadc.Instance = (ADC_TypeDef *)pinmap_peripheral(analogInputToPinName(cs_params->pins[0]), PinMap_ADC);
+
+ if(hadc.Instance == ADC1) __HAL_RCC_ADC1_CLK_ENABLE();
+#ifdef ADC2 // if defined ADC2
+ else if(hadc.Instance == ADC2) __HAL_RCC_ADC2_CLK_ENABLE();
+#endif
+#ifdef ADC3 // if defined ADC3
+ else if(hadc.Instance == ADC3) __HAL_RCC_ADC3_CLK_ENABLE();
+#endif
+ else{
+#ifdef SIMPLEFOC_STM32_DEBUG
+ SIMPLEFOC_DEBUG("STM32-CS: ERR: Pin does not belong to any ADC!");
+#endif
+ return -1; // error not a valid ADC instance
+ }
+
+#ifdef SIMPLEFOC_STM32_DEBUG
+ SIMPLEFOC_DEBUG("STM32-CS: Using ADC: ", _adcToIndex(&hadc)+1);
+#endif
+
+ hadc.Init.ClockPrescaler = ADC_CLOCK_SYNC_PCLK_DIV2;
+ hadc.Init.Resolution = ADC_RESOLUTION_12B;
+ hadc.Init.ScanConvMode = ENABLE;
+ hadc.Init.ContinuousConvMode = DISABLE;
+ hadc.Init.DiscontinuousConvMode = DISABLE;
+ hadc.Init.ExternalTrigConvEdge = ADC_EXTERNALTRIGCONVEDGE_NONE;
+ hadc.Init.ExternalTrigConv = ADC_SOFTWARE_START; // for now
+ hadc.Init.DataAlign = ADC_DATAALIGN_RIGHT;
+ hadc.Init.NbrOfConversion = 1;
+ hadc.Init.DMAContinuousRequests = DISABLE;
+ hadc.Init.EOCSelection = ADC_EOC_SINGLE_CONV;
+ if ( HAL_ADC_Init(&hadc) != HAL_OK){
+#ifdef SIMPLEFOC_STM32_DEBUG
+ SIMPLEFOC_DEBUG("STM32-CS: ERR: cannot init ADC!");
+#endif
+ return -1;
+ }
+
+ /**Configures for the selected ADC injected channel its corresponding rank in the sequencer and its sample time
+ */
+ sConfigInjected.InjectedNbrOfConversion = _isset(cs_params->pins[2]) ? 3 : 2;
+ sConfigInjected.InjectedSamplingTime = ADC_SAMPLETIME_3CYCLES;
+ sConfigInjected.ExternalTrigInjecConvEdge = ADC_EXTERNALTRIGINJECCONVEDGE_RISINGFALLING;
+ sConfigInjected.AutoInjectedConv = DISABLE;
+ sConfigInjected.InjectedDiscontinuousConvMode = DISABLE;
+ sConfigInjected.InjectedOffset = 0;
+
+ // automating TRGO flag finding - hardware specific
+ uint8_t tim_num = 0;
+ for (size_t i=0; i<6; i++) {
+ HardwareTimer *timer_to_check = driver_params->timers[tim_num++];
+ TIM_TypeDef *instance_to_check = timer_to_check->getHandle()->Instance;
+
+ // bool TRGO_already_configured = instance_to_check->CR2 & LL_TIM_TRGO_UPDATE;
+ // if(TRGO_already_configured) continue;
+
+ uint32_t trigger_flag = _timerToInjectedTRGO(timer_to_check);
+ if(trigger_flag == _TRGO_NOT_AVAILABLE) continue; // timer does not have valid trgo for injected channels
+
+ // if the code comes here, it has found the timer available
+ // timer does have trgo flag for injected channels
+ sConfigInjected.ExternalTrigInjecConv = trigger_flag;
+
+ // this will be the timer with which the ADC will sync
+ cs_params->timer_handle = timer_to_check;
+ if (!IS_TIM_REPETITION_COUNTER_INSTANCE(instance_to_check)) {
+ // workaround for errata 2.2.1 in ES0290 Rev 7
+ // https://www.st.com/resource/en/errata_sheet/es0290-stm32f74xxx-and-stm32f75xxx-device-limitations-stmicroelectronics.pdf
+ __HAL_RCC_DAC_CLK_ENABLE();
+ }
+ // done
+ break;
+ }
+ if( cs_params->timer_handle == NP ){
+ // not possible to use these timers for low-side current sense
+ #ifdef SIMPLEFOC_STM32_DEBUG
+ SIMPLEFOC_DEBUG("STM32-CS: ERR: cannot sync any timer to injected channels!");
+ #endif
+ return -1;
+ }
+ // display which timer is being used
+ #ifdef SIMPLEFOC_STM32_DEBUG
+ // it would be better to use the getTimerNumber from driver
+ SIMPLEFOC_DEBUG("STM32-CS: injected trigger for timer index: ", get_timer_index(cs_params->timer_handle->getHandle()->Instance) + 1);
+ #endif
+
+
+ // first channel
+ sConfigInjected.InjectedRank = ADC_INJECTED_RANK_1;
+ sConfigInjected.InjectedChannel = _getADCChannel(analogInputToPinName(cs_params->pins[0]));
+ if (HAL_ADCEx_InjectedConfigChannel(&hadc, &sConfigInjected) != HAL_OK){
+#ifdef SIMPLEFOC_STM32_DEBUG
+ SIMPLEFOC_DEBUG("STM32-CS: ERR: cannot init injected channel: ", (int)_getADCChannel(analogInputToPinName(cs_params->pins[0])) );
+#endif
+ return -1;
+ }
+
+ // second channel
+ sConfigInjected.InjectedRank = ADC_INJECTED_RANK_2;
+ sConfigInjected.InjectedChannel = _getADCChannel(analogInputToPinName(cs_params->pins[1]));
+ if (HAL_ADCEx_InjectedConfigChannel(&hadc, &sConfigInjected) != HAL_OK){
+#ifdef SIMPLEFOC_STM32_DEBUG
+ SIMPLEFOC_DEBUG("STM32-CS: ERR: cannot init injected channel: ", (int)_getADCChannel(analogInputToPinName(cs_params->pins[1]))) ;
+#endif
+ return -1;
+ }
+
+ // third channel - if exists
+ if(_isset(cs_params->pins[2])){
+ sConfigInjected.InjectedRank = ADC_INJECTED_RANK_3;
+ sConfigInjected.InjectedChannel = _getADCChannel(analogInputToPinName(cs_params->pins[2]));
+ if (HAL_ADCEx_InjectedConfigChannel(&hadc, &sConfigInjected) != HAL_OK){
+#ifdef SIMPLEFOC_STM32_DEBUG
+ SIMPLEFOC_DEBUG("STM32-CS: ERR: cannot init injected channel: ", (int)_getADCChannel(analogInputToPinName(cs_params->pins[2]))) ;
+#endif
+ return -1;
+ }
+ }
+
+ #ifdef SIMPLEFOC_STM32_ADC_INTERRUPT
+ // enable interrupt
+ HAL_NVIC_SetPriority(ADC_IRQn, 0, 0);
+ HAL_NVIC_EnableIRQ(ADC_IRQn);
+ #endif
+
+ cs_params->adc_handle = &hadc;
+ return 0;
+}
+
+void _adc_gpio_init(Stm32CurrentSenseParams* cs_params, const int pinA, const int pinB, const int pinC)
+{
+ uint8_t cnt = 0;
+ if(_isset(pinA)){
+ pinmap_pinout(analogInputToPinName(pinA), PinMap_ADC);
+ cs_params->pins[cnt++] = pinA;
+ }
+ if(_isset(pinB)){
+ pinmap_pinout(analogInputToPinName(pinB), PinMap_ADC);
+ cs_params->pins[cnt++] = pinB;
+ }
+ if(_isset(pinC)){
+ pinmap_pinout(analogInputToPinName(pinC), PinMap_ADC);
+ cs_params->pins[cnt] = pinC;
+ }
+}
+
+#ifdef SIMPLEFOC_STM32_ADC_INTERRUPT
+extern "C" {
+ void ADC_IRQHandler(void)
+ {
+ HAL_ADC_IRQHandler(&hadc);
+ }
+}
+#endif
+
+#endif
\ No newline at end of file
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/hardware_specific/stm32/stm32f7/stm32f7_hal.h b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/hardware_specific/stm32/stm32f7/stm32f7_hal.h
new file mode 100644
index 0000000..0a3614b
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/hardware_specific/stm32/stm32f7/stm32f7_hal.h
@@ -0,0 +1,15 @@
+#pragma once
+
+#include "Arduino.h"
+
+#if defined(STM32F7xx)
+#include "stm32f7xx_hal.h"
+#include "../../../../common/foc_utils.h"
+#include "../../../../drivers/hardware_specific/stm32/stm32_mcu.h"
+#include "../stm32_mcu.h"
+#include "stm32f7_utils.h"
+
+int _adc_init(Stm32CurrentSenseParams* cs_params, const STM32DriverParams* driver_params);
+void _adc_gpio_init(Stm32CurrentSenseParams* cs_params, const int pinA, const int pinB, const int pinC);
+
+#endif
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/hardware_specific/stm32/stm32f7/stm32f7_mcu.cpp b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/hardware_specific/stm32/stm32f7/stm32f7_mcu.cpp
new file mode 100644
index 0000000..f5ca70f
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/hardware_specific/stm32/stm32f7/stm32f7_mcu.cpp
@@ -0,0 +1,116 @@
+#include "../../../hardware_api.h"
+
+#if defined(STM32F7xx)
+#include "../../../../common/foc_utils.h"
+#include "../../../../drivers/hardware_api.h"
+#include "../../../../drivers/hardware_specific/stm32/stm32_mcu.h"
+#include "../../../hardware_api.h"
+#include "../stm32_mcu.h"
+#include "stm32f7_hal.h"
+#include "stm32f7_utils.h"
+#include "Arduino.h"
+
+
+#define _ADC_VOLTAGE 3.3f
+#define _ADC_RESOLUTION 4096.0f
+
+
+// array of values of 4 injected channels per adc instance (3)
+uint32_t adc_val[3][4]={0};
+// does adc interrupt need a downsample - per adc (3)
+bool needs_downsample[3] = {1};
+// downsampling variable - per adc (3)
+uint8_t tim_downsample[3] = {1};
+
+void* _configureADCLowSide(const void* driver_params, const int pinA, const int pinB, const int pinC){
+
+ Stm32CurrentSenseParams* cs_params= new Stm32CurrentSenseParams {
+ .pins={(int)NOT_SET,(int)NOT_SET,(int)NOT_SET},
+ .adc_voltage_conv = (_ADC_VOLTAGE) / (_ADC_RESOLUTION)
+ };
+ _adc_gpio_init(cs_params, pinA,pinB,pinC);
+ if(_adc_init(cs_params, (STM32DriverParams*)driver_params) != 0) return SIMPLEFOC_CURRENT_SENSE_INIT_FAILED;
+ return cs_params;
+}
+
+
+void* _driverSyncLowSide(void* _driver_params, void* _cs_params){
+ STM32DriverParams* driver_params = (STM32DriverParams*)_driver_params;
+ Stm32CurrentSenseParams* cs_params = (Stm32CurrentSenseParams*)_cs_params;
+
+ // if compatible timer has not been found
+ if (cs_params->timer_handle == NULL) return SIMPLEFOC_CURRENT_SENSE_INIT_FAILED;
+
+ // stop all the timers for the driver
+ _stopTimers(driver_params->timers, 6);
+
+ // if timer has repetition counter - it will downsample using it
+ // and it does not need the software downsample
+ if( IS_TIM_REPETITION_COUNTER_INSTANCE(cs_params->timer_handle->getHandle()->Instance) ){
+ // adjust the initial timer state such that the trigger
+ // - for DMA transfer aligns with the pwm peaks instead of throughs.
+ // - for interrupt based ADC transfer
+ // - only necessary for the timers that have repetition counters
+
+ cs_params->timer_handle->getHandle()->Instance->CR1 |= TIM_CR1_DIR;
+ cs_params->timer_handle->getHandle()->Instance->CNT = cs_params->timer_handle->getHandle()->Instance->ARR;
+ // remember that this timer has repetition counter - no need to downasmple
+ needs_downsample[_adcToIndex(cs_params->adc_handle)] = 0;
+ }
+ // set the trigger output event
+ LL_TIM_SetTriggerOutput(cs_params->timer_handle->getHandle()->Instance, LL_TIM_TRGO_UPDATE);
+
+ // start the adc
+ #ifdef SIMPLEFOC_STM32_ADC_INTERRUPT
+ HAL_ADCEx_InjectedStart_IT(cs_params->adc_handle);
+ #else
+ HAL_ADCEx_InjectedStart(cs_params->adc_handle);
+ #endif
+
+ // restart all the timers of the driver
+ _startTimers(driver_params->timers, 6);
+
+ // return the cs parameters
+ // successfully initialized
+ // TODO verify if success in future
+ return _cs_params;
+}
+
+
+// function reading an ADC value and returning the read voltage
+float _readADCVoltageLowSide(const int pin, const void* cs_params){
+ for(int i=0; i < 3; i++){
+ if( pin == ((Stm32CurrentSenseParams*)cs_params)->pins[i]){ // found in the buffer
+ #ifdef SIMPLEFOC_STM32_ADC_INTERRUPT
+ return adc_val[_adcToIndex(((Stm32CurrentSenseParams*)cs_params)->adc_handle)][i] * ((Stm32CurrentSenseParams*)cs_params)->adc_voltage_conv;
+ #else
+ // an optimized way to go from i to the channel i=0 -> channel 1, i=1 -> channel 2, i=2 -> channel 3
+ uint32_t channel = (i == 0) ? ADC_INJECTED_RANK_1 : (i == 1) ? ADC_INJECTED_RANK_2 : ADC_INJECTED_RANK_3;
+ return HAL_ADCEx_InjectedGetValue(((Stm32CurrentSenseParams*)cs_params)->adc_handle, channel) * ((Stm32CurrentSenseParams*)cs_params)->adc_voltage_conv;
+ #endif
+ }
+ }
+ return 0;
+}
+
+#ifdef SIMPLEFOC_STM32_ADC_INTERRUPT
+extern "C" {
+ void HAL_ADCEx_InjectedConvCpltCallback(ADC_HandleTypeDef *AdcHandle){
+
+ // calculate the instance
+ int adc_index = _adcToIndex(AdcHandle);
+
+ // if the timer han't repetition counter - downsample two times
+ if( needs_downsample[adc_index] && tim_downsample[adc_index]++ > 0) {
+ tim_downsample[adc_index] = 0;
+ return;
+ }
+
+ adc_val[adc_index][0]=HAL_ADCEx_InjectedGetValue(AdcHandle, ADC_INJECTED_RANK_1);
+ adc_val[adc_index][1]=HAL_ADCEx_InjectedGetValue(AdcHandle, ADC_INJECTED_RANK_2);
+ adc_val[adc_index][2]=HAL_ADCEx_InjectedGetValue(AdcHandle, ADC_INJECTED_RANK_3);
+ }
+}
+#endif
+
+#endif
\ No newline at end of file
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/hardware_specific/stm32/stm32f7/stm32f7_utils.cpp b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/hardware_specific/stm32/stm32f7/stm32f7_utils.cpp
new file mode 100644
index 0000000..d5f8c6b
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/hardware_specific/stm32/stm32f7/stm32f7_utils.cpp
@@ -0,0 +1,255 @@
+#include "stm32f7_utils.h"
+
+#if defined(STM32F7xx)
+
+/* Exported Functions */
+
+
+PinName analog_to_pin(uint32_t pin) {
+ PinName pin_name = analogInputToPinName(pin);
+ if (pin_name == NC) {
+ return (PinName) pin;
+ }
+ return pin_name;
+}
+
+
+/**
+ * @brief Return ADC HAL channel linked to a PinName
+ * @param pin: PinName
+ * @retval Valid HAL channel
+ */
+uint32_t _getADCChannel(PinName pin)
+{
+ uint32_t function = pinmap_function(pin, PinMap_ADC);
+ uint32_t channel = 0;
+ switch (STM_PIN_CHANNEL(function)) {
+#ifdef ADC_CHANNEL_0
+ case 0:
+ channel = ADC_CHANNEL_0;
+ break;
+#endif
+ case 1:
+ channel = ADC_CHANNEL_1;
+ break;
+ case 2:
+ channel = ADC_CHANNEL_2;
+ break;
+ case 3:
+ channel = ADC_CHANNEL_3;
+ break;
+ case 4:
+ channel = ADC_CHANNEL_4;
+ break;
+ case 5:
+ channel = ADC_CHANNEL_5;
+ break;
+ case 6:
+ channel = ADC_CHANNEL_6;
+ break;
+ case 7:
+ channel = ADC_CHANNEL_7;
+ break;
+ case 8:
+ channel = ADC_CHANNEL_8;
+ break;
+ case 9:
+ channel = ADC_CHANNEL_9;
+ break;
+ case 10:
+ channel = ADC_CHANNEL_10;
+ break;
+ case 11:
+ channel = ADC_CHANNEL_11;
+ break;
+ case 12:
+ channel = ADC_CHANNEL_12;
+ break;
+ case 13:
+ channel = ADC_CHANNEL_13;
+ break;
+ case 14:
+ channel = ADC_CHANNEL_14;
+ break;
+ case 15:
+ channel = ADC_CHANNEL_15;
+ break;
+#ifdef ADC_CHANNEL_16
+ case 16:
+ channel = ADC_CHANNEL_16;
+ break;
+#endif
+ case 17:
+ channel = ADC_CHANNEL_17;
+ break;
+#ifdef ADC_CHANNEL_18
+ case 18:
+ channel = ADC_CHANNEL_18;
+ break;
+#endif
+#ifdef ADC_CHANNEL_19
+ case 19:
+ channel = ADC_CHANNEL_19;
+ break;
+#endif
+#ifdef ADC_CHANNEL_20
+ case 20:
+ channel = ADC_CHANNEL_20;
+ break;
+ case 21:
+ channel = ADC_CHANNEL_21;
+ break;
+ case 22:
+ channel = ADC_CHANNEL_22;
+ break;
+ case 23:
+ channel = ADC_CHANNEL_23;
+ break;
+#ifdef ADC_CHANNEL_24
+ case 24:
+ channel = ADC_CHANNEL_24;
+ break;
+ case 25:
+ channel = ADC_CHANNEL_25;
+ break;
+ case 26:
+ channel = ADC_CHANNEL_26;
+ break;
+#ifdef ADC_CHANNEL_27
+ case 27:
+ channel = ADC_CHANNEL_27;
+ break;
+ case 28:
+ channel = ADC_CHANNEL_28;
+ break;
+ case 29:
+ channel = ADC_CHANNEL_29;
+ break;
+ case 30:
+ channel = ADC_CHANNEL_30;
+ break;
+ case 31:
+ channel = ADC_CHANNEL_31;
+ break;
+#endif
+#endif
+#endif
+ default:
+ _Error_Handler("ADC: Unknown adc channel", (int)(STM_PIN_CHANNEL(function)));
+ break;
+ }
+ return channel;
+}
+/*
+TIM1
+TIM2
+TIM3
+TIM4
+TIM5
+TIM6
+TIM7
+TIM12
+TIM13
+TIM14
+
+ADC_EXTERNALTRIGINJECCONV_T1_TRGO
+ADC_EXTERNALTRIGINJECCONV_T2_TRGO
+ADC_EXTERNALTRIGINJECCONV_T4_TRGO
+
+ADC_EXTERNALTRIGINJECCONV_T1_TRGO2
+ADC_EXTERNALTRIGINJECCONV_T8_TRGO2
+ADC_EXTERNALTRIGINJECCONV_T5_TRGO
+ADC_EXTERNALTRIGINJECCONV_T6_TRGO
+*/
+// timer to injected TRGO
+// https://github.com/stm32duino/Arduino_Core_STM32/blob/e156c32db24d69cb4818208ccc28894e2f427cfa/system/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_adc_ex.h#L179
+uint32_t _timerToInjectedTRGO(HardwareTimer* timer){
+
+ if(timer->getHandle()->Instance == TIM1)
+ return ADC_EXTERNALTRIGINJECCONV_T1_TRGO;
+#ifdef TIM2 // if defined timer 2
+ else if(timer->getHandle()->Instance == TIM2)
+ return ADC_EXTERNALTRIGINJECCONV_T2_TRGO;
+#endif
+#ifdef TIM4 // if defined timer 4
+ else if(timer->getHandle()->Instance == TIM4)
+ return ADC_EXTERNALTRIGINJECCONV_T4_TRGO;
+#endif
+#ifdef TIM5 // if defined timer 5
+ else if(timer->getHandle()->Instance == TIM5)
+ return ADC_EXTERNALTRIGINJECCONV_T5_TRGO;
+#endif
+#ifdef TIM6 // if defined timer 6
+ else if(timer->getHandle()->Instance == TIM6)
+ return ADC_EXTERNALTRIGINJECCONV_T6_TRGO;
+#endif
+#ifdef TIM8 // if defined timer 8
+ else if(timer->getHandle()->Instance == TIM8)
+ return ADC_EXTERNALTRIGINJECCONV_T8_TRGO;
+#endif
+ else
+ return _TRGO_NOT_AVAILABLE;
+}
+/*
+
+ADC_EXTERNALTRIGCONV_T5_TRGO
+ADC_EXTERNALTRIGCONV_T8_TRGO
+ADC_EXTERNALTRIGCONV_T8_TRGO2
+ADC_EXTERNALTRIGCONV_T1_TRGO
+ADC_EXTERNALTRIGCONV_T1_TRGO2
+ADC_EXTERNALTRIGCONV_T2_TRGO
+ADC_EXTERNALTRIGCONV_T4_TRGO
+ADC_EXTERNALTRIGCONV_T6_TRGO
+*/
+
+// timer to regular TRGO
+// https://github.com/stm32duino/Arduino_Core_STM32/blob/e156c32db24d69cb4818208ccc28894e2f427cfa/system/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_adc.h#L331
+uint32_t _timerToRegularTRGO(HardwareTimer* timer){
+ if(timer->getHandle()->Instance == TIM1)
+ return ADC_EXTERNALTRIGCONV_T1_TRGO;
+#ifdef TIM2 // if defined timer 2
+ else if(timer->getHandle()->Instance == TIM2)
+ return ADC_EXTERNALTRIGCONV_T2_TRGO;
+#endif
+#ifdef TIM4 // if defined timer 4
+ else if(timer->getHandle()->Instance == TIM4)
+ return ADC_EXTERNALTRIGCONV_T4_TRGO;
+#endif
+#ifdef TIM5 // if defined timer 5
+ else if(timer->getHandle()->Instance == TIM5)
+ return ADC_EXTERNALTRIGCONV_T5_TRGO;
+#endif
+#ifdef TIM6 // if defined timer 6
+ else if(timer->getHandle()->Instance == TIM6)
+ return ADC_EXTERNALTRIGCONV_T6_TRGO;
+#endif
+#ifdef TIM8 // if defined timer 8
+ else if(timer->getHandle()->Instance == TIM8)
+ return ADC_EXTERNALTRIGCONV_T8_TRGO;
+#endif
+ else
+ return _TRGO_NOT_AVAILABLE;
+}
+
+
+int _adcToIndex(ADC_TypeDef *AdcHandle){
+ if(AdcHandle == ADC1) return 0;
+#ifdef ADC2 // if ADC2 exists
+ else if(AdcHandle == ADC2) return 1;
+#endif
+#ifdef ADC3 // if ADC3 exists
+ else if(AdcHandle == ADC3) return 2;
+#endif
+#ifdef ADC4 // if ADC4 exists
+ else if(AdcHandle == ADC4) return 3;
+#endif
+#ifdef ADC5 // if ADC5 exists
+ else if(AdcHandle == ADC5) return 4;
+#endif
+ return 0;
+}
+int _adcToIndex(ADC_HandleTypeDef *AdcHandle){
+ return _adcToIndex(AdcHandle->Instance);
+}
+
+#endif
\ No newline at end of file
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/hardware_specific/stm32/stm32f7/stm32f7_utils.h b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/hardware_specific/stm32/stm32f7/stm32f7_utils.h
new file mode 100644
index 0000000..017ff46
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/hardware_specific/stm32/stm32f7/stm32f7_utils.h
@@ -0,0 +1,30 @@
+#pragma once
+
+#include "Arduino.h"
+
+#if defined(STM32F7xx)
+
+#define _TRGO_NOT_AVAILABLE 12345
+
+
+/* Exported Functions */
+/**
+ * @brief Return ADC HAL channel linked to a PinName
+ * @param pin: PinName
+ * @retval Valid HAL channel
+ */
+uint32_t _getADCChannel(PinName pin);
+
+// timer to injected TRGO
+// https://github.com/stm32duino/Arduino_Core_STM32/blob/e156c32db24d69cb4818208ccc28894e2f427cfa/system/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_adc_ex.h#L179
+uint32_t _timerToInjectedTRGO(HardwareTimer* timer);
+
+// timer to regular TRGO
+// https://github.com/stm32duino/Arduino_Core_STM32/blob/e156c32db24d69cb4818208ccc28894e2f427cfa/system/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_adc.h#L331
+uint32_t _timerToRegularTRGO(HardwareTimer* timer);
+
+// function returning index of the ADC instance
+int _adcToIndex(ADC_HandleTypeDef *AdcHandle);
+int _adcToIndex(ADC_TypeDef *AdcHandle);
+
+#endif
\ No newline at end of file
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/hardware_specific/stm32/stm32g4/stm32g4_hal.cpp b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/hardware_specific/stm32/stm32g4/stm32g4_hal.cpp
new file mode 100644
index 0000000..fd1090a
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/hardware_specific/stm32/stm32g4/stm32g4_hal.cpp
@@ -0,0 +1,231 @@
+#include "stm32g4_hal.h"
+
+#if defined(STM32G4xx) && !defined(ARDUINO_B_G431B_ESC1)
+
+#include "../../../../communication/SimpleFOCDebug.h"
+
+#define SIMPLEFOC_STM32_DEBUG
+
+ADC_HandleTypeDef hadc;
+
+int _adc_init(Stm32CurrentSenseParams* cs_params, const STM32DriverParams* driver_params)
+{
+ ADC_InjectionConfTypeDef sConfigInjected;
+
+ // check if all pins belong to the same ADC
+ ADC_TypeDef* adc_pin1 = (ADC_TypeDef*)pinmap_peripheral(analogInputToPinName(cs_params->pins[0]), PinMap_ADC);
+ ADC_TypeDef* adc_pin2 = (ADC_TypeDef*)pinmap_peripheral(analogInputToPinName(cs_params->pins[1]), PinMap_ADC);
+ ADC_TypeDef* adc_pin3 = _isset(cs_params->pins[2]) ? (ADC_TypeDef*)pinmap_peripheral(analogInputToPinName(cs_params->pins[2]), PinMap_ADC) : nullptr;
+ if ( (adc_pin1 != adc_pin2) || ( (adc_pin3) && (adc_pin1 != adc_pin3) )){
+#ifdef SIMPLEFOC_STM32_DEBUG
+ SIMPLEFOC_DEBUG("STM32-CS: ERR: Analog pins dont belong to the same ADC!");
+#endif
+ return -1;
+ }
+
+
+ /**Configure the global features of the ADC (Clock, Resolution, Data Alignment and number of conversion)
+ */
+ hadc.Instance = (ADC_TypeDef *)pinmap_peripheral(analogInputToPinName(cs_params->pins[0]), PinMap_ADC);
+
+ if(hadc.Instance == ADC1) {
+#ifdef __HAL_RCC_ADC1_CLK_ENABLE
+ __HAL_RCC_ADC1_CLK_ENABLE();
+#endif
+#ifdef __HAL_RCC_ADC12_CLK_ENABLE
+ __HAL_RCC_ADC12_CLK_ENABLE();
+#endif
+ }
+#ifdef ADC2
+ else if (hadc.Instance == ADC2) {
+#ifdef __HAL_RCC_ADC2_CLK_ENABLE
+ __HAL_RCC_ADC2_CLK_ENABLE();
+#endif
+#ifdef __HAL_RCC_ADC12_CLK_ENABLE
+ __HAL_RCC_ADC12_CLK_ENABLE();
+#endif
+ }
+#endif
+#ifdef ADC3
+ else if (hadc.Instance == ADC3) {
+#ifdef __HAL_RCC_ADC3_CLK_ENABLE
+ __HAL_RCC_ADC3_CLK_ENABLE();
+#endif
+#ifdef __HAL_RCC_ADC34_CLK_ENABLE
+ __HAL_RCC_ADC34_CLK_ENABLE();
+#endif
+#if defined(ADC345_COMMON)
+ __HAL_RCC_ADC345_CLK_ENABLE();
+#endif
+ }
+#endif
+#ifdef ADC4
+ else if (hadc.Instance == ADC4) {
+#ifdef __HAL_RCC_ADC4_CLK_ENABLE
+ __HAL_RCC_ADC4_CLK_ENABLE();
+#endif
+#ifdef __HAL_RCC_ADC34_CLK_ENABLE
+ __HAL_RCC_ADC34_CLK_ENABLE();
+#endif
+#if defined(ADC345_COMMON)
+ __HAL_RCC_ADC345_CLK_ENABLE();
+#endif
+ }
+#endif
+#ifdef ADC5
+ else if (hadc.Instance == ADC5) {
+#if defined(ADC345_COMMON)
+ __HAL_RCC_ADC345_CLK_ENABLE();
+#endif
+ }
+#endif
+ else{
+#ifdef SIMPLEFOC_STM32_DEBUG
+ SIMPLEFOC_DEBUG("STM32-CS: ERR: Pin does not belong to any ADC!");
+#endif
+ return -1; // error not a valid ADC instance
+ }
+
+#ifdef SIMPLEFOC_STM32_DEBUG
+ SIMPLEFOC_DEBUG("STM32-CS: Using ADC: ", _adcToIndex(&hadc)+1);
+#endif
+
+ hadc.Init.ClockPrescaler = ADC_CLOCK_SYNC_PCLK_DIV4;
+ hadc.Init.Resolution = ADC_RESOLUTION_12B;
+ hadc.Init.ScanConvMode = ADC_SCAN_ENABLE;
+ hadc.Init.ContinuousConvMode = DISABLE;
+ hadc.Init.LowPowerAutoWait = DISABLE;
+ hadc.Init.GainCompensation = 0;
+ hadc.Init.DiscontinuousConvMode = DISABLE;
+ hadc.Init.ExternalTrigConvEdge = ADC_EXTERNALTRIGCONVEDGE_NONE;
+ hadc.Init.ExternalTrigConv = ADC_SOFTWARE_START; // for now
+ hadc.Init.DataAlign = ADC_DATAALIGN_RIGHT;
+ hadc.Init.NbrOfConversion = 1;
+ hadc.Init.DMAContinuousRequests = DISABLE;
+ hadc.Init.EOCSelection = ADC_EOC_SINGLE_CONV;
+ hadc.Init.Overrun = ADC_OVR_DATA_PRESERVED;
+ if ( HAL_ADC_Init(&hadc) != HAL_OK){
+#ifdef SIMPLEFOC_STM32_DEBUG
+ SIMPLEFOC_DEBUG("STM32-CS: ERR: cannot init ADC!");
+#endif
+ return -1;
+ }
+
+ /**Configures for the selected ADC injected channel its corresponding rank in the sequencer and its sample time
+ */
+ sConfigInjected.InjectedNbrOfConversion = _isset(cs_params->pins[2]) ? 3 : 2;
+ sConfigInjected.InjectedSamplingTime = ADC_SAMPLETIME_2CYCLES_5;
+ sConfigInjected.ExternalTrigInjecConvEdge = ADC_EXTERNALTRIGINJECCONV_EDGE_RISING;
+ sConfigInjected.AutoInjectedConv = DISABLE;
+ sConfigInjected.InjectedSingleDiff = ADC_SINGLE_ENDED;
+ sConfigInjected.InjectedDiscontinuousConvMode = DISABLE;
+ sConfigInjected.InjectedOffsetNumber = ADC_OFFSET_NONE;
+ sConfigInjected.InjectedOffset = 0;
+ sConfigInjected.InjecOversamplingMode = DISABLE;
+ sConfigInjected.QueueInjectedContext = DISABLE;
+
+ // automating TRGO flag finding - hardware specific
+ uint8_t tim_num = 0;
+ while(driver_params->timers[tim_num] != NP && tim_num < 6){
+ uint32_t trigger_flag = _timerToInjectedTRGO(driver_params->timers[tim_num++]);
+ if(trigger_flag == _TRGO_NOT_AVAILABLE) continue; // timer does not have valid trgo for injected channels
+
+ // if the code comes here, it has found the timer available
+ // timer does have trgo flag for injected channels
+ sConfigInjected.ExternalTrigInjecConv = trigger_flag;
+
+ // this will be the timer with which the ADC will sync
+ cs_params->timer_handle = driver_params->timers[tim_num-1];
+ // done
+ break;
+ }
+ if( cs_params->timer_handle == NP ){
+ // not possible to use these timers for low-side current sense
+#ifdef SIMPLEFOC_STM32_DEBUG
+ SIMPLEFOC_DEBUG("STM32-CS: ERR: cannot sync any timer to injected channels!");
+#endif
+ return -1;
+ }
+
+
+ // first channel
+ sConfigInjected.InjectedRank = ADC_INJECTED_RANK_1;
+ sConfigInjected.InjectedChannel = _getADCChannel(analogInputToPinName(cs_params->pins[0]));
+ if (HAL_ADCEx_InjectedConfigChannel(&hadc, &sConfigInjected) != HAL_OK){
+#ifdef SIMPLEFOC_STM32_DEBUG
+ SIMPLEFOC_DEBUG("STM32-CS: ERR: cannot init injected channel: ", (int)_getADCChannel(analogInputToPinName(cs_params->pins[0])) );
+#endif
+ return -1;
+ }
+
+ // second channel
+ sConfigInjected.InjectedRank = ADC_INJECTED_RANK_2;
+ sConfigInjected.InjectedChannel = _getADCChannel(analogInputToPinName(cs_params->pins[1]));
+ if (HAL_ADCEx_InjectedConfigChannel(&hadc, &sConfigInjected) != HAL_OK){
+#ifdef SIMPLEFOC_STM32_DEBUG
+ SIMPLEFOC_DEBUG("STM32-CS: ERR: cannot init injected channel: ", (int)_getADCChannel(analogInputToPinName(cs_params->pins[1]))) ;
+#endif
+ return -1;
+ }
+
+ // third channel - if exists
+ if(_isset(cs_params->pins[2])){
+ sConfigInjected.InjectedRank = ADC_INJECTED_RANK_3;
+ sConfigInjected.InjectedChannel = _getADCChannel(analogInputToPinName(cs_params->pins[2]));
+ if (HAL_ADCEx_InjectedConfigChannel(&hadc, &sConfigInjected) != HAL_OK){
+#ifdef SIMPLEFOC_STM32_DEBUG
+ SIMPLEFOC_DEBUG("STM32-CS: ERR: cannot init injected channel: ", (int)_getADCChannel(analogInputToPinName(cs_params->pins[2]))) ;
+#endif
+ return -1;
+ }
+ }
+
+ cs_params->adc_handle = &hadc;
+ return 0;
+}
+
+void _adc_gpio_init(Stm32CurrentSenseParams* cs_params, const int pinA, const int pinB, const int pinC)
+{
+ uint8_t cnt = 0;
+ if(_isset(pinA)){
+ pinmap_pinout(analogInputToPinName(pinA), PinMap_ADC);
+ cs_params->pins[cnt++] = pinA;
+ }
+ if(_isset(pinB)){
+ pinmap_pinout(analogInputToPinName(pinB), PinMap_ADC);
+ cs_params->pins[cnt++] = pinB;
+ }
+ if(_isset(pinC)){
+ pinmap_pinout(analogInputToPinName(pinC), PinMap_ADC);
+ cs_params->pins[cnt] = pinC;
+ }
+}
+
+extern "C" {
+ void ADC1_2_IRQHandler(void)
+ {
+ HAL_ADC_IRQHandler(&hadc);
+ }
+#ifdef ADC3
+ void ADC3_IRQHandler(void)
+ {
+ HAL_ADC_IRQHandler(&hadc);
+ }
+#endif
+
+#ifdef ADC4
+ void ADC4_IRQHandler(void)
+ {
+ HAL_ADC_IRQHandler(&hadc);
+ }
+#endif
+
+#ifdef ADC5
+ void ADC5_IRQHandler(void)
+ {
+ HAL_ADC_IRQHandler(&hadc);
+ }
+#endif
+}
+
+#endif
\ No newline at end of file
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/hardware_specific/stm32/stm32g4/stm32g4_hal.h b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/hardware_specific/stm32/stm32g4/stm32g4_hal.h
new file mode 100644
index 0000000..2298b17
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/hardware_specific/stm32/stm32g4/stm32g4_hal.h
@@ -0,0 +1,19 @@
+#ifndef STM32G4_LOWSIDE_HAL
+#define STM32G4_LOWSIDE_HAL
+
+#include "Arduino.h"
+
+#if defined(STM32G4xx) && !defined(ARDUINO_B_G431B_ESC1)
+
+#include "stm32g4xx_hal.h"
+#include "../../../../common/foc_utils.h"
+#include "../../../../drivers/hardware_specific/stm32/stm32_mcu.h"
+#include "../stm32_mcu.h"
+#include "stm32g4_utils.h"
+
+int _adc_init(Stm32CurrentSenseParams* cs_params, const STM32DriverParams* driver_params);
+void _adc_gpio_init(Stm32CurrentSenseParams* cs_params, const int pinA, const int pinB, const int pinC);
+
+#endif
+
+#endif
\ No newline at end of file
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/hardware_specific/stm32/stm32g4/stm32g4_mcu.cpp b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/hardware_specific/stm32/stm32g4/stm32g4_mcu.cpp
new file mode 100644
index 0000000..9c73f6d
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/hardware_specific/stm32/stm32g4/stm32g4_mcu.cpp
@@ -0,0 +1,167 @@
+#include "../../../hardware_api.h"
+
+#if defined(STM32G4xx) && !defined(ARDUINO_B_G431B_ESC1)
+
+#include "../../../../common/foc_utils.h"
+#include "../../../../drivers/hardware_api.h"
+#include "../../../../drivers/hardware_specific/stm32/stm32_mcu.h"
+#include "../../../hardware_api.h"
+#include "../stm32_mcu.h"
+#include "stm32g4_hal.h"
+#include "stm32g4_utils.h"
+#include "Arduino.h"
+
+// #define SIMPLEFOC_STM32_ADC_INTERRUPT
+
+#define _ADC_VOLTAGE_G4 3.3f
+#define _ADC_RESOLUTION_G4 4096.0f
+
+
+// array of values of 4 injected channels per adc instance (5)
+uint32_t adc_val[5][4]={0};
+// does adc interrupt need a downsample - per adc (5)
+bool needs_downsample[5] = {1};
+// downsampling variable - per adc (5)
+uint8_t tim_downsample[5] = {0};
+
+#ifdef SIMPLEFOC_STM32_ADC_INTERRUPT
+uint8_t use_adc_interrupt = 1;
+#else
+uint8_t use_adc_interrupt = 0;
+#endif
+
+void* _configureADCLowSide(const void* driver_params, const int pinA, const int pinB, const int pinC){
+
+ Stm32CurrentSenseParams* cs_params= new Stm32CurrentSenseParams {
+ .pins={(int)NOT_SET, (int)NOT_SET, (int)NOT_SET},
+ .adc_voltage_conv = (_ADC_VOLTAGE_G4) / (_ADC_RESOLUTION_G4)
+ };
+ _adc_gpio_init(cs_params, pinA,pinB,pinC);
+ if(_adc_init(cs_params, (STM32DriverParams*)driver_params) != 0) return SIMPLEFOC_CURRENT_SENSE_INIT_FAILED;
+ return cs_params;
+}
+
+
+void* _driverSyncLowSide(void* _driver_params, void* _cs_params){
+ STM32DriverParams* driver_params = (STM32DriverParams*)_driver_params;
+ Stm32CurrentSenseParams* cs_params = (Stm32CurrentSenseParams*)_cs_params;
+
+ // if compatible timer has not been found
+ if (cs_params->timer_handle == NULL) return SIMPLEFOC_CURRENT_SENSE_INIT_FAILED;
+
+ // stop all the timers for the driver
+ _stopTimers(driver_params->timers, 6);
+
+ // if timer has repetition counter - it will downsample using it
+ // and it does not need the software downsample
+ if( IS_TIM_REPETITION_COUNTER_INSTANCE(cs_params->timer_handle->getHandle()->Instance) ){
+ // adjust the initial timer state such that the trigger
+ // - for DMA transfer aligns with the pwm peaks instead of throughs.
+ // - for interrupt based ADC transfer
+ // - only necessary for the timers that have repetition counters
+ cs_params->timer_handle->getHandle()->Instance->CR1 |= TIM_CR1_DIR;
+ cs_params->timer_handle->getHandle()->Instance->CNT = cs_params->timer_handle->getHandle()->Instance->ARR;
+ // remember that this timer has repetition counter - no need to downasmple
+ needs_downsample[_adcToIndex(cs_params->adc_handle)] = 0;
+ }else{
+ if(!use_adc_interrupt){
+ // If the timer has no repetition counter, it needs to use the interrupt to downsample for low side sensing
+ use_adc_interrupt = 1;
+ #ifdef SIMPLEFOC_STM32_DEBUG
+ SIMPLEFOC_DEBUG("STM32-CS: timer has no repetition counter, ADC interrupt has to be used");
+ #endif
+ }
+ }
+
+ // set the trigger output event
+ LL_TIM_SetTriggerOutput(cs_params->timer_handle->getHandle()->Instance, LL_TIM_TRGO_UPDATE);
+
+ // Start the adc calibration
+ HAL_ADCEx_Calibration_Start(cs_params->adc_handle,ADC_SINGLE_ENDED);
+
+ // start the adc
+ if (use_adc_interrupt){
+ // enable interrupt
+ if(cs_params->adc_handle->Instance == ADC1) {
+ // enable interrupt
+ HAL_NVIC_SetPriority(ADC1_2_IRQn, 0, 0);
+ HAL_NVIC_EnableIRQ(ADC1_2_IRQn);
+ }
+ #ifdef ADC2
+ else if (cs_params->adc_handle->Instance == ADC2) {
+ // enable interrupt
+ HAL_NVIC_SetPriority(ADC1_2_IRQn, 0, 0);
+ HAL_NVIC_EnableIRQ(ADC1_2_IRQn);
+ }
+ #endif
+ #ifdef ADC3
+ else if (cs_params->adc_handle->Instance == ADC3) {
+ // enable interrupt
+ HAL_NVIC_SetPriority(ADC3_IRQn, 0, 0);
+ HAL_NVIC_EnableIRQ(ADC3_IRQn);
+ }
+ #endif
+ #ifdef ADC4
+ else if (cs_params->adc_handle->Instance == ADC4) {
+ // enable interrupt
+ HAL_NVIC_SetPriority(ADC4_IRQn, 0, 0);
+ HAL_NVIC_EnableIRQ(ADC4_IRQn);
+ }
+ #endif
+ #ifdef ADC5
+ else if (cs_params->adc_handle->Instance == ADC5) {
+ // enable interrupt
+ HAL_NVIC_SetPriority(ADC5_IRQn, 0, 0);
+ HAL_NVIC_EnableIRQ(ADC5_IRQn);
+ }
+ #endif
+
+ HAL_ADCEx_InjectedStart_IT(cs_params->adc_handle);
+ }else{
+ HAL_ADCEx_InjectedStart(cs_params->adc_handle);
+ }
+
+ // restart all the timers of the driver
+ _startTimers(driver_params->timers, 6);
+
+ // return the cs parameters
+ // successfully initialized
+ // TODO verify if success in future
+ return _cs_params;
+}
+
+
+// function reading an ADC value and returning the read voltage
+float _readADCVoltageLowSide(const int pin, const void* cs_params){
+ for(int i=0; i < 3; i++){
+ if( pin == ((Stm32CurrentSenseParams*)cs_params)->pins[i]){ // found in the buffer
+ if (use_adc_interrupt){
+ return adc_val[_adcToIndex(((Stm32CurrentSenseParams*)cs_params)->adc_handle)][i] * ((Stm32CurrentSenseParams*)cs_params)->adc_voltage_conv;
+ }else{
+ // an optimized way to go from i to the channel i=0 -> channel 1, i=1 -> channel 2, i=2 -> channel 3
+ uint32_t channel = (i == 0) ? ADC_INJECTED_RANK_1 : (i == 1) ? ADC_INJECTED_RANK_2 : ADC_INJECTED_RANK_3;
+ return HAL_ADCEx_InjectedGetValue(((Stm32CurrentSenseParams*)cs_params)->adc_handle, channel) * ((Stm32CurrentSenseParams*)cs_params)->adc_voltage_conv;
+ }
+ }
+ }
+ return 0;
+}
+
+extern "C" {
+ void HAL_ADCEx_InjectedConvCpltCallback(ADC_HandleTypeDef *AdcHandle){
+ // calculate the instance
+ int adc_index = _adcToIndex(AdcHandle);
+
+ // if the timer han't repetition counter - downsample two times
+ if( needs_downsample[adc_index] && tim_downsample[adc_index]++ > 0) {
+ tim_downsample[adc_index] = 0;
+ return;
+ }
+
+ adc_val[adc_index][0]=HAL_ADCEx_InjectedGetValue(AdcHandle, ADC_INJECTED_RANK_1);
+ adc_val[adc_index][1]=HAL_ADCEx_InjectedGetValue(AdcHandle, ADC_INJECTED_RANK_2);
+ adc_val[adc_index][2]=HAL_ADCEx_InjectedGetValue(AdcHandle, ADC_INJECTED_RANK_3);
+ }
+}
+
+#endif
\ No newline at end of file
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/hardware_specific/stm32/stm32g4/stm32g4_utils.cpp b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/hardware_specific/stm32/stm32g4/stm32g4_utils.cpp
new file mode 100644
index 0000000..89a9bc3
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/hardware_specific/stm32/stm32g4/stm32g4_utils.cpp
@@ -0,0 +1,237 @@
+#include "stm32g4_utils.h"
+
+#if defined(STM32G4xx) && !defined(ARDUINO_B_G431B_ESC1)
+
+/* Exported Functions */
+/**
+ * @brief Return ADC HAL channel linked to a PinName
+ * @param pin: PinName
+ * @retval Valid HAL channel
+ */
+uint32_t _getADCChannel(PinName pin)
+{
+ uint32_t function = pinmap_function(pin, PinMap_ADC);
+ uint32_t channel = 0;
+ switch (STM_PIN_CHANNEL(function)) {
+#ifdef ADC_CHANNEL_0
+ case 0:
+ channel = ADC_CHANNEL_0;
+ break;
+#endif
+ case 1:
+ channel = ADC_CHANNEL_1;
+ break;
+ case 2:
+ channel = ADC_CHANNEL_2;
+ break;
+ case 3:
+ channel = ADC_CHANNEL_3;
+ break;
+ case 4:
+ channel = ADC_CHANNEL_4;
+ break;
+ case 5:
+ channel = ADC_CHANNEL_5;
+ break;
+ case 6:
+ channel = ADC_CHANNEL_6;
+ break;
+ case 7:
+ channel = ADC_CHANNEL_7;
+ break;
+ case 8:
+ channel = ADC_CHANNEL_8;
+ break;
+ case 9:
+ channel = ADC_CHANNEL_9;
+ break;
+ case 10:
+ channel = ADC_CHANNEL_10;
+ break;
+ case 11:
+ channel = ADC_CHANNEL_11;
+ break;
+ case 12:
+ channel = ADC_CHANNEL_12;
+ break;
+ case 13:
+ channel = ADC_CHANNEL_13;
+ break;
+ case 14:
+ channel = ADC_CHANNEL_14;
+ break;
+ case 15:
+ channel = ADC_CHANNEL_15;
+ break;
+#ifdef ADC_CHANNEL_16
+ case 16:
+ channel = ADC_CHANNEL_16;
+ break;
+#endif
+ case 17:
+ channel = ADC_CHANNEL_17;
+ break;
+#ifdef ADC_CHANNEL_18
+ case 18:
+ channel = ADC_CHANNEL_18;
+ break;
+#endif
+#ifdef ADC_CHANNEL_19
+ case 19:
+ channel = ADC_CHANNEL_19;
+ break;
+#endif
+#ifdef ADC_CHANNEL_20
+ case 20:
+ channel = ADC_CHANNEL_20;
+ break;
+ case 21:
+ channel = ADC_CHANNEL_21;
+ break;
+ case 22:
+ channel = ADC_CHANNEL_22;
+ break;
+ case 23:
+ channel = ADC_CHANNEL_23;
+ break;
+#ifdef ADC_CHANNEL_24
+ case 24:
+ channel = ADC_CHANNEL_24;
+ break;
+ case 25:
+ channel = ADC_CHANNEL_25;
+ break;
+ case 26:
+ channel = ADC_CHANNEL_26;
+ break;
+#ifdef ADC_CHANNEL_27
+ case 27:
+ channel = ADC_CHANNEL_27;
+ break;
+ case 28:
+ channel = ADC_CHANNEL_28;
+ break;
+ case 29:
+ channel = ADC_CHANNEL_29;
+ break;
+ case 30:
+ channel = ADC_CHANNEL_30;
+ break;
+ case 31:
+ channel = ADC_CHANNEL_31;
+ break;
+#endif
+#endif
+#endif
+ default:
+ _Error_Handler("ADC: Unknown adc channel", (int)(STM_PIN_CHANNEL(function)));
+ break;
+ }
+ return channel;
+}
+
+
+// timer to injected TRGO
+// https://github.com/stm32duino/Arduino_Core_STM32/blob/6588dee03382e73ed42c4a5e473900ab3b79d6e4/system/Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_hal_adc_ex.h#L217
+uint32_t _timerToInjectedTRGO(HardwareTimer* timer){
+ if(timer->getHandle()->Instance == TIM1)
+ return ADC_EXTERNALTRIGINJEC_T1_TRGO;
+#ifdef TIM2 // if defined timer 2
+ else if(timer->getHandle()->Instance == TIM2)
+ return ADC_EXTERNALTRIGINJEC_T2_TRGO;
+#endif
+#ifdef TIM3 // if defined timer 3
+ else if(timer->getHandle()->Instance == TIM3)
+ return ADC_EXTERNALTRIGINJEC_T3_TRGO;
+#endif
+#ifdef TIM4 // if defined timer 4
+ else if(timer->getHandle()->Instance == TIM4)
+ return ADC_EXTERNALTRIGINJEC_T4_TRGO;
+#endif
+#ifdef TIM6 // if defined timer 6
+ else if(timer->getHandle()->Instance == TIM6)
+ return ADC_EXTERNALTRIGINJEC_T6_TRGO;
+#endif
+#ifdef TIM7 // if defined timer 7
+ else if(timer->getHandle()->Instance == TIM7)
+ return ADC_EXTERNALTRIGINJEC_T7_TRGO;
+#endif
+#ifdef TIM8 // if defined timer 8
+ else if(timer->getHandle()->Instance == TIM8)
+ return ADC_EXTERNALTRIGINJEC_T8_TRGO;
+#endif
+#ifdef TIM15 // if defined timer 15
+ else if(timer->getHandle()->Instance == TIM15)
+ return ADC_EXTERNALTRIGINJEC_T15_TRGO;
+#endif
+#ifdef TIM20 // if defined timer 15
+ else if(timer->getHandle()->Instance == TIM20)
+ return ADC_EXTERNALTRIGINJEC_T20_TRGO;
+#endif
+ else
+ return _TRGO_NOT_AVAILABLE;
+}
+
+// timer to regular TRGO
+// https://github.com/stm32duino/Arduino_Core_STM32/blob/6588dee03382e73ed42c4a5e473900ab3b79d6e4/system/Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_hal_adc.h#L519
+uint32_t _timerToRegularTRGO(HardwareTimer* timer){
+ if(timer->getHandle()->Instance == TIM1)
+ return ADC_EXTERNALTRIG_T1_TRGO;
+#ifdef TIM2 // if defined timer 2
+ else if(timer->getHandle()->Instance == TIM2)
+ return ADC_EXTERNALTRIG_T2_TRGO;
+#endif
+#ifdef TIM3 // if defined timer 3
+ else if(timer->getHandle()->Instance == TIM3)
+ return ADC_EXTERNALTRIG_T3_TRGO;
+#endif
+#ifdef TIM4 // if defined timer 4
+ else if(timer->getHandle()->Instance == TIM4)
+ return ADC_EXTERNALTRIG_T4_TRGO;
+#endif
+#ifdef TIM6 // if defined timer 6
+ else if(timer->getHandle()->Instance == TIM6)
+ return ADC_EXTERNALTRIG_T6_TRGO;
+#endif
+#ifdef TIM7 // if defined timer 7
+ else if(timer->getHandle()->Instance == TIM7)
+ return ADC_EXTERNALTRIG_T7_TRGO;
+#endif
+#ifdef TIM8 // if defined timer 8
+ else if(timer->getHandle()->Instance == TIM8)
+ return ADC_EXTERNALTRIG_T7_TRGO;
+#endif
+#ifdef TIM15 // if defined timer 15
+ else if(timer->getHandle()->Instance == TIM15)
+ return ADC_EXTERNALTRIG_T15_TRGO;
+#endif
+#ifdef TIM20 // if defined timer 15
+ else if(timer->getHandle()->Instance == TIM20)
+ return ADC_EXTERNALTRIG_T20_TRGO;
+#endif
+ else
+ return _TRGO_NOT_AVAILABLE;
+}
+
+
+int _adcToIndex(ADC_TypeDef *AdcHandle){
+ if(AdcHandle == ADC1) return 0;
+#ifdef ADC2 // if ADC2 exists
+ else if(AdcHandle == ADC2) return 1;
+#endif
+#ifdef ADC3 // if ADC3 exists
+ else if(AdcHandle == ADC3) return 2;
+#endif
+#ifdef ADC4 // if ADC4 exists
+ else if(AdcHandle == ADC4) return 3;
+#endif
+#ifdef ADC5 // if ADC5 exists
+ else if(AdcHandle == ADC5) return 4;
+#endif
+ return 0;
+}
+int _adcToIndex(ADC_HandleTypeDef *AdcHandle){
+ return _adcToIndex(AdcHandle->Instance);
+}
+
+#endif
\ No newline at end of file
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/hardware_specific/stm32/stm32g4/stm32g4_utils.h b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/hardware_specific/stm32/stm32g4/stm32g4_utils.h
new file mode 100644
index 0000000..fa857bd
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/hardware_specific/stm32/stm32g4/stm32g4_utils.h
@@ -0,0 +1,34 @@
+
+#ifndef STM32G4_UTILS_HAL
+#define STM32G4_UTILS_HAL
+
+#include "Arduino.h"
+
+#if defined(STM32G4xx) && !defined(ARDUINO_B_G431B_ESC1)
+
+#define _TRGO_NOT_AVAILABLE 12345
+
+
+/* Exported Functions */
+/**
+ * @brief Return ADC HAL channel linked to a PinName
+ * @param pin: PinName
+ * @retval Valid HAL channel
+ */
+uint32_t _getADCChannel(PinName pin);
+
+// timer to injected TRGO
+// https://github.com/stm32duino/Arduino_Core_STM32/blob/6588dee03382e73ed42c4a5e473900ab3b79d6e4/system/Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_hal_adc_ex.h#L217
+uint32_t _timerToInjectedTRGO(HardwareTimer* timer);
+
+// timer to regular TRGO
+// https://github.com/stm32duino/Arduino_Core_STM32/blob/6588dee03382e73ed42c4a5e473900ab3b79d6e4/system/Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_hal_adc.h#L519
+uint32_t _timerToRegularTRGO(HardwareTimer* timer);
+
+// function returning index of the ADC instance
+int _adcToIndex(ADC_HandleTypeDef *AdcHandle);
+int _adcToIndex(ADC_TypeDef *AdcHandle);
+
+#endif
+
+#endif
\ No newline at end of file
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/hardware_specific/stm32/stm32l4/stm32l4_hal.cpp b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/hardware_specific/stm32/stm32l4/stm32l4_hal.cpp
new file mode 100644
index 0000000..67a0473
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/hardware_specific/stm32/stm32l4/stm32l4_hal.cpp
@@ -0,0 +1,230 @@
+#include "stm32l4_hal.h"
+
+#if defined(STM32L4xx)
+
+#include "../../../../communication/SimpleFOCDebug.h"
+
+#define SIMPLEFOC_STM32_DEBUG
+
+ADC_HandleTypeDef hadc;
+
+int _adc_init(Stm32CurrentSenseParams* cs_params, const STM32DriverParams* driver_params)
+{
+ ADC_InjectionConfTypeDef sConfigInjected;
+
+ // check if all pins belong to the same ADC
+ ADC_TypeDef* adc_pin1 = (ADC_TypeDef*)pinmap_peripheral(analogInputToPinName(cs_params->pins[0]), PinMap_ADC);
+ ADC_TypeDef* adc_pin2 = (ADC_TypeDef*)pinmap_peripheral(analogInputToPinName(cs_params->pins[1]), PinMap_ADC);
+ ADC_TypeDef* adc_pin3 = _isset(cs_params->pins[2]) ? (ADC_TypeDef*)pinmap_peripheral(analogInputToPinName(cs_params->pins[2]), PinMap_ADC) : nullptr;
+ if ( (adc_pin1 != adc_pin2) || ( (adc_pin3) && (adc_pin1 != adc_pin3) )){
+#ifdef SIMPLEFOC_STM32_DEBUG
+ SIMPLEFOC_DEBUG("STM32-CS: ERR: Analog pins dont belong to the same ADC!");
+#endif
+ return -1;
+ }
+
+
+ /**Configure the global features of the ADC (Clock, Resolution, Data Alignment and number of conversion)
+ */
+ hadc.Instance = (ADC_TypeDef *)pinmap_peripheral(analogInputToPinName(cs_params->pins[0]), PinMap_ADC);
+
+ if(hadc.Instance == ADC1) {
+#ifdef __HAL_RCC_ADC1_CLK_ENABLE
+ __HAL_RCC_ADC1_CLK_ENABLE();
+#endif
+#ifdef __HAL_RCC_ADC12_CLK_ENABLE
+ __HAL_RCC_ADC12_CLK_ENABLE();
+#endif
+ }
+#ifdef ADC2
+ else if (hadc.Instance == ADC2) {
+#ifdef __HAL_RCC_ADC2_CLK_ENABLE
+ __HAL_RCC_ADC2_CLK_ENABLE();
+#endif
+#ifdef __HAL_RCC_ADC12_CLK_ENABLE
+ __HAL_RCC_ADC12_CLK_ENABLE();
+#endif
+ }
+#endif
+#ifdef ADC3
+ else if (hadc.Instance == ADC3) {
+#ifdef __HAL_RCC_ADC3_CLK_ENABLE
+ __HAL_RCC_ADC3_CLK_ENABLE();
+#endif
+#ifdef __HAL_RCC_ADC34_CLK_ENABLE
+ __HAL_RCC_ADC34_CLK_ENABLE();
+#endif
+#if defined(ADC345_COMMON)
+ __HAL_RCC_ADC345_CLK_ENABLE();
+#endif
+ }
+#endif
+#ifdef ADC4
+ else if (hadc.Instance == ADC4) {
+#ifdef __HAL_RCC_ADC4_CLK_ENABLE
+ __HAL_RCC_ADC4_CLK_ENABLE();
+#endif
+#ifdef __HAL_RCC_ADC34_CLK_ENABLE
+ __HAL_RCC_ADC34_CLK_ENABLE();
+#endif
+#if defined(ADC345_COMMON)
+ __HAL_RCC_ADC345_CLK_ENABLE();
+#endif
+ }
+#endif
+#ifdef ADC5
+ else if (hadc.Instance == ADC5) {
+#if defined(ADC345_COMMON)
+ __HAL_RCC_ADC345_CLK_ENABLE();
+#endif
+ }
+#endif
+ else{
+#ifdef SIMPLEFOC_STM32_DEBUG
+ SIMPLEFOC_DEBUG("STM32-CS: ERR: Pin does not belong to any ADC!");
+#endif
+ return -1; // error not a valid ADC instance
+ }
+
+#ifdef SIMPLEFOC_STM32_DEBUG
+ SIMPLEFOC_DEBUG("STM32-CS: Using ADC: ", _adcToIndex(&hadc)+1);
+#endif
+
+ hadc.Init.ClockPrescaler = ADC_CLOCK_SYNC_PCLK_DIV4;
+ hadc.Init.Resolution = ADC_RESOLUTION_12B;
+ hadc.Init.ScanConvMode = ADC_SCAN_ENABLE;
+ hadc.Init.ContinuousConvMode = DISABLE;
+ hadc.Init.LowPowerAutoWait = DISABLE;
+ hadc.Init.DiscontinuousConvMode = DISABLE;
+ hadc.Init.ExternalTrigConvEdge = ADC_EXTERNALTRIGCONVEDGE_NONE;
+ hadc.Init.ExternalTrigConv = ADC_SOFTWARE_START; // for now
+ hadc.Init.DataAlign = ADC_DATAALIGN_RIGHT;
+ hadc.Init.NbrOfConversion = 1;
+ hadc.Init.DMAContinuousRequests = DISABLE;
+ hadc.Init.EOCSelection = ADC_EOC_SINGLE_CONV;
+ hadc.Init.Overrun = ADC_OVR_DATA_PRESERVED;
+ if ( HAL_ADC_Init(&hadc) != HAL_OK){
+#ifdef SIMPLEFOC_STM32_DEBUG
+ SIMPLEFOC_DEBUG("STM32-CS: ERR: cannot init ADC!");
+#endif
+ return -1;
+ }
+
+ /**Configures for the selected ADC injected channel its corresponding rank in the sequencer and its sample time
+ */
+ sConfigInjected.InjectedNbrOfConversion = _isset(cs_params->pins[2]) ? 3 : 2;
+ sConfigInjected.InjectedSamplingTime = ADC_SAMPLETIME_2CYCLES_5;
+ sConfigInjected.ExternalTrigInjecConvEdge = ADC_EXTERNALTRIGINJECCONV_EDGE_RISING;
+ sConfigInjected.AutoInjectedConv = DISABLE;
+ sConfigInjected.InjectedSingleDiff = ADC_SINGLE_ENDED;
+ sConfigInjected.InjectedDiscontinuousConvMode = DISABLE;
+ sConfigInjected.InjectedOffsetNumber = ADC_OFFSET_NONE;
+ sConfigInjected.InjectedOffset = 0;
+ sConfigInjected.InjecOversamplingMode = DISABLE;
+ sConfigInjected.QueueInjectedContext = DISABLE;
+
+ // automating TRGO flag finding - hardware specific
+ uint8_t tim_num = 0;
+ while(driver_params->timers[tim_num] != NP && tim_num < 6){
+ uint32_t trigger_flag = _timerToInjectedTRGO(driver_params->timers[tim_num++]);
+ if(trigger_flag == _TRGO_NOT_AVAILABLE) continue; // timer does not have valid trgo for injected channels
+
+ // if the code comes here, it has found the timer available
+ // timer does have trgo flag for injected channels
+ sConfigInjected.ExternalTrigInjecConv = trigger_flag;
+
+ // this will be the timer with which the ADC will sync
+ cs_params->timer_handle = driver_params->timers[tim_num-1];
+ // done
+ break;
+ }
+ if( cs_params->timer_handle == NP ){
+ // not possible to use these timers for low-side current sense
+#ifdef SIMPLEFOC_STM32_DEBUG
+ SIMPLEFOC_DEBUG("STM32-CS: ERR: cannot sync any timer to injected channels!");
+#endif
+ return -1;
+ }
+
+
+ // first channel
+ sConfigInjected.InjectedRank = ADC_INJECTED_RANK_1;
+ sConfigInjected.InjectedChannel = _getADCChannel(analogInputToPinName(cs_params->pins[0]));
+ if (HAL_ADCEx_InjectedConfigChannel(&hadc, &sConfigInjected) != HAL_OK){
+#ifdef SIMPLEFOC_STM32_DEBUG
+ SIMPLEFOC_DEBUG("STM32-CS: ERR: cannot init injected channel: ", (int)_getADCChannel(analogInputToPinName(cs_params->pins[0])) );
+#endif
+ return -1;
+ }
+
+ // second channel
+ sConfigInjected.InjectedRank = ADC_INJECTED_RANK_2;
+ sConfigInjected.InjectedChannel = _getADCChannel(analogInputToPinName(cs_params->pins[1]));
+ if (HAL_ADCEx_InjectedConfigChannel(&hadc, &sConfigInjected) != HAL_OK){
+#ifdef SIMPLEFOC_STM32_DEBUG
+ SIMPLEFOC_DEBUG("STM32-CS: ERR: cannot init injected channel: ", (int)_getADCChannel(analogInputToPinName(cs_params->pins[1]))) ;
+#endif
+ return -1;
+ }
+
+ // third channel - if exists
+ if(_isset(cs_params->pins[2])){
+ sConfigInjected.InjectedRank = ADC_INJECTED_RANK_3;
+ sConfigInjected.InjectedChannel = _getADCChannel(analogInputToPinName(cs_params->pins[2]));
+ if (HAL_ADCEx_InjectedConfigChannel(&hadc, &sConfigInjected) != HAL_OK){
+#ifdef SIMPLEFOC_STM32_DEBUG
+ SIMPLEFOC_DEBUG("STM32-CS: ERR: cannot init injected channel: ", (int)_getADCChannel(analogInputToPinName(cs_params->pins[2]))) ;
+#endif
+ return -1;
+ }
+ }
+
+ cs_params->adc_handle = &hadc;
+ return 0;
+}
+
+void _adc_gpio_init(Stm32CurrentSenseParams* cs_params, const int pinA, const int pinB, const int pinC)
+{
+ uint8_t cnt = 0;
+ if(_isset(pinA)){
+ pinmap_pinout(analogInputToPinName(pinA), PinMap_ADC);
+ cs_params->pins[cnt++] = pinA;
+ }
+ if(_isset(pinB)){
+ pinmap_pinout(analogInputToPinName(pinB), PinMap_ADC);
+ cs_params->pins[cnt++] = pinB;
+ }
+ if(_isset(pinC)){
+ pinmap_pinout(analogInputToPinName(pinC), PinMap_ADC);
+ cs_params->pins[cnt] = pinC;
+ }
+}
+
+extern "C" {
+ void ADC1_2_IRQHandler(void)
+ {
+ HAL_ADC_IRQHandler(&hadc);
+ }
+#ifdef ADC3
+ void ADC3_IRQHandler(void)
+ {
+ HAL_ADC_IRQHandler(&hadc);
+ }
+#endif
+
+#ifdef ADC4
+ void ADC4_IRQHandler(void)
+ {
+ HAL_ADC_IRQHandler(&hadc);
+ }
+#endif
+
+#ifdef ADC5
+ void ADC5_IRQHandler(void)
+ {
+ HAL_ADC_IRQHandler(&hadc);
+ }
+#endif
+}
+
+#endif
\ No newline at end of file
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/hardware_specific/stm32/stm32l4/stm32l4_hal.h b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/hardware_specific/stm32/stm32l4/stm32l4_hal.h
new file mode 100644
index 0000000..0317b74
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/hardware_specific/stm32/stm32l4/stm32l4_hal.h
@@ -0,0 +1,19 @@
+#ifndef STM32L4_LOWSIDE_HAL
+#define STM32L4_LOWSIDE_HAL
+
+#include "Arduino.h"
+
+#if defined(STM32L4xx)
+
+#include "stm32l4xx_hal.h"
+#include "../../../../common/foc_utils.h"
+#include "../../../../drivers/hardware_specific/stm32/stm32_mcu.h"
+#include "../stm32_mcu.h"
+#include "stm32l4_utils.h"
+
+int _adc_init(Stm32CurrentSenseParams* cs_params, const STM32DriverParams* driver_params);
+void _adc_gpio_init(Stm32CurrentSenseParams* cs_params, const int pinA, const int pinB, const int pinC);
+
+#endif
+
+#endif
\ No newline at end of file
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/hardware_specific/stm32/stm32l4/stm32l4_mcu.cpp b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/hardware_specific/stm32/stm32l4/stm32l4_mcu.cpp
new file mode 100644
index 0000000..5de6432
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/hardware_specific/stm32/stm32l4/stm32l4_mcu.cpp
@@ -0,0 +1,163 @@
+#include "../../../hardware_api.h"
+
+#if defined(STM32L4xx)
+
+#include "../../../../common/foc_utils.h"
+#include "../../../../drivers/hardware_api.h"
+#include "../../../../drivers/hardware_specific/stm32/stm32_mcu.h"
+#include "../../../hardware_api.h"
+#include "../stm32_mcu.h"
+#include "stm32l4_hal.h"
+#include "stm32l4_utils.h"
+#include "Arduino.h"
+
+
+#define _ADC_VOLTAGE_L4 3.3f
+#define _ADC_RESOLUTION_L4 4096.0f
+
+
+// array of values of 4 injected channels per adc instance (5)
+uint32_t adc_val[5][4]={0};
+// does adc interrupt need a downsample - per adc (5)
+bool needs_downsample[5] = {1};
+// downsampling variable - per adc (5)
+uint8_t tim_downsample[5] = {0};
+
+#ifdef SIMPLEFOC_STM32_ADC_INTERRUPT
+uint8_t use_adc_interrupt = 1;
+#else
+uint8_t use_adc_interrupt = 0;
+#endif
+
+void* _configureADCLowSide(const void* driver_params, const int pinA, const int pinB, const int pinC){
+
+ Stm32CurrentSenseParams* cs_params= new Stm32CurrentSenseParams {
+ .pins={(int)NOT_SET, (int)NOT_SET, (int)NOT_SET},
+ .adc_voltage_conv = (_ADC_VOLTAGE_L4) / (_ADC_RESOLUTION_L4)
+ };
+ _adc_gpio_init(cs_params, pinA,pinB,pinC);
+ if(_adc_init(cs_params, (STM32DriverParams*)driver_params) != 0) return SIMPLEFOC_CURRENT_SENSE_INIT_FAILED;
+ return cs_params;
+}
+
+
+void* _driverSyncLowSide(void* _driver_params, void* _cs_params){
+ STM32DriverParams* driver_params = (STM32DriverParams*)_driver_params;
+ Stm32CurrentSenseParams* cs_params = (Stm32CurrentSenseParams*)_cs_params;
+
+ // if compatible timer has not been found
+ if (cs_params->timer_handle == NULL) return SIMPLEFOC_CURRENT_SENSE_INIT_FAILED;
+
+ // stop all the timers for the driver
+ _stopTimers(driver_params->timers, 6);
+
+ // if timer has repetition counter - it will downsample using it
+ // and it does not need the software downsample
+ if( IS_TIM_REPETITION_COUNTER_INSTANCE(cs_params->timer_handle->getHandle()->Instance) ){
+ // adjust the initial timer state such that the trigger
+ // - for DMA transfer aligns with the pwm peaks instead of throughs.
+ // - for interrupt based ADC transfer
+ // - only necessary for the timers that have repetition counters
+ cs_params->timer_handle->getHandle()->Instance->CR1 |= TIM_CR1_DIR;
+ cs_params->timer_handle->getHandle()->Instance->CNT = cs_params->timer_handle->getHandle()->Instance->ARR;
+ // remember that this timer has repetition counter - no need to downasmple
+ needs_downsample[_adcToIndex(cs_params->adc_handle)] = 0;
+ }else{
+ if(!use_adc_interrupt){
+ // If the timer has no repetition counter, it needs to use the interrupt to downsample for low side sensing
+ use_adc_interrupt = 1;
+ #ifdef SIMPLEFOC_STM32_DEBUG
+ SIMPLEFOC_DEBUG("STM32-CS: timer has no repetition counter, ADC interrupt has to be used");
+ #endif
+ }
+ }
+
+ // set the trigger output event
+ LL_TIM_SetTriggerOutput(cs_params->timer_handle->getHandle()->Instance, LL_TIM_TRGO_UPDATE);
+
+ // Start the adc calibration
+ HAL_ADCEx_Calibration_Start(cs_params->adc_handle,ADC_SINGLE_ENDED);
+
+ // start the adc
+ if (use_adc_interrupt){
+ if(cs_params->adc_handle->Instance == ADC1) {
+ // enable interrupt
+ HAL_NVIC_SetPriority(ADC1_2_IRQn, 0, 0);
+ HAL_NVIC_EnableIRQ(ADC1_2_IRQn);
+ }
+ #ifdef ADC2
+ else if (cs_params->adc_handle->Instance == ADC2) {
+ // enable interrupt
+ HAL_NVIC_SetPriority(ADC1_2_IRQn, 0, 0);
+ HAL_NVIC_EnableIRQ(ADC1_2_IRQn);
+ }
+ #endif
+ #ifdef ADC3
+ else if (cs_params->adc_handle->Instance == ADC3) {
+ // enable interrupt
+ HAL_NVIC_SetPriority(ADC3_IRQn, 0, 0);
+ HAL_NVIC_EnableIRQ(ADC3_IRQn);
+ }
+ #endif
+ #ifdef ADC4
+ else if (cs_params->adc_handle->Instance == ADC4) {
+ // enable interrupt
+ HAL_NVIC_SetPriority(ADC4_IRQn, 0, 0);
+ HAL_NVIC_EnableIRQ(ADC4_IRQn);
+ }
+ #endif
+ #ifdef ADC5
+ else if (cs_params->adc_handle->Instance == ADC5) {
+ // enable interrupt
+ HAL_NVIC_SetPriority(ADC5_IRQn, 0, 0);
+ HAL_NVIC_EnableIRQ(ADC5_IRQn);
+ }
+ #endif
+ HAL_ADCEx_InjectedStart_IT(cs_params->adc_handle);
+ }else{
+ HAL_ADCEx_InjectedStart(cs_params->adc_handle);
+ }
+
+ // restart all the timers of the driver
+ _startTimers(driver_params->timers, 6);
+ // return the cs parameters
+ // successfully initialized
+ // TODO verify if success in future
+ return _cs_params;
+}
+
+
+// function reading an ADC value and returning the read voltage
+float _readADCVoltageLowSide(const int pin, const void* cs_params){
+ for(int i=0; i < 3; i++){
+ if( pin == ((Stm32CurrentSenseParams*)cs_params)->pins[i]){ // found in the buffer
+ if (use_adc_interrupt){
+ return adc_val[_adcToIndex(((Stm32CurrentSenseParams*)cs_params)->adc_handle)][i] * ((Stm32CurrentSenseParams*)cs_params)->adc_voltage_conv;
+ }else{
+ // an optimized way to go from i to the channel i=0 -> channel 1, i=1 -> channel 2, i=2 -> channel 3
+ uint32_t channel = (i == 0) ? ADC_INJECTED_RANK_1 : (i == 1) ? ADC_INJECTED_RANK_2 : ADC_INJECTED_RANK_3;
+ return HAL_ADCEx_InjectedGetValue(((Stm32CurrentSenseParams*)cs_params)->adc_handle,channel) * ((Stm32CurrentSenseParams*)cs_params)->adc_voltage_conv;
+ }
+ }
+ }
+ return 0;
+}
+
+extern "C" {
+ void HAL_ADCEx_InjectedConvCpltCallback(ADC_HandleTypeDef *AdcHandle){
+ // calculate the instance
+ int adc_index = _adcToIndex(AdcHandle);
+
+ // if the timer han't repetition counter - downsample two times
+ if( needs_downsample[adc_index] && tim_downsample[adc_index]++ > 0) {
+ tim_downsample[adc_index] = 0;
+ return;
+ }
+
+ adc_val[adc_index][0]=HAL_ADCEx_InjectedGetValue(AdcHandle, ADC_INJECTED_RANK_1);
+ adc_val[adc_index][1]=HAL_ADCEx_InjectedGetValue(AdcHandle, ADC_INJECTED_RANK_2);
+ adc_val[adc_index][2]=HAL_ADCEx_InjectedGetValue(AdcHandle, ADC_INJECTED_RANK_3);
+ }
+}
+
+#endif
\ No newline at end of file
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/hardware_specific/stm32/stm32l4/stm32l4_utils.cpp b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/hardware_specific/stm32/stm32l4/stm32l4_utils.cpp
new file mode 100644
index 0000000..376d9d6
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/hardware_specific/stm32/stm32l4/stm32l4_utils.cpp
@@ -0,0 +1,221 @@
+#include "stm32l4_utils.h"
+
+#if defined(STM32L4xx)
+
+/* Exported Functions */
+/**
+ * @brief Return ADC HAL channel linked to a PinName
+ * @param pin: PinName
+ * @retval Valid HAL channel
+ */
+uint32_t _getADCChannel(PinName pin)
+{
+ uint32_t function = pinmap_function(pin, PinMap_ADC);
+ uint32_t channel = 0;
+ switch (STM_PIN_CHANNEL(function)) {
+#ifdef ADC_CHANNEL_0
+ case 0:
+ channel = ADC_CHANNEL_0;
+ break;
+#endif
+ case 1:
+ channel = ADC_CHANNEL_1;
+ break;
+ case 2:
+ channel = ADC_CHANNEL_2;
+ break;
+ case 3:
+ channel = ADC_CHANNEL_3;
+ break;
+ case 4:
+ channel = ADC_CHANNEL_4;
+ break;
+ case 5:
+ channel = ADC_CHANNEL_5;
+ break;
+ case 6:
+ channel = ADC_CHANNEL_6;
+ break;
+ case 7:
+ channel = ADC_CHANNEL_7;
+ break;
+ case 8:
+ channel = ADC_CHANNEL_8;
+ break;
+ case 9:
+ channel = ADC_CHANNEL_9;
+ break;
+ case 10:
+ channel = ADC_CHANNEL_10;
+ break;
+ case 11:
+ channel = ADC_CHANNEL_11;
+ break;
+ case 12:
+ channel = ADC_CHANNEL_12;
+ break;
+ case 13:
+ channel = ADC_CHANNEL_13;
+ break;
+ case 14:
+ channel = ADC_CHANNEL_14;
+ break;
+ case 15:
+ channel = ADC_CHANNEL_15;
+ break;
+#ifdef ADC_CHANNEL_16
+ case 16:
+ channel = ADC_CHANNEL_16;
+ break;
+#endif
+ case 17:
+ channel = ADC_CHANNEL_17;
+ break;
+#ifdef ADC_CHANNEL_18
+ case 18:
+ channel = ADC_CHANNEL_18;
+ break;
+#endif
+#ifdef ADC_CHANNEL_19
+ case 19:
+ channel = ADC_CHANNEL_19;
+ break;
+#endif
+#ifdef ADC_CHANNEL_20
+ case 20:
+ channel = ADC_CHANNEL_20;
+ break;
+ case 21:
+ channel = ADC_CHANNEL_21;
+ break;
+ case 22:
+ channel = ADC_CHANNEL_22;
+ break;
+ case 23:
+ channel = ADC_CHANNEL_23;
+ break;
+#ifdef ADC_CHANNEL_24
+ case 24:
+ channel = ADC_CHANNEL_24;
+ break;
+ case 25:
+ channel = ADC_CHANNEL_25;
+ break;
+ case 26:
+ channel = ADC_CHANNEL_26;
+ break;
+#ifdef ADC_CHANNEL_27
+ case 27:
+ channel = ADC_CHANNEL_27;
+ break;
+ case 28:
+ channel = ADC_CHANNEL_28;
+ break;
+ case 29:
+ channel = ADC_CHANNEL_29;
+ break;
+ case 30:
+ channel = ADC_CHANNEL_30;
+ break;
+ case 31:
+ channel = ADC_CHANNEL_31;
+ break;
+#endif
+#endif
+#endif
+ default:
+ _Error_Handler("ADC: Unknown adc channel", (int)(STM_PIN_CHANNEL(function)));
+ break;
+ }
+ return channel;
+}
+
+
+// timer to injected TRGO
+// https://github.com/stm32duino/Arduino_Core_STM32/blob/e156c32db24d69cb4818208ccc28894e2f427cfa/system/Drivers/STM32L4xx_HAL_Driver/Inc/stm32l4xx_hal_adc_ex.h#L210
+uint32_t _timerToInjectedTRGO(HardwareTimer* timer){
+ if(timer->getHandle()->Instance == TIM1)
+ return ADC_EXTERNALTRIGINJEC_T1_TRGO;
+#ifdef TIM2 // if defined timer 2
+ else if(timer->getHandle()->Instance == TIM2)
+ return ADC_EXTERNALTRIGINJEC_T2_TRGO;
+#endif
+#ifdef TIM3 // if defined timer 3
+ else if(timer->getHandle()->Instance == TIM3)
+ return ADC_EXTERNALTRIGINJEC_T3_TRGO;
+#endif
+#ifdef TIM4 // if defined timer 4
+ else if(timer->getHandle()->Instance == TIM4)
+ return ADC_EXTERNALTRIGINJEC_T4_TRGO;
+#endif
+#ifdef TIM6 // if defined timer 6
+ else if(timer->getHandle()->Instance == TIM6)
+ return ADC_EXTERNALTRIGINJEC_T6_TRGO;
+#endif
+#ifdef TIM8 // if defined timer 8
+ else if(timer->getHandle()->Instance == TIM8)
+ return ADC_EXTERNALTRIGINJEC_T8_TRGO;
+#endif
+#ifdef TIM15 // if defined timer 15
+ else if(timer->getHandle()->Instance == TIM15)
+ return ADC_EXTERNALTRIGINJEC_T15_TRGO;
+#endif
+ else
+ return _TRGO_NOT_AVAILABLE;
+}
+
+// timer to regular TRGO
+// https://github.com/stm32duino/Arduino_Core_STM32/blob/6588dee03382e73ed42c4a5e473900ab3b79d6e4/system/Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_hal_adc.h#L519
+uint32_t _timerToRegularTRGO(HardwareTimer* timer){
+ if(timer->getHandle()->Instance == TIM1)
+ return ADC_EXTERNALTRIG_T1_TRGO;
+#ifdef TIM2 // if defined timer 2
+ else if(timer->getHandle()->Instance == TIM2)
+ return ADC_EXTERNALTRIG_T2_TRGO;
+#endif
+#ifdef TIM3 // if defined timer 3
+ else if(timer->getHandle()->Instance == TIM3)
+ return ADC_EXTERNALTRIG_T3_TRGO;
+#endif
+#ifdef TIM4 // if defined timer 4
+ else if(timer->getHandle()->Instance == TIM4)
+ return ADC_EXTERNALTRIG_T4_TRGO;
+#endif
+#ifdef TIM6 // if defined timer 6
+ else if(timer->getHandle()->Instance == TIM6)
+ return ADC_EXTERNALTRIG_T6_TRGO;
+#endif
+#ifdef TIM8 // if defined timer 8
+ else if(timer->getHandle()->Instance == TIM8)
+ return ADC_EXTERNALTRIG_T8_TRGO;
+#endif
+#ifdef TIM15 // if defined timer 15
+ else if(timer->getHandle()->Instance == TIM15)
+ return ADC_EXTERNALTRIG_T15_TRGO;
+#endif
+ else
+ return _TRGO_NOT_AVAILABLE;
+}
+
+
+int _adcToIndex(ADC_TypeDef *AdcHandle){
+ if(AdcHandle == ADC1) return 0;
+#ifdef ADC2 // if ADC2 exists
+ else if(AdcHandle == ADC2) return 1;
+#endif
+#ifdef ADC3 // if ADC3 exists
+ else if(AdcHandle == ADC3) return 2;
+#endif
+#ifdef ADC4 // if ADC4 exists
+ else if(AdcHandle == ADC4) return 3;
+#endif
+#ifdef ADC5 // if ADC5 exists
+ else if(AdcHandle == ADC5) return 4;
+#endif
+ return 0;
+}
+int _adcToIndex(ADC_HandleTypeDef *AdcHandle){
+ return _adcToIndex(AdcHandle->Instance);
+}
+
+#endif
\ No newline at end of file
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/hardware_specific/stm32/stm32l4/stm32l4_utils.h b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/hardware_specific/stm32/stm32l4/stm32l4_utils.h
new file mode 100644
index 0000000..ceef9be
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/hardware_specific/stm32/stm32l4/stm32l4_utils.h
@@ -0,0 +1,34 @@
+
+#ifndef STM32L4_UTILS_HAL
+#define STM32L4_UTILS_HAL
+
+#include "Arduino.h"
+
+#if defined(STM32L4xx)
+
+#define _TRGO_NOT_AVAILABLE 12345
+
+
+/* Exported Functions */
+/**
+ * @brief Return ADC HAL channel linked to a PinName
+ * @param pin: PinName
+ * @retval Valid HAL channel
+ */
+uint32_t _getADCChannel(PinName pin);
+
+// timer to injected TRGO
+// https://github.com/stm32duino/Arduino_Core_STM32/blob/6588dee03382e73ed42c4a5e473900ab3b79d6e4/system/Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_hal_adc_ex.h#L217
+uint32_t _timerToInjectedTRGO(HardwareTimer* timer);
+
+// timer to regular TRGO
+// https://github.com/stm32duino/Arduino_Core_STM32/blob/6588dee03382e73ed42c4a5e473900ab3b79d6e4/system/Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_hal_adc.h#L519
+uint32_t _timerToRegularTRGO(HardwareTimer* timer);
+
+// function returning index of the ADC instance
+int _adcToIndex(ADC_HandleTypeDef *AdcHandle);
+int _adcToIndex(ADC_TypeDef *AdcHandle);
+
+#endif
+
+#endif
\ No newline at end of file
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/hardware_specific/teensy/teensy4_mcu.cpp b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/hardware_specific/teensy/teensy4_mcu.cpp
new file mode 100644
index 0000000..3a542b5
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/hardware_specific/teensy/teensy4_mcu.cpp
@@ -0,0 +1,249 @@
+#include "teensy4_mcu.h"
+#include "../../../drivers/hardware_specific/teensy/teensy4_mcu.h"
+// #include "../../../common/lowpass_filter.h"
+#include "../../../common/foc_utils.h"
+#include "../../../communication/SimpleFOCDebug.h"
+
+// if defined
+// - Teensy 4.0
+// - Teensy 4.1
+#if defined(__arm__) && defined(CORE_TEENSY) && ( defined(__IMXRT1062__) || defined(ARDUINO_TEENSY40) || defined(ARDUINO_TEENSY41) || defined(ARDUINO_TEENSY_MICROMOD) )
+
+// #define SIMPLEFOC_TEENSY4_ADC_INTERRUPT_DEBUG
+
+
+volatile uint32_t val0, val1, val2;
+
+// #define _BANDWIDTH_CS 10000.0f // [Hz] bandwidth for the current sense
+// LowPassFilter lp1 = LowPassFilter(1.0/_BANDWIDTH_CS);
+// LowPassFilter lp2 = LowPassFilter(1.0/_BANDWIDTH_CS);
+// LowPassFilter lp3 = LowPassFilter(1.0/_BANDWIDTH_CS);
+
+void read_currents(uint32_t *a, uint32_t*b, uint32_t *c=nullptr){
+ *a = val0;
+ *b = val1;
+ *c = val2;
+}
+
+// interrupt service routine for the ADC_ETC0
+// reading the ADC values and clearing the interrupt
+void adcetc0_isr() {
+#ifdef SIMPLEFOC_TEENSY4_ADC_INTERRUPT_DEBUG
+ digitalWrite(30,HIGH);
+#endif
+ // page 3509 , section 66.5.1.3.3
+ ADC_ETC_DONE0_1_IRQ |= 1; // clear Done0 for trg0 at 1st bit
+ // val0 = lp1(ADC_ETC_TRIG0_RESULT_1_0 & 4095);
+ val0 = (ADC_ETC_TRIG0_RESULT_1_0 & 4095);
+ // val1 = lp2((ADC_ETC_TRIG0_RESULT_1_0 >> 16) & 4095);
+ val1 = (ADC_ETC_TRIG0_RESULT_1_0 >> 16) & 4095;
+#ifdef SIMPLEFOC_TEENSY4_ADC_INTERRUPT_DEBUG
+ digitalWrite(30,LOW);
+#endif
+}
+
+
+void adcetc1_isr() {
+#ifdef SIMPLEFOC_TEENSY4_ADC_INTERRUPT_DEBUG
+ digitalWrite(30,HIGH);
+#endif
+ // page 3509 , section 66.5.1.3.3
+ ADC_ETC_DONE0_1_IRQ |= 1 << 16; // clear Done1 for trg0 at 16th bit
+ val2 = ADC_ETC_TRIG0_RESULT_3_2 & 4095;
+// val2 = lp3( ADC_ETC_TRIG0_RESULT_3_2 & 4095);
+#ifdef SIMPLEFOC_TEENSY4_ADC_INTERRUPT_DEBUG
+ digitalWrite(30,LOW);
+#endif
+}
+
+// function initializing the ADC2
+// and the ADC_ETC trigger for the low side current sensing
+void adc1_init(int pin1, int pin2, int pin3=NOT_SET) {
+ //Tried many configurations, but this seems to be best:
+ ADC1_CFG = ADC_CFG_OVWREN //Allow overwriting of the next converted Data onto the existing
+ | ADC_CFG_ADICLK(0) // input clock select - IPG clock
+ | ADC_CFG_MODE(2) // 12-bit conversion 0 8-bit conversion 1 10-bit conversion 2 12-bit conversion
+ | ADC_CFG_ADIV(2) // Input clock / 2 (0 for /1, 1 for /2 and 2 for / 4) (1 is faster and maybe with some filtering could provide better results but 2 for now)
+ | ADC_CFG_ADSTS(0) // Sample period (ADC clocks) = 3 if ADLSMP=0b
+ | ADC_CFG_ADHSC // High speed operation
+ | ADC_CFG_ADTRG; // Hardware trigger selected
+
+
+ //Calibration of ADC1
+ ADC1_GC |= ADC_GC_CAL; // begin cal ADC1
+ while (ADC1_GC & ADC_GC_CAL) ;
+
+ ADC1_HC0 = 16; // ADC_ETC channel
+ // use the second interrupt if necessary (for more than 2 channels)
+ if(_isset(pin3)) {
+ ADC1_HC1 = 16;
+ }
+}
+
+// function initializing the ADC2
+// and the ADC_ETC trigger for the low side current sensing
+void adc2_init(){
+
+ // configuring ADC2
+ //Tried many configurations, but this seems to be best:
+ ADC1_CFG = ADC_CFG_OVWREN //Allow overwriting of the next converted Data onto the existing
+ | ADC_CFG_ADICLK(0) // input clock select - IPG clock
+ | ADC_CFG_MODE(2) // 12-bit conversion 0 8-bit conversion 1 10-bit conversion 2 12-bit conversion
+ | ADC_CFG_ADIV(2) // Input clock / 2 (0 for /1, 1 for /2 and 2 for / 4)
+ | ADC_CFG_ADSTS(0) // Sample period (ADC clocks) = 3 if ADLSMP=0b
+ | ADC_CFG_ADHSC // High speed operation
+ | ADC_CFG_ADTRG; // Hardware trigger selected
+
+ //Calibration of ADC2
+ ADC2_GC |= ADC_GC_CAL; // begin cal ADC2
+ while (ADC2_GC & ADC_GC_CAL) ;
+
+ ADC2_HC0 = 16; // ADC_ETC channel
+ // use the second interrupt if necessary (for more than 2 channels)
+ // ADC2_HC1 = 16;
+}
+
+// function initializing the ADC_ETC trigger for the low side current sensing
+// it uses only the ADC1
+// if the pin3 is not set it uses only 2 channels
+void adc_etc_init(int pin1, int pin2, int pin3=NOT_SET) {
+ ADC_ETC_CTRL &= ~(1 << 31); // SOFTRST
+ ADC_ETC_CTRL = 0x40000001; // start with trigger 0
+ ADC_ETC_TRIG0_CTRL = ADC_ETC_TRIG_CTRL_TRIG_CHAIN( _isset(pin3) ? 2 : 1) ; // 2 if 3 channels, 1 if 2 channels
+
+ // ADC1 7 8, chain channel, HWTS, IE, B2B
+ // pg 3516, section 66.5.1.8
+ ADC_ETC_TRIG0_CHAIN_1_0 =
+ ADC_ETC_TRIG_CHAIN_IE1(0) | // no interrupt on first or set 2 if interrupt when Done1
+ ADC_ETC_TRIG_CHAIN_B2B1 | // Enable B2B, back to back ADC trigger
+ ADC_ETC_TRIG_CHAIN_HWTS1(1) |
+ ADC_ETC_TRIG_CHAIN_CSEL1(pin_to_channel[pin1]) | // ADC channel 8
+ ADC_ETC_TRIG_CHAIN_IE0(1) | // interrupt when Done0
+ ADC_ETC_TRIG_CHAIN_B2B1 | // Enable B2B, back to back ADC trigger
+ ADC_ETC_TRIG_CHAIN_HWTS0(1) |
+ ADC_ETC_TRIG_CHAIN_CSEL0(pin_to_channel[pin2]); // ADC channel 7
+
+ attachInterruptVector(IRQ_ADC_ETC0, adcetc0_isr);
+ NVIC_ENABLE_IRQ(IRQ_ADC_ETC0);
+ // use the second interrupt if necessary (for more than 2 channels)
+ if(_isset(pin3)) {
+ ADC_ETC_TRIG0_CHAIN_3_2 =
+ ADC_ETC_TRIG_CHAIN_IE0(2) | // interrupt when Done1
+ ADC_ETC_TRIG_CHAIN_B2B0 | // Enable B2B, back to back ADC trigger
+ ADC_ETC_TRIG_CHAIN_HWTS0(1) |
+ ADC_ETC_TRIG_CHAIN_CSEL0(pin_to_channel[pin3]);
+
+ attachInterruptVector(IRQ_ADC_ETC1, adcetc1_isr);
+ NVIC_ENABLE_IRQ(IRQ_ADC_ETC1);
+ }
+}
+
+
+
+// function reading an ADC value and returning the read voltage
+float _readADCVoltageLowSide(const int pinA, const void* cs_params){
+
+ if(!_isset(pinA)) return 0.0; // if the pin is not set return 0
+ GenericCurrentSenseParams* params = (GenericCurrentSenseParams*) cs_params;
+ float adc_voltage_conv = params->adc_voltage_conv;
+ if (pinA == params->pins[0]) {
+ return val0 * adc_voltage_conv;
+ } else if (pinA == params->pins[1]) {
+ return val1 * adc_voltage_conv;
+ }else if (pinA == params->pins[2]) {
+ return val2 * adc_voltage_conv;
+ }
+ return 0.0;
+}
+
+// Configure low side for generic mcu
+// cannot do much but
+void* _configureADCLowSide(const void* driver_params, const int pinA,const int pinB,const int pinC){
+ Teensy4DriverParams* par = (Teensy4DriverParams*) ((TeensyDriverParams*)driver_params)->additional_params;
+ if(par == nullptr){
+ SIMPLEFOC_DEBUG("TEENSY-CS: Low side current sense failed, driver not supported!");
+ return SIMPLEFOC_CURRENT_SENSE_INIT_FAILED;
+ }
+
+ SIMPLEFOC_DEBUG("TEENSY-CS: Configuring low side current sense!");
+
+#ifdef SIMPLEFOC_TEENSY4_ADC_INTERRUPT_DEBUG
+ pinMode(30,OUTPUT);
+#endif
+
+ if( _isset(pinA) ) pinMode(pinA, INPUT);
+ if( _isset(pinB) ) pinMode(pinB, INPUT);
+ if( _isset(pinC) ) pinMode(pinC, INPUT);
+
+ // check if either of the pins are not set
+ // and dont use it if it isn't
+ int pin_count = 0;
+ int pins[3] = {NOT_SET, NOT_SET, NOT_SET};
+ if(_isset(pinA)) pins[pin_count++] = pinA;
+ if(_isset(pinB)) pins[pin_count++] = pinB;
+ if(_isset(pinC)) pins[pin_count++] = pinC;
+
+
+ adc1_init(pins[0], pins[1], pins[2]);
+ adc_etc_init(pins[0], pins[1], pins[2]);
+
+ xbar_init();
+
+ GenericCurrentSenseParams* params = new GenericCurrentSenseParams {
+ .pins = {pins[0], pins[1], pins[2] },
+ .adc_voltage_conv = (_ADC_VOLTAGE)/(_ADC_RESOLUTION)
+ };
+ return params;
+}
+
+// sync driver and the adc
+void* _driverSyncLowSide(void* driver_params, void* cs_params){
+ Teensy4DriverParams* par = (Teensy4DriverParams*) ((TeensyDriverParams*)driver_params)->additional_params;
+ IMXRT_FLEXPWM_t* flexpwm = par->flextimers[0];
+ int submodule = par->submodules[0];
+
+ SIMPLEFOC_DEBUG("TEENSY-CS: Syncing low side current sense!");
+ char buff[50];
+ sprintf(buff, "TEENSY-CS: Syncing to FlexPWM: %d, Submodule: %d", flexpwm_to_index(flexpwm), submodule);
+ SIMPLEFOC_DEBUG(buff);
+
+ // find the xbar trigger for the flexpwm
+ int xbar_trig_pwm = flexpwm_submodule_to_trig(flexpwm, submodule);
+ if(xbar_trig_pwm<0) return;
+
+ // allow theFlexPWM to trigger the ADC_ETC
+ xbar_connect((uint32_t)xbar_trig_pwm, XBARA1_OUT_ADC_ETC_TRIG00); //FlexPWM to adc_etc
+
+ // setup the ADC_ETC trigger to be triggered by the FlexPWM channel 1 (val1)
+ //This val1 interrupt on match is in the center of the PWM
+ flexpwm->SM[submodule].TCTRL = FLEXPWM_SMTCTRL_OUT_TRIG_EN(1<<1);
+
+
+ // if needed the interrupt can be moved to some other point in the PWM cycle by using an addional val register example: VAL4
+ // setup the ADC_ETC trigger to be triggered by the FlexPWM channel 4 (val4)
+ // flexpwm->SM[submodule].TCTRL = FLEXPWM_SMTCTRL_OUT_TRIG_EN(1<<4);
+ // setup this val4 for interrupt on match for ADC sync
+ // this code assumes that the val4 is not used for anything else!
+ // reading two ADC takes about 2.5us. So put the interrupt 2.5us befor the center
+ // flexpwm->SM[submodule].VAL4 = int(flexpwm->SM[submodule].VAL1*(1.0f - 2.5e-6*par->pwm_frequency)) ; // 2.5us before center
+
+
+#ifdef SIMPLEFOC_TEENSY4_ADC_INTERRUPT_DEBUG
+ // pin 4 observes out trigger line for 'scope
+ xbar_connect (xbar_trig_pwm, XBARA1_OUT_IOMUX_XBAR_INOUT08) ;
+ IOMUXC_GPR_GPR6 |= IOMUXC_GPR_GPR6_IOMUXC_XBAR_DIR_SEL_8 ; // select output mode for INOUT8
+ // Select alt 3 for EMC_06 (XBAR), rather than original 5 (GPIO)
+ CORE_PIN4_CONFIG = 3 ; // shorthand for IOMUXC_SW_MUX_CTL_PAD_GPIO_EMC_06 = 3 ;
+ // turn up drive & speed as very short pulse
+ IOMUXC_SW_PAD_CTL_PAD_GPIO_EMC_06 = IOMUXC_PAD_DSE(7) | IOMUXC_PAD_SPEED(3) | IOMUXC_PAD_SRE ;
+#endif
+
+
+ // return the cs parameters
+ // successfully initialized
+ // TODO verify if success in future
+ return cs_params;
+}
+
+
+#endif
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/hardware_specific/teensy/teensy4_mcu.h b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/hardware_specific/teensy/teensy4_mcu.h
new file mode 100644
index 0000000..2cf77df
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/hardware_specific/teensy/teensy4_mcu.h
@@ -0,0 +1,77 @@
+
+#ifndef TEENSY4_CURRENTSENSE_MCU_DEF
+#define TEENSY4_CURRENTSENSE_MCU_DEF
+
+#include "../../hardware_api.h"
+#include "../../../common/foc_utils.h"
+
+// if defined
+// - Teensy 4.0
+// - Teensy 4.1
+#if defined(__arm__) && defined(CORE_TEENSY) && ( defined(__IMXRT1062__) || defined(ARDUINO_TEENSY40) || defined(ARDUINO_TEENSY41) || defined(ARDUINO_TEENSY_MICROMOD) )
+
+#define _ADC_VOLTAGE 3.3f
+#define _ADC_RESOLUTION 4026.0f
+
+// generic implementation of the hardware specific structure
+// containing all the necessary current sense parameters
+// will be returned as a void pointer from the _configureADCx functions
+// will be provided to the _readADCVoltageX() as a void pointer
+typedef struct Teensy4CurrentSenseParams {
+ int pins[3] = {(int)NOT_SET};
+ float adc_voltage_conv;
+} Teensy4CurrentSenseParams;
+
+
+
+const uint8_t pin_to_channel[] = { // pg 482
+ 7, // 0/A0 AD_B1_02
+ 8, // 1/A1 AD_B1_03
+ 12, // 2/A2 AD_B1_07
+ 11, // 3/A3 AD_B1_06
+ 6, // 4/A4 AD_B1_01
+ 5, // 5/A5 AD_B1_00
+ 15, // 6/A6 AD_B1_10
+ 0, // 7/A7 AD_B1_11
+ 13, // 8/A8 AD_B1_08
+ 14, // 9/A9 AD_B1_09
+ 1, // 24/A10 AD_B0_12
+ 2, // 25/A11 AD_B0_13
+ 128+3, // 26/A12 AD_B1_14 - only on ADC2, 3
+ 128+4, // 27/A13 AD_B1_15 - only on ADC2, 4
+ 7, // 14/A0 AD_B1_02
+ 8, // 15/A1 AD_B1_03
+ 12, // 16/A2 AD_B1_07
+ 11, // 17/A3 AD_B1_06
+ 6, // 18/A4 AD_B1_01
+ 5, // 19/A5 AD_B1_00
+ 15, // 20/A6 AD_B1_10
+ 0, // 21/A7 AD_B1_11
+ 13, // 22/A8 AD_B1_08
+ 14, // 23/A9 AD_B1_09
+ 1, // 24/A10 AD_B0_12
+ 2, // 25/A11 AD_B0_13
+ 128+3, // 26/A12 AD_B1_14 - only on ADC2, 3
+ 128+4, // 27/A13 AD_B1_15 - only on ADC2, 4
+#ifdef ARDUINO_TEENSY41
+ 255, // 28
+ 255, // 29
+ 255, // 30
+ 255, // 31
+ 255, // 32
+ 255, // 33
+ 255, // 34
+ 255, // 35
+ 255, // 36
+ 255, // 37
+ 128+1, // 38/A14 AD_B1_12 - only on ADC2, 1
+ 128+2, // 39/A15 AD_B1_13 - only on ADC2, 2
+ 9, // 40/A16 AD_B1_04
+ 10, // 41/A17 AD_B1_05
+#endif
+};
+
+
+#endif
+
+#endif
\ No newline at end of file
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/hardware_specific/teensy/teensy_mcu.cpp b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/hardware_specific/teensy/teensy_mcu.cpp
new file mode 100644
index 0000000..7669edc
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/current_sense/hardware_specific/teensy/teensy_mcu.cpp
@@ -0,0 +1,24 @@
+#include "../../hardware_api.h"
+
+#if defined(__arm__) && defined(CORE_TEENSY)
+
+#define _ADC_VOLTAGE 3.3f
+#define _ADC_RESOLUTION 1024.0f
+
+// function reading an ADC value and returning the read voltage
+void* _configureADCInline(const void* driver_params, const int pinA,const int pinB,const int pinC){
+ _UNUSED(driver_params);
+
+ if( _isset(pinA) ) pinMode(pinA, INPUT);
+ if( _isset(pinB) ) pinMode(pinB, INPUT);
+ if( _isset(pinC) ) pinMode(pinC, INPUT);
+
+ GenericCurrentSenseParams* params = new GenericCurrentSenseParams {
+ .pins = { pinA, pinB, pinC },
+ .adc_voltage_conv = (_ADC_VOLTAGE)/(_ADC_RESOLUTION)
+ };
+
+ return params;
+}
+
+#endif
\ No newline at end of file
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/drivers/BLDCDriver3PWM.cpp b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/drivers/BLDCDriver3PWM.cpp
new file mode 100644
index 0000000..637c8db
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/drivers/BLDCDriver3PWM.cpp
@@ -0,0 +1,92 @@
+#include "BLDCDriver3PWM.h"
+
+BLDCDriver3PWM::BLDCDriver3PWM(int phA, int phB, int phC, int en1, int en2, int en3){
+ // Pin initialization
+ pwmA = phA;
+ pwmB = phB;
+ pwmC = phC;
+
+ // enable_pin pin
+ enableA_pin = en1;
+ enableB_pin = en2;
+ enableC_pin = en3;
+
+ // default power-supply value
+ voltage_power_supply = DEF_POWER_SUPPLY;
+ voltage_limit = NOT_SET;
+ pwm_frequency = NOT_SET;
+
+}
+
+// enable motor driver
+void BLDCDriver3PWM::enable(){
+ // enable_pin the driver - if enable_pin pin available
+ if ( _isset(enableA_pin) ) digitalWrite(enableA_pin, enable_active_high);
+ if ( _isset(enableB_pin) ) digitalWrite(enableB_pin, enable_active_high);
+ if ( _isset(enableC_pin) ) digitalWrite(enableC_pin, enable_active_high);
+ // set zero to PWM
+ setPwm(0,0,0);
+}
+
+// disable motor driver
+void BLDCDriver3PWM::disable()
+{
+ // set zero to PWM
+ setPwm(0, 0, 0);
+ // disable the driver - if enable_pin pin available
+ if ( _isset(enableA_pin) ) digitalWrite(enableA_pin, !enable_active_high);
+ if ( _isset(enableB_pin) ) digitalWrite(enableB_pin, !enable_active_high);
+ if ( _isset(enableC_pin) ) digitalWrite(enableC_pin, !enable_active_high);
+
+}
+
+// init hardware pins
+int BLDCDriver3PWM::init() {
+ // PWM pins
+ pinMode(pwmA, OUTPUT);
+ pinMode(pwmB, OUTPUT);
+ pinMode(pwmC, OUTPUT);
+ if( _isset(enableA_pin)) pinMode(enableA_pin, OUTPUT);
+ if( _isset(enableB_pin)) pinMode(enableB_pin, OUTPUT);
+ if( _isset(enableC_pin)) pinMode(enableC_pin, OUTPUT);
+
+
+ // sanity check for the voltage limit configuration
+ if(!_isset(voltage_limit) || voltage_limit > voltage_power_supply) voltage_limit = voltage_power_supply;
+
+ // Set the pwm frequency to the pins
+ // hardware specific function - depending on driver and mcu
+ params = _configure3PWM(pwm_frequency, pwmA, pwmB, pwmC);
+ initialized = (params!=SIMPLEFOC_DRIVER_INIT_FAILED);
+ return params!=SIMPLEFOC_DRIVER_INIT_FAILED;
+}
+
+
+
+// Set voltage to the pwm pin
+void BLDCDriver3PWM::setPhaseState(PhaseState sa, PhaseState sb, PhaseState sc) {
+ // disable if needed
+ if( _isset(enableA_pin) && _isset(enableB_pin) && _isset(enableC_pin) ){
+ digitalWrite(enableA_pin, sa == PhaseState::PHASE_ON ? enable_active_high:!enable_active_high);
+ digitalWrite(enableB_pin, sb == PhaseState::PHASE_ON ? enable_active_high:!enable_active_high);
+ digitalWrite(enableC_pin, sc == PhaseState::PHASE_ON ? enable_active_high:!enable_active_high);
+ }
+}
+
+// Set voltage to the pwm pin
+void BLDCDriver3PWM::setPwm(float Ua, float Ub, float Uc) {
+
+ // limit the voltage in driver
+ Ua = _constrain(Ua, 0.0f, voltage_limit);
+ Ub = _constrain(Ub, 0.0f, voltage_limit);
+ Uc = _constrain(Uc, 0.0f, voltage_limit);
+ // calculate duty cycle
+ // limited in [0,1]
+ dc_a = _constrain(Ua / voltage_power_supply, 0.0f , 1.0f );
+ dc_b = _constrain(Ub / voltage_power_supply, 0.0f , 1.0f );
+ dc_c = _constrain(Uc / voltage_power_supply, 0.0f , 1.0f );
+
+ // hardware specific writing
+ // hardware specific function - depending on driver and mcu
+ _writeDutyCycle3PWM(dc_a, dc_b, dc_c, params);
+}
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/drivers/BLDCDriver3PWM.h b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/drivers/BLDCDriver3PWM.h
new file mode 100644
index 0000000..75ee478
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/drivers/BLDCDriver3PWM.h
@@ -0,0 +1,64 @@
+#ifndef BLDCDriver3PWM_h
+#define BLDCDriver3PWM_h
+
+#include "../common/base_classes/BLDCDriver.h"
+#include "../common/foc_utils.h"
+#include "../common/time_utils.h"
+#include "../common/defaults.h"
+#include "hardware_api.h"
+
+/**
+ 3 pwm bldc driver class
+*/
+class BLDCDriver3PWM: public BLDCDriver
+{
+ public:
+ /**
+ BLDCDriver class constructor
+ @param phA A phase pwm pin
+ @param phB B phase pwm pin
+ @param phC C phase pwm pin
+ @param en1 enable pin (optional input)
+ @param en2 enable pin (optional input)
+ @param en3 enable pin (optional input)
+ */
+ BLDCDriver3PWM(int phA,int phB,int phC, int en1 = NOT_SET, int en2 = NOT_SET, int en3 = NOT_SET);
+
+ /** Motor hardware init function */
+ int init() override;
+ /** Motor disable function */
+ void disable() override;
+ /** Motor enable function */
+ void enable() override;
+
+ // hardware variables
+ int pwmA; //!< phase A pwm pin number
+ int pwmB; //!< phase B pwm pin number
+ int pwmC; //!< phase C pwm pin number
+ int enableA_pin; //!< enable pin number
+ int enableB_pin; //!< enable pin number
+ int enableC_pin; //!< enable pin number
+
+ /**
+ * Set phase voltages to the hardware
+ *
+ * @param Ua - phase A voltage
+ * @param Ub - phase B voltage
+ * @param Uc - phase C voltage
+ */
+ void setPwm(float Ua, float Ub, float Uc) override;
+
+ /**
+ * Set phase voltages to the hardware
+ * > Only possible is the driver has separate enable pins for all phases!
+ *
+ * @param sc - phase A state : active / disabled ( high impedance )
+ * @param sb - phase B state : active / disabled ( high impedance )
+ * @param sa - phase C state : active / disabled ( high impedance )
+ */
+ virtual void setPhaseState(PhaseState sa, PhaseState sb, PhaseState sc) override;
+ private:
+};
+
+
+#endif
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/drivers/BLDCDriver6PWM.cpp b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/drivers/BLDCDriver6PWM.cpp
new file mode 100644
index 0000000..4981858
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/drivers/BLDCDriver6PWM.cpp
@@ -0,0 +1,103 @@
+#include "BLDCDriver6PWM.h"
+
+BLDCDriver6PWM::BLDCDriver6PWM(int phA_h,int phA_l,int phB_h,int phB_l,int phC_h,int phC_l, int en){
+ // Pin initialization
+ pwmA_h = phA_h;
+ pwmB_h = phB_h;
+ pwmC_h = phC_h;
+ pwmA_l = phA_l;
+ pwmB_l = phB_l;
+ pwmC_l = phC_l;
+
+ // enable_pin pin
+ enable_pin = en;
+
+ // default power-supply value
+ voltage_power_supply = DEF_POWER_SUPPLY;
+ voltage_limit = NOT_SET;
+ pwm_frequency = NOT_SET;
+
+ // dead zone initial - 2%
+ dead_zone = 0.02f;
+
+}
+
+// enable motor driver
+void BLDCDriver6PWM::enable(){
+ // enable_pin the driver - if enable_pin pin available
+ if ( _isset(enable_pin) ) digitalWrite(enable_pin, enable_active_high);
+ // set phase state enabled
+ setPhaseState(PhaseState::PHASE_ON, PhaseState::PHASE_ON, PhaseState::PHASE_ON);
+ // set zero to PWM
+ setPwm(0, 0, 0);
+}
+
+// disable motor driver
+void BLDCDriver6PWM::disable()
+{
+ // set phase state to disabled
+ setPhaseState(PhaseState::PHASE_OFF, PhaseState::PHASE_OFF, PhaseState::PHASE_OFF);
+ // set zero to PWM
+ setPwm(0, 0, 0);
+ // disable the driver - if enable_pin pin available
+ if ( _isset(enable_pin) ) digitalWrite(enable_pin, !enable_active_high);
+
+}
+
+// init hardware pins
+int BLDCDriver6PWM::init() {
+
+ // PWM pins
+ pinMode(pwmA_h, OUTPUT);
+ pinMode(pwmB_h, OUTPUT);
+ pinMode(pwmC_h, OUTPUT);
+ pinMode(pwmA_l, OUTPUT);
+ pinMode(pwmB_l, OUTPUT);
+ pinMode(pwmC_l, OUTPUT);
+ if(_isset(enable_pin)) pinMode(enable_pin, OUTPUT);
+
+
+ // sanity check for the voltage limit configuration
+ if( !_isset(voltage_limit) || voltage_limit > voltage_power_supply) voltage_limit = voltage_power_supply;
+
+ // set phase state to disabled
+ phase_state[0] = PhaseState::PHASE_OFF;
+ phase_state[1] = PhaseState::PHASE_OFF;
+ phase_state[2] = PhaseState::PHASE_OFF;
+
+ // set zero to PWM
+ dc_a = dc_b = dc_c = 0;
+
+ // configure 6pwm
+ // hardware specific function - depending on driver and mcu
+ params = _configure6PWM(pwm_frequency, dead_zone, pwmA_h,pwmA_l, pwmB_h,pwmB_l, pwmC_h,pwmC_l);
+ initialized = (params!=SIMPLEFOC_DRIVER_INIT_FAILED);
+ return params!=SIMPLEFOC_DRIVER_INIT_FAILED;
+}
+
+
+// Set voltage to the pwm pin
+void BLDCDriver6PWM::setPwm(float Ua, float Ub, float Uc) {
+ // limit the voltage in driver
+ Ua = _constrain(Ua, 0, voltage_limit);
+ Ub = _constrain(Ub, 0, voltage_limit);
+ Uc = _constrain(Uc, 0, voltage_limit);
+ // calculate duty cycle
+ // limited in [0,1]
+ dc_a = _constrain(Ua / voltage_power_supply, 0.0f , 1.0f );
+ dc_b = _constrain(Ub / voltage_power_supply, 0.0f , 1.0f );
+ dc_c = _constrain(Uc / voltage_power_supply, 0.0f , 1.0f );
+ // hardware specific writing
+ // hardware specific function - depending on driver and mcu
+ _writeDutyCycle6PWM(dc_a, dc_b, dc_c, phase_state, params);
+}
+
+
+// Set the phase state
+// actually changing the state is only done on the next call to setPwm, and depends
+// on the hardware capabilities of the driver and MCU.
+void BLDCDriver6PWM::setPhaseState(PhaseState sa, PhaseState sb, PhaseState sc) {
+ phase_state[0] = sa;
+ phase_state[1] = sb;
+ phase_state[2] = sc;
+}
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/drivers/BLDCDriver6PWM.h b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/drivers/BLDCDriver6PWM.h
new file mode 100644
index 0000000..7ba7631
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/drivers/BLDCDriver6PWM.h
@@ -0,0 +1,69 @@
+#ifndef BLDCDriver6PWM_h
+#define BLDCDriver6PWM_h
+
+#include "../common/base_classes/BLDCDriver.h"
+#include "../common/foc_utils.h"
+#include "../common/time_utils.h"
+#include "../common/defaults.h"
+#include "hardware_api.h"
+
+/**
+ 6 pwm bldc driver class
+*/
+class BLDCDriver6PWM: public BLDCDriver
+{
+ public:
+ /**
+ BLDCDriver class constructor
+ @param phA_h A phase pwm pin
+ @param phA_l A phase pwm pin
+ @param phB_h B phase pwm pin
+ @param phB_l A phase pwm pin
+ @param phC_h C phase pwm pin
+ @param phC_l A phase pwm pin
+ @param en enable pin (optional input)
+ */
+ BLDCDriver6PWM(int phA_h,int phA_l,int phB_h,int phB_l,int phC_h,int phC_l, int en = NOT_SET);
+
+ /** Motor hardware init function */
+ int init() override;
+ /** Motor disable function */
+ void disable() override;
+ /** Motor enable function */
+ void enable() override;
+
+ // hardware variables
+ int pwmA_h,pwmA_l; //!< phase A pwm pin number
+ int pwmB_h,pwmB_l; //!< phase B pwm pin number
+ int pwmC_h,pwmC_l; //!< phase C pwm pin number
+ int enable_pin; //!< enable pin number
+
+ float dead_zone; //!< a percentage of dead-time(zone) (both high and low side in low) for each pwm cycle [0,1]
+
+ PhaseState phase_state[3]; //!< phase state (active / disabled)
+
+
+ /**
+ * Set phase voltages to the harware
+ *
+ * @param Ua - phase A voltage
+ * @param Ub - phase B voltage
+ * @param Uc - phase C voltage
+ */
+ void setPwm(float Ua, float Ub, float Uc) override;
+
+ /**
+ * Set phase voltages to the harware
+ *
+ * @param sc - phase A state : active / disabled ( high impedance )
+ * @param sb - phase B state : active / disabled ( high impedance )
+ * @param sa - phase C state : active / disabled ( high impedance )
+ */
+ virtual void setPhaseState(PhaseState sa, PhaseState sb, PhaseState sc) override;
+
+ private:
+
+};
+
+
+#endif
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/drivers/StepperDriver2PWM.cpp b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/drivers/StepperDriver2PWM.cpp
new file mode 100644
index 0000000..e8ccc6c
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/drivers/StepperDriver2PWM.cpp
@@ -0,0 +1,115 @@
+#include "StepperDriver2PWM.h"
+
+StepperDriver2PWM::StepperDriver2PWM(int _pwm1, int* _in1, int _pwm2, int* _in2, int en1, int en2){
+ // Pin initialization
+ pwm1 = _pwm1; // phase 1 pwm pin number
+ dir1a = _in1[0]; // phase 1 INA pin number
+ dir1b = _in1[1]; // phase 1 INB pin number
+ pwm2 = _pwm2; // phase 2 pwm pin number
+ dir2a = _in2[0]; // phase 2 INA pin number
+ dir2b = _in2[1]; // phase 2 INB pin number
+
+ // enable_pin pin
+ enable_pin1 = en1;
+ enable_pin2 = en2;
+
+ // default power-supply value
+ voltage_power_supply = DEF_POWER_SUPPLY;
+ voltage_limit = NOT_SET;
+ pwm_frequency = NOT_SET;
+
+}
+
+StepperDriver2PWM::StepperDriver2PWM(int _pwm1, int _dir1, int _pwm2, int _dir2, int en1, int en2){
+ // Pin initialization
+ pwm1 = _pwm1; // phase 1 pwm pin number
+ dir1a = _dir1; // phase 1 direction pin
+ pwm2 = _pwm2; // phase 2 pwm pin number
+ dir2a = _dir2; // phase 2 direction pin
+ // these pins are not used
+ dir1b = NOT_SET;
+ dir2b = NOT_SET;
+
+ // enable_pin pin
+ enable_pin1 = en1;
+ enable_pin2 = en2;
+
+ // default power-supply value
+ voltage_power_supply = DEF_POWER_SUPPLY;
+ voltage_limit = NOT_SET;
+ pwm_frequency = NOT_SET;
+
+}
+
+// enable motor driver
+void StepperDriver2PWM::enable(){
+ // enable_pin the driver - if enable_pin pin available
+ if ( _isset(enable_pin1) ) digitalWrite(enable_pin1, enable_active_high);
+ if ( _isset(enable_pin2) ) digitalWrite(enable_pin2, enable_active_high);
+ // set zero to PWM
+ setPwm(0,0);
+}
+
+// disable motor driver
+void StepperDriver2PWM::disable()
+{
+ // set zero to PWM
+ setPwm(0, 0);
+ // disable the driver - if enable_pin pin available
+ if ( _isset(enable_pin1) ) digitalWrite(enable_pin1, !enable_active_high);
+ if ( _isset(enable_pin2) ) digitalWrite(enable_pin2, !enable_active_high);
+
+}
+
+// init hardware pins
+int StepperDriver2PWM::init() {
+ // PWM pins
+ pinMode(pwm1, OUTPUT);
+ pinMode(pwm2, OUTPUT);
+ pinMode(dir1a, OUTPUT);
+ pinMode(dir2a, OUTPUT);
+ if( _isset(dir1b) ) pinMode(dir1b, OUTPUT);
+ if( _isset(dir2b) ) pinMode(dir2b, OUTPUT);
+
+ if( _isset(enable_pin1) ) pinMode(enable_pin1, OUTPUT);
+ if( _isset(enable_pin2) ) pinMode(enable_pin2, OUTPUT);
+
+ // sanity check for the voltage limit configuration
+ if( !_isset(voltage_limit) || voltage_limit > voltage_power_supply) voltage_limit = voltage_power_supply;
+
+ // Set the pwm frequency to the pins
+ // hardware specific function - depending on driver and mcu
+ params = _configure2PWM(pwm_frequency, pwm1, pwm2);
+ initialized = (params!=SIMPLEFOC_DRIVER_INIT_FAILED);
+ return params!=SIMPLEFOC_DRIVER_INIT_FAILED;
+}
+
+// Set voltage to the pwm pin
+void StepperDriver2PWM::setPhaseState(PhaseState sa, PhaseState sb) {
+ // disable if needed
+ if( _isset(enable_pin1) && _isset(enable_pin2)){
+ digitalWrite(enable_pin1, sa == PhaseState::PHASE_ON ? enable_active_high:!enable_active_high);
+ digitalWrite(enable_pin2, sb == PhaseState::PHASE_ON ? enable_active_high:!enable_active_high);
+ }
+}
+
+// Set voltage to the pwm pin
+void StepperDriver2PWM::setPwm(float Ua, float Ub) {
+ float duty_cycle1(0.0f),duty_cycle2(0.0f);
+ // limit the voltage in driver
+ Ua = _constrain(Ua, -voltage_limit, voltage_limit);
+ Ub = _constrain(Ub, -voltage_limit, voltage_limit);
+ // hardware specific writing
+ duty_cycle1 = _constrain(abs(Ua)/voltage_power_supply,0.0f,1.0f);
+ duty_cycle2 = _constrain(abs(Ub)/voltage_power_supply,0.0f,1.0f);
+
+ // phase 1 direction
+ digitalWrite(dir1a, Ua >= 0 ? LOW : HIGH);
+ if( _isset(dir1b) ) digitalWrite(dir1b, Ua >= 0 ? HIGH : LOW );
+ // phase 2 direction
+ digitalWrite(dir2a, Ub >= 0 ? LOW : HIGH);
+ if( _isset(dir2b) ) digitalWrite(dir2b, Ub >= 0 ? HIGH : LOW );
+
+ // write to hardware
+ _writeDutyCycle2PWM(duty_cycle1, duty_cycle2, params);
+}
\ No newline at end of file
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/drivers/StepperDriver2PWM.h b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/drivers/StepperDriver2PWM.h
new file mode 100644
index 0000000..1bd00db
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/drivers/StepperDriver2PWM.h
@@ -0,0 +1,77 @@
+#ifndef STEPPER_DRIVER_2PWM_h
+#define STEPPER_DRIVER_2PWM_h
+
+#include "../common/base_classes/StepperDriver.h"
+#include "../common/foc_utils.h"
+#include "../common/time_utils.h"
+#include "../common/defaults.h"
+#include "hardware_api.h"
+
+/**
+ 2 pwm stepper driver class
+*/
+class StepperDriver2PWM: public StepperDriver
+{
+ public:
+ /**
+ StepperMotor class constructor
+ @param pwm1 PWM1 phase pwm pin
+ @param in1 IN1A phase dir pin
+ @param pwm2 PWM2 phase pwm pin
+ @param in2 IN2A phase dir
+ @param en1 enable pin phase 1 (optional input)
+ @param en2 enable pin phase 2 (optional input)
+ */
+ StepperDriver2PWM(int pwm1, int* in1, int pwm2, int* in2, int en1 = NOT_SET, int en2 = NOT_SET);
+
+ /**
+ StepperMotor class constructor
+ @param pwm1 PWM1 phase pwm pin
+ @param dir1 DIR1 phase dir pin
+ @param pwm2 PWM2 phase pwm pin
+ @param dir2 DIR2 phase dir pin
+ @param en1 enable pin phase 1 (optional input)
+ @param en2 enable pin phase 2 (optional input)
+ */
+ StepperDriver2PWM(int pwm1, int dir1, int pwm2, int dir2, int en1 = NOT_SET, int en2 = NOT_SET);
+
+ /** Motor hardware init function */
+ int init() override;
+ /** Motor disable function */
+ void disable() override;
+ /** Motor enable function */
+ void enable() override;
+
+ // hardware variables
+ int pwm1; //!< phase 1 pwm pin number
+ int dir1a; //!< phase 1 INA pin number
+ int dir1b; //!< phase 1 INB pin number
+ int pwm2; //!< phase 2 pwm pin number
+ int dir2a; //!< phase 2 INA pin number
+ int dir2b; //!< phase 2 INB pin number
+ int enable_pin1; //!< enable pin number phase 1
+ int enable_pin2; //!< enable pin number phase 2
+
+ /**
+ * Set phase voltages to the harware
+ *
+ * @param Ua phase A voltage
+ * @param Ub phase B voltage
+ */
+ void setPwm(float Ua, float Ub) override;
+
+ /**
+ * Set phase voltages to the hardware
+ * > Only possible is the driver has separate enable pins for both phases!
+ *
+ * @param sa phase A state : active / disabled ( high impedance )
+ * @param sb phase B state : active / disabled ( high impedance )
+ */
+ virtual void setPhaseState(PhaseState sa, PhaseState sb) override;
+
+ private:
+
+};
+
+
+#endif
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/drivers/StepperDriver4PWM.cpp b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/drivers/StepperDriver4PWM.cpp
new file mode 100644
index 0000000..52f1c1d
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/drivers/StepperDriver4PWM.cpp
@@ -0,0 +1,90 @@
+#include "StepperDriver4PWM.h"
+
+StepperDriver4PWM::StepperDriver4PWM(int ph1A,int ph1B,int ph2A,int ph2B,int en1, int en2){
+ // Pin initialization
+ pwm1A = ph1A;
+ pwm1B = ph1B;
+ pwm2A = ph2A;
+ pwm2B = ph2B;
+
+ // enable_pin pin
+ enable_pin1 = en1;
+ enable_pin2 = en2;
+
+ // default power-supply value
+ voltage_power_supply = DEF_POWER_SUPPLY;
+ voltage_limit = NOT_SET;
+ pwm_frequency = NOT_SET;
+
+}
+
+// enable motor driver
+void StepperDriver4PWM::enable(){
+ // enable_pin the driver - if enable_pin pin available
+ if ( _isset(enable_pin1) ) digitalWrite(enable_pin1, enable_active_high);
+ if ( _isset(enable_pin2) ) digitalWrite(enable_pin2, enable_active_high);
+ // set zero to PWM
+ setPwm(0,0);
+}
+
+// disable motor driver
+void StepperDriver4PWM::disable()
+{
+ // set zero to PWM
+ setPwm(0, 0);
+ // disable the driver - if enable_pin pin available
+ if ( _isset(enable_pin1) ) digitalWrite(enable_pin1, !enable_active_high);
+ if ( _isset(enable_pin2) ) digitalWrite(enable_pin2, !enable_active_high);
+
+}
+
+// init hardware pins
+int StepperDriver4PWM::init() {
+
+ // PWM pins
+ pinMode(pwm1A, OUTPUT);
+ pinMode(pwm1B, OUTPUT);
+ pinMode(pwm2A, OUTPUT);
+ pinMode(pwm2B, OUTPUT);
+ if( _isset(enable_pin1) ) pinMode(enable_pin1, OUTPUT);
+ if( _isset(enable_pin2) ) pinMode(enable_pin2, OUTPUT);
+
+ // sanity check for the voltage limit configuration
+ if( !_isset(voltage_limit) || voltage_limit > voltage_power_supply) voltage_limit = voltage_power_supply;
+
+ // Set the pwm frequency to the pins
+ // hardware specific function - depending on driver and mcu
+ params = _configure4PWM(pwm_frequency, pwm1A, pwm1B, pwm2A, pwm2B);
+ initialized = (params!=SIMPLEFOC_DRIVER_INIT_FAILED);
+ return params!=SIMPLEFOC_DRIVER_INIT_FAILED;
+}
+
+// Set voltage to the pwm pin
+void StepperDriver4PWM::setPhaseState(PhaseState sa, PhaseState sb) {
+ // disable if needed
+ if( _isset(enable_pin1) && _isset(enable_pin2)){
+ digitalWrite(enable_pin1, sa == PhaseState::PHASE_ON ? enable_active_high:!enable_active_high);
+ digitalWrite(enable_pin2, sb == PhaseState::PHASE_ON ? enable_active_high:!enable_active_high);
+ }
+}
+
+
+// Set voltage to the pwm pin
+void StepperDriver4PWM::setPwm(float Ualpha, float Ubeta) {
+ float duty_cycle1A(0.0f),duty_cycle1B(0.0f),duty_cycle2A(0.0f),duty_cycle2B(0.0f);
+ // limit the voltage in driver
+ Ualpha = _constrain(Ualpha, -voltage_limit, voltage_limit);
+ Ubeta = _constrain(Ubeta, -voltage_limit, voltage_limit);
+ // hardware specific writing
+ if( Ualpha > 0 )
+ duty_cycle1B = _constrain(abs(Ualpha)/voltage_power_supply,0.0f,1.0f);
+ else
+ duty_cycle1A = _constrain(abs(Ualpha)/voltage_power_supply,0.0f,1.0f);
+
+ if( Ubeta > 0 )
+ duty_cycle2B = _constrain(abs(Ubeta)/voltage_power_supply,0.0f,1.0f);
+ else
+ duty_cycle2A = _constrain(abs(Ubeta)/voltage_power_supply,0.0f,1.0f);
+ // write to hardware
+ _writeDutyCycle4PWM(duty_cycle1A, duty_cycle1B, duty_cycle2A, duty_cycle2B, params);
+}
\ No newline at end of file
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/drivers/StepperDriver4PWM.h b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/drivers/StepperDriver4PWM.h
new file mode 100644
index 0000000..33e7d0c
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/drivers/StepperDriver4PWM.h
@@ -0,0 +1,65 @@
+#ifndef STEPPER_DRIVER_4PWM_h
+#define STEPPER_DRIVER_4PWM_h
+
+#include "../common/base_classes/StepperDriver.h"
+#include "../common/foc_utils.h"
+#include "../common/time_utils.h"
+#include "../common/defaults.h"
+#include "hardware_api.h"
+
+/**
+ 4 pwm stepper driver class
+*/
+class StepperDriver4PWM: public StepperDriver
+{
+ public:
+ /**
+ StepperMotor class constructor
+ @param ph1A 1A phase pwm pin
+ @param ph1B 1B phase pwm pin
+ @param ph2A 2A phase pwm pin
+ @param ph2B 2B phase pwm pin
+ @param en1 enable pin phase 1 (optional input)
+ @param en2 enable pin phase 2 (optional input)
+ */
+ StepperDriver4PWM(int ph1A,int ph1B,int ph2A,int ph2B, int en1 = NOT_SET, int en2 = NOT_SET);
+
+ /** Motor hardware init function */
+ int init() override;
+ /** Motor disable function */
+ void disable() override;
+ /** Motor enable function */
+ void enable() override;
+
+ // hardware variables
+ int pwm1A; //!< phase 1A pwm pin number
+ int pwm1B; //!< phase 1B pwm pin number
+ int pwm2A; //!< phase 2A pwm pin number
+ int pwm2B; //!< phase 2B pwm pin number
+ int enable_pin1; //!< enable pin number phase 1
+ int enable_pin2; //!< enable pin number phase 2
+
+ /**
+ * Set phase voltages to the harware
+ *
+ * @param Ua phase A voltage
+ * @param Ub phase B voltage
+ */
+ void setPwm(float Ua, float Ub) override;
+
+
+ /**
+ * Set phase voltages to the hardware.
+ * > Only possible is the driver has separate enable pins for both phases!
+ *
+ * @param sa phase A state : active / disabled ( high impedance )
+ * @param sb phase B state : active / disabled ( high impedance )
+ */
+ virtual void setPhaseState(PhaseState sa, PhaseState sb) override;
+
+ private:
+
+};
+
+
+#endif
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/drivers/hardware_api.h b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/drivers/hardware_api.h
new file mode 100644
index 0000000..7809233
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/drivers/hardware_api.h
@@ -0,0 +1,177 @@
+#ifndef HARDWARE_UTILS_DRIVER_H
+#define HARDWARE_UTILS_DRIVER_H
+
+#include "../common/foc_utils.h"
+#include "../common/time_utils.h"
+#include "../communication/SimpleFOCDebug.h"
+#include "../common/base_classes/BLDCDriver.h"
+
+
+// these defines determine the polarity of the PWM output. Normally, the polarity is active-high,
+// i.e. a high-level PWM output is expected to switch on the MOSFET. But should your driver design
+// require inverted polarity, you can change the defines below, or set them via your build environment
+// or board definition files.
+
+// used for 1-PWM, 2-PWM, 3-PWM, and 4-PWM modes
+#ifndef SIMPLEFOC_PWM_ACTIVE_HIGH
+#define SIMPLEFOC_PWM_ACTIVE_HIGH true
+#endif
+// used for 6-PWM mode, high-side
+#ifndef SIMPLEFOC_PWM_HIGHSIDE_ACTIVE_HIGH
+#define SIMPLEFOC_PWM_HIGHSIDE_ACTIVE_HIGH true
+#endif
+// used for 6-PWM mode, low-side
+#ifndef SIMPLEFOC_PWM_LOWSIDE_ACTIVE_HIGH
+#define SIMPLEFOC_PWM_LOWSIDE_ACTIVE_HIGH true
+#endif
+
+// flag returned if driver init fails
+#define SIMPLEFOC_DRIVER_INIT_FAILED ((void*)-1)
+
+// generic implementation of the hardware specific structure
+// containing all the necessary driver parameters
+// will be returned as a void pointer from the _configurexPWM functions
+// will be provided to the _writeDutyCyclexPWM() as a void pointer
+typedef struct GenericDriverParams {
+ int pins[6];
+ long pwm_frequency;
+ float dead_zone;
+} GenericDriverParams;
+
+
+/**
+ * Configuring PWM frequency, resolution and alignment
+ * - Stepper driver - 2PWM setting
+ * - hardware specific
+ *
+ * @param pwm_frequency - frequency in hertz - if applicable
+ * @param pinA pinA pwm pin
+ *
+ * @return -1 if failed, or pointer to internal driver parameters struct if successful
+ */
+void* _configure1PWM(long pwm_frequency, const int pinA);
+
+/**
+ * Configuring PWM frequency, resolution and alignment
+ * - Stepper driver - 2PWM setting
+ * - hardware specific
+ *
+ * @param pwm_frequency - frequency in hertz - if applicable
+ * @param pinA pinA bldc driver
+ * @param pinB pinB bldc driver
+ *
+ * @return -1 if failed, or pointer to internal driver parameters struct if successful
+ */
+void* _configure2PWM(long pwm_frequency, const int pinA, const int pinB);
+
+/**
+ * Configuring PWM frequency, resolution and alignment
+ * - BLDC driver - 3PWM setting
+ * - hardware specific
+ *
+ * @param pwm_frequency - frequency in hertz - if applicable
+ * @param pinA pinA bldc driver
+ * @param pinB pinB bldc driver
+ * @param pinC pinC bldc driver
+ *
+ * @return -1 if failed, or pointer to internal driver parameters struct if successful
+ */
+void* _configure3PWM(long pwm_frequency, const int pinA, const int pinB, const int pinC);
+
+/**
+ * Configuring PWM frequency, resolution and alignment
+ * - Stepper driver - 4PWM setting
+ * - hardware specific
+ *
+ * @param pwm_frequency - frequency in hertz - if applicable
+ * @param pin1A pin1A stepper driver
+ * @param pin1B pin1B stepper driver
+ * @param pin2A pin2A stepper driver
+ * @param pin2B pin2B stepper driver
+ *
+ * @return -1 if failed, or pointer to internal driver parameters struct if successful
+ */
+void* _configure4PWM(long pwm_frequency, const int pin1A, const int pin1B, const int pin2A, const int pin2B);
+
+/**
+ * Configuring PWM frequency, resolution and alignment
+ * - BLDC driver - 6PWM setting
+ * - hardware specific
+ *
+ * @param pwm_frequency - frequency in hertz - if applicable
+ * @param dead_zone duty cycle protection zone [0, 1] - both low and high side low - if applicable
+ * @param pinA_h pinA high-side bldc driver
+ * @param pinA_l pinA low-side bldc driver
+ * @param pinB_h pinA high-side bldc driver
+ * @param pinB_l pinA low-side bldc driver
+ * @param pinC_h pinA high-side bldc driver
+ * @param pinC_l pinA low-side bldc driver
+ *
+ * @return -1 if failed, or pointer to internal driver parameters struct if successful
+ */
+void* _configure6PWM(long pwm_frequency, float dead_zone, const int pinA_h, const int pinA_l, const int pinB_h, const int pinB_l, const int pinC_h, const int pinC_l);
+
+/**
+ * Function setting the duty cycle to the pwm pin (ex. analogWrite())
+ * - Stepper driver - 2PWM setting
+ * - hardware specific
+ *
+ * @param dc_a duty cycle phase A [0, 1]
+ * @param dc_b duty cycle phase B [0, 1]
+ * @param params the driver parameters
+ */
+void _writeDutyCycle1PWM(float dc_a, void* params);
+
+/**
+ * Function setting the duty cycle to the pwm pin (ex. analogWrite())
+ * - Stepper driver - 2PWM setting
+ * - hardware specific
+ *
+ * @param dc_a duty cycle phase A [0, 1]
+ * @param dc_b duty cycle phase B [0, 1]
+ * @param params the driver parameters
+ */
+void _writeDutyCycle2PWM(float dc_a, float dc_b, void* params);
+
+/**
+ * Function setting the duty cycle to the pwm pin (ex. analogWrite())
+ * - BLDC driver - 3PWM setting
+ * - hardware specific
+ *
+ * @param dc_a duty cycle phase A [0, 1]
+ * @param dc_b duty cycle phase B [0, 1]
+ * @param dc_c duty cycle phase C [0, 1]
+ * @param params the driver parameters
+ */
+void _writeDutyCycle3PWM(float dc_a, float dc_b, float dc_c, void* params);
+
+/**
+ * Function setting the duty cycle to the pwm pin (ex. analogWrite())
+ * - Stepper driver - 4PWM setting
+ * - hardware specific
+ *
+ * @param dc_1a duty cycle phase 1A [0, 1]
+ * @param dc_1b duty cycle phase 1B [0, 1]
+ * @param dc_2a duty cycle phase 2A [0, 1]
+ * @param dc_2b duty cycle phase 2B [0, 1]
+ * @param params the driver parameters
+ */
+void _writeDutyCycle4PWM(float dc_1a, float dc_1b, float dc_2a, float dc_2b, void* params);
+
+
+/**
+ * Function setting the duty cycle to the pwm pin (ex. analogWrite())
+ * - BLDC driver - 6PWM setting
+ * - hardware specific
+ *
+ * @param dc_a duty cycle phase A [0, 1]
+ * @param dc_b duty cycle phase B [0, 1]
+ * @param dc_c duty cycle phase C [0, 1]
+ * @param phase_state pointer to PhaseState[3] array
+ * @param params the driver parameters
+ *
+ */
+void _writeDutyCycle6PWM(float dc_a, float dc_b, float dc_c, PhaseState *phase_state, void* params);
+
+
+#endif
\ No newline at end of file
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/drivers/hardware_specific/atmega/atmega2560_mcu.cpp b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/drivers/hardware_specific/atmega/atmega2560_mcu.cpp
new file mode 100644
index 0000000..532b3ce
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/drivers/hardware_specific/atmega/atmega2560_mcu.cpp
@@ -0,0 +1,282 @@
+#include "../../hardware_api.h"
+
+#if defined(__AVR_ATmega2560__) || defined(AVR_ATmega1280)
+
+
+#pragma message("")
+#pragma message("SimpleFOC: compiling for Arduino/ATmega2560 or Arduino/ATmega1280")
+#pragma message("")
+
+
+#define _PWM_FREQUENCY 32000
+#define _PWM_FREQUENCY_MAX 32000
+#define _PWM_FREQUENCY_MIN 4000
+
+// set pwm frequency to 32KHz
+void _pinHighFrequency(const int pin, const long frequency){
+ bool high_fq = false;
+ // set 32kHz frequency if requested freq is higher than the middle of the range (14kHz)
+ // else set the 4kHz
+ if(frequency >= 0.5*(_PWM_FREQUENCY_MAX-_PWM_FREQUENCY_MIN)) high_fq=true;
+ // High PWM frequency
+ // https://sites.google.com/site/qeewiki/books/avr-guide/timers-on-the-ATmega2560
+ // https://forum.arduino.cc/index.php?topic=72092.0
+ if (pin == 13 || pin == 4 ) {
+ TCCR0A = ((TCCR0A & 0b11111100) | 0x01); // configure the pwm phase-corrected mode
+ if(high_fq) TCCR0B = ((TCCR0B & 0b11110000) | 0x01); // set prescaler to 1 - 32kHz
+ else TCCR0B = ((TCCR0B & 0b11110000) | 0x02); // set prescaler to 2 - 4kHz
+ }
+ else if (pin == 12 || pin == 11 )
+ if(high_fq) TCCR1B = ((TCCR1B & 0b11110000) | 0x01); // set prescaler to 1 - 32kHz
+ else TCCR1B = ((TCCR1B & 0b11110000) | 0x02); // set prescaler to 2 - 4kHz
+ else if (pin == 10 || pin == 9 )
+ if(high_fq) TCCR2B = ((TCCR2B & 0b11110000) | 0x01); // set prescaler to 1 - 32kHz
+ else TCCR2B = ((TCCR2B & 0b11110000) | 0x02); // set prescaler to 2 - 4kHz
+ else if (pin == 5 || pin == 3 || pin == 2)
+ if(high_fq) TCCR3B = ((TCCR3B & 0b11110000) | 0x01); // set prescaler to 1 - 32kHz
+ else TCCR3B = ((TCCR3B & 0b11110000) | 0x02); // set prescaler to 2 - 4kHz
+ else if (pin == 8 || pin == 7 || pin == 6)
+ if(high_fq) TCCR4B = ((TCCR4B & 0b11110000) | 0x01); // set prescaler to 1 - 32kHz
+ else TCCR4B = ((TCCR4B & 0b11110000) | 0x02); // set prescaler to 2 - 4kHz
+ else if (pin == 44 || pin == 45 || pin == 46)
+ if(high_fq) TCCR5B = ((TCCR5B & 0b11110000) | 0x01); // set prescaler to 1 - 32kHz
+ else TCCR5B = ((TCCR5B & 0b11110000) | 0x02); // set prescaler to 2 - 4kHz
+
+}
+
+
+// function setting the high pwm frequency to the supplied pins
+// - Stepper motor - 2PWM setting
+// - hardware specific
+// supports Arduino/ATmega2560
+void* _configure1PWM(long pwm_frequency,const int pinA) {
+ if(!pwm_frequency || !_isset(pwm_frequency) ) pwm_frequency = _PWM_FREQUENCY; // default frequency 32kHz
+ else pwm_frequency = _constrain(pwm_frequency, _PWM_FREQUENCY_MIN, _PWM_FREQUENCY_MAX); // constrain to 4-32kHz max
+ // High PWM frequency
+ // - always max 32kHz
+ _pinHighFrequency(pinA, pwm_frequency);
+ GenericDriverParams* params = new GenericDriverParams {
+ .pins = { pinA },
+ .pwm_frequency = pwm_frequency,
+ .dead_zone = 0.0f
+ };
+ return params;
+}
+
+// function setting the high pwm frequency to the supplied pins
+// - Stepper motor - 2PWM setting
+// - hardware specific
+// supports Arduino/ATmega2560
+void* _configure2PWM(long pwm_frequency,const int pinA, const int pinB) {
+ if(!pwm_frequency || !_isset(pwm_frequency) ) pwm_frequency = _PWM_FREQUENCY; // default frequency 32kHz
+ else pwm_frequency = _constrain(pwm_frequency, _PWM_FREQUENCY_MIN, _PWM_FREQUENCY_MAX); // constrain to 4-32kHz max
+ // High PWM frequency
+ // - always max 32kHz
+ _pinHighFrequency(pinA, pwm_frequency);
+ _pinHighFrequency(pinB, pwm_frequency);
+ GenericDriverParams* params = new GenericDriverParams {
+ .pins = { pinA, pinB },
+ .pwm_frequency = pwm_frequency,
+ .dead_zone = 0.0f
+ };
+ return params;
+}
+
+// function setting the high pwm frequency to the supplied pins
+// - BLDC motor - 3PWM setting
+// - hardware specific
+// supports Arduino/ATmega2560
+void* _configure3PWM(long pwm_frequency,const int pinA, const int pinB, const int pinC) {
+ if(!pwm_frequency || !_isset(pwm_frequency) ) pwm_frequency = _PWM_FREQUENCY; // default frequency 32kHz
+ else pwm_frequency = _constrain(pwm_frequency, _PWM_FREQUENCY_MIN, _PWM_FREQUENCY_MAX); // constrain to 4-32kHz max
+ // High PWM frequency
+ // - always max 32kHz
+ _pinHighFrequency(pinA, pwm_frequency);
+ _pinHighFrequency(pinB, pwm_frequency);
+ _pinHighFrequency(pinC, pwm_frequency);
+ GenericDriverParams* params = new GenericDriverParams {
+ .pins = { pinA, pinB, pinC },
+ .pwm_frequency = pwm_frequency,
+ .dead_zone = 0.0f
+ };
+ // _syncAllTimers();
+ return params;
+}
+
+// function setting the pwm duty cycle to the hardware
+// - Stepper motor - 2PWM setting
+// - hardware specific
+void _writeDutyCycle1PWM(float dc_a, void* params){
+ // transform duty cycle from [0,1] to [0,255]
+ analogWrite(((GenericDriverParams*)params)->pins[0], 255.0f*dc_a);
+}
+
+// function setting the pwm duty cycle to the hardware
+// - Stepper motor - 2PWM setting
+// - hardware specific
+void _writeDutyCycle2PWM(float dc_a, float dc_b, void* params){
+ // transform duty cycle from [0,1] to [0,255]
+ analogWrite(((GenericDriverParams*)params)->pins[0], 255.0f*dc_a);
+ analogWrite(((GenericDriverParams*)params)->pins[1], 255.0f*dc_b);
+}
+
+// function setting the pwm duty cycle to the hardware
+// - BLDC motor - 3PWM setting
+// - hardware specific
+void _writeDutyCycle3PWM(float dc_a, float dc_b, float dc_c, void* params){
+ // transform duty cycle from [0,1] to [0,255]
+ analogWrite(((GenericDriverParams*)params)->pins[0], 255.0f*dc_a);
+ analogWrite(((GenericDriverParams*)params)->pins[1], 255.0f*dc_b);
+ analogWrite(((GenericDriverParams*)params)->pins[2], 255.0f*dc_c);
+}
+
+// function setting the high pwm frequency to the supplied pins
+// - Stepper motor - 4PWM setting
+// - hardware specific
+void* _configure4PWM(long pwm_frequency,const int pin1A, const int pin1B, const int pin2A, const int pin2B) {
+ if(!pwm_frequency || !_isset(pwm_frequency) ) pwm_frequency = _PWM_FREQUENCY; // default frequency 32kHz
+ else pwm_frequency = _constrain(pwm_frequency, _PWM_FREQUENCY_MIN, _PWM_FREQUENCY_MAX); // constrain to 4-32kHz max
+ // High PWM frequency
+ // - always max 32kHz
+ _pinHighFrequency(pin1A,pwm_frequency);
+ _pinHighFrequency(pin1B,pwm_frequency);
+ _pinHighFrequency(pin2A,pwm_frequency);
+ _pinHighFrequency(pin2B,pwm_frequency);
+ GenericDriverParams* params = new GenericDriverParams {
+ .pins = { pin1A, pin1B, pin2A, pin2B },
+ .pwm_frequency = pwm_frequency,
+ .dead_zone = 0.0f
+ };
+ return params;
+}
+
+// function setting the pwm duty cycle to the hardware
+// - Stepper motor - 4PWM setting
+// - hardware specific
+void _writeDutyCycle4PWM(float dc_1a, float dc_1b, float dc_2a, float dc_2b, void* params) {
+ // transform duty cycle from [0,1] to [0,255]
+ analogWrite(((GenericDriverParams*)params)->pins[0], 255.0f*dc_1a);
+ analogWrite(((GenericDriverParams*)params)->pins[1], 255.0f*dc_1b);
+ analogWrite(((GenericDriverParams*)params)->pins[2], 255.0f*dc_2a);
+ analogWrite(((GenericDriverParams*)params)->pins[3], 255.0f*dc_2b);
+}
+
+
+// function configuring pair of high-low side pwm channels, 32khz frequency and center aligned pwm
+// supports Arduino/ATmega2560
+// https://ww1.microchip.com/downloads/en/devicedoc/atmel-2549-8-bit-avr-microcontroller-atmega640-1280-1281-2560-2561_datasheet.pdf
+// https://docs.arduino.cc/hacking/hardware/PinMapping2560
+int _configureComplementaryPair(const int pinH,const int pinL, long frequency) {
+ bool high_fq = false;
+ // set 32kHz frequency if requested freq is higher than the middle of the range (14kHz)
+ // else set the 4kHz
+ if(frequency >= 0.5*(_PWM_FREQUENCY_MAX-_PWM_FREQUENCY_MIN)) high_fq=true;
+
+ // configure pin pairs
+ if( (pinH == 4 && pinL == 13 ) || (pinH == 13 && pinL == 4 ) ){
+ // configure the pwm phase-corrected mode
+ TCCR0A = ((TCCR0A & 0b11111100) | 0x01);
+ // configure complementary pwm on low side
+ if(pinH == 13 ) TCCR0A = 0b10110000 | (TCCR0A & 0b00001111) ;
+ else TCCR0A = 0b11100000 | (TCCR0A & 0b00001111) ;
+ // set frequency
+ if(high_fq) TCCR0B = ((TCCR0B & 0b11110000) | 0x01); // set prescaler to 1 - 32kHz
+ else TCCR0B = ((TCCR0B & 0b11110000) | 0x02); // set prescaler to 2 - 4kHz
+ }else if( (pinH == 11 && pinL == 12 ) || (pinH == 12 && pinL == 11 ) ){
+ // set frequency
+ if(high_fq) TCCR1B = ((TCCR1B & 0b11110000) | 0x01); // set prescaler to 1 - 32kHz
+ else TCCR1B = ((TCCR1B & 0b11110000) | 0x02); // set prescaler to 2 - 4kHz
+ // configure complementary pwm on low side
+ if(pinH == 11 ) TCCR1A = 0b10110000 | (TCCR1A & 0b00001111) ;
+ else TCCR1A = 0b11100000 | (TCCR1A & 0b00001111) ;
+ }else if((pinH == 10 && pinL == 9 ) || (pinH == 9 && pinL == 10 ) ){
+ // set frequency
+ if(high_fq) TCCR2B = ((TCCR2B & 0b11110000) | 0x01); // set prescaler to 1 - 32kHz
+ else TCCR2B = ((TCCR2B & 0b11110000) | 0x02); // set prescaler to 2 - 4kHz
+ // configure complementary pwm on low side
+ if(pinH == 10 ) TCCR2A = 0b10110000 | (TCCR2A & 0b00001111) ;
+ else TCCR2A = 0b11100000 | (TCCR2A & 0b00001111) ;
+ }else if((pinH == 5 && pinL == 2 ) || (pinH == 2 && pinL == 5 ) ){
+ // set frequency
+ if(high_fq) TCCR3B = ((TCCR3B & 0b11110000) | 0x01); // set prescaler to 1 - 32kHz
+ else TCCR3B = ((TCCR3B & 0b11110000) | 0x02); // set prescaler to 2 - 4kHz
+ // configure complementary pwm on low side
+ if(pinH == 5 ) TCCR3A = 0b10110000 | (TCCR3A & 0b00001111) ;
+ else TCCR3A = 0b11100000 | (TCCR3A & 0b00001111) ;
+ }else if((pinH == 6 && pinL == 7 ) || (pinH == 7 && pinL == 6 ) ){
+ // set frequency
+ if(high_fq) TCCR4B = ((TCCR4B & 0b11110000) | 0x01); // set prescaler to 1 - 32kHz
+ else TCCR4B = ((TCCR4B & 0b11110000) | 0x02); // set prescaler to 2 - 4kHz
+ // configure complementary pwm on low side
+ if(pinH == 6 ) TCCR4A = 0b10110000 | (TCCR4A & 0b00001111) ;
+ else TCCR4A = 0b11100000 | (TCCR4A & 0b00001111) ;
+ }else if((pinH == 46 && pinL == 45 ) || (pinH == 45 && pinL == 46 ) ){
+ // set frequency
+ if(high_fq) TCCR5B = ((TCCR5B & 0b11110000) | 0x01); // set prescaler to 1 - 32kHz
+ else TCCR5B = ((TCCR5B & 0b11110000) | 0x02); // set prescaler to 2 - 4kHz
+ // configure complementary pwm on low side
+ if(pinH == 46 ) TCCR5A = 0b10110000 | (TCCR5A & 0b00001111) ;
+ else TCCR5A = 0b11100000 | (TCCR5A & 0b00001111) ;
+ }else{
+ return -1;
+ }
+ return 0;
+}
+
+// Configuring PWM frequency, resolution and alignment
+// - BLDC driver - setting
+// - hardware specific
+// supports Arduino/ATmega2560
+void* _configure6PWM(long pwm_frequency, float dead_zone, const int pinA_h, const int pinA_l, const int pinB_h, const int pinB_l, const int pinC_h, const int pinC_l) {
+ if(!pwm_frequency || !_isset(pwm_frequency) ) pwm_frequency = _PWM_FREQUENCY; // default frequency 32kHz
+ else pwm_frequency = _constrain(pwm_frequency, _PWM_FREQUENCY_MIN, _PWM_FREQUENCY_MAX); // constrain to 4-32kHz max
+ // High PWM frequency
+ // - always max 32kHz
+ int ret_flag = 0;
+ ret_flag += _configureComplementaryPair(pinA_h, pinA_l, pwm_frequency);
+ ret_flag += _configureComplementaryPair(pinB_h, pinB_l, pwm_frequency);
+ ret_flag += _configureComplementaryPair(pinC_h, pinC_l, pwm_frequency);
+ if (ret_flag!=0) return SIMPLEFOC_DRIVER_INIT_FAILED;
+ GenericDriverParams* params = new GenericDriverParams {
+ .pins = { pinA_h, pinA_l, pinB_h, pinB_l, pinC_h, pinC_l },
+ .pwm_frequency = pwm_frequency,
+ .dead_zone = dead_zone
+ };
+ // _syncAllTimers();
+ return params;
+}
+
+// function setting the
+void _setPwmPair(int pinH, int pinL, float val, int dead_time, PhaseState ps)
+{
+ int pwm_h = _constrain(val-dead_time/2,0,255);
+ int pwm_l = _constrain(val+dead_time/2,0,255);
+ // determine the phase state and set the pwm accordingly
+ // deactivate phases if needed
+ if((ps == PhaseState::PHASE_OFF) || (ps == PhaseState::PHASE_LO)){
+ digitalWrite(pinH, LOW);
+ }else{
+ analogWrite(pinH, pwm_h);
+ }
+ if((ps == PhaseState::PHASE_OFF) || (ps == PhaseState::PHASE_HI)){
+ digitalWrite(pinL, LOW);
+ }else{
+ if(pwm_l == 255 || pwm_l == 0)
+ digitalWrite(pinL, pwm_l ? LOW : HIGH);
+ else
+ analogWrite(pinL, pwm_l);
+ }
+
+}
+
+// Function setting the duty cycle to the pwm pin (ex. analogWrite())
+// - BLDC driver - 6PWM setting
+// - hardware specific
+// supports Arduino/ATmega328
+void _writeDutyCycle6PWM(float dc_a, float dc_b, float dc_c, PhaseState *phase_state, void* params){
+ _setPwmPair(((GenericDriverParams*)params)->pins[0], ((GenericDriverParams*)params)->pins[1], dc_a*255.0, ((GenericDriverParams*)params)->dead_zone*255.0, phase_state[0]);
+ _setPwmPair(((GenericDriverParams*)params)->pins[2], ((GenericDriverParams*)params)->pins[3], dc_b*255.0, ((GenericDriverParams*)params)->dead_zone*255.0, phase_state[1]);
+ _setPwmPair(((GenericDriverParams*)params)->pins[4], ((GenericDriverParams*)params)->pins[5], dc_c*255.0, ((GenericDriverParams*)params)->dead_zone*255.0, phase_state[2]);
+}
+
+#endif
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/drivers/hardware_specific/atmega/atmega328_mcu.cpp b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/drivers/hardware_specific/atmega/atmega328_mcu.cpp
new file mode 100644
index 0000000..9df9b8a
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/drivers/hardware_specific/atmega/atmega328_mcu.cpp
@@ -0,0 +1,259 @@
+#include "../../hardware_api.h"
+
+#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) || defined(__AVR_ATmega328PB__)
+
+#pragma message("")
+#pragma message("SimpleFOC: compiling for Arduino/ATmega328 ATmega168 ATmega328PB")
+#pragma message("")
+
+#define _PWM_FREQUENCY 32000
+#define _PWM_FREQUENCY_MAX 32000
+#define _PWM_FREQUENCY_MIN 4000
+
+// set pwm frequency to 32KHz
+void _pinHighFrequency(const int pin, const long frequency){
+ bool high_fq = false;
+ // set 32kHz frequency if requested freq is higher than the middle of the range (14kHz)
+ // else set the 4kHz
+ if(frequency >= 0.5*(_PWM_FREQUENCY_MAX-_PWM_FREQUENCY_MIN)) high_fq=true;
+ // High PWM frequency
+ // https://www.arxterra.com/9-atmega328p-timers/
+ if (pin == 5 || pin == 6 ) {
+ TCCR0A = ((TCCR0A & 0b11111100) | 0x01); // configure the pwm phase-corrected mode
+ if(high_fq) TCCR0B = ((TCCR0B & 0b11110000) | 0x01); // set prescaler to 1 - 32kHz
+ else TCCR0B = ((TCCR0B & 0b11110000) | 0x02); // set prescaler to 2 - 4kHz
+ }else if (pin == 9 || pin == 10 ){
+ if(high_fq) TCCR1B = ((TCCR1B & 0b11110000) | 0x01); // set prescaler to 1 - 32kHz
+ else TCCR1B = ((TCCR1B & 0b11110000) | 0x02); // set prescaler to 2 - 4kHz
+ }else if (pin == 3 || pin == 11){
+ if(high_fq) TCCR2B = ((TCCR2B & 0b11110000) | 0x01); // set prescaler to 1 - 32kHz
+ else TCCR2B = ((TCCR2B & 0b11110000) | 0x02); // set prescaler to 2 - 4kHz
+ }
+}
+
+void _syncAllTimers(){
+ GTCCR = (1<pins[0], 255.0f*dc_a);
+}
+
+
+// function setting the pwm duty cycle to the hardware
+// - Stepper motor - 2PWM setting
+// - hardware specific
+void _writeDutyCycle2PWM(float dc_a, float dc_b, void* params){
+ // transform duty cycle from [0,1] to [0,255]
+ analogWrite(((GenericDriverParams*)params)->pins[0], 255.0f*dc_a);
+ analogWrite(((GenericDriverParams*)params)->pins[1], 255.0f*dc_b);
+}
+
+// function setting the pwm duty cycle to the hardware
+// - BLDC motor - 3PWM setting
+// - hardware specific
+void _writeDutyCycle3PWM(float dc_a, float dc_b, float dc_c, void* params){
+ // transform duty cycle from [0,1] to [0,255]
+ analogWrite(((GenericDriverParams*)params)->pins[0], 255.0f*dc_a);
+ analogWrite(((GenericDriverParams*)params)->pins[1], 255.0f*dc_b);
+ analogWrite(((GenericDriverParams*)params)->pins[2], 255.0f*dc_c);
+}
+
+// function setting the high pwm frequency to the supplied pins
+// - Stepper motor - 4PWM setting
+// - hardware specific
+// supports Arduino/ATmega328
+void* _configure4PWM(long pwm_frequency,const int pin1A, const int pin1B, const int pin2A, const int pin2B) {
+ if(!pwm_frequency || !_isset(pwm_frequency) ) pwm_frequency = _PWM_FREQUENCY; // default frequency 32kHz
+ else pwm_frequency = _constrain(pwm_frequency, _PWM_FREQUENCY_MIN, _PWM_FREQUENCY_MAX); // constrain to 4-32kHz max
+ // High PWM frequency
+ // - always max 32kHz
+ _pinHighFrequency(pin1A,pwm_frequency);
+ _pinHighFrequency(pin1B,pwm_frequency);
+ _pinHighFrequency(pin2A,pwm_frequency);
+ _pinHighFrequency(pin2B,pwm_frequency);
+ GenericDriverParams* params = new GenericDriverParams {
+ .pins = { pin1A, pin1B, pin2A, pin2B },
+ .pwm_frequency = pwm_frequency,
+ .dead_zone = 0.0f
+ };
+ return params;
+}
+
+// function setting the pwm duty cycle to the hardware
+// - Stepper motor - 4PWM setting
+// - hardware specific
+void _writeDutyCycle4PWM(float dc_1a, float dc_1b, float dc_2a, float dc_2b, void* params){
+ // transform duty cycle from [0,1] to [0,255]
+ analogWrite(((GenericDriverParams*)params)->pins[0], 255.0f*dc_1a);
+ analogWrite(((GenericDriverParams*)params)->pins[1], 255.0f*dc_1b);
+ analogWrite(((GenericDriverParams*)params)->pins[2], 255.0f*dc_2a);
+ analogWrite(((GenericDriverParams*)params)->pins[3], 255.0f*dc_2b);
+}
+
+
+// function configuring pair of high-low side pwm channels, 32khz frequency and center aligned pwm
+int _configureComplementaryPair(const int pinH, const int pinL, long frequency) {
+ bool high_fq = false;
+ // set 32kHz frequency if requested freq is higher than the middle of the range (14kHz)
+ // else set the 4kHz
+ if(frequency >= 0.5*(_PWM_FREQUENCY_MAX-_PWM_FREQUENCY_MIN)) high_fq=true;
+
+ // configure pins
+ if( (pinH == 5 && pinL == 6 ) || (pinH == 6 && pinL == 5 ) ){
+ // configure the pwm phase-corrected mode
+ TCCR0A = ((TCCR0A & 0b11111100) | 0x01);
+ // configure complementary pwm on low side
+ if(pinH == 6 ) TCCR0A = 0b10110000 | (TCCR0A & 0b00001111) ;
+ else TCCR0A = 0b11100000 | (TCCR0A & 0b00001111) ;
+ // set frequency
+ if(high_fq) TCCR0B = ((TCCR0B & 0b11110000) | 0x01); // set prescaler to 1 - 32kHz
+ else TCCR0B = ((TCCR0B & 0b11110000) | 0x02); // set prescaler to 2 - 4kHz
+ }else if( (pinH == 9 && pinL == 10 ) || (pinH == 10 && pinL == 9 ) ){
+ // set frequency
+ if(high_fq) TCCR1B = ((TCCR1B & 0b11110000) | 0x01); // set prescaler to 1 - 32kHz
+ else TCCR1B = ((TCCR1B & 0b11110000) | 0x02); // set prescaler to 2 - 4kHz
+ // configure complementary pwm on low side
+ if(pinH == 9 ) TCCR1A = 0b10110000 | (TCCR1A & 0b00001111) ;
+ else TCCR1A = 0b11100000 | (TCCR1A & 0b00001111) ;
+ }else if((pinH == 3 && pinL == 11 ) || (pinH == 11 && pinL == 3 ) ){
+ // set frequency
+ if(high_fq) TCCR2B = ((TCCR2B & 0b11110000) | 0x01); // set prescaler to 1 - 32kHz
+ else TCCR2B = ((TCCR2B & 0b11110000) | 0x02); // set prescaler to 2 - 4kHz
+ // configure complementary pwm on low side
+ if(pinH == 11 ) TCCR2A = 0b10110000 | (TCCR2A & 0b00001111) ;
+ else TCCR2A = 0b11100000 | (TCCR2A & 0b00001111) ;
+ }else{
+ return -1;
+ }
+ return 0;
+}
+
+// Configuring PWM frequency, resolution and alignment
+// - BLDC driver - setting
+// - hardware specific
+// supports Arduino/ATmega328
+void* _configure6PWM(long pwm_frequency, float dead_zone, const int pinA_h, const int pinA_l, const int pinB_h, const int pinB_l, const int pinC_h, const int pinC_l) {
+ if(!pwm_frequency || !_isset(pwm_frequency) ) pwm_frequency = _PWM_FREQUENCY; // default frequency 32kHz
+ else pwm_frequency = _constrain(pwm_frequency, _PWM_FREQUENCY_MIN, _PWM_FREQUENCY_MAX); // constrain to 4-32kHz max
+ // High PWM frequency
+ // - always max 32kHz
+ int ret_flag = 0;
+ ret_flag += _configureComplementaryPair(pinA_h, pinA_l, pwm_frequency);
+ ret_flag += _configureComplementaryPair(pinB_h, pinB_l, pwm_frequency);
+ ret_flag += _configureComplementaryPair(pinC_h, pinC_l, pwm_frequency);
+ if (ret_flag!=0) return SIMPLEFOC_DRIVER_INIT_FAILED;
+ GenericDriverParams* params = new GenericDriverParams {
+ .pins = { pinA_h, pinA_l, pinB_h, pinB_l, pinC_h, pinC_l },
+ .pwm_frequency = pwm_frequency,
+ .dead_zone = dead_zone
+ };
+ _syncAllTimers();
+ return params;
+}
+
+// function setting the
+void _setPwmPair(int pinH, int pinL, float val, int dead_time, PhaseState ps)
+{
+ int pwm_h = _constrain(val-dead_time/2,0,255);
+ int pwm_l = _constrain(val+dead_time/2,0,255);
+ // determine the phase state and set the pwm accordingly
+ // deactivate phases if needed
+ if((ps == PhaseState::PHASE_OFF) || (ps == PhaseState::PHASE_LO)){
+ digitalWrite(pinH, LOW);
+ }else{
+ analogWrite(pinH, pwm_h);
+ }
+ if((ps == PhaseState::PHASE_OFF) || (ps == PhaseState::PHASE_HI)){
+ digitalWrite(pinL, LOW);
+ }else{
+ if(pwm_l == 255 || pwm_l == 0)
+ digitalWrite(pinL, pwm_l ? LOW : HIGH);
+ else
+ analogWrite(pinL, pwm_l);
+ }
+
+
+}
+
+// Function setting the duty cycle to the pwm pin (ex. analogWrite())
+// - BLDC driver - 6PWM setting
+// - hardware specific
+// supports Arduino/ATmega328
+void _writeDutyCycle6PWM(float dc_a, float dc_b, float dc_c, PhaseState *phase_state, void* params){
+ _setPwmPair(((GenericDriverParams*)params)->pins[0], ((GenericDriverParams*)params)->pins[1], dc_a*255.0, ((GenericDriverParams*)params)->dead_zone*255.0, phase_state[0]);
+ _setPwmPair(((GenericDriverParams*)params)->pins[2], ((GenericDriverParams*)params)->pins[3], dc_b*255.0, ((GenericDriverParams*)params)->dead_zone*255.0, phase_state[1]);
+ _setPwmPair(((GenericDriverParams*)params)->pins[4], ((GenericDriverParams*)params)->pins[5], dc_c*255.0, ((GenericDriverParams*)params)->dead_zone*255.0, phase_state[2]);
+}
+
+#endif
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/drivers/hardware_specific/atmega/atmega32u4_mcu.cpp b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/drivers/hardware_specific/atmega/atmega32u4_mcu.cpp
new file mode 100644
index 0000000..4cf454a
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/drivers/hardware_specific/atmega/atmega32u4_mcu.cpp
@@ -0,0 +1,226 @@
+
+#include "../../hardware_api.h"
+
+#if defined(__AVR_ATmega32U4__)
+
+#pragma message("")
+#pragma message("SimpleFOC: compiling for Arduino/ATmega32U4")
+#pragma message("")
+
+// set pwm frequency to 32KHz
+void _pinHighFrequency(const int pin){
+ // High PWM frequency
+ // reference: http://r6500.blogspot.com/2014/12/fast-pwm-on-arduino-leonardo.html
+ if (pin == 3 || pin == 11 ) {
+ TCCR0A = ((TCCR0A & 0b11111100) | 0x01); // configure the pwm phase-corrected mode
+ TCCR0B = ((TCCR0B & 0b11110000) | 0x01); // set prescaler to 1
+ }
+ else if (pin == 9 || pin == 10 )
+ TCCR1B = ((TCCR1B & 0b11111000) | 0x01); // set prescaler to 1
+ else if (pin == 5 )
+ TCCR3B = ((TCCR3B & 0b11111000) | 0x01); // set prescaler to 1
+ else if ( pin == 6 || pin == 13 ) { // a bit more complicated 10 bit timer
+ // PLL Configuration
+ PLLFRQ= ((PLLFRQ & 0b11001111) | 0x20); // Use 96MHz / 1.5 = 64MHz
+ TCCR4B = ((TCCR4B & 0b11110000) | 0xB); // configure prescaler to get 64M/2/1024 = 31.25 kHz
+ TCCR4D = ((TCCR4D & 0b11111100) | 0x01); // configure the pwm phase-corrected mode
+
+ if (pin == 6) TCCR4A = 0x82; // activate channel A - pin 13
+ else if (pin == 13) TCCR4C |= 0x09; // Activate channel D - pin 6
+ }
+
+}
+
+
+// function setting the high pwm frequency to the supplied pins
+// - Stepper motor - 2PWM setting
+// - hardware speciffic
+void* _configure1PWM(long pwm_frequency,const int pinA) {
+ // High PWM frequency
+ // - always max 32kHz
+ _pinHighFrequency(pinA);
+ GenericDriverParams* params = new GenericDriverParams {
+ .pins = { pinA },
+ .pwm_frequency = pwm_frequency,
+ .dead_zone = 0.0f
+ };
+ return params;
+}
+
+// function setting the high pwm frequency to the supplied pins
+// - Stepper motor - 2PWM setting
+// - hardware speciffic
+void* _configure2PWM(long pwm_frequency,const int pinA, const int pinB) {
+ // High PWM frequency
+ // - always max 32kHz
+ _pinHighFrequency(pinA);
+ _pinHighFrequency(pinB);
+ GenericDriverParams* params = new GenericDriverParams {
+ .pins = { pinA, pinB },
+ .pwm_frequency = pwm_frequency,
+ .dead_zone = 0.0f
+ };
+ return params;
+}
+
+// function setting the high pwm frequency to the supplied pins
+// - BLDC motor - 3PWM setting
+// - hardware speciffic
+void* _configure3PWM(long pwm_frequency,const int pinA, const int pinB, const int pinC) {
+ // High PWM frequency
+ // - always max 32kHz
+ _pinHighFrequency(pinA);
+ _pinHighFrequency(pinB);
+ _pinHighFrequency(pinC);
+ GenericDriverParams* params = new GenericDriverParams {
+ .pins = { pinA, pinB, pinC },
+ .pwm_frequency = pwm_frequency,
+ .dead_zone = 0.0f
+ };
+ return params;
+}
+
+
+
+// function setting the pwm duty cycle to the hardware
+// - Stepper motor - 2PWM setting
+// - hardware speciffic
+void _writeDutyCycle1PWM(float dc_a, void* params){
+ // transform duty cycle from [0,1] to [0,255]
+ analogWrite(((GenericDriverParams*)params)->pins[0], 255.0f*dc_a);
+}
+
+
+// function setting the pwm duty cycle to the hardware
+// - Stepper motor - 2PWM setting
+// - hardware speciffic
+void _writeDutyCycle2PWM(float dc_a, float dc_b, void* params){
+ // transform duty cycle from [0,1] to [0,255]
+ analogWrite(((GenericDriverParams*)params)->pins[0], 255.0f*dc_a);
+ analogWrite(((GenericDriverParams*)params)->pins[1], 255.0f*dc_b);
+}
+
+// function setting the pwm duty cycle to the hardware
+// - BLDC motor - 3PWM setting
+// - hardware speciffic
+void _writeDutyCycle3PWM(float dc_a, float dc_b, float dc_c, int pinA, void* params){
+ // transform duty cycle from [0,1] to [0,255]
+ analogWrite(((GenericDriverParams*)params)->pins[0], 255.0f*dc_a);
+ analogWrite(((GenericDriverParams*)params)->pins[1], 255.0f*dc_b);
+ analogWrite(((GenericDriverParams*)params)->pins[2], 255.0f*dc_c);
+}
+
+// function setting the high pwm frequency to the supplied pins
+// - Stepper motor - 4PWM setting
+// - hardware speciffic
+void* _configure4PWM(long pwm_frequency,const int pin1A, const int pin1B, const int pin2A, const int pin2B) {
+ // High PWM frequency
+ // - always max 32kHz
+ _pinHighFrequency(pin1A);
+ _pinHighFrequency(pin1B);
+ _pinHighFrequency(pin2A);
+ _pinHighFrequency(pin2B);
+ GenericDriverParams* params = new GenericDriverParams {
+ .pins = { pin1A, pin1B, pin2A, pin2B },
+ .pwm_frequency = pwm_frequency,
+ .dead_zone = 0.0f
+ };
+ return params;
+}
+
+// function setting the pwm duty cycle to the hardware
+// - Stepper motor - 4PWM setting
+// - hardware speciffic
+void _writeDutyCycle4PWM(float dc_1a, float dc_1b, float dc_2a, float dc_2b, void* params){
+ // transform duty cycle from [0,1] to [0,255]
+ analogWrite(((GenericDriverParams*)params)->pins[0], 255.0f*dc_1a);
+ analogWrite(((GenericDriverParams*)params)->pins[1], 255.0f*dc_1b);
+ analogWrite(((GenericDriverParams*)params)->pins[2], 255.0f*dc_2a);
+ analogWrite(((GenericDriverParams*)params)->pins[3], 255.0f*dc_2b);
+}
+
+
+
+
+// function configuring pair of high-low side pwm channels, 32khz frequency and center aligned pwm
+int _configureComplementaryPair(int pinH, int pinL) {
+ if( (pinH == 3 && pinL == 11 ) || (pinH == 11 && pinL == 3 ) ){
+ // configure the pwm phase-corrected mode
+ TCCR0A = ((TCCR0A & 0b11111100) | 0x01);
+ // configure complementary pwm on low side
+ if(pinH == 11 ) TCCR0A = 0b10110000 | (TCCR0A & 0b00001111) ;
+ else TCCR0A = 0b11100000 | (TCCR0A & 0b00001111) ;
+ // set prescaler to 1 - 32kHz freq
+ TCCR0B = ((TCCR0B & 0b11110000) | 0x01);
+ }else if( (pinH == 9 && pinL == 10 ) || (pinH == 10 && pinL == 9 ) ){
+ // set prescaler to 1 - 32kHz freq
+ TCCR1B = ((TCCR1B & 0b11111000) | 0x01);
+ // configure complementary pwm on low side
+ if(pinH == 9 ) TCCR1A = 0b10110000 | (TCCR1A & 0b00001111) ;
+ else TCCR1A = 0b11100000 | (TCCR1A & 0b00001111) ;
+ }else if((pinH == 6 && pinL == 13 ) || (pinH == 13 && pinL == 6 ) ){
+ // PLL Configuration
+ PLLFRQ= ((PLLFRQ & 0b11001111) | 0x20); // Use 96MHz / 1.5 = 64MHz
+ TCCR4B = ((TCCR4B & 0b11110000) | 0xB); // configure prescaler to get 64M/2/1024 = 31.25 kHz
+ TCCR4D = ((TCCR4D & 0b11111100) | 0x01); // configure the pwm phase-corrected mode
+
+ // configure complementary pwm on low side
+ if(pinH == 13 ){
+ TCCR4A = 0x82; // activate channel A - pin 13
+ TCCR4C |= 0x0d; // Activate complementary channel D - pin 6
+ }else {
+ TCCR4C |= 0x09; // Activate channel D - pin 6
+ TCCR4A = 0xc2; // activate complementary channel A - pin 13
+ }
+ }else{
+ return -1;
+ }
+ return 0;
+}
+
+
+// Configuring PWM frequency, resolution and alignment
+// - BLDC driver - 6PWM setting
+// - hardware specific
+void* _configure6PWM(long pwm_frequency, float dead_zone, const int pinA_h, const int pinA_l, const int pinB_h, const int pinB_l, const int pinC_h, const int pinC_l) {
+ // High PWM frequency
+ // - always max 32kHz
+ int ret_flag = 0;
+ ret_flag += _configureComplementaryPair(pinA_h, pinA_l);
+ ret_flag += _configureComplementaryPair(pinB_h, pinB_l);
+ ret_flag += _configureComplementaryPair(pinC_h, pinC_l);
+ if (ret_flag!=0) return SIMPLEFOC_DRIVER_INIT_FAILED;
+ GenericDriverParams* params = new GenericDriverParams {
+ .pins = { pinA_h, pinA_l, pinB_h, pinB_l, pinC_h, pinC_l },
+ .pwm_frequency = pwm_frequency,
+ .dead_zone = dead_zone
+ };
+ return params;
+}
+
+// function setting the
+void _setPwmPair(int pinH, int pinL, float val, int dead_time)
+{
+ int pwm_h = _constrain(val-dead_time/2,0,255);
+ int pwm_l = _constrain(val+dead_time/2,0,255);
+
+ analogWrite(pinH, pwm_h);
+ if(pwm_l == 255 || pwm_l == 0)
+ digitalWrite(pinL, pwm_l ? LOW : HIGH);
+ else
+ analogWrite(pinL, pwm_l);
+}
+
+// Function setting the duty cycle to the pwm pin (ex. analogWrite())
+// - BLDC driver - 6PWM setting
+// - hardware specific
+// supports Arudino/ATmega328
+void _writeDutyCycle6PWM(float dc_a, float dc_b, float dc_c, PhaseState *phase_state, void* params){
+ _setPwmPair(((GenericDriverParams*)params)->pins[0], ((GenericDriverParams*)params)->pins[1], dc_a*255.0, ((GenericDriverParams*)params)->dead_zone*255.0);
+ _setPwmPair(((GenericDriverParams*)params)->pins[2], ((GenericDriverParams*)params)->pins[3], dc_b*255.0, ((GenericDriverParams*)params)->dead_zone*255.0);
+ _setPwmPair(((GenericDriverParams*)params)->pins[4], ((GenericDriverParams*)params)->pins[5], dc_c*255.0, ((GenericDriverParams*)params)->dead_zone*255.0);
+
+ _UNUSED(phase_state);
+}
+
+#endif
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/drivers/hardware_specific/due_mcu.cpp b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/drivers/hardware_specific/due_mcu.cpp
new file mode 100644
index 0000000..4397114
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/drivers/hardware_specific/due_mcu.cpp
@@ -0,0 +1,449 @@
+#include "../hardware_api.h"
+
+#if defined(__arm__) && defined(__SAM3X8E__)
+
+
+#pragma message("")
+#pragma message("SimpleFOC: compiling for Arduino/Due")
+#pragma message("")
+
+
+#define _PWM_FREQUENCY 25000 // 25khz
+#define _PWM_FREQUENCY_MAX 50000 // 50khz
+
+#define _PWM_RES_MIN 255 // 50khz
+
+// pwm frequency and max duty cycle
+static unsigned long _pwm_frequency;
+static int _max_pwm_value = 1023;
+
+// array mapping the timer values to the interrupt handlers
+static IRQn_Type irq_type[] = {TC0_IRQn, TC0_IRQn, TC1_IRQn, TC1_IRQn, TC2_IRQn, TC2_IRQn, TC3_IRQn, TC3_IRQn, TC4_IRQn, TC4_IRQn, TC5_IRQn, TC5_IRQn, TC6_IRQn, TC6_IRQn, TC7_IRQn, TC7_IRQn, TC8_IRQn, TC8_IRQn};
+// current counter values
+static volatile uint32_t pwm_counter_vals[] = {0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0};
+
+
+// variables copied from wiring_analog.cpp for arduino due
+static uint8_t PWMEnabled = 0;
+static uint8_t TCChanEnabled[] = {0, 0, 0, 0, 0, 0, 0, 0, 0};
+static const uint32_t channelToChNo[] = { 0, 0, 1, 1, 2, 2, 0, 0, 1, 1, 2, 2, 0, 0, 1, 1, 2, 2 };
+static const uint32_t channelToAB[] = { 1, 0, 1, 0, 1, 0, 1, 0, 1, 0, 1, 0, 1, 0, 1, 0, 1, 0 };
+static Tc *channelToTC[] = {
+ TC0, TC0, TC0, TC0, TC0, TC0,
+ TC1, TC1, TC1, TC1, TC1, TC1,
+ TC2, TC2, TC2, TC2, TC2, TC2 };
+static const uint32_t channelToId[] = { 0, 0, 1, 1, 2, 2, 3, 3, 4, 4, 5, 5, 6, 6, 7, 7, 8, 8 };
+
+
+// function setting the CMR register
+static void TC_SetCMR_ChannelA(Tc *tc, uint32_t chan, uint32_t v){ tc->TC_CHANNEL[chan].TC_CMR = (tc->TC_CHANNEL[chan].TC_CMR & 0xFFF0FFFF) | v;}
+static void TC_SetCMR_ChannelB(Tc *tc, uint32_t chan, uint32_t v){ tc->TC_CHANNEL[chan].TC_CMR = (tc->TC_CHANNEL[chan].TC_CMR & 0xF0FFFFFF) | v; }
+
+
+// function which starts and syncs the timers
+// if the pin is the true PWM pin this function does not do anything
+void syncTimers(uint32_t ulPin1,uint32_t ulPin2, uint32_t ulPin3 = -1, uint32_t ulPin4 = -1){
+ uint32_t chNo1,chNo2,chNo3,chNo4;
+ Tc *chTC1 = nullptr,*chTC2 = nullptr,*chTC3 = nullptr,*chTC4 = nullptr;
+
+ // configure timer channel for the first pin if it is a timer pin
+ uint32_t attr = g_APinDescription[ulPin1].ulPinAttribute;
+ if ((attr & PIN_ATTR_TIMER) == PIN_ATTR_TIMER) {
+ ETCChannel channel1 = g_APinDescription[ulPin1].ulTCChannel;
+ chNo1 = channelToChNo[channel1];
+ chTC1 = channelToTC[channel1];
+ TCChanEnabled[channelToId[channel1]] = 1;
+ }
+
+ // configure timer channel for the first pin if it is a timer pin
+ attr = g_APinDescription[ulPin2].ulPinAttribute;
+ if ((attr & PIN_ATTR_TIMER) == PIN_ATTR_TIMER) {
+ ETCChannel channel2 = g_APinDescription[ulPin2].ulTCChannel;
+ chNo2 = channelToChNo[channel2];
+ chTC2 = channelToTC[channel2];
+ TCChanEnabled[channelToId[channel2]] = 1;
+ }
+ if(ulPin3 > 0 ){
+ // configure timer channel for the first pin if it is a timer pin
+ attr = g_APinDescription[ulPin3].ulPinAttribute;
+ if ((attr & PIN_ATTR_TIMER) == PIN_ATTR_TIMER) {
+ ETCChannel channel3 = g_APinDescription[ulPin3].ulTCChannel;
+ chNo3 = channelToChNo[channel3];
+ chTC3 = channelToTC[channel3];
+ TCChanEnabled[channelToId[channel3]] = 1;
+ }
+ }
+ if(ulPin4 > 0 ){
+ // configure timer channel for the first pin if it is a timer pin
+ attr = g_APinDescription[ulPin4].ulPinAttribute;
+ if ((attr & PIN_ATTR_TIMER) == PIN_ATTR_TIMER) {
+ ETCChannel channel4 = g_APinDescription[ulPin4].ulTCChannel;
+ chNo4 = channelToChNo[channel4];
+ chTC4 = channelToTC[channel4];
+ TCChanEnabled[channelToId[channel4]] = 1;
+ }
+ }
+ // start timers and make them synced
+ if(chTC1){
+ TC_Start(chTC1, chNo1);
+ chTC1->TC_BCR = TC_BCR_SYNC;
+ }
+ if(chTC2){
+ TC_Start(chTC2, chNo2);
+ chTC2->TC_BCR = TC_BCR_SYNC;
+ }
+ if(chTC3 && ulPin3){
+ TC_Start(chTC3, chNo3);
+ chTC3->TC_BCR = TC_BCR_SYNC;
+ }
+ if(chTC4 && ulPin4){
+ TC_Start(chTC4, chNo4);
+ chTC4->TC_BCR = TC_BCR_SYNC;
+ }
+}
+
+// function configuring the pwm frequency for given pin
+// possible to supply the pwm pin and the timer pin
+void initPWM(uint32_t ulPin, uint32_t pwm_freq){
+ // check which pin type
+ uint32_t attr = g_APinDescription[ulPin].ulPinAttribute;
+ if ((attr & PIN_ATTR_PWM) == PIN_ATTR_PWM) { // if pwm pin
+
+ if (!PWMEnabled) {
+ // PWM Startup code
+ pmc_enable_periph_clk(PWM_INTERFACE_ID);
+ // this function does not work too well - I'll rewrite it
+ // PWMC_ConfigureClocks(PWM_FREQUENCY * _max_pwm_value, 0, VARIANT_MCK);
+
+ // finding the divisors an prescalers form FindClockConfiguration function
+ uint32_t divisors[11] = {1, 2, 4, 8, 16, 32, 64, 128, 256, 512, 1024};
+ uint8_t divisor = 0;
+ uint32_t prescaler;
+
+ /* Find prescaler and divisor values */
+ prescaler = (VARIANT_MCK / divisors[divisor]) / (pwm_freq*_max_pwm_value);
+ while ((prescaler > 255) && (divisor < 11)) {
+ divisor++;
+ prescaler = (VARIANT_MCK / divisors[divisor]) / (pwm_freq*_max_pwm_value);
+ }
+ // update the divisor*prescaler value
+ prescaler = prescaler | (divisor << 8);
+
+ // now calculate the real resolution timer period necessary (pwm resolution)
+ // pwm_res = bus_freq / (pwm_freq * (prescaler))
+ _max_pwm_value = (double)VARIANT_MCK / (double)pwm_freq / (double)(prescaler);
+ // set the prescaler value
+ PWM->PWM_CLK = prescaler;
+
+ PWMEnabled = 1;
+ }
+
+ uint32_t chan = g_APinDescription[ulPin].ulPWMChannel;
+ if ((g_pinStatus[ulPin] & 0xF) != PIN_STATUS_PWM) {
+ // Setup PWM for this pin
+ PIO_Configure(g_APinDescription[ulPin].pPort,
+ g_APinDescription[ulPin].ulPinType,
+ g_APinDescription[ulPin].ulPin,
+ g_APinDescription[ulPin].ulPinConfiguration);
+ // PWM_CMR_CALG - center align
+ // PWMC_ConfigureChannel(PWM_INTERFACE, chan, PWM_CMR_CPRE_CLKA, PWM_CMR_CALG, 0);
+ PWMC_ConfigureChannel(PWM_INTERFACE, chan, PWM_CMR_CPRE_CLKA, 0, 0);
+ PWMC_SetPeriod(PWM_INTERFACE, chan, _max_pwm_value);
+ PWMC_SetDutyCycle(PWM_INTERFACE, chan, 0);
+ PWMC_EnableChannel(PWM_INTERFACE, chan);
+ g_pinStatus[ulPin] = (g_pinStatus[ulPin] & 0xF0) | PIN_STATUS_PWM;
+ }
+ return;
+ }
+
+ if ((attr & PIN_ATTR_TIMER) == PIN_ATTR_TIMER) { // if timer pin
+ // We use MCLK/2 as clock.
+ const uint32_t TC = VARIANT_MCK / 2 / pwm_freq ;
+ // Setup Timer for this pin
+ ETCChannel channel = g_APinDescription[ulPin].ulTCChannel;
+ uint32_t chNo = channelToChNo[channel];
+ uint32_t chA = channelToAB[channel];
+ Tc *chTC = channelToTC[channel];
+ uint32_t interfaceID = channelToId[channel];
+
+ if (!TCChanEnabled[interfaceID]) {
+ pmc_enable_periph_clk(TC_INTERFACE_ID + interfaceID);
+ TC_Configure(chTC, chNo,
+ TC_CMR_TCCLKS_TIMER_CLOCK1 |
+ TC_CMR_WAVE | // Waveform mode
+ TC_CMR_WAVSEL_UP_RC | // Counter running up and reset when equals to RC
+ TC_CMR_EEVT_XC0 | // Set external events from XC0 (this setup TIOB as output)
+ TC_CMR_ACPA_CLEAR | TC_CMR_ACPC_CLEAR |
+ TC_CMR_BCPB_CLEAR | TC_CMR_BCPC_CLEAR);
+ TC_SetRC(chTC, chNo, TC);
+ }
+
+ // disable the counter on start
+ if (chA){
+ TC_SetCMR_ChannelA(chTC, chNo, TC_CMR_ACPA_CLEAR | TC_CMR_ACPC_SET);
+ }else{
+ TC_SetCMR_ChannelB(chTC, chNo, TC_CMR_BCPB_CLEAR | TC_CMR_BCPC_SET);
+ }
+ // configure input-ouput structure
+ if ((g_pinStatus[ulPin] & 0xF) != PIN_STATUS_PWM) {
+ PIO_Configure(g_APinDescription[ulPin].pPort,
+ g_APinDescription[ulPin].ulPinType,
+ g_APinDescription[ulPin].ulPin,
+ g_APinDescription[ulPin].ulPinConfiguration);
+ g_pinStatus[ulPin] = (g_pinStatus[ulPin] & 0xF0) | PIN_STATUS_PWM;
+ }
+ // enable interrupts
+ chTC->TC_CHANNEL[chNo].TC_IER = TC_IER_CPAS // interrupt on RA compare match
+ | TC_IER_CPBS // interrupt on RB compare match
+ | TC_IER_CPCS; // interrupt on RC compare match
+ chTC->TC_CHANNEL[chNo].TC_IDR = ~TC_IER_CPAS // interrupt on RA compare match
+ & ~TC_IER_CPBS // interrupt on RB compare match
+ & ~ TC_IER_CPCS; // interrupt on RC compare match
+ // enable interrupts for this timer
+ NVIC_EnableIRQ(irq_type[channel]);
+ return;
+ }
+}
+
+// pwm setting function
+// it sets the duty cycle for pwm pin or timer pin
+void setPwm(uint32_t ulPin, uint32_t ulValue) {
+ // check pin type
+ uint32_t attr = g_APinDescription[ulPin].ulPinAttribute;
+ if ((attr & PIN_ATTR_PWM) == PIN_ATTR_PWM) { // if pwm
+ uint32_t chan = g_APinDescription[ulPin].ulPWMChannel;
+ PWMC_SetDutyCycle(PWM_INTERFACE, chan, ulValue);
+ return;
+ }
+
+ if ((attr & PIN_ATTR_TIMER) == PIN_ATTR_TIMER) { // if timer pin
+ // get the timer variables
+ ETCChannel channel = g_APinDescription[ulPin].ulTCChannel;
+ Tc *chTC = channelToTC[channel];
+ uint32_t chNo = channelToChNo[channel];
+ if(!ulValue) {
+ // if the value 0 disable counter
+ if (channelToAB[channel])
+ TC_SetCMR_ChannelA(chTC, chNo, TC_CMR_ACPA_CLEAR | TC_CMR_ACPC_CLEAR);
+ else
+ TC_SetCMR_ChannelB(chTC, chNo, TC_CMR_BCPB_CLEAR | TC_CMR_BCPC_CLEAR);
+ }else{
+ // if the value not zero
+ // calculate clock
+ const uint32_t TC = VARIANT_MCK / 2 / _pwm_frequency;
+ // Map value to Timer ranges 0..max_duty_cycle => 0..TC
+ // Setup Timer for this pin
+ ulValue = ulValue * TC ;
+ pwm_counter_vals[channel] = ulValue / _max_pwm_value;
+ // enable counter
+ if (channelToAB[channel])
+ TC_SetCMR_ChannelA(chTC, chNo, TC_CMR_ACPA_CLEAR | TC_CMR_ACPC_SET);
+ else
+ TC_SetCMR_ChannelB(chTC, chNo, TC_CMR_BCPB_CLEAR | TC_CMR_BCPC_SET);
+ }
+
+ return;
+ }
+}
+
+// interrupt handlers for seamless pwm duty-cycle setting
+void TC0_Handler()
+{
+ // read/clear interrupt status
+ TC_GetStatus(TC0, 0);
+ // update the counters
+ if(pwm_counter_vals[0]) TC_SetRA(TC0, 0, pwm_counter_vals[0]);
+ if(pwm_counter_vals[1]) TC_SetRB(TC0, 0, pwm_counter_vals[1]);
+}
+
+void TC1_Handler()
+{
+ // read/clear interrupt status
+ TC_GetStatus(TC0, 1);
+ // update the counters
+ if(pwm_counter_vals[2]) TC_SetRA(TC0, 1, pwm_counter_vals[2]);
+ if(pwm_counter_vals[3]) TC_SetRB(TC0, 1, pwm_counter_vals[3]);
+}
+
+void TC2_Handler()
+{
+ // read/clear interrupt status
+ TC_GetStatus(TC0, 2);
+ // update the counters
+ if(pwm_counter_vals[4]) TC_SetRA(TC0, 2, pwm_counter_vals[4]);
+ if(pwm_counter_vals[5]) TC_SetRB(TC0, 2, pwm_counter_vals[5]);
+}
+void TC3_Handler()
+{
+ // read/clear interrupt status
+ TC_GetStatus(TC1, 0);
+ // update the counters
+ if(pwm_counter_vals[6]) TC_SetRA(TC1, 0, pwm_counter_vals[6]);
+ if(pwm_counter_vals[7]) TC_SetRB(TC1, 0, pwm_counter_vals[7]);
+}
+
+void TC4_Handler()
+{
+ // read/clear interrupt status
+ TC_GetStatus(TC1, 1);
+ // update the counters
+ if(pwm_counter_vals[8]) TC_SetRA(TC1, 1, pwm_counter_vals[8]);
+ if(pwm_counter_vals[9]) TC_SetRB(TC1, 1, pwm_counter_vals[9]);
+}
+
+void TC5_Handler()
+{
+ // read/clear interrupt status
+ TC_GetStatus(TC1, 2);
+ // update the counters
+ if(pwm_counter_vals[10]) TC_SetRA(TC1, 2, pwm_counter_vals[10]);
+ if(pwm_counter_vals[11]) TC_SetRB(TC1, 2, pwm_counter_vals[11]);
+}
+void TC6_Handler()
+{
+ // read/clear interrupt status
+ TC_GetStatus(TC2, 0);
+ // update the counters
+ if(pwm_counter_vals[12]) TC_SetRA(TC2, 0, pwm_counter_vals[12]);
+ if(pwm_counter_vals[13]) TC_SetRB(TC2, 0, pwm_counter_vals[13]);
+}
+
+void TC7_Handler()
+{
+ // read/clear interrupt status
+ TC_GetStatus(TC2, 1);
+ // update the counters
+ if(pwm_counter_vals[14]) TC_SetRA(TC2, 1, pwm_counter_vals[14]);
+ if(pwm_counter_vals[15]) TC_SetRB(TC2, 1, pwm_counter_vals[15]);
+}
+
+void TC8_Handler()
+{
+ // read/clear interrupt status
+ TC_GetStatus(TC2, 2);
+ // update the counters
+ if(pwm_counter_vals[16]) TC_SetRA(TC2, 2, pwm_counter_vals[16]);
+ if(pwm_counter_vals[17]) TC_SetRB(TC2, 2, pwm_counter_vals[17]);
+}
+
+
+
+
+
+// implementation of the hardware_api.cpp
+// ---------------------------------------------------------------------------------------------------------------------------------
+
+// function setting the high pwm frequency to the supplied pins
+// - BLDC motor - 3PWM setting
+// - hardware specific
+void* _configure3PWM(long pwm_frequency,const int pinA, const int pinB, const int pinC) {
+ if(!pwm_frequency || !_isset(pwm_frequency) ) pwm_frequency = _PWM_FREQUENCY; // default frequency 50khz
+ else pwm_frequency = _constrain(pwm_frequency, 0, _PWM_FREQUENCY_MAX); // constrain to 50kHz max
+ // save the pwm frequency
+ _pwm_frequency = pwm_frequency;
+ // cinfigure pwm pins
+ initPWM(pinA, _pwm_frequency);
+ initPWM(pinB, _pwm_frequency);
+ initPWM(pinC, _pwm_frequency);
+ // sync the timers if possible
+ syncTimers(pinA, pinB, pinC);
+
+ GenericDriverParams* params = new GenericDriverParams {
+ .pins = { pinA, pinB, pinC },
+ .pwm_frequency = pwm_frequency
+ };
+ return params;
+}
+
+
+
+
+// Configuring PWM frequency, resolution and alignment
+//- Stepper driver - 2PWM setting
+// - hardware specific
+void* _configure2PWM(long pwm_frequency, const int pinA, const int pinB) {
+ if(!pwm_frequency || !_isset(pwm_frequency)) pwm_frequency = _PWM_FREQUENCY; // default frequency 50khz
+ else pwm_frequency = _constrain(pwm_frequency, 0, _PWM_FREQUENCY_MAX); // constrain to 50kHz max
+ // save the pwm frequency
+ _pwm_frequency = pwm_frequency;
+ // cinfigure pwm pins
+ initPWM(pinA, _pwm_frequency);
+ initPWM(pinB, _pwm_frequency);
+ // sync the timers if possible
+ syncTimers(pinA, pinB);
+
+ GenericDriverParams* params = new GenericDriverParams {
+ .pins = { pinA, pinB },
+ .pwm_frequency = pwm_frequency
+ };
+ return params;
+}
+
+
+
+
+// function setting the high pwm frequency to the supplied pins
+// - Stepper motor - 4PWM setting
+// - hardware speciffic
+void* _configure4PWM(long pwm_frequency,const int pinA, const int pinB, const int pinC, const int pinD) {
+ if(!pwm_frequency || !_isset(pwm_frequency)) pwm_frequency = _PWM_FREQUENCY; // default frequency 50khz
+ else pwm_frequency = _constrain(pwm_frequency, 0, _PWM_FREQUENCY_MAX); // constrain to 50kHz max
+ // save the pwm frequency
+ _pwm_frequency = pwm_frequency;
+ // cinfigure pwm pins
+ initPWM(pinA, _pwm_frequency);
+ initPWM(pinB, _pwm_frequency);
+ initPWM(pinC, _pwm_frequency);
+ initPWM(pinD, _pwm_frequency);
+ // sync the timers if possible
+ syncTimers(pinA, pinB, pinC, pinD);
+
+ GenericDriverParams* params = new GenericDriverParams {
+ .pins = { pinA, pinB, pinC, pinD },
+ .pwm_frequency = pwm_frequency
+ };
+ return params;
+}
+
+
+
+
+// function setting the pwm duty cycle to the hardware
+// - BLDC motor - 3PWM setting
+// - hardware speciffic
+void _writeDutyCycle3PWM(float dc_a, float dc_b, float dc_c, void* param){
+ // transform duty cycle from [0,1] to [0,_max_pwm_value]
+ GenericDriverParams* p = (GenericDriverParams*)param;
+ setPwm(p->pins[0], _max_pwm_value*dc_a);
+ setPwm(p->pins[1], _max_pwm_value*dc_b);
+ setPwm(p->pins[2], _max_pwm_value*dc_c);
+}
+
+
+
+// function setting the pwm duty cycle to the hardware
+// - Stepper motor - 4PWM setting
+// - hardware speciffic
+void _writeDutyCycle4PWM(float dc_1a, float dc_1b, float dc_2a, float dc_2b, void* param){
+ // transform duty cycle from [0,1] to [0,_max_pwm_value]
+ GenericDriverParams* p = (GenericDriverParams*)param;
+ setPwm(p->pins[0], _max_pwm_value*dc_1a);
+ setPwm(p->pins[1], _max_pwm_value*dc_1b);
+ setPwm(p->pins[2], _max_pwm_value*dc_2a);
+ setPwm(p->pins[3], _max_pwm_value*dc_2b);
+}
+
+
+
+// Function setting the duty cycle to the pwm pin (ex. analogWrite())
+// - Stepper driver - 2PWM setting
+// - hardware specific
+void _writeDutyCycle2PWM(float dc_a, float dc_b, void* param){
+ // transform duty cycle from [0,1] to [0,_max_pwm_value]
+ GenericDriverParams* p = (GenericDriverParams*)param;
+ setPwm(p->pins[0], _max_pwm_value*dc_a);
+ setPwm(p->pins[1], _max_pwm_value*dc_b);
+}
+
+
+#endif
\ No newline at end of file
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/drivers/hardware_specific/esp32/esp32_driver_mcpwm.cpp b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/drivers/hardware_specific/esp32/esp32_driver_mcpwm.cpp
new file mode 100644
index 0000000..a481c6f
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/drivers/hardware_specific/esp32/esp32_driver_mcpwm.cpp
@@ -0,0 +1,508 @@
+
+/*
+* MCPWM in espressif v5.x has
+* - 2x groups (units)
+* each one has
+* - 3 timers
+* - 3 operators (that can be associated with any timer)
+* which control a 2xPWM signals
+* - 1x comparator + 1x generator per PWM signal
+
+
+* Independent mode:
+* ------------------
+* 6 PWM independent signals per unit
+* unit(0/1) > timer(0-2) > operator(0-2) > comparator(0-1) > generator(0-1) > pwm(A/B)
+*
+* -------------------------------------- Table View -----------------------------
+*
+* group | timer | operator | comparator | generator | pwm
+* --------------------------------------------------------------------------------
+* 0-1 | 0-2 | 0 | 0 | 0 | A
+* 0-1 | 0-2 | 0 | 1 | 1 | B
+* 0-1 | 0-2 | 1 | 0 | 0 | A
+* 0-1 | 0-2 | 1 | 1 | 1 | B
+* 0-1 | 0-2 | 2 | 0 | 0 | A
+* 0-1 | 0-2 | 2 | 1 | 1 | B
+*
+* ------------------------------------- Example 3PWM ------------------------------
+* ┌─ comparator 0 - generator 0 -> pwm A
+* ┌─ operator 0 -|
+* | └─ comparator 1 - generator 1 -> pmw B
+* unit - timer 0-2 -|
+* 0-1 └─ operator 1 - comparator 0 - generator 0 - pwm C
+*
+* ------------------------------------- Example 2PWM ------------------------------
+* ┌─ comparator 0 - generator 0 -> pwm A
+* unit - timer 0-2 - operator 0 -|
+* 0-1 └─ comparator 1 - generator 1 -> pmw B
+*
+* -------------------------------------- Example 4PWM -----------------------------
+* ┌─ comparator 0 - generator 0 -> pwm A
+* ┌─ operator 0 -|
+* | └─ comparator 1 - generator 1 -> pmw B
+* unit - timer 0-2 -|
+* 0-1 | ┌─ comparator 0 - generator 0 -> pwm C
+* └─ operator 1 -|
+* └─ comparator 0 - generator 0 -> pwm D
+
+
+* Complementary mode
+* ------------------
+* - : 3 pairs of complementary PWM signals per unit
+* unit(0/1) > timer(0) > operator(0-2) > comparator(0-1) > generator(0-1) > pwm(high/low pair)
+*
+* -------------------------------------- Table View -----------------------------
+*
+* group | timer | operator | comparator | generator | pwm
+* ------------------------------------------------------------------------
+* 0-1 | 0 | 0 | 0 | 0 | A
+* 0-1 | 0 | 0 | 1 | 1 | B
+* 0-1 | 0 | 1 | 0 | 0 | A
+* 0-1 | 0 | 1 | 1 | 1 | B
+* 0-1 | 0 | 2 | 0 | 0 | A
+* 0-1 | 0 | 2 | 1 | 1 | B
+*
+* -------------------------------------- Example 6PWM -----------------------------
+*
+* ┌─ comparator 0 - generator 0 -> pwm A_h
+* ┌─ operator 0 -|
+* | └─ comparator 1 - generator 1 -> pmw A_l
+* |
+* unit | ┌─ comparator 0 - generator 0 -> pwm B_h
+* (group) - timer 0 -|- operator 1 -|
+* 0-1 | └─ comparator 1 - generator 1 -> pmw B_l
+* |
+* | ┌─ comparator 0 - generator 0 -> pwm C_h
+* └─ operator 2 -|
+* └─ comparator 1 - generator 1 -> pmw C_l
+*
+
+
+* More info
+* ----------
+* - timers can be associated with any operator, and multiple operators can be associated with the same timer
+* - comparators can be associated with any operator
+* - two comparators per operator for independent mode
+* - one comparator per operator for complementary mode
+* - generators can be associated with any comparator
+* - one generator per PWM signal for independent mode
+* - two generators per pair of PWM signals for complementary mode (not used in simplefoc)
+* - dead-time can be set for each generator pair in complementary mode
+*
+* Docs
+* -------
+* More info here: https:*www.espressif.com/sites/default/files/documentation/esp32_technical_reference_manual_en.pdf#mcpwm
+* and here: // https://docs.espressif.com/projects/esp-idf/en/v5.1.4/esp32/migration-guides/release-5.x/5.0/peripherals.html
+*/
+
+#include "../../hardware_api.h"
+
+#if defined(ESP_H) && defined(ARDUINO_ARCH_ESP32) && defined(SOC_MCPWM_SUPPORTED) && !defined(SIMPLEFOC_ESP32_USELEDC)
+
+#include "esp32_driver_mcpwm.h"
+
+// MCPWM driver hardware timer pointers
+mcpwm_timer_handle_t timers[2][3] = {NULL};
+// MCPWM timer periods configured (directly related to the pwm frequency)
+uint32_t pwm_periods[2][3];
+// how many pins from the groups 6 pins is used
+uint8_t group_pins_used[2] = {0};
+// last operator in the group
+mcpwm_oper_handle_t last_operator[2];
+
+
+
+// checking if group has pins available
+bool _hasAvailablePins(int group, int no_pins){
+ if(group_pins_used[group] + no_pins > 6){
+ return false;
+ }
+ return true;
+}
+
+// returns the index of the last timer in the group
+// -1 if no timer instantiated yet
+uint8_t _findLastTimer(int group){
+ int i = 0;
+ for(; i<3; i++){
+ if(timers[group][i] == NULL){
+ return i-1;
+ }
+ }
+ // return the last index
+ return i;
+}
+// returns the index of the next timer to instantiate
+// -1 if no timers available
+uint8_t _findNextTimer(int group){
+ int i = 0;
+ for(; i<3; i++){
+ if(timers[group][i] == NULL){
+ return i;
+ }
+ }
+ return -1;
+}
+
+/*
+ * find the best group for the pins
+ * if 6pwm
+ * - Only option is an an empty group
+ * if 3pwm
+ * - Best is an empty group (we can set a pwm frequency)
+ * - Second best is a group with 4pwms (2 operators) available (we can set the pwm frequency -> new timer+new operator)
+ * - Third best option is any group which has 3pwms available (but uses previously defined pwm_frequency)
+ * if 1pwm
+ * - Best option is an empty group (we can set the pwm frequency)
+ * - Second best is a group with 2pwms (one operator) available (we can set the pwm frequency -> new timer+new operator)
+ * - Third best is a group with 1pwm available (but uses previously defined pwm_frequency )
+ * if 2pwm
+ * - Best option is an empty group (we can set the pwm frequency)
+ * - Second best is a group with 2pwms available (we can set the pwm frequency -> new timer+new operator)
+ * - Third best is one pin per group (but uses previously defined pwm_frequency )
+ * if 4pwm
+ * - best option is an empty group (we can set the pwm frequency)
+ * - second best is a group with 4pwms available (we can set the pwm frequency -> new timer + new operators)
+ * - third best is 2pwms per group (we can set the pwm frequency -> new timers + new operators)
+ *
+ * PROBLEM: Skipping/loosing channels happens in some cases when the group has already used some odd number of pwm channels (for example 3pwm or 1pwm)
+ * For example if the group has already used 3pwms, there is one generator that has one pwm channel left.
+ * If we use this channel we have to use the same timer it has been used with before, so we cannot change the pwm frequency.
+ * Current implementation does use the remaining channel only if there isn't other options that would allow changing the pwm frequency.
+ * In this example where we have 3pwms already configured, if we try to configure 2pws after, we will skip the remaining channel
+ * and use a new timer and operator to allow changing the pwm frequency. In such cases we loose (cannot be used) the remaining channel.
+ * TODO: use the pwm_frequency to avoid skipping pwm channels !
+ *
+ * returns
+ * - 1 if solution found in one group
+ * - 2 if solution requires using both groups
+ * - 0 if no solution possible
+*/
+int _findBestGroup(int no_pins, long pwm_freq, int* group, int* timer){
+ // an empty group is always the best option
+ for(int i=0; i<2; i++){
+ if(!group_pins_used[i]){
+ *group = i;
+ *timer=0; // use the first timer in an empty group
+ return 1;
+ }
+ }
+
+ // if 3 or 1pwm
+ // check if there is available space in one of the groups
+ // otherwise fail
+ if(no_pins == 3 || no_pins==1){
+ // second best option is if there is a group with
+ // pair number of pwms available as we can then
+ // set the pwm frequency
+ for(int i=0; i<2; i++){
+ if(_hasAvailablePins(i, no_pins+1)) {
+ *group=i;
+ *timer = _findNextTimer(i);
+ return 1;
+ }
+ }
+ // third best option is any group that has enough pins
+ for(int i=0; i<2; i++){
+ if(_hasAvailablePins(i, no_pins)) {
+ *group=i;
+ *timer = _findLastTimer(i);
+ return 1;
+ }
+ }
+ }
+
+ // if 2 or 4 pwm
+ // check if there is available space in one of the groups
+ // if not check if they can be separated in two groups
+ if(no_pins == 2 || no_pins==4){
+ // second best option is any group that has enough pins
+ for(int i=0; i<2; i++){
+ if(_hasAvailablePins(i, no_pins)) {
+ *group=i;
+ *timer = _findNextTimer(i);
+ return 1;
+ }
+ }
+ // third best option is half pwms per group
+ int half_no_pins = (int)no_pins/2;
+ if(_hasAvailablePins(0,half_no_pins) && _hasAvailablePins(1 ,half_no_pins)){
+ return 2;
+ }
+ }
+
+ // otherwise fail
+ return 0;
+}
+
+
+// configuring center aligned pwm
+// More info here: https://docs.espressif.com/projects/esp-idf/en/v5.1.4/esp32/api-reference/peripherals/mcpwm.html#symmetric-dual-edge-active-low
+int _configureCenterAlign(mcpwm_gen_handle_t gena, mcpwm_cmpr_handle_t cmpa, bool inverted = false){
+ if(inverted)
+ return mcpwm_generator_set_actions_on_compare_event(gena,
+ MCPWM_GEN_COMPARE_EVENT_ACTION(MCPWM_TIMER_DIRECTION_UP, cmpa, MCPWM_GEN_ACTION_HIGH),
+ MCPWM_GEN_COMPARE_EVENT_ACTION(MCPWM_TIMER_DIRECTION_DOWN, cmpa, MCPWM_GEN_ACTION_LOW),
+ MCPWM_GEN_COMPARE_EVENT_ACTION_END());
+ else
+ return mcpwm_generator_set_actions_on_compare_event(gena,
+ MCPWM_GEN_COMPARE_EVENT_ACTION(MCPWM_TIMER_DIRECTION_UP, cmpa, MCPWM_GEN_ACTION_LOW),
+ MCPWM_GEN_COMPARE_EVENT_ACTION(MCPWM_TIMER_DIRECTION_DOWN, cmpa, MCPWM_GEN_ACTION_HIGH),
+ MCPWM_GEN_COMPARE_EVENT_ACTION_END());
+}
+
+
+
+// Helper function calculating the pwm period from the pwm frequency
+// - pwm_frequency - pwm frequency in hertz
+// returns pwm period in ticks (uint32_t)
+uint32_t _calcPWMPeriod(long pwm_frequency) {
+ return (uint32_t)(1 * _PWM_TIMEBASE_RESOLUTION_HZ / pwm_frequency);
+}
+/*
+ Helper function calculating the pwm frequency from the pwm period
+ - pwm_period - pwm period in ticks
+ returns pwm frequency in hertz (long)
+*/
+long _calcPWMFreq(long pwm_period) {
+ return (uint32_t)(1 * _PWM_TIMEBASE_RESOLUTION_HZ / pwm_period / 2);
+}
+
+void* _configure6PWMPinsMCPWM(long pwm_frequency, int mcpwm_group, int timer_no, float dead_zone, int* pins){
+ ESP32MCPWMDriverParams* params = new ESP32MCPWMDriverParams{
+ .pwm_frequency = pwm_frequency,
+ .group_id = mcpwm_group
+ };
+
+ mcpwm_timer_config_t pwm_config;
+ pwm_config.group_id = mcpwm_group;
+ pwm_config.clk_src = MCPWM_TIMER_CLK_SRC_DEFAULT;
+ pwm_config.resolution_hz = _PWM_TIMEBASE_RESOLUTION_HZ;
+ pwm_config.count_mode = MCPWM_TIMER_COUNT_MODE_UP_DOWN;
+ pwm_config.intr_priority = 0;
+ pwm_config.period_ticks = _calcPWMPeriod(pwm_frequency);
+
+ CHECK_ERR(mcpwm_new_timer(&pwm_config, &timers[mcpwm_group][timer_no]), "Could not initialize the timer in group: " + String(mcpwm_group));
+ pwm_periods[mcpwm_group][timer_no] = pwm_config.period_ticks / 2;
+ params->timers[0] = timers[mcpwm_group][timer_no];
+ params->mcpwm_period = pwm_periods[mcpwm_group][timer_no];
+
+ uint8_t no_operators = 3; // use 3 comparators one per pair of pwms
+ SIMPLEFOC_ESP32_DRV_DEBUG("Configuring " + String(no_operators) + " operators.");
+ mcpwm_operator_config_t operator_config = { .group_id = mcpwm_group };
+ operator_config.intr_priority = 0;
+ operator_config.flags.update_gen_action_on_tep = true;
+ operator_config.flags.update_gen_action_on_tez = true;
+ for (int i = 0; i < no_operators; i++) {
+ CHECK_ERR(mcpwm_new_operator(&operator_config, ¶ms->oper[i]),"Could not create operator "+String(i));
+ CHECK_ERR(mcpwm_operator_connect_timer(params->oper[i], params->timers[0]),"Could not connect timer to operator: " + String(i));
+ }
+
+#if SIMPLEFOC_ESP32_HW_DEADTIME == true // hardware dead-time (hardware 6pwm)
+
+ SIMPLEFOC_ESP32_DRV_DEBUG("Configuring 6PWM with hardware dead-time");
+
+ SIMPLEFOC_ESP32_DRV_DEBUG("Configuring " + String(no_operators) + " comparators.");
+ // Create and configure comparators
+ mcpwm_comparator_config_t comparator_config = {0};
+ comparator_config.flags.update_cmp_on_tez = true;
+ for (int i = 0; i < no_operators; i++) {
+ CHECK_ERR(mcpwm_new_comparator(params->oper[i], &comparator_config, ¶ms->comparator[i]),"Could not create comparator: " + String(i));
+ CHECK_ERR(mcpwm_comparator_set_compare_value(params->comparator[i], (0)), "Could not set duty on comparator: " + String(i));
+ }
+
+#else // software dead-time (software 6pwm)
+// software dead-time (software 6pwm)
+ SIMPLEFOC_ESP32_DRV_DEBUG("Configuring 6PWM with software dead-time");
+
+ int no_pins = 6;
+ SIMPLEFOC_ESP32_DRV_DEBUG("Configuring " + String(no_pins) + " comparators.");
+ // Create and configure comparators
+ mcpwm_comparator_config_t comparator_config = {0};
+ comparator_config.flags.update_cmp_on_tez = true;
+ for (int i = 0; i < no_pins; i++) {
+ int oper_index = (int)floor(i / 2);
+ CHECK_ERR(mcpwm_new_comparator(params->oper[oper_index], &comparator_config, ¶ms->comparator[i]),"Could not create comparator: " + String(i));
+ CHECK_ERR(mcpwm_comparator_set_compare_value(params->comparator[i], (0)), "Could not set duty on comparator: " + String(i));
+ }
+#endif
+
+ int no_generators = 6; // one per pwm
+ SIMPLEFOC_ESP32_DRV_DEBUG("Configuring " + String(no_generators) + " generators.");
+ // Create and configure generators
+ mcpwm_generator_config_t generator_config = {};
+ for (int i = 0; i < no_generators; i++) {
+ generator_config.gen_gpio_num = pins[i];
+ int oper_index = (int)floor(i / 2);
+ CHECK_ERR(mcpwm_new_generator(params->oper[oper_index], &generator_config, ¶ms->generator[i]),"Could not create generator " + String(i) +String(" on pin: ")+String(pins[i]));
+ }
+
+ SIMPLEFOC_ESP32_DRV_DEBUG("Configuring Center-Aligned 6 pwm.");
+
+#if SIMPLEFOC_ESP32_HW_DEADTIME == true // hardware dead-time (hardware 6pwm)
+ for (int i = 0; i < no_operators; i++) {
+ CHECK_ERR(_configureCenterAlign(params->generator[2*i],params->comparator[i]), "Failed to configure high-side center align pwm: " + String(2*i));
+ CHECK_ERR(_configureCenterAlign(params->generator[2*i+1],params->comparator[i]), "Failed to configure low-side center align pwm: " + String(2*i+1));
+
+ }
+ // only available for 6pwm
+ SIMPLEFOC_ESP32_DRV_DEBUG("Configuring dead-time.");
+ uint32_t dead_time = (int)pwm_periods[mcpwm_group][timer_no] * dead_zone;
+ mcpwm_dead_time_config_t dt_config_high;
+ dt_config_high.posedge_delay_ticks = dead_time;
+ dt_config_high.negedge_delay_ticks = 0;
+ dt_config_high.flags.invert_output = !SIMPLEFOC_PWM_HIGHSIDE_ACTIVE_HIGH;
+ mcpwm_dead_time_config_t dt_config_low;
+ dt_config_low.posedge_delay_ticks = 0;
+ dt_config_low.negedge_delay_ticks = dead_time;
+ dt_config_low.flags.invert_output = SIMPLEFOC_PWM_LOWSIDE_ACTIVE_HIGH;
+ for (int i = 0; i < no_operators; i++) {
+ CHECK_ERR(mcpwm_generator_set_dead_time(params->generator[2*i], params->generator[2*i], &dt_config_high),"Could not set dead time for generator: " + String(i));
+ CHECK_ERR(mcpwm_generator_set_dead_time(params->generator[2*i+1], params->generator[2*i+1], &dt_config_low),"Could not set dead time for generator: " + String(i+1));
+ }
+#else // software dead-time (software 6pwm)
+ for (int i = 0; i < 3; i++) {
+ CHECK_ERR(_configureCenterAlign(params->generator[2*i],params->comparator[2*i], !SIMPLEFOC_PWM_HIGHSIDE_ACTIVE_HIGH), "Failed to configure high-side center align pwm: " + String(2*i));
+ CHECK_ERR(_configureCenterAlign(params->generator[2*i+1],params->comparator[2*i+1], SIMPLEFOC_PWM_LOWSIDE_ACTIVE_HIGH) , "Failed to configure low-side center align pwm: " + String(2*i+1));
+ }
+#endif
+
+ SIMPLEFOC_ESP32_DRV_DEBUG("Enabling timer: "+String(timer_no));
+ // Enable and start timer
+ CHECK_ERR(mcpwm_timer_enable(params->timers[0]), "Failed to enable timer!");
+ CHECK_ERR(mcpwm_timer_start_stop(params->timers[0], MCPWM_TIMER_START_NO_STOP), "Failed to start the timer!");
+
+ _delay(1);
+ SIMPLEFOC_ESP32_DRV_DEBUG("MCPWM configured!");
+ params->dead_zone = dead_zone;
+ // save the configuration variables for later
+ group_pins_used[mcpwm_group] = 6;
+ return params;
+}
+
+
+/*
+ function configuring the pins for the mcpwm
+ - pwm_frequency - pwm frequency
+ - mcpwm_group - mcpwm group
+ - timer_no - timer number
+ - no_pins - number of pins
+ - pins - array of pins
+ - dead_zone - dead zone
+
+ returns the driver parameters
+*/
+void* _configurePinsMCPWM(long pwm_frequency, int mcpwm_group, int timer_no, int no_pins, int* pins){
+
+ ESP32MCPWMDriverParams* params = new ESP32MCPWMDriverParams{
+ .pwm_frequency = pwm_frequency,
+ .group_id = mcpwm_group
+ };
+
+ bool shared_timer = false;
+ // check if timer is configured
+ if (timers[mcpwm_group][timer_no] == NULL){
+ mcpwm_timer_config_t pwm_config;
+ pwm_config.group_id = mcpwm_group;
+ pwm_config.clk_src = MCPWM_TIMER_CLK_SRC_DEFAULT;
+ pwm_config.resolution_hz = _PWM_TIMEBASE_RESOLUTION_HZ;
+ pwm_config.count_mode = MCPWM_TIMER_COUNT_MODE_UP_DOWN;
+ pwm_config.intr_priority = 0;
+ pwm_config.period_ticks = _calcPWMPeriod(pwm_frequency);
+ // initialise the timer
+ CHECK_ERR(mcpwm_new_timer(&pwm_config, &timers[mcpwm_group][timer_no]), "Could not initialize the timer in group: " + String(mcpwm_group));
+ // save variables for later
+ pwm_periods[mcpwm_group][timer_no] = pwm_config.period_ticks / 2;
+ params->timers[0] = timers[mcpwm_group][timer_no];
+ // if the numer of used channels it not pair skip one channel
+ // the skipped channel cannot be used with the new timer
+ // TODO avoid loosing channels like this
+ if(group_pins_used[mcpwm_group] %2) group_pins_used[mcpwm_group]++;
+ }else{
+ // we will use an already instantiated timer
+ params->timers[0] = timers[mcpwm_group][timer_no];
+ SIMPLEFOC_ESP32_DRV_DEBUG("Using previously configured timer: " + String(timer_no));
+ // but we cannot change its configuration without affecting the other drivers
+ // so let's first verify that the configuration is the same
+ if(_calcPWMPeriod(pwm_frequency)/2 != pwm_periods[mcpwm_group][timer_no]){
+ SIMPLEFOC_ESP32_DRV_DEBUG("ERR: Timer: "+String(timer_no)+" is confgured for freq: "+String(_calcPWMFreq(pwm_periods[mcpwm_group][timer_no]))+", not for freq:" +String(pwm_frequency));
+ return SIMPLEFOC_DRIVER_INIT_FAILED;
+ }
+ CHECK_ERR(mcpwm_timer_start_stop( params->timers[0], MCPWM_TIMER_STOP_EMPTY), "Failed to stop the timer!");
+
+ shared_timer = true;
+ }
+
+ uint8_t no_operators = ceil(no_pins / 2.0);
+ SIMPLEFOC_ESP32_DRV_DEBUG("Configuring " + String(no_operators) + " operators.");
+ mcpwm_operator_config_t operator_config = { .group_id = mcpwm_group };
+ operator_config.intr_priority = 0;
+ operator_config.flags.update_gen_action_on_tep = true;
+ operator_config.flags.update_gen_action_on_tez = true;
+ for (int i = 0; i < no_operators; i++) {
+ if (shared_timer && i == 0) { // first operator already configured
+ params->oper[0] = last_operator[mcpwm_group];
+ continue;
+ }
+ CHECK_ERR(mcpwm_new_operator(&operator_config, ¶ms->oper[i]),"Could not create operator "+String(i));
+ CHECK_ERR(mcpwm_operator_connect_timer(params->oper[i], params->timers[0]),"Could not connect timer to operator: " + String(i));
+ }
+ // save the last operator in this group
+ last_operator[mcpwm_group] = params->oper[no_operators - 1];
+
+ SIMPLEFOC_ESP32_DRV_DEBUG("Configuring " + String(no_pins) + " comparators.");
+ // Create and configure comparators
+ mcpwm_comparator_config_t comparator_config = {0};
+ comparator_config.flags.update_cmp_on_tez = true;
+ for (int i = 0; i < no_pins; i++) {
+ int oper_index = shared_timer ? (int)floor((i + 1) / 2) : (int)floor(i / 2);
+ CHECK_ERR(mcpwm_new_comparator(params->oper[oper_index], &comparator_config, ¶ms->comparator[i]),"Could not create comparator: " + String(i));
+ CHECK_ERR(mcpwm_comparator_set_compare_value(params->comparator[i], (0)), "Could not set duty on comparator: " + String(i));
+ }
+
+ SIMPLEFOC_ESP32_DRV_DEBUG("Configuring " + String(no_pins) + " generators.");
+ // Create and configure generators;
+ mcpwm_generator_config_t generator_config = {};
+ for (int i = 0; i < no_pins; i++) {
+ generator_config.gen_gpio_num = pins[i];
+ int oper_index = shared_timer ? (int)floor((i + 1) / 2) : (int)floor(i / 2);
+ CHECK_ERR(mcpwm_new_generator(params->oper[oper_index], &generator_config, ¶ms->generator[i]), "Could not create generator " + String(i) +String(" on pin: ")+String(pins[i]));
+ }
+
+
+ SIMPLEFOC_ESP32_DRV_DEBUG("Configuring center-aligned pwm.");
+ for (int i = 0; i < no_pins; i++) {
+ CHECK_ERR(_configureCenterAlign(params->generator[i],params->comparator[i], !SIMPLEFOC_PWM_ACTIVE_HIGH), "Failed to configure center align pwm: " + String(i));
+ }
+
+ SIMPLEFOC_ESP32_DRV_DEBUG("Enabling timer: "+String(timer_no));
+ // Enable and start timer if not shared
+ if (!shared_timer) CHECK_ERR(mcpwm_timer_enable(params->timers[0]), "Failed to enable timer!");
+ // start the timer
+ CHECK_ERR(mcpwm_timer_start_stop(params->timers[0], MCPWM_TIMER_START_NO_STOP), "Failed to start the timer!");
+
+ _delay(1);
+ SIMPLEFOC_ESP32_DRV_DEBUG("MCPWM configured!");
+ // save the configuration variables for later
+ params->mcpwm_period = pwm_periods[mcpwm_group][timer_no];
+ group_pins_used[mcpwm_group] += no_pins;
+ return params;
+}
+
+// function setting the duty cycle to the MCPWM pin
+void _setDutyCycle(mcpwm_cmpr_handle_t cmpr, uint32_t mcpwm_period, float duty_cycle){
+ float duty = _constrain(duty_cycle, 0.0, 1.0);
+ mcpwm_comparator_set_compare_value(cmpr, (uint32_t)(mcpwm_period*duty));
+}
+
+// function setting the duty cycle to the MCPWM pin
+void _forcePhaseState(mcpwm_gen_handle_t generator_high, mcpwm_gen_handle_t generator_low, PhaseState phase_state){
+ // phase state is forced in hardware pwm mode
+ // esp-idf docs: https://docs.espressif.com/projects/esp-idf/en/v5.1.4/esp32/api-reference/peripherals/mcpwm.html#generator-force-actions
+ // github issue: https://github.com/espressif/esp-idf/issues/12237
+ mcpwm_generator_set_force_level(generator_high, (phase_state == PHASE_ON || phase_state == PHASE_HI) ? -1 : 0, true);
+ mcpwm_generator_set_force_level(generator_low, (phase_state == PHASE_ON || phase_state == PHASE_LO) ? -1 : 1, true);
+}
+
+#endif
\ No newline at end of file
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/drivers/hardware_specific/esp32/esp32_driver_mcpwm.h b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/drivers/hardware_specific/esp32/esp32_driver_mcpwm.h
new file mode 100644
index 0000000..5726e90
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/drivers/hardware_specific/esp32/esp32_driver_mcpwm.h
@@ -0,0 +1,158 @@
+#ifndef ESP32_DRIVER_MCPWM_H
+#define ESP32_DRIVER_MCPWM_H
+
+#include "../../hardware_api.h"
+
+#if defined(ESP_H) && defined(ARDUINO_ARCH_ESP32) && defined(SOC_MCPWM_SUPPORTED) && !defined(SIMPLEFOC_ESP32_USELEDC)
+
+#include "driver/mcpwm_prelude.h"
+#include "soc/mcpwm_reg.h"
+#include "soc/mcpwm_struct.h"
+#include "esp_idf_version.h"
+
+// version check - this mcpwm driver is specific for ESP-IDF 5.x and arduino-esp32 3.x
+#if ESP_IDF_VERSION < ESP_IDF_VERSION_VAL(5, 0, 0)
+#error SimpleFOC: ESP-IDF version 4 or lower detected. Please update to ESP-IDF 5.x and Arduino-esp32 3.0 (or higher)
+#endif
+
+#ifndef SIMPLEFOC_ESP32_HW_DEADTIME
+ #define SIMPLEFOC_ESP32_HW_DEADTIME true // TODO: Change to false when sw-deadtime & phase_state is approved ready for general use.
+#endif
+
+//!< ESP32 MCPWM driver parameters
+typedef struct ESP32MCPWMDriverParams {
+ long pwm_frequency; //!< frequency of the pwm signal
+ int group_id; //!< group of the mcpwm
+ mcpwm_timer_handle_t timers[2]; //!< timers of the mcpwm
+ mcpwm_oper_handle_t oper[3]; //!< operators of the mcpwm
+ mcpwm_cmpr_handle_t comparator[6]; //!< comparators of the mcpwm
+ mcpwm_gen_handle_t generator[6]; //!< generators of the mcpwm
+ uint32_t mcpwm_period; //!< period of the pwm signal
+ float dead_zone; //!< dead zone of the pwm signal
+} ESP32MCPWMDriverParams;
+
+
+#define SIMPLEFOC_ESP32_DEBUG(tag, str)\
+ SimpleFOCDebug::println( "ESP32-"+String(tag)+ ": "+ String(str));
+
+#define SIMPLEFOC_ESP32_DRV_DEBUG(str)\
+ SIMPLEFOC_ESP32_DEBUG("DRV", str);\
+
+// macro for checking the error of the mcpwm functions
+// if the function returns an error the function will return SIMPLEFOC_DRIVER_INIT_FAILED
+#define CHECK_ERR(func_call, message) \
+ if ((func_call) != ESP_OK) { \
+ SIMPLEFOC_ESP32_DRV_DEBUG("ERROR - " + String(message)); \
+ return SIMPLEFOC_DRIVER_INIT_FAILED; \
+ }
+
+
+// ABI bus frequency - would be better to take it from somewhere
+// but I did nto find a good exposed variable
+#define _MCPWM_FREQ 160e6f
+#define _PWM_TIMEBASE_RESOLUTION_HZ (_MCPWM_FREQ) /*!< Resolution of MCPWM */
+// pwm frequency settings
+#define _PWM_FREQUENCY 25000 // 25khz
+#define _PWM_FREQUENCY_MAX 50000 // 50kHz
+
+
+// low-level configuration API
+
+/**
+ * checking if group has pins available
+ * @param group - group of the mcpwm
+ * @param no_pins - number of pins
+ * @returns true if pins are available, false otherwise
+ */
+bool _hasAvailablePins(int group, int no_pins);
+/**
+ * function finding the last timer in the group
+ * @param group - group of the mcpwm
+ * @returns index of the last timer in the group
+ * -1 if no timer instantiated yet
+ */
+uint8_t _findLastTimer(int group);
+
+/**
+ * function finding the next timer in the group
+ * @param group - group of the mcpwm
+ * @returns index of the next timer in the group
+ * -1 if all timers are used
+ */
+uint8_t _findNextTimer(int group);
+
+
+/**
+ * function finding the best group and timer for the pwm signals
+ *
+ * @param no_pins - number of pins
+ * @param pwm_freq - frequency of the pwm signal
+ * @param group - pointer to the group
+ * @param timer - pointer to the timer
+ * @returns
+ * 1 if solution found in one group
+ * 2 if solution requires using both groups
+ * 0 if no solution possible
+ */
+int _findBestGroup(int no_pins, long pwm_freq, int* group, int* timer);
+
+
+/**
+ * function configuring the center alignement and inversion of a pwm signal
+ * @param gena - mcpwm generator handle
+ * @param cmpa - mcpwm comparator handle
+ * @param inverted - true if the signal is inverted, false otherwise
+ */
+int _configureCenterAlign(mcpwm_gen_handle_t gena, mcpwm_cmpr_handle_t cmpa, bool inverted);
+
+/**
+ * function calculating the pwm period
+ * @param pwm_frequency - frequency of the pwm signal
+ * @return uint32_t - period of the pwm signal
+ */
+uint32_t _calcPWMPeriod(long pwm_frequency);
+/**
+ * function calculating the pwm frequency
+ * @param pwm_period - period of the pwm signal
+ * @return long - frequency of the pwm signal
+ */
+long _calcPWMFreq(long pwm_period);
+
+/**
+ * function configuring the MCPWM for 6pwm
+ * @param pwm_frequency - frequency of the pwm signal
+ * @param mcpwm_group - group of the mcpwm
+ * @param timer_no - timer number
+ * @param dead_zone - dead zone of the pwm signal
+ * @param pins - array of pins
+ * @return ESP32MCPWMDriverParams* - pointer to the driver parameters if successful, -1 if failed
+ */
+void* _configure6PWMPinsMCPWM(long pwm_frequency, int mcpwm_group, int timer_no, float dead_zone, int* pins);
+/**
+ * function configuring the MCPWM for pwm generation
+ * @param pwm_frequency - frequency of the pwm signal
+ * @param mcpwm_group - group of the mcpwm
+ * @param timer_no - timer number
+ * @param no_pins - number of pins
+ * @param pins - array of pins
+ * @return ESP32MCPWMDriverParams* - pointer to the driver parameters if successful, -1 if failed
+ */
+void* _configurePinsMCPWM(long pwm_frequency, int mcpwm_group, int timer_no, int no_pins, int* pins);
+/**
+ * function setting the duty cycle to the MCPWM channel
+ * @param cmpr - mcpwm channel handle
+ * @param mcpwm_period - period of the pwm signal
+ * @param duty_cycle - duty cycle of the pwm signal
+ */
+void _setDutyCycle(mcpwm_cmpr_handle_t cmpr, uint32_t mcpwm_period, float duty_cycle);
+
+/**
+ * function setting the phase state
+ * @param generator_high - mcpwm generator handle for the high side
+ * @param generator_low - mcpwm generator handle for the low side
+ * @param phase_state - phase state
+ */
+void _forcePhaseState(mcpwm_gen_handle_t generator_high, mcpwm_gen_handle_t generator_low, PhaseState phase_state);
+
+#endif
+#endif
\ No newline at end of file
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/drivers/hardware_specific/esp32/esp32_ledc_mcu.cpp b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/drivers/hardware_specific/esp32/esp32_ledc_mcu.cpp
new file mode 100644
index 0000000..dc667ab
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/drivers/hardware_specific/esp32/esp32_ledc_mcu.cpp
@@ -0,0 +1,404 @@
+#include "../../hardware_api.h"
+
+#if defined(ESP_H) && defined(ARDUINO_ARCH_ESP32) && ( !defined(SOC_MCPWM_SUPPORTED) || defined(SIMPLEFOC_ESP32_USELEDC) )
+
+#pragma message("")
+#pragma message("SimpleFOC: compiling for ESP32 LEDC driver")
+#pragma message("")
+
+#include "driver/ledc.h"
+#include "esp_idf_version.h"
+
+
+// version check - this ledc driver is specific for ESP-IDF 5.x and arduino-esp32 3.x
+#if ESP_IDF_VERSION < ESP_IDF_VERSION_VAL(5, 0, 0)
+#error SimpleFOC: ESP-IDF version 4 or lower detected. Please update to ESP-IDF 5.x and Arduino-esp32 3.0 (or higher)
+#endif
+
+#define _PWM_FREQUENCY 25000 // 25khz
+#define _PWM_FREQUENCY_MAX 38000 // 38khz max to be able to have 10 bit pwm resolution
+#define _PWM_RES_BIT 10 // 10 bir resolution
+#define _PWM_RES 1023 // 2^10-1 = 1024-1
+
+
+// figure out how many ledc channels are available
+// esp32 - 2x8=16
+// esp32s2 - 8
+// esp32c3 - 6
+#include "soc/soc_caps.h"
+#ifdef SOC_LEDC_SUPPORT_HS_MODE
+#define LEDC_CHANNELS (SOC_LEDC_CHANNEL_NUM<<1)
+#else
+#define LEDC_CHANNELS (SOC_LEDC_CHANNEL_NUM)
+#endif
+
+#define LEDC_CHANNELS_GROUP0 (LEDC_CHANNELS < 8 ? LEDC_CHANNELS : 8)
+#define LEDC_CHANNELS_GROUP1 (LEDC_CHANNELS < 8 ? 0 : LEDC_CHANNELS - 8)
+
+
+// currently used ledc channels
+// support for multiple motors
+// esp32 has 16 channels
+// esp32s2 has 8 channels
+// esp32c3 has 6 channels
+// channels from 0-7 are in group 0 and 8-15 in group 1
+// - only esp32 as of mid 2024 has the second group, all the s versions don't
+int group_channels_used[2] = {0};
+
+
+typedef struct ESP32LEDCDriverParams {
+ ledc_channel_t channels[6];
+ ledc_mode_t groups[6];
+ long pwm_frequency;
+ float dead_zone;
+} ESP32LEDCDriverParams;
+
+
+/*
+ Function to attach a channel to a pin with advanced settings
+ - freq - pwm frequency
+ - resolution - pwm resolution
+ - channel - ledc channel
+ - inverted - output inverted
+ - group - ledc group
+
+ This function is a workaround for the ledcAttachPin function that is not available in the ESP32 Arduino core, in which the
+ PWM signals are synchronized in pairs, while the simplefoc requires a bit more flexible configuration.
+ This function sets also allows configuring a channel as inverted, which is not possible with the ledcAttachPin function.
+
+ Function returns true if the channel was successfully attached, false otherwise.
+*/
+bool _ledcAttachChannelAdvanced(uint8_t pin, int _channel, int _group, uint32_t freq, uint8_t resolution, bool inverted) {
+
+
+ ledc_channel_t channel = static_cast(_channel);
+ ledc_mode_t group = static_cast(_group);
+
+ ledc_timer_bit_t res = static_cast(resolution);
+ ledc_timer_config_t ledc_timer;
+ ledc_timer.speed_mode = group;
+ ledc_timer.timer_num = LEDC_TIMER_0;
+ ledc_timer.duty_resolution = res;
+ ledc_timer.freq_hz = freq;
+ ledc_timer.clk_cfg = LEDC_AUTO_CLK;
+ if (ledc_timer_config(&ledc_timer) != ESP_OK) {
+ SIMPLEFOC_DEBUG("EP32-DRV: ERROR - Failed to configure the timer:", LEDC_TIMER_0);
+ return false;
+ }
+
+ // if active high is false invert
+ int pin_high_level = SIMPLEFOC_PWM_ACTIVE_HIGH ? 0 : 1;
+ if (inverted) pin_high_level = !pin_high_level;
+
+ uint32_t duty = ledc_get_duty(group, channel);
+ ledc_channel_config_t ledc_channel;
+ ledc_channel.speed_mode = group;
+ ledc_channel.channel = channel;
+ ledc_channel.timer_sel = LEDC_TIMER_0;
+ ledc_channel.intr_type = LEDC_INTR_DISABLE;
+ ledc_channel.gpio_num = pin;
+ ledc_channel.duty = duty;
+ ledc_channel.hpoint = 0;
+ ledc_channel.flags.output_invert = pin_high_level; // 0 is active high, 1 is active low
+ if (ledc_channel_config(&ledc_channel)!= ESP_OK) {
+ SIMPLEFOC_DEBUG("EP32-DRV: ERROR - Failed to attach channel:", _channel);
+ return false;
+ }
+
+ return true;
+}
+
+
+// returns the number of available channels in the group
+int _availableGroupChannels(int group){
+ if(group == 0) return LEDC_CHANNELS_GROUP0 - group_channels_used[0];
+ else if(group == 1) return LEDC_CHANNELS_GROUP1 - group_channels_used[1];
+ return 0;
+}
+
+// returns the number of the group that has enough channels available
+// returns -1 if no group has enough channels
+//
+// NOT IMPLEMENTED BUT COULD BE USEFUL
+// returns 2 if no group has enough channels but combined they do
+int _findGroupWithChannelsAvailable(int no_channels){
+ if(no_channels <= _availableGroupChannels(0)) return 0;
+ if(no_channels <= _availableGroupChannels(1)) return 1;
+ return -1;
+}
+
+
+void* _configure1PWM(long pwm_frequency, const int pinA) {
+ if(!pwm_frequency || !_isset(pwm_frequency) ) pwm_frequency = _PWM_FREQUENCY; // default frequency 25khz
+ else pwm_frequency = _constrain(pwm_frequency, 0, _PWM_FREQUENCY_MAX); // constrain to 50kHz max
+
+ SIMPLEFOC_DEBUG("EP32-DRV: Configuring 1PWM");
+ // check if enough channels available
+ int group = _findGroupWithChannelsAvailable(1);
+ if (group < 0){
+ SIMPLEFOC_DEBUG("EP32-DRV: ERROR - Not enough channels available!");
+ return SIMPLEFOC_DRIVER_INIT_FAILED;
+ }
+ SIMPLEFOC_DEBUG("EP32-DRV: 1PWM setup in group: ", (group));
+
+ // configure the channel
+ group_channels_used[group] += 1;
+ if(!_ledcAttachChannelAdvanced(pinA, group_channels_used[group], group, pwm_frequency, _PWM_RES_BIT, false)){
+ SIMPLEFOC_DEBUG("EP32-DRV: ERROR - Failed to configure pin:", pinA);
+ return SIMPLEFOC_DRIVER_INIT_FAILED;
+ }
+
+
+ ESP32LEDCDriverParams* params = new ESP32LEDCDriverParams {
+ .channels = { static_cast(group_channels_used[group]) },
+ .groups = { (ledc_mode_t)group },
+ .pwm_frequency = pwm_frequency
+ };
+ SIMPLEFOC_DEBUG("EP32-DRV: 1PWM setup successful in group: ", (group));
+ return params;
+}
+
+
+
+
+
+
+
+
+void* _configure2PWM(long pwm_frequency, const int pinA, const int pinB) {
+ if(!pwm_frequency || !_isset(pwm_frequency) ) pwm_frequency = _PWM_FREQUENCY; // default frequency 25khz
+ else pwm_frequency = _constrain(pwm_frequency, 0, _PWM_FREQUENCY_MAX); // constrain to 50kHz max
+
+ SIMPLEFOC_DEBUG("EP32-DRV: Configuring 2PWM");
+
+ // check if enough channels available
+ int group = _findGroupWithChannelsAvailable(2);
+ if (group < 0) {
+ SIMPLEFOC_DEBUG("EP32-DRV: ERROR - Not enough channels available!");
+ return SIMPLEFOC_DRIVER_INIT_FAILED;
+ }
+ SIMPLEFOC_DEBUG("EP32-DRV: 2PWM setup in group: ", (group));
+
+ ESP32LEDCDriverParams* params = new ESP32LEDCDriverParams {
+ .channels = { static_cast(0)},
+ .groups = { (ledc_mode_t)0 },
+ .pwm_frequency = pwm_frequency
+ };
+
+ int pins[2] = {pinA, pinB};
+ for(int i = 0; i < 2; i++){
+ group_channels_used[group]++;
+ if(!_ledcAttachChannelAdvanced(pins[i], group_channels_used[group], group, pwm_frequency, _PWM_RES_BIT, false)){
+ SIMPLEFOC_DEBUG("EP32-DRV: ERROR - Failed to configure pin:", pins[i]);
+ return SIMPLEFOC_DRIVER_INIT_FAILED;
+ }
+
+ params->channels[i] = static_cast(group_channels_used[group]);
+ params->groups[i] = (ledc_mode_t)group;
+ }
+ SIMPLEFOC_DEBUG("EP32-DRV: 2PWM setup successful in group: ", (group));
+ return params;
+}
+
+
+
+void* _configure3PWM(long pwm_frequency,const int pinA, const int pinB, const int pinC) {
+ if(!pwm_frequency || !_isset(pwm_frequency) ) pwm_frequency = _PWM_FREQUENCY; // default frequency 25khz
+ else pwm_frequency = _constrain(pwm_frequency, 0, _PWM_FREQUENCY_MAX); // constrain to 50kHz max
+
+ SIMPLEFOC_DEBUG("EP32-DRV: Configuring 3PWM");
+
+ // check if enough channels available
+ int group = _findGroupWithChannelsAvailable(3);
+ if (group < 0) {
+ SIMPLEFOC_DEBUG("EP32-DRV: ERROR - Not enough channels available!");
+ return SIMPLEFOC_DRIVER_INIT_FAILED;
+ }
+ SIMPLEFOC_DEBUG("EP32-DRV: 3PWM setup in group: ", (group));
+
+ ESP32LEDCDriverParams* params = new ESP32LEDCDriverParams {
+ .channels = { static_cast(0)},
+ .groups = { (ledc_mode_t)0 },
+ .pwm_frequency = pwm_frequency
+ };
+
+ int pins[3] = {pinA, pinB, pinC};
+ for(int i = 0; i < 3; i++){
+ group_channels_used[group]++;
+ if(!_ledcAttachChannelAdvanced(pins[i], group_channels_used[group], group, pwm_frequency, _PWM_RES_BIT, false)){
+ SIMPLEFOC_DEBUG("EP32-DRV: ERROR - Failed to configure pin:", pins[i]);
+ return SIMPLEFOC_DRIVER_INIT_FAILED;
+ }
+
+ params->channels[i] = static_cast(group_channels_used[group]);
+ params->groups[i] = (ledc_mode_t)group;
+ }
+ SIMPLEFOC_DEBUG("EP32-DRV: 3PWM setup successful in group: ", (group));
+ return params;
+}
+
+
+
+void* _configure4PWM(long pwm_frequency,const int pinA, const int pinB, const int pinC, const int pinD) {
+ if(!pwm_frequency || !_isset(pwm_frequency) ) pwm_frequency = _PWM_FREQUENCY; // default frequency 25khz
+ else pwm_frequency = _constrain(pwm_frequency, 0, _PWM_FREQUENCY_MAX); // constrain to 50kHz max
+
+
+ ESP32LEDCDriverParams* params = new ESP32LEDCDriverParams {
+ .channels = { static_cast(0)},
+ .groups = { (ledc_mode_t)0 },
+ .pwm_frequency = pwm_frequency
+ };
+
+ SIMPLEFOC_DEBUG("EP32-DRV: Configuring 4PWM");
+ // check if enough channels available
+ int group = _findGroupWithChannelsAvailable(4);
+ if (group < 0){
+ // not enough channels available on any individual group
+ // check if their combined number is enough (two channels per group)
+ if(_availableGroupChannels(0) >=2 && _availableGroupChannels(1) >=2){
+ group = 2;
+ SIMPLEFOC_DEBUG("EP32-DRV: WARNING: Not enough available ledc channels for 4pwm in a single group! Using two groups!");
+ SIMPLEFOC_DEBUG("EP32-DRV: 4PWM setup in groups: 0 and 1!");
+ params->groups[2] = (ledc_mode_t)1;
+ params->groups[3] = (ledc_mode_t)1;
+ }else{
+ SIMPLEFOC_DEBUG("EP32-DRV: ERROR - Not enough available ledc channels for 4pwm!");
+ return SIMPLEFOC_DRIVER_INIT_FAILED;
+ }
+ }else{
+ SIMPLEFOC_DEBUG("EP32-DRV: 4PWM setup in group: ", (group));
+ params->groups[0] = (ledc_mode_t)group;
+ params->groups[1] = (ledc_mode_t)group;
+ params->groups[2] = (ledc_mode_t)group;
+ params->groups[3] = (ledc_mode_t)group;
+ }
+
+
+
+ int pins[4] = {pinA, pinB, pinC, pinD};
+ for(int i = 0; i < 4; i++){
+ group_channels_used[params->groups[i]]++;
+ if(!_ledcAttachChannelAdvanced(pins[i], group_channels_used[params->groups[i]], params->groups[i], pwm_frequency, _PWM_RES_BIT, false)){
+ SIMPLEFOC_DEBUG("EP32-DRV: ERROR - Failed to configure pin:", pins[i]);
+ return SIMPLEFOC_DRIVER_INIT_FAILED;
+ }
+ params->channels[i] = static_cast(group_channels_used[params->groups[i]]);
+ }
+ SIMPLEFOC_DEBUG("EP32-DRV: 4PWM setup successful!");
+ return params;
+}
+
+
+void _writeDutyCycle(float dc, void* params, int index){
+ ledc_set_duty_with_hpoint(((ESP32LEDCDriverParams*)params)->groups[index],((ESP32LEDCDriverParams*)params)->channels[index], _PWM_RES*dc, _PWM_RES/2.0*(1.0-dc));
+ ledc_update_duty(((ESP32LEDCDriverParams*)params)->groups[index],((ESP32LEDCDriverParams*)params)->channels[index]);
+}
+
+void _writeDutyCycle1PWM(float dc_a, void* params){
+ _writeDutyCycle(dc_a, params, 0);
+}
+
+
+
+void _writeDutyCycle2PWM(float dc_a, float dc_b, void* params){
+ _writeDutyCycle(dc_a, params, 0);
+ _writeDutyCycle(dc_b, params, 1);
+}
+
+
+
+void _writeDutyCycle3PWM(float dc_a, float dc_b, float dc_c, void* params){
+ _writeDutyCycle(dc_a, params, 0);
+ _writeDutyCycle(dc_b, params, 1);
+ _writeDutyCycle(dc_c, params, 2);
+}
+
+
+
+void _writeDutyCycle4PWM(float dc_1a, float dc_1b, float dc_2a, float dc_2b, void* params){
+ _writeDutyCycle(dc_1a, params, 0);
+ _writeDutyCycle(dc_1b, params, 1);
+ _writeDutyCycle(dc_2a, params, 2);
+ _writeDutyCycle(dc_2b, params, 3);
+}
+
+
+void* _configure6PWM(long pwm_frequency, float dead_zone, const int pinA_h, const int pinA_l, const int pinB_h, const int pinB_l, const int pinC_h, const int pinC_l){
+ if(!pwm_frequency || !_isset(pwm_frequency) ) pwm_frequency = _PWM_FREQUENCY; // default frequency 25khz
+ else pwm_frequency = _constrain(pwm_frequency, 0, _PWM_FREQUENCY_MAX); // constrain to 50kHz max
+
+ SIMPLEFOC_DEBUG("EP32-DRV: Configuring 6PWM");
+ SIMPLEFOC_DEBUG("EP32-DRV: WARNING - 6PWM on LEDC is poorly supported and not tested, consider using MCPWM driver instead!");
+ // check if enough channels available
+ int group = _findGroupWithChannelsAvailable(6);
+ if (group < 0){
+ SIMPLEFOC_DEBUG("EP32-DRV: ERROR - Not enough channels available!");
+ return SIMPLEFOC_DRIVER_INIT_FAILED;
+ }
+ SIMPLEFOC_DEBUG("EP32-DRV: 6PWM setup in group: ", (group));
+ ESP32LEDCDriverParams* params = new ESP32LEDCDriverParams {
+ .channels = { static_cast(0)},
+ .groups = { (ledc_mode_t)group },
+ .pwm_frequency = pwm_frequency,
+ .dead_zone = dead_zone
+ };
+
+ int high_side_invert = SIMPLEFOC_PWM_HIGHSIDE_ACTIVE_HIGH ? false : true;
+ int low_side_invert = SIMPLEFOC_PWM_LOWSIDE_ACTIVE_HIGH ? true : false;
+
+ int pin_pairs[6][2] = {
+ {pinA_h, pinA_l},
+ {pinB_h, pinB_l},
+ {pinC_h, pinC_l}
+ };
+
+ for(int i = 0; i < 3; i++){
+ group_channels_used[group]++;
+ if(!_ledcAttachChannelAdvanced(pin_pairs[i][0], group_channels_used[group], group, pwm_frequency, _PWM_RES_BIT, high_side_invert)){
+ SIMPLEFOC_DEBUG("EP32-DRV: ERROR - Failed to configure pin:", pin_pairs[i][0]);
+ return SIMPLEFOC_DRIVER_INIT_FAILED;
+ }
+
+ params->channels[2*i] = static_cast(group_channels_used[group]);
+ params->groups[2*i] = (ledc_mode_t)group;
+
+ group_channels_used[group]++;
+ if(!_ledcAttachChannelAdvanced(pin_pairs[i][1], group_channels_used[group], group, pwm_frequency, _PWM_RES_BIT, low_side_invert)){
+ SIMPLEFOC_DEBUG("EP32-DRV: ERROR - Failed to configure pin:", pin_pairs[i][0]);
+ return SIMPLEFOC_DRIVER_INIT_FAILED;
+ }
+
+ params->channels[2*i+1] = static_cast(group_channels_used[group]);
+ params->groups[2*i+1] = (ledc_mode_t)group;
+ }
+
+ SIMPLEFOC_DEBUG("EP32-DRV: 6PWM setup successful in group: ", (group));
+ return params;
+}
+
+void _setPwmPairDutyCycle( void* params, int ind_h, int ind_l, float val, float dead_time, PhaseState ps){
+ float pwm_h = _constrain(val - dead_time/2.0, 0, 1.0);
+ float pwm_l = _constrain(val + dead_time/2.0, 0, 1.0);
+
+ // determine the phase state and set the pwm accordingly
+ // deactivate phases if needed
+ if((ps == PhaseState::PHASE_OFF) || (ps == PhaseState::PHASE_LO)){
+ _writeDutyCycle(0, params, ind_h);
+ }else{
+ _writeDutyCycle(pwm_h, params, ind_h);
+ }
+ if((ps == PhaseState::PHASE_OFF) || (ps == PhaseState::PHASE_HI)){
+ _writeDutyCycle(0, params, ind_l);
+ }else{
+ _writeDutyCycle(pwm_l, params, ind_l);
+ }
+}
+
+void _writeDutyCycle6PWM(float dc_a, float dc_b, float dc_c, PhaseState *phase_state, void* params){
+ _setPwmPairDutyCycle(params, 0, 1, dc_a, ((ESP32LEDCDriverParams*)params)->dead_zone, phase_state[0]);
+ _setPwmPairDutyCycle(params, 2, 3, dc_b, ((ESP32LEDCDriverParams*)params)->dead_zone, phase_state[1]);
+ _setPwmPairDutyCycle(params, 4, 5, dc_c, ((ESP32LEDCDriverParams*)params)->dead_zone, phase_state[2]);
+}
+
+#endif
\ No newline at end of file
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/drivers/hardware_specific/esp32/esp32_mcpwm_mcu.cpp b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/drivers/hardware_specific/esp32/esp32_mcpwm_mcu.cpp
new file mode 100644
index 0000000..e2c621c
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/drivers/hardware_specific/esp32/esp32_mcpwm_mcu.cpp
@@ -0,0 +1,226 @@
+#include "esp32_driver_mcpwm.h"
+
+#if defined(ESP_H) && defined(ARDUINO_ARCH_ESP32) && defined(SOC_MCPWM_SUPPORTED) && !defined(SIMPLEFOC_ESP32_USELEDC)
+
+#pragma message("")
+#pragma message("SimpleFOC: compiling for ESP32 MCPWM driver")
+#pragma message("")
+
+// function setting the high pwm frequency to the supplied pins
+// - DC motor - 1PWM setting
+// - hardware specific
+void* _configure1PWM(long pwm_frequency, const int pinA) {
+ if(!pwm_frequency || !_isset(pwm_frequency) ) pwm_frequency = _PWM_FREQUENCY; // default frequency 25hz
+ else pwm_frequency = _constrain(pwm_frequency, 0, _PWM_FREQUENCY_MAX); // constrain to 40kHz max
+
+ int group, timer;
+ if(!_findBestGroup(1, pwm_frequency, &group, &timer)) {
+ SIMPLEFOC_ESP32_DRV_DEBUG("Not enough pins available for 1PWM!");
+ return SIMPLEFOC_DRIVER_INIT_FAILED;
+ }
+ SIMPLEFOC_ESP32_DRV_DEBUG("Configuring 1PWM in group: "+String(group)+" on timer: "+String(timer));
+ // configure the timer
+ int pins[1] = {pinA};
+ return _configurePinsMCPWM(pwm_frequency, group, timer, 1, pins);
+}
+
+
+// function setting the high pwm frequency to the supplied pins
+// - Stepper motor - 2PWM setting
+// - hardware specific
+void* _configure2PWM(long pwm_frequency, const int pinA, const int pinB) {
+ if(!pwm_frequency || !_isset(pwm_frequency) ) pwm_frequency = _PWM_FREQUENCY; // default frequency 25hz
+ else pwm_frequency = _constrain(pwm_frequency, 0, _PWM_FREQUENCY_MAX); // constrain to 40kHz max
+
+ int group, timer;
+ int ret = _findBestGroup(2, pwm_frequency, &group, &timer);
+ if(!ret) {
+ SIMPLEFOC_ESP32_DRV_DEBUG("Not enough pins available for 2PWM!");
+ return SIMPLEFOC_DRIVER_INIT_FAILED;
+ }
+ if(ret == 1){
+ // configure the 2pwm on only one group
+ SIMPLEFOC_ESP32_DRV_DEBUG("Configuring 2PWM in group: "+String(group)+" on timer: "+String(timer));
+ // configure the timer
+ int pins[2] = {pinA, pinB};
+ return _configurePinsMCPWM(pwm_frequency, group, timer, 2, pins);
+ }else{
+ SIMPLEFOC_ESP32_DRV_DEBUG("Configuring 2PWM as two 1PWM drivers");
+ ESP32MCPWMDriverParams* params[2];
+
+ // the code is a bit huge for what it does
+ // it just instantiates two 2PMW drivers and combines the returned params
+ int pins[2][1] = {{pinA}, {pinB}};
+ for(int i =0; i<2; i++){
+ int timer = _findLastTimer(i); //find last created timer in group i
+ SIMPLEFOC_ESP32_DRV_DEBUG("Configuring 1PWM in group: "+String(i)+" on timer: "+String(timer));
+ void* p = _configurePinsMCPWM(pwm_frequency, i, timer, 1, pins[i]);
+ if(p == SIMPLEFOC_DRIVER_INIT_FAILED){
+ SIMPLEFOC_ESP32_DRV_DEBUG("Error configuring 1PWM");
+ return SIMPLEFOC_DRIVER_INIT_FAILED;
+ }else{
+ params[i] = (ESP32MCPWMDriverParams*)p;
+ }
+ }
+ // combine the driver parameters
+ ESP32MCPWMDriverParams* ret_params = new ESP32MCPWMDriverParams{
+ .pwm_frequency = params[0]->pwm_frequency,
+ .group_id = 2, // both groups
+ };
+ for(int i =0; i<2; i++){
+ ret_params->timers[i] = params[i]->timers[0];
+ ret_params->oper[i] = params[i]->oper[0];
+ ret_params->comparator[i] = params[i]->comparator[0];
+ ret_params->generator[i] = params[i]->generator[0];
+ }
+ ret_params->mcpwm_period = params[0]->mcpwm_period;
+ return ret_params;
+ }
+}
+
+// function setting the high pwm frequency to the supplied pins
+// - BLDC motor - 3PWM setting
+// - hardware specific
+void* _configure3PWM(long pwm_frequency, const int pinA, const int pinB, const int pinC) {
+ if(!pwm_frequency || !_isset(pwm_frequency) ) pwm_frequency = _PWM_FREQUENCY; // default frequency 25hz
+ else pwm_frequency = _constrain(pwm_frequency, 0, _PWM_FREQUENCY_MAX); // constrain to 40kHz max
+
+ int group, timer;
+ if(!_findBestGroup(3, pwm_frequency, &group, &timer)) {
+ SIMPLEFOC_ESP32_DRV_DEBUG("Not enough pins available for 3PWM!");
+ return SIMPLEFOC_DRIVER_INIT_FAILED;
+ }
+ SIMPLEFOC_ESP32_DRV_DEBUG("Configuring 3PWM in group: "+String(group)+" on timer: "+String(timer));
+ // configure the timer
+ int pins[3] = {pinA, pinB, pinC};
+ return _configurePinsMCPWM(pwm_frequency, group, timer, 3, pins);
+}
+
+
+
+// function setting the high pwm frequency to the supplied pins
+// - Stepper motor - 4PWM setting
+// - hardware specific
+void* _configure4PWM(long pwm_frequency,const int pinA, const int pinB, const int pinC, const int pinD){
+ if(!pwm_frequency || !_isset(pwm_frequency) ) pwm_frequency = _PWM_FREQUENCY; // default frequency 25hz
+ else pwm_frequency = _constrain(pwm_frequency, 0, _PWM_FREQUENCY_MAX); // constrain to 40kHz max
+
+ int group, timer;
+ int ret = _findBestGroup(4, pwm_frequency, &group, &timer);
+ if(!ret) {
+ SIMPLEFOC_ESP32_DRV_DEBUG("Not enough pins available for 4PWM!");
+ return SIMPLEFOC_DRIVER_INIT_FAILED;
+ }
+ if(ret == 1){
+ SIMPLEFOC_ESP32_DRV_DEBUG("Configuring 4PWM in group: "+String(group)+" on timer: "+String(timer));
+ // configure the timer
+ int pins[4] = {pinA, pinB, pinC, pinD};
+ return _configurePinsMCPWM(pwm_frequency, group, timer, 4, pins);
+ }else{
+ SIMPLEFOC_ESP32_DRV_DEBUG("Configuring 4PWM as two 2PWM drivers");
+ ESP32MCPWMDriverParams* params[2];
+
+ // the code is a bit huge for what it does
+ // it just instantiates two 2PMW drivers and combines the returned params
+ int pins[2][2] = {{pinA, pinB},{pinC, pinD}};
+ for(int i =0; i<2; i++){
+ int timer = _findNextTimer(i); //find next available timer in group i
+ SIMPLEFOC_ESP32_DRV_DEBUG("Configuring 2PWM in group: "+String(i)+" on timer: "+String(timer));
+ void* p = _configurePinsMCPWM(pwm_frequency, i, timer, 2, pins[i]);
+ if(p == SIMPLEFOC_DRIVER_INIT_FAILED){
+ SIMPLEFOC_ESP32_DRV_DEBUG("Error configuring 2PWM");
+ return SIMPLEFOC_DRIVER_INIT_FAILED;
+ }else{
+ params[i] = (ESP32MCPWMDriverParams*)p;
+ }
+ }
+ // combine the driver parameters
+ ESP32MCPWMDriverParams* ret_params = new ESP32MCPWMDriverParams{
+ .pwm_frequency = params[0]->pwm_frequency,
+ .group_id = 2, // both groups
+ .timers = {params[0]->timers[0], params[1]->timers[0]},
+ .oper = {params[0]->oper[0], params[1]->oper[0]}
+ };
+ for(int i =0; i<4; i++){
+ ret_params->comparator[i] = params[(int)floor(i/2)]->comparator[i%2];
+ ret_params->generator[i] = params[(int)floor(i/2)]->generator[i%2];
+ }
+ ret_params->mcpwm_period = params[0]->mcpwm_period;
+ return ret_params;
+ }
+}
+
+
+void* _configure6PWM(long pwm_frequency, float dead_zone, const int pinA_h, const int pinA_l, const int pinB_h, const int pinB_l, const int pinC_h, const int pinC_l){
+ if(!pwm_frequency || !_isset(pwm_frequency) ) pwm_frequency = _PWM_FREQUENCY; // default frequency 25hz
+ else pwm_frequency = _constrain(pwm_frequency, 0, _PWM_FREQUENCY_MAX); // constrain to 40kHz max
+
+ int group, timer;
+ if(!_findBestGroup(6, pwm_frequency, &group, &timer)) {
+ SIMPLEFOC_ESP32_DRV_DEBUG("Not enough pins available for 6PWM!");
+ return SIMPLEFOC_DRIVER_INIT_FAILED;
+ }
+ SIMPLEFOC_ESP32_DRV_DEBUG("Configuring 6PWM in group: "+String(group)+" on timer: "+String(timer));
+ // configure the timer
+ int pins[6] = {pinA_h,pinA_l, pinB_h, pinB_l, pinC_h, pinC_l};
+ return _configure6PWMPinsMCPWM(pwm_frequency, group, timer, dead_zone, pins);
+}
+
+// function setting the pwm duty cycle to the hardware
+// - BLDC motor - 3PWM setting
+void _writeDutyCycle3PWM(float dc_a, float dc_b, float dc_c, void* params){
+ _setDutyCycle(((ESP32MCPWMDriverParams*)params)->comparator[0], ((ESP32MCPWMDriverParams*)params)->mcpwm_period, dc_a);
+ _setDutyCycle(((ESP32MCPWMDriverParams*)params)->comparator[1], ((ESP32MCPWMDriverParams*)params)->mcpwm_period, dc_b);
+ _setDutyCycle(((ESP32MCPWMDriverParams*)params)->comparator[2], ((ESP32MCPWMDriverParams*)params)->mcpwm_period, dc_c);
+}
+
+// function setting the pwm duty cycle to the hardware
+// - DCMotor -1PWM setting
+// - hardware specific
+void _writeDutyCycle1PWM(float dc_a, void* params){
+ _setDutyCycle(((ESP32MCPWMDriverParams*)params)->comparator[0], ((ESP32MCPWMDriverParams*)params)->mcpwm_period, dc_a);
+}
+
+// function setting the pwm duty cycle to the hardware
+// - Stepper motor - 2PWM setting
+// - hardware specific
+void _writeDutyCycle2PWM(float dc_a, float dc_b, void* params){
+ _setDutyCycle(((ESP32MCPWMDriverParams*)params)->comparator[0], ((ESP32MCPWMDriverParams*)params)->mcpwm_period, dc_a);
+ _setDutyCycle(((ESP32MCPWMDriverParams*)params)->comparator[1], ((ESP32MCPWMDriverParams*)params)->mcpwm_period, dc_b);
+}
+
+
+
+// function setting the pwm duty cycle to the hardware
+// - Stepper motor - 4PWM setting
+// - hardware specific
+void _writeDutyCycle4PWM(float dc_1a, float dc_1b, float dc_2a, float dc_2b, void* params){
+ // se the PWM on the slot timers
+ _setDutyCycle(((ESP32MCPWMDriverParams*)params)->comparator[0], ((ESP32MCPWMDriverParams*)params)->mcpwm_period, dc_1a);
+ _setDutyCycle(((ESP32MCPWMDriverParams*)params)->comparator[1], ((ESP32MCPWMDriverParams*)params)->mcpwm_period, dc_1b);
+ _setDutyCycle(((ESP32MCPWMDriverParams*)params)->comparator[2], ((ESP32MCPWMDriverParams*)params)->mcpwm_period, dc_2a);
+ _setDutyCycle(((ESP32MCPWMDriverParams*)params)->comparator[3], ((ESP32MCPWMDriverParams*)params)->mcpwm_period, dc_2b);
+}
+
+void _writeDutyCycle6PWM(float dc_a, float dc_b, float dc_c, PhaseState *phase_state, void* params){
+#if SIMPLEFOC_ESP32_HW_DEADTIME == true
+ _setDutyCycle(((ESP32MCPWMDriverParams*)params)->comparator[0], ((ESP32MCPWMDriverParams*)params)->mcpwm_period, dc_a);
+ _setDutyCycle(((ESP32MCPWMDriverParams*)params)->comparator[1], ((ESP32MCPWMDriverParams*)params)->mcpwm_period, dc_b);
+ _setDutyCycle(((ESP32MCPWMDriverParams*)params)->comparator[2], ((ESP32MCPWMDriverParams*)params)->mcpwm_period, dc_c);
+
+ // set the phase state
+ _forcePhaseState(((ESP32MCPWMDriverParams*)params)->generator[0], ((ESP32MCPWMDriverParams*)params)->generator[1], phase_state[0]);
+ _forcePhaseState(((ESP32MCPWMDriverParams*)params)->generator[2], ((ESP32MCPWMDriverParams*)params)->generator[3], phase_state[1]);
+ _forcePhaseState(((ESP32MCPWMDriverParams*)params)->generator[4], ((ESP32MCPWMDriverParams*)params)->generator[5], phase_state[2]);
+#else
+ uint32_t period = ((ESP32MCPWMDriverParams*)params)->mcpwm_period;
+ float dead_zone = (float)((ESP32MCPWMDriverParams*)params)->dead_zone /2.0f;
+ _setDutyCycle(((ESP32MCPWMDriverParams*)params)->comparator[0], period, (phase_state[0] == PHASE_ON || phase_state[0] == PHASE_HI) ? dc_a-dead_zone : 0.0f);
+ _setDutyCycle(((ESP32MCPWMDriverParams*)params)->comparator[1], period, (phase_state[0] == PHASE_ON || phase_state[0] == PHASE_LO) ? dc_a+dead_zone : 1.0f);
+ _setDutyCycle(((ESP32MCPWMDriverParams*)params)->comparator[2], period, (phase_state[1] == PHASE_ON || phase_state[1] == PHASE_HI) ? dc_b-dead_zone : 0.0f);
+ _setDutyCycle(((ESP32MCPWMDriverParams*)params)->comparator[3], period, (phase_state[1] == PHASE_ON || phase_state[1] == PHASE_LO) ? dc_b+dead_zone : 1.0f);
+ _setDutyCycle(((ESP32MCPWMDriverParams*)params)->comparator[4], period, (phase_state[2] == PHASE_ON || phase_state[2] == PHASE_HI) ? dc_c-dead_zone : 0.0f);
+ _setDutyCycle(((ESP32MCPWMDriverParams*)params)->comparator[5], period, (phase_state[2] == PHASE_ON || phase_state[2] == PHASE_LO) ? dc_c+dead_zone : 1.0f);
+#endif
+}
+#endif
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/drivers/hardware_specific/esp32/mcpwm_private.h b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/drivers/hardware_specific/esp32/mcpwm_private.h
new file mode 100644
index 0000000..dbf4897
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/drivers/hardware_specific/esp32/mcpwm_private.h
@@ -0,0 +1,82 @@
+/*
+ * This is a private declaration of different MCPWM structures and types.
+ * It has been copied from: https://github.com/espressif/esp-idf/blob/v5.1.4/components/driver/mcpwm/mcpwm_private.h
+ *
+ * extracted by askuric 16.06.2024
+ *
+ * SPDX-FileCopyrightText: 2022-2023 Espressif Systems (Shanghai) CO LTD
+ *
+ * SPDX-License-Identifier: Apache-2.0
+ */
+
+#ifndef MCPWM_PRIVATE_H
+#define MCPWM_PRIVATE_H
+
+
+#if defined(ESP_H) && defined(ARDUINO_ARCH_ESP32) && defined(SOC_MCPWM_SUPPORTED) && !defined(SIMPLEFOC_ESP32_USELEDC)
+
+#include "freertos/FreeRTOS.h"
+#include "esp_intr_alloc.h"
+#include "esp_heap_caps.h"
+#include "esp_pm.h"
+#include "soc/soc_caps.h"
+#include "hal/mcpwm_hal.h"
+#include "hal/mcpwm_types.h"
+#include "driver/mcpwm_types.h"
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+typedef struct mcpwm_group_t mcpwm_group_t;
+typedef struct mcpwm_timer_t mcpwm_timer_t;
+typedef struct mcpwm_cap_timer_t mcpwm_cap_timer_t;
+typedef struct mcpwm_oper_t mcpwm_oper_t;
+typedef struct mcpwm_gpio_fault_t mcpwm_gpio_fault_t;
+typedef struct mcpwm_gpio_sync_src_t mcpwm_gpio_sync_src_t;
+typedef struct mcpwm_timer_sync_src_t mcpwm_timer_sync_src_t;
+
+struct mcpwm_group_t {
+ int group_id; // group ID, index from 0
+ int intr_priority; // MCPWM interrupt priority
+ mcpwm_hal_context_t hal; // HAL instance is at group level
+ portMUX_TYPE spinlock; // group level spinlock
+ uint32_t prescale; // group prescale
+ uint32_t resolution_hz; // MCPWM group clock resolution: clock_src_hz / clock_prescale = resolution_hz
+ esp_pm_lock_handle_t pm_lock; // power management lock
+ soc_module_clk_t clk_src; // peripheral source clock
+ mcpwm_cap_timer_t *cap_timer; // mcpwm capture timers
+ mcpwm_timer_t *timers[SOC_MCPWM_TIMERS_PER_GROUP]; // mcpwm timer array
+ mcpwm_oper_t *operators[SOC_MCPWM_OPERATORS_PER_GROUP]; // mcpwm operator array
+ mcpwm_gpio_fault_t *gpio_faults[SOC_MCPWM_GPIO_FAULTS_PER_GROUP]; // mcpwm fault detectors array
+ mcpwm_gpio_sync_src_t *gpio_sync_srcs[SOC_MCPWM_GPIO_SYNCHROS_PER_GROUP]; // mcpwm gpio sync array
+};
+
+typedef enum {
+ MCPWM_TIMER_FSM_INIT,
+ MCPWM_TIMER_FSM_ENABLE,
+} mcpwm_timer_fsm_t;
+
+struct mcpwm_timer_t {
+ int timer_id; // timer ID, index from 0
+ mcpwm_group_t *group; // which group the timer belongs to
+ mcpwm_timer_fsm_t fsm; // driver FSM
+ portMUX_TYPE spinlock; // spin lock
+ intr_handle_t intr; // interrupt handle
+ uint32_t resolution_hz; // resolution of the timer
+ uint32_t peak_ticks; // peak ticks that the timer could reach to
+ mcpwm_timer_sync_src_t *sync_src; // timer sync_src
+ mcpwm_timer_count_mode_t count_mode; // count mode
+ mcpwm_timer_event_cb_t on_full; // callback function when MCPWM timer counts to peak value
+ mcpwm_timer_event_cb_t on_empty; // callback function when MCPWM timer counts to zero
+ mcpwm_timer_event_cb_t on_stop; // callback function when MCPWM timer stops
+ void *user_data; // user data which would be passed to the timer callbacks
+};
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif
+
+#endif /* MCPWM_PRIVATE_H */
\ No newline at end of file
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/drivers/hardware_specific/esp8266_mcu.cpp b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/drivers/hardware_specific/esp8266_mcu.cpp
new file mode 100644
index 0000000..23d9411
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/drivers/hardware_specific/esp8266_mcu.cpp
@@ -0,0 +1,121 @@
+#include "../hardware_api.h"
+
+#if defined(ESP_H) && defined(ARDUINO_ARCH_ESP8266)
+
+
+#pragma message("")
+#pragma message("SimpleFOC: compiling for ESP8266")
+#pragma message("")
+
+
+#define _PWM_FREQUENCY 25000 // 25khz
+#define _PWM_FREQUENCY_MAX 50000 // 50khz
+
+// configure High PWM frequency
+void _setHighFrequency(const long freq, const int pin){
+ analogWrite(pin, 0);
+ analogWriteFreq(freq);
+}
+
+
+// function setting the high pwm frequency to the supplied pins
+// - Stepper motor - 2PWM setting
+// - hardware speciffic
+void* _configure1PWM(long pwm_frequency, const int pinA) {
+ if(!pwm_frequency || !_isset(pwm_frequency) ) pwm_frequency = _PWM_FREQUENCY; // default frequency 25khz
+ else pwm_frequency = _constrain(pwm_frequency, 0, _PWM_FREQUENCY_MAX); // constrain to 50kHz max
+ _setHighFrequency(pwm_frequency, pinA);
+ GenericDriverParams* params = new GenericDriverParams {
+ .pins = { pinA },
+ .pwm_frequency = pwm_frequency
+ };
+ return params;
+}
+
+
+
+// function setting the high pwm frequency to the supplied pins
+// - Stepper motor - 2PWM setting
+// - hardware speciffic
+void* _configure2PWM(long pwm_frequency, const int pinA, const int pinB) {
+ if(!pwm_frequency || !_isset(pwm_frequency) ) pwm_frequency = _PWM_FREQUENCY; // default frequency 25khz
+ else pwm_frequency = _constrain(pwm_frequency, 0, _PWM_FREQUENCY_MAX); // constrain to 50kHz max
+ _setHighFrequency(pwm_frequency, pinA);
+ _setHighFrequency(pwm_frequency, pinB);
+ GenericDriverParams* params = new GenericDriverParams {
+ .pins = { pinA, pinB },
+ .pwm_frequency = pwm_frequency
+ };
+ return params;
+}
+
+// function setting the high pwm frequency to the supplied pins
+// - BLDC motor - 3PWM setting
+// - hardware speciffic
+void* _configure3PWM(long pwm_frequency,const int pinA, const int pinB, const int pinC) {
+ if(!pwm_frequency || !_isset(pwm_frequency) ) pwm_frequency = _PWM_FREQUENCY; // default frequency 25khz
+ else pwm_frequency = _constrain(pwm_frequency, 0, _PWM_FREQUENCY_MAX); // constrain to 50kHz max
+ _setHighFrequency(pwm_frequency, pinA);
+ _setHighFrequency(pwm_frequency, pinB);
+ _setHighFrequency(pwm_frequency, pinC);
+ GenericDriverParams* params = new GenericDriverParams {
+ .pins = { pinA, pinB, pinC },
+ .pwm_frequency = pwm_frequency
+ };
+ return params;
+}
+
+// function setting the high pwm frequency to the supplied pins
+// - Stepper motor - 4PWM setting
+// - hardware speciffic
+void* _configure4PWM(long pwm_frequency,const int pinA, const int pinB, const int pinC, const int pinD) {
+ if(!pwm_frequency || !_isset(pwm_frequency) ) pwm_frequency = _PWM_FREQUENCY; // default frequency 25khz
+ else pwm_frequency = _constrain(pwm_frequency, 0, _PWM_FREQUENCY_MAX); // constrain to 50kHz max
+ _setHighFrequency(pwm_frequency, pinA);
+ _setHighFrequency(pwm_frequency, pinB);
+ _setHighFrequency(pwm_frequency, pinC);
+ _setHighFrequency(pwm_frequency, pinD);
+ GenericDriverParams* params = new GenericDriverParams {
+ .pins = { pinA, pinB, pinC, pinD },
+ .pwm_frequency = pwm_frequency
+ };
+ return params;
+}
+
+// function setting the pwm duty cycle to the hardware
+// - Stepper motor - 2PWM setting
+// - hardware speciffic
+void _writeDutyCycle1PWM(float dc_a, void* params){
+ // transform duty cycle from [0,1] to [0,255]
+ analogWrite(((GenericDriverParams*)params)->pins[0], 255.0f*dc_a);
+}
+// function setting the pwm duty cycle to the hardware
+// - Stepper motor - 2PWM setting
+// - hardware speciffic
+void _writeDutyCycle2PWM(float dc_a, float dc_b, void* params){
+ // transform duty cycle from [0,1] to [0,255]
+ analogWrite(((GenericDriverParams*)params)->pins[0], 255.0f*dc_a);
+ analogWrite(((GenericDriverParams*)params)->pins[1], 255.0f*dc_b);
+}
+// function setting the pwm duty cycle to the hardware
+// - BLDC motor - 3PWM setting
+// - hardware speciffic
+void _writeDutyCycle3PWM(float dc_a, float dc_b, float dc_c, void* params){
+ // transform duty cycle from [0,1] to [0,255]
+ analogWrite(((GenericDriverParams*)params)->pins[0], 255.0f*dc_a);
+ analogWrite(((GenericDriverParams*)params)->pins[1], 255.0f*dc_b);
+ analogWrite(((GenericDriverParams*)params)->pins[2], 255.0f*dc_c);
+}
+
+// function setting the pwm duty cycle to the hardware
+// - Stepper motor - 4PWM setting
+// - hardware speciffic
+void _writeDutyCycle4PWM(float dc_1a, float dc_1b, float dc_2a, float dc_2b, void* params){
+ // transform duty cycle from [0,1] to [0,255]
+ analogWrite(((GenericDriverParams*)params)->pins[0], 255.0f*dc_1a);
+ analogWrite(((GenericDriverParams*)params)->pins[1], 255.0f*dc_1b);
+ analogWrite(((GenericDriverParams*)params)->pins[2], 255.0f*dc_2a);
+ analogWrite(((GenericDriverParams*)params)->pins[3], 255.0f*dc_2b);
+}
+
+#endif
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/drivers/hardware_specific/generic_mcu.cpp b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/drivers/hardware_specific/generic_mcu.cpp
new file mode 100644
index 0000000..b6bc2f0
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/drivers/hardware_specific/generic_mcu.cpp
@@ -0,0 +1,125 @@
+
+#include "../hardware_api.h"
+
+// if the mcu doen't have defiend analogWrite
+#if defined(ESP_H) && defined(ARDUINO_ARCH_ESP32) && !defined(analogWrite)
+ __attribute__((weak)) void analogWrite(uint8_t pin, int value){ };
+#endif
+
+// function setting the high pwm frequency to the supplied pin
+// - Stepper motor - 1PWM setting
+// - hardware speciffic
+// in generic case dont do anything
+__attribute__((weak)) void* _configure1PWM(long pwm_frequency, const int pinA) {
+ GenericDriverParams* params = new GenericDriverParams {
+ .pins = { pinA },
+ .pwm_frequency = pwm_frequency
+ };
+ return params;
+}
+
+// function setting the high pwm frequency to the supplied pins
+// - Stepper motor - 2PWM setting
+// - hardware speciffic
+// in generic case dont do anything
+__attribute__((weak)) void* _configure2PWM(long pwm_frequency,const int pinA, const int pinB) {
+ GenericDriverParams* params = new GenericDriverParams {
+ .pins = { pinA, pinB },
+ .pwm_frequency = pwm_frequency
+ };
+ return params;
+}
+
+// function setting the high pwm frequency to the supplied pins
+// - BLDC motor - 3PWM setting
+// - hardware speciffic
+// in generic case dont do anything
+__attribute__((weak)) void* _configure3PWM(long pwm_frequency,const int pinA, const int pinB, const int pinC) {
+ GenericDriverParams* params = new GenericDriverParams {
+ .pins = { pinA, pinB, pinC },
+ .pwm_frequency = pwm_frequency
+ };
+ return params;
+}
+
+
+// function setting the high pwm frequency to the supplied pins
+// - Stepper motor - 4PWM setting
+// - hardware speciffic
+// in generic case dont do anything
+__attribute__((weak)) void* _configure4PWM(long pwm_frequency, const int pin1A, const int pin1B, const int pin2A, const int pin2B) {
+ GenericDriverParams* params = new GenericDriverParams {
+ .pins = { pin1A, pin1B, pin2A, pin2B },
+ .pwm_frequency = pwm_frequency
+ };
+ return params;
+}
+
+// Configuring PWM frequency, resolution and alignment
+// - BLDC driver - 6PWM setting
+// - hardware specific
+__attribute__((weak)) void* _configure6PWM(long pwm_frequency, float dead_zone, const int pinA_h, const int pinA_l, const int pinB_h, const int pinB_l, const int pinC_h, const int pinC_l){
+ _UNUSED(pwm_frequency);
+ _UNUSED(dead_zone);
+ _UNUSED(pinA_h);
+ _UNUSED(pinA_l);
+ _UNUSED(pinB_h);
+ _UNUSED(pinB_l);
+ _UNUSED(pinC_h);
+ _UNUSED(pinC_l);
+
+ return SIMPLEFOC_DRIVER_INIT_FAILED;
+}
+
+
+// function setting the pwm duty cycle to the hardware
+// - Stepper motor - 1PWM setting
+// - hardware speciffic
+__attribute__((weak)) void _writeDutyCycle1PWM(float dc_a, void* params){
+ // transform duty cycle from [0,1] to [0,255]
+ analogWrite(((GenericDriverParams*)params)->pins[0], 255.0f*dc_a);
+}
+
+
+// function setting the pwm duty cycle to the hardware
+// - Stepper motor - 2PWM setting
+// - hardware speciffic
+__attribute__((weak)) void _writeDutyCycle2PWM(float dc_a, float dc_b, void* params){
+ // transform duty cycle from [0,1] to [0,255]
+ analogWrite(((GenericDriverParams*)params)->pins[0], 255.0f*dc_a);
+ analogWrite(((GenericDriverParams*)params)->pins[1], 255.0f*dc_b);
+}
+
+// function setting the pwm duty cycle to the hardware
+// - BLDC motor - 3PWM setting
+// - hardware speciffic
+__attribute__((weak)) void _writeDutyCycle3PWM(float dc_a, float dc_b, float dc_c, void* params){
+ // transform duty cycle from [0,1] to [0,255]
+ analogWrite(((GenericDriverParams*)params)->pins[0], 255.0f*dc_a);
+ analogWrite(((GenericDriverParams*)params)->pins[1], 255.0f*dc_b);
+ analogWrite(((GenericDriverParams*)params)->pins[2], 255.0f*dc_c);
+}
+
+// function setting the pwm duty cycle to the hardware
+// - Stepper motor - 4PWM setting
+// - hardware speciffic
+__attribute__((weak)) void _writeDutyCycle4PWM(float dc_1a, float dc_1b, float dc_2a, float dc_2b, void* params){
+ // transform duty cycle from [0,1] to [0,255]
+
+ analogWrite(((GenericDriverParams*)params)->pins[0], 255.0f*dc_1a);
+ analogWrite(((GenericDriverParams*)params)->pins[1], 255.0f*dc_1b);
+ analogWrite(((GenericDriverParams*)params)->pins[2], 255.0f*dc_2a);
+ analogWrite(((GenericDriverParams*)params)->pins[3], 255.0f*dc_2b);
+}
+
+
+// Function setting the duty cycle to the pwm pin (ex. analogWrite())
+// - BLDC driver - 6PWM setting
+// - hardware specific
+__attribute__((weak)) void _writeDutyCycle6PWM(float dc_a, float dc_b, float dc_c, PhaseState *phase_state, void* params){
+ _UNUSED(dc_a);
+ _UNUSED(dc_b);
+ _UNUSED(dc_c);
+ _UNUSED(phase_state);
+ _UNUSED(params);
+}
\ No newline at end of file
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/drivers/hardware_specific/nrf52_mcu.cpp b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/drivers/hardware_specific/nrf52_mcu.cpp
new file mode 100644
index 0000000..a20b828
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/drivers/hardware_specific/nrf52_mcu.cpp
@@ -0,0 +1,397 @@
+
+#include "../hardware_api.h"
+
+#if defined(NRF52_SERIES)
+
+#pragma message("")
+#pragma message("SimpleFOC: compiling for NRF52")
+#pragma message("")
+
+
+#define PWM_CLK (16000000)
+#define PWM_FREQ (40000)
+#define PWM_RESOLUTION (PWM_CLK/PWM_FREQ)
+#define PWM_MAX_FREQ (62500)
+#define DEAD_ZONE (250) // in ns
+#define DEAD_TIME (DEAD_ZONE / (PWM_RESOLUTION * 0.25 * 62.5)) // 62.5ns resolution of PWM
+
+#ifdef NRF_PWM3
+#define PWM_COUNT 4
+#else
+#define PWM_COUNT 3
+#endif
+
+// empty motor slot
+#define _EMPTY_SLOT (-0xAA)
+#define _TAKEN_SLOT (-0x55)
+
+int pwm_range;
+
+
+static NRF_PWM_Type* pwms[PWM_COUNT] = {
+ NRF_PWM0,
+ NRF_PWM1,
+ NRF_PWM2,
+ #ifdef NRF_PWM3
+ NRF_PWM3
+ #endif
+};
+
+typedef struct {
+ int pinA;
+ NRF_PWM_Type* mcpwm;
+ uint16_t mcpwm_channel_sequence[4];
+} bldc_3pwm_motor_slots_t;
+
+typedef struct {
+ int pin1A;
+ NRF_PWM_Type* mcpwm;
+ uint16_t mcpwm_channel_sequence[4];
+} stepper_motor_slots_t;
+
+typedef struct {
+ int pinAH;
+ NRF_PWM_Type* mcpwm1;
+ NRF_PWM_Type* mcpwm2;
+ uint16_t mcpwm_channel_sequence[8];
+} bldc_6pwm_motor_slots_t;
+
+// define bldc motor slots array
+bldc_3pwm_motor_slots_t nrf52_bldc_3pwm_motor_slots[4] = {
+ {_EMPTY_SLOT, pwms[0], {0,0,0,0}},// 1st motor will be PWM0
+ {_EMPTY_SLOT, pwms[1], {0,0,0,0}},// 2nd motor will be PWM1
+ {_EMPTY_SLOT, pwms[2], {0,0,0,0}},// 3rd motor will be PWM2
+ {_EMPTY_SLOT, pwms[3], {0,0,0,0}} // 4th motor will be PWM3
+ };
+
+// define stepper motor slots array
+stepper_motor_slots_t nrf52_stepper_motor_slots[4] = {
+ {_EMPTY_SLOT, pwms[0], {0,0,0,0}},// 1st motor will be on PWM0
+ {_EMPTY_SLOT, pwms[1], {0,0,0,0}},// 1st motor will be on PWM1
+ {_EMPTY_SLOT, pwms[2], {0,0,0,0}},// 1st motor will be on PWM2
+ {_EMPTY_SLOT, pwms[3], {0,0,0,0}} // 1st motor will be on PWM3
+ };
+
+// define BLDC motor slots array
+bldc_6pwm_motor_slots_t nrf52_bldc_6pwm_motor_slots[2] = {
+ {_EMPTY_SLOT, pwms[0], pwms[1], {0,0,0,0,0,0,0,0}},// 1st motor will be on PWM0 & PWM1
+ {_EMPTY_SLOT, pwms[2], pwms[3], {0,0,0,0,0,0,0,0}} // 2nd motor will be on PWM1 & PWM2
+ };
+
+
+
+typedef struct NRF52DriverParams {
+ union {
+ bldc_3pwm_motor_slots_t* slot3pwm;
+ bldc_6pwm_motor_slots_t* slot6pwm;
+ stepper_motor_slots_t* slotstep;
+ } slot;
+ long pwm_frequency;
+ float dead_time;
+} NRF52DriverParams;
+
+
+
+
+// configuring high frequency pwm timer
+void _configureHwPwm(NRF_PWM_Type* mcpwm1, NRF_PWM_Type* mcpwm2){
+
+ mcpwm1->ENABLE = (PWM_ENABLE_ENABLE_Enabled << PWM_ENABLE_ENABLE_Pos);
+ mcpwm1->PRESCALER = (PWM_PRESCALER_PRESCALER_DIV_1 << PWM_PRESCALER_PRESCALER_Pos);
+ mcpwm1->MODE = (PWM_MODE_UPDOWN_UpAndDown << PWM_MODE_UPDOWN_Pos);
+ mcpwm1->COUNTERTOP = pwm_range; //pwm freq.
+ mcpwm1->LOOP = (PWM_LOOP_CNT_Disabled << PWM_LOOP_CNT_Pos);
+ mcpwm1->DECODER = ((uint32_t)PWM_DECODER_LOAD_Individual << PWM_DECODER_LOAD_Pos) | ((uint32_t)PWM_DECODER_MODE_RefreshCount << PWM_DECODER_MODE_Pos);
+ mcpwm1->SEQ[0].REFRESH = 0;
+ mcpwm1->SEQ[0].ENDDELAY = 0;
+
+ if(mcpwm1 != mcpwm2){
+ mcpwm2->ENABLE = (PWM_ENABLE_ENABLE_Enabled << PWM_ENABLE_ENABLE_Pos);
+ mcpwm2->PRESCALER = (PWM_PRESCALER_PRESCALER_DIV_1 << PWM_PRESCALER_PRESCALER_Pos);
+ mcpwm2->MODE = (PWM_MODE_UPDOWN_UpAndDown << PWM_MODE_UPDOWN_Pos);
+ mcpwm2->COUNTERTOP = pwm_range; //pwm freq.
+ mcpwm2->LOOP = (PWM_LOOP_CNT_Disabled << PWM_LOOP_CNT_Pos);
+ mcpwm2->DECODER = ((uint32_t)PWM_DECODER_LOAD_Individual << PWM_DECODER_LOAD_Pos) | ((uint32_t)PWM_DECODER_MODE_RefreshCount << PWM_DECODER_MODE_Pos);
+ mcpwm2->SEQ[0].REFRESH = 0;
+ mcpwm2->SEQ[0].ENDDELAY = 0;
+ }else{
+ mcpwm1->MODE = (PWM_MODE_UPDOWN_Up << PWM_MODE_UPDOWN_Pos);
+ }
+}
+
+
+
+// can we support it using the generic driver on this MCU? Commented out to fall back to generic driver for 2-pwm
+// void* _configure2PWM(long pwm_frequency, const int pinA, const int pinB) {
+// return SIMPLEFOC_DRIVER_INIT_FAILED; // not supported
+// }
+
+
+
+
+// function setting the high pwm frequency to the supplied pins
+// - BLDC motor - 3PWM setting
+// - hardware speciffic
+void* _configure3PWM(long pwm_frequency,const int pinA, const int pinB, const int pinC) {
+
+ if( !pwm_frequency || pwm_frequency == NOT_SET) pwm_frequency = PWM_FREQ; // default frequency 20khz for a resolution of 800
+ else pwm_frequency = _constrain(pwm_frequency, 0, PWM_MAX_FREQ); // constrain to 62.5kHz max for a resolution of 256
+
+ pwm_range = (PWM_CLK / pwm_frequency);
+
+ int pA = digitalPinToPinName(pinA); //g_ADigitalPinMap[pinA];
+ int pB = digitalPinToPinName(pinB); //g_ADigitalPinMap[pinB];
+ int pC = digitalPinToPinName(pinC); //g_ADigitalPinMap[pinC];
+
+ // determine which motor are we connecting
+ // and set the appropriate configuration parameters
+ int slot_num;
+ for(slot_num = 0; slot_num < 4; slot_num++){
+ if(nrf52_bldc_3pwm_motor_slots[slot_num].pinA == _EMPTY_SLOT){ // put the new motor in the first empty slot
+ nrf52_bldc_3pwm_motor_slots[slot_num].pinA = pinA;
+ break;
+ }
+ }
+ // if no slots available
+ if(slot_num >= 4) return SIMPLEFOC_DRIVER_INIT_FAILED;
+
+ // disable all the slots with the same MCPWM
+ if(slot_num < 2){
+ // slot 0 of the stepper
+ nrf52_stepper_motor_slots[slot_num].pin1A = _TAKEN_SLOT;
+ // slot 0 of the 6pwm bldc
+ nrf52_bldc_6pwm_motor_slots[0].pinAH = _TAKEN_SLOT;
+ //NRF_PPI->CHEN &= ~1UL;
+ }else{
+ // slot 1 of the stepper
+ nrf52_stepper_motor_slots[slot_num].pin1A = _TAKEN_SLOT;
+ // slot 0 of the 6pwm bldc
+ nrf52_bldc_6pwm_motor_slots[1].pinAH = _TAKEN_SLOT;
+ //NRF_PPI->CHEN &= ~2UL;
+ }
+
+ // configure pwm outputs
+
+ nrf52_bldc_3pwm_motor_slots[slot_num].mcpwm->PSEL.OUT[0] = pA;
+ nrf52_bldc_3pwm_motor_slots[slot_num].mcpwm->PSEL.OUT[1] = pB;
+ nrf52_bldc_3pwm_motor_slots[slot_num].mcpwm->PSEL.OUT[2] = pC;
+
+ nrf52_bldc_3pwm_motor_slots[slot_num].mcpwm->SEQ[0].PTR = (uint32_t)&nrf52_bldc_3pwm_motor_slots[slot_num].mcpwm_channel_sequence[0];
+ nrf52_bldc_3pwm_motor_slots[slot_num].mcpwm->SEQ[0].CNT = 4;
+
+ // configure the pwm
+ _configureHwPwm(nrf52_bldc_3pwm_motor_slots[slot_num].mcpwm, nrf52_bldc_3pwm_motor_slots[slot_num].mcpwm);
+
+ NRF52DriverParams* params = new NRF52DriverParams();
+ params->slot.slot3pwm = &(nrf52_bldc_3pwm_motor_slots[slot_num]);
+ params->pwm_frequency = pwm_frequency;
+ return params;
+}
+
+
+
+
+// function setting the high pwm frequency to the supplied pins
+// - Stepper motor - 4PWM setting
+// - hardware speciffic
+void* _configure4PWM(long pwm_frequency, const int pinA, const int pinB, const int pinC, const int pinD) {
+
+ if( !pwm_frequency || pwm_frequency == NOT_SET) pwm_frequency = PWM_FREQ; // default frequency 20khz for a resolution of 800
+ else pwm_frequency = _constrain(pwm_frequency, 0, PWM_MAX_FREQ); // constrain to 62.5kHz max for a resolution of 256
+
+ pwm_range = (PWM_CLK / pwm_frequency);
+
+ int pA = digitalPinToPinName(pinA); //g_ADigitalPinMap[pinA];
+ int pB = digitalPinToPinName(pinB); //g_ADigitalPinMap[pinB];
+ int pC = digitalPinToPinName(pinC); //g_ADigitalPinMap[pinC];
+ int pD = digitalPinToPinName(pinD); //g_ADigitalPinMap[pinD];
+
+ // determine which motor are we connecting
+ // and set the appropriate configuration parameters
+ int slot_num;
+ for(slot_num = 0; slot_num < 4; slot_num++){
+ if(nrf52_stepper_motor_slots[slot_num].pin1A == _EMPTY_SLOT){ // put the new motor in the first empty slot
+ nrf52_stepper_motor_slots[slot_num].pin1A = pinA;
+ break;
+ }
+ }
+ // if no slots available
+ if (slot_num >= 4) return SIMPLEFOC_DRIVER_INIT_FAILED;
+
+ // disable all the slots with the same MCPWM
+ if (slot_num < 2){
+ // slots 0 and 1 of the 3pwm bldc
+ nrf52_bldc_3pwm_motor_slots[slot_num].pinA = _TAKEN_SLOT;
+ // slot 0 of the 6pwm bldc
+ nrf52_bldc_6pwm_motor_slots[0].pinAH = _TAKEN_SLOT;
+ //NRF_PPI->CHEN &= ~1UL;
+ }else{
+ // slots 2 and 3 of the 3pwm bldc
+ nrf52_bldc_3pwm_motor_slots[slot_num].pinA = _TAKEN_SLOT;
+ // slot 1 of the 6pwm bldc
+ nrf52_bldc_6pwm_motor_slots[1].pinAH = _TAKEN_SLOT;
+ //NRF_PPI->CHEN &= ~2UL;
+ }
+
+ // configure pwm outputs
+
+ nrf52_stepper_motor_slots[slot_num].mcpwm->PSEL.OUT[0] = pA;
+ nrf52_stepper_motor_slots[slot_num].mcpwm->PSEL.OUT[1] = pB;
+ nrf52_stepper_motor_slots[slot_num].mcpwm->PSEL.OUT[2] = pC;
+ nrf52_stepper_motor_slots[slot_num].mcpwm->PSEL.OUT[3] = pD;
+
+ nrf52_stepper_motor_slots[slot_num].mcpwm->SEQ[0].PTR = (uint32_t)&nrf52_stepper_motor_slots[slot_num].mcpwm_channel_sequence[0];
+ nrf52_stepper_motor_slots[slot_num].mcpwm->SEQ[0].CNT = 4;
+
+ // configure the pwm
+ _configureHwPwm(nrf52_stepper_motor_slots[slot_num].mcpwm, nrf52_stepper_motor_slots[slot_num].mcpwm);
+
+ NRF52DriverParams* params = new NRF52DriverParams();
+ params->slot.slotstep = &(nrf52_stepper_motor_slots[slot_num]);
+ params->pwm_frequency = pwm_frequency;
+ return params;
+}
+
+
+
+
+// function setting the pwm duty cycle to the hardware
+// - BLDC motor - 3PWM setting
+// - hardware speciffic
+void _writeDutyCycle3PWM(float dc_a, float dc_b, float dc_c, void* params){
+ // transform duty cycle from [0,1] to [0,range]
+ bldc_3pwm_motor_slots_t* p = ((NRF52DriverParams*)params)->slot.slot3pwm;
+ p->mcpwm_channel_sequence[0] = (int)(dc_a * pwm_range) | 0x8000;
+ p->mcpwm_channel_sequence[1] = (int)(dc_b * pwm_range) | 0x8000;
+ p->mcpwm_channel_sequence[2] = (int)(dc_c * pwm_range) | 0x8000;
+
+ p->mcpwm->TASKS_SEQSTART[0] = 1;
+}
+
+
+
+
+// function setting the pwm duty cycle to the hardware
+// - Stepper motor - 4PWM setting
+// - hardware speciffic
+void _writeDutyCycle4PWM(float dc_1a, float dc_1b, float dc_2a, float dc_2b, void* params){
+
+ stepper_motor_slots_t* p = ((NRF52DriverParams*)params)->slot.slotstep;
+ p->mcpwm_channel_sequence[0] = (int)(dc_1a * pwm_range) | 0x8000;
+ p->mcpwm_channel_sequence[1] = (int)(dc_1b * pwm_range) | 0x8000;
+ p->mcpwm_channel_sequence[2] = (int)(dc_2a * pwm_range) | 0x8000;
+ p->mcpwm_channel_sequence[3] = (int)(dc_2b * pwm_range) | 0x8000;
+
+ p->mcpwm->TASKS_SEQSTART[0] = 1;
+}
+
+/* Configuring PWM frequency, resolution and alignment
+// - BLDC driver - 6PWM setting
+// - hardware specific
+*/
+void* _configure6PWM(long pwm_frequency, float dead_zone, const int pinA_h, const int pinA_l, const int pinB_h, const int pinB_l, const int pinC_h, const int pinC_l){
+
+ if( !pwm_frequency || pwm_frequency == NOT_SET) pwm_frequency = PWM_FREQ; // default frequency 20khz - centered pwm has twice lower frequency for a resolution of 400
+ else pwm_frequency = _constrain(pwm_frequency*2, 0, PWM_MAX_FREQ); // constrain to 62.5kHz max => 31.25kHz for a resolution of 256
+
+ pwm_range = (PWM_CLK / pwm_frequency);
+ pwm_range /= 2; // scale the frequency (centered PWM)
+
+ float dead_time;
+ if (dead_zone != NOT_SET){
+ dead_time = dead_zone/2;
+ }else{
+ dead_time = DEAD_TIME/2;
+ }
+
+ int pA_l = digitalPinToPinName(pinA_l); //g_ADigitalPinMap[pinA_l];
+ int pA_h = digitalPinToPinName(pinA_h); //g_ADigitalPinMap[pinA_h];
+ int pB_l = digitalPinToPinName(pinB_l); //g_ADigitalPinMap[pinB_l];
+ int pB_h = digitalPinToPinName(pinB_h); //g_ADigitalPinMap[pinB_h];
+ int pC_l = digitalPinToPinName(pinC_l); //g_ADigitalPinMap[pinC_l];
+ int pC_h = digitalPinToPinName(pinC_h); //g_ADigitalPinMap[pinC_h];
+
+
+ // determine which motor are we connecting
+ // and set the appropriate configuration parameters
+ int slot_num;
+ for(slot_num = 0; slot_num < 2; slot_num++){
+ if(nrf52_bldc_6pwm_motor_slots[slot_num].pinAH == _EMPTY_SLOT){ // put the new motor in the first empty slot
+ nrf52_bldc_6pwm_motor_slots[slot_num].pinAH = pinA_h;
+ break;
+ }
+ }
+ // if no slots available
+ if(slot_num >= 2) return SIMPLEFOC_DRIVER_INIT_FAILED;
+
+ // disable all the slots with the same MCPWM
+ if( slot_num == 0 ){
+ // slots 0 and 1 of the 3pwm bldc
+ nrf52_bldc_3pwm_motor_slots[0].pinA = _TAKEN_SLOT;
+ nrf52_bldc_3pwm_motor_slots[1].pinA = _TAKEN_SLOT;
+ // slot 0 and 1 of the stepper
+ nrf52_stepper_motor_slots[0].pin1A = _TAKEN_SLOT;
+ nrf52_stepper_motor_slots[1].pin1A = _TAKEN_SLOT;
+ }else{
+ // slots 2 and 3 of the 3pwm bldc
+ nrf52_bldc_3pwm_motor_slots[2].pinA = _TAKEN_SLOT;
+ nrf52_bldc_3pwm_motor_slots[3].pinA = _TAKEN_SLOT;
+ // slot 1 of the stepper
+ nrf52_stepper_motor_slots[2].pin1A = _TAKEN_SLOT;
+ nrf52_stepper_motor_slots[3].pin1A = _TAKEN_SLOT;
+ }
+
+ // Configure pwm outputs
+
+ nrf52_bldc_6pwm_motor_slots[slot_num].mcpwm1->PSEL.OUT[0] = pA_h;
+ nrf52_bldc_6pwm_motor_slots[slot_num].mcpwm1->PSEL.OUT[1] = pA_l;
+ nrf52_bldc_6pwm_motor_slots[slot_num].mcpwm1->PSEL.OUT[2] = pB_h;
+ nrf52_bldc_6pwm_motor_slots[slot_num].mcpwm1->PSEL.OUT[3] = pB_l;
+ nrf52_bldc_6pwm_motor_slots[slot_num].mcpwm1->SEQ[0].PTR = (uint32_t)&nrf52_bldc_6pwm_motor_slots[slot_num].mcpwm_channel_sequence[0];
+ nrf52_bldc_6pwm_motor_slots[slot_num].mcpwm1->SEQ[0].CNT = 4;
+
+ nrf52_bldc_6pwm_motor_slots[slot_num].mcpwm2->PSEL.OUT[0] = pC_h;
+ nrf52_bldc_6pwm_motor_slots[slot_num].mcpwm2->PSEL.OUT[1] = pC_l;
+ nrf52_bldc_6pwm_motor_slots[slot_num].mcpwm2->SEQ[0].PTR = (uint32_t)&nrf52_bldc_6pwm_motor_slots[slot_num].mcpwm_channel_sequence[4];
+ nrf52_bldc_6pwm_motor_slots[slot_num].mcpwm2->SEQ[0].CNT = 4;
+
+ // Initializing the PPI peripheral for sync the pwm slots
+
+ NRF_PPI->CH[slot_num].EEP = (uint32_t)&NRF_EGU0->EVENTS_TRIGGERED[0];
+ NRF_PPI->CH[slot_num].TEP = (uint32_t)&nrf52_bldc_6pwm_motor_slots[slot_num].mcpwm1->TASKS_SEQSTART[0];
+ NRF_PPI->FORK[slot_num].TEP = (uint32_t)&nrf52_bldc_6pwm_motor_slots[slot_num].mcpwm2->TASKS_SEQSTART[0];
+ NRF_PPI->CHEN = 1UL << slot_num;
+
+ // configure the pwm type
+ _configureHwPwm(nrf52_bldc_6pwm_motor_slots[slot_num].mcpwm1, nrf52_bldc_6pwm_motor_slots[slot_num].mcpwm2);
+
+ NRF52DriverParams* params = new NRF52DriverParams();
+ params->slot.slot6pwm = &(nrf52_bldc_6pwm_motor_slots[slot_num]);
+ params->pwm_frequency = pwm_frequency;
+ params->dead_time = dead_time;
+ return params;
+}
+
+
+
+
+/* Function setting the duty cycle to the pwm pin
+// - BLDC driver - 6PWM setting
+// - hardware specific
+*/
+void _writeDutyCycle6PWM(float dc_a, float dc_b, float dc_c, PhaseState *phase_state, void* params){
+ bldc_6pwm_motor_slots_t* p = ((NRF52DriverParams*)params)->slot.slot6pwm;
+ float dead_time = ((NRF52DriverParams*)params)->dead_time;
+ p->mcpwm_channel_sequence[0] = (int)(_constrain(dc_a-dead_time,0,1)*pwm_range) | 0x8000;
+ p->mcpwm_channel_sequence[1] = (int)(_constrain(dc_a+dead_time,0,1)*pwm_range);
+ p->mcpwm_channel_sequence[2] = (int)(_constrain(dc_b-dead_time,0,1)*pwm_range) | 0x8000;
+ p->mcpwm_channel_sequence[3] = (int)(_constrain(dc_b+dead_time,0,1)*pwm_range);
+ p->mcpwm_channel_sequence[4] = (int)(_constrain(dc_c-dead_time,0,1)*pwm_range) | 0x8000;
+ p->mcpwm_channel_sequence[5] = (int)(_constrain(dc_c+dead_time,0,1)*pwm_range);
+ NRF_EGU0->TASKS_TRIGGER[0] = 1;
+
+ _UNUSED(phase_state);
+}
+
+
+#endif
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/drivers/hardware_specific/portenta_h7_mcu.cpp b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/drivers/hardware_specific/portenta_h7_mcu.cpp
new file mode 100644
index 0000000..ad16646
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/drivers/hardware_specific/portenta_h7_mcu.cpp
@@ -0,0 +1,545 @@
+
+#include "../hardware_api.h"
+
+#if defined(TARGET_PORTENTA_H7)
+
+
+#pragma message("")
+#pragma message("SimpleFOC: compiling for Arduino/Portenta_H7")
+#pragma message("")
+
+
+#include "pwmout_api.h"
+#include "pinDefinitions.h"
+#include "platform/mbed_critical.h"
+#include "platform/mbed_power_mgmt.h"
+#include "platform/mbed_assert.h"
+#include "PeripheralPins.h"
+#include "pwmout_device.h"
+
+// default pwm parameters
+#define _PWM_FREQUENCY 25000 // 25khz
+#define _PWM_FREQUENCY_MAX 50000 // 50khz
+
+
+// // 6pwm parameters
+// #define _HARDWARE_6PWM 1
+// #define _SOFTWARE_6PWM 0
+// #define _ERROR_6PWM -1
+
+
+
+typedef struct PortentaDriverParams {
+ pwmout_t pins[4];
+ long pwm_frequency;
+// float dead_zone;
+} PortentaDriverParams;
+
+
+
+/* Convert STM32 Cube HAL channel to LL channel */
+uint32_t _TIM_ChannelConvert_HAL2LL(uint32_t channel, pwmout_t *obj)
+{
+#if !defined(PWMOUT_INVERTED_NOT_SUPPORTED)
+ if (obj->inverted) {
+ switch (channel) {
+ case TIM_CHANNEL_1 :
+ return LL_TIM_CHANNEL_CH1N;
+ case TIM_CHANNEL_2 :
+ return LL_TIM_CHANNEL_CH2N;
+ case TIM_CHANNEL_3 :
+ return LL_TIM_CHANNEL_CH3N;
+#if defined(LL_TIM_CHANNEL_CH4N)
+ case TIM_CHANNEL_4 :
+ return LL_TIM_CHANNEL_CH4N;
+#endif
+ default : /* Optional */
+ return 0;
+ }
+ } else
+#endif
+ {
+ switch (channel) {
+ case TIM_CHANNEL_1 :
+ return LL_TIM_CHANNEL_CH1;
+ case TIM_CHANNEL_2 :
+ return LL_TIM_CHANNEL_CH2;
+ case TIM_CHANNEL_3 :
+ return LL_TIM_CHANNEL_CH3;
+ case TIM_CHANNEL_4 :
+ return LL_TIM_CHANNEL_CH4;
+ default : /* Optional */
+ return 0;
+ }
+ }
+}
+
+
+
+// int _pwm_init(pwmout_t *obj, uint32_t pin, long frequency){
+// return _pwm_init(obj, digitalPinToPinName(pin), frequency);
+// }
+
+int _pwm_init(pwmout_t *obj, uint32_t pin, long frequency){
+ int peripheral = (int)pinmap_peripheral(digitalPinToPinName(pin), PinMap_PWM);
+ int function = (int)pinmap_find_function(digitalPinToPinName(pin), PinMap_PWM);
+
+ const PinMap static_pinmap = {digitalPinToPinName(pin), peripheral, function};
+
+ pwmout_init_direct(obj, &static_pinmap);
+
+ TIM_HandleTypeDef TimHandle;
+ TimHandle.Instance = (TIM_TypeDef *)(obj->pwm);
+ RCC_ClkInitTypeDef RCC_ClkInitStruct;
+ uint32_t PclkFreq = 0;
+ uint32_t APBxCLKDivider = RCC_HCLK_DIV1;
+ uint8_t i = 0;
+
+
+ __HAL_TIM_DISABLE(&TimHandle);
+
+ // Get clock configuration
+ // Note: PclkFreq contains here the Latency (not used after)
+ HAL_RCC_GetClockConfig(&RCC_ClkInitStruct, &PclkFreq);
+
+ /* Parse the pwm / apb mapping table to find the right entry */
+ while (pwm_apb_map_table[i].pwm != obj->pwm) i++;
+ // sanity check
+ if (pwm_apb_map_table[i].pwm == 0) return -1;
+
+
+ if (pwm_apb_map_table[i].pwmoutApb == PWMOUT_ON_APB1) {
+ PclkFreq = HAL_RCC_GetPCLK1Freq();
+ APBxCLKDivider = RCC_ClkInitStruct.APB1CLKDivider;
+ } else {
+#if !defined(PWMOUT_APB2_NOT_SUPPORTED)
+ PclkFreq = HAL_RCC_GetPCLK2Freq();
+ APBxCLKDivider = RCC_ClkInitStruct.APB2CLKDivider;
+#endif
+ }
+
+ long period_us = 500000.0/((float)frequency);
+ /* By default use, 1us as SW pre-scaler */
+ obj->prescaler = 1;
+ // TIMxCLK = PCLKx when the APB prescaler = 1 else TIMxCLK = 2 * PCLKx
+ if (APBxCLKDivider == RCC_HCLK_DIV1) {
+ TimHandle.Init.Prescaler = (((PclkFreq) / 1000000)) - 1; // 1 us tick
+ } else {
+ TimHandle.Init.Prescaler = (((PclkFreq * 2) / 1000000)) - 1; // 1 us tick
+ }
+ TimHandle.Init.Period = (period_us - 1);
+
+ /* In case period or pre-scalers are out of range, loop-in to get valid values */
+ while ((TimHandle.Init.Period > 0xFFFF) || (TimHandle.Init.Prescaler > 0xFFFF)) {
+ obj->prescaler = obj->prescaler * 2;
+ if (APBxCLKDivider == RCC_HCLK_DIV1) {
+ TimHandle.Init.Prescaler = (((PclkFreq) / 1000000) * obj->prescaler) - 1;
+ } else {
+ TimHandle.Init.Prescaler = (((PclkFreq * 2) / 1000000) * obj->prescaler) - 1;
+ }
+ TimHandle.Init.Period = (period_us - 1) / obj->prescaler;
+ /* Period decreases and prescaler increases over loops, so check for
+ * possible out of range cases */
+ if ((TimHandle.Init.Period < 0xFFFF) && (TimHandle.Init.Prescaler > 0xFFFF)) {
+ break;
+ }
+ }
+
+ TimHandle.Init.ClockDivision = 0;
+ TimHandle.Init.CounterMode = TIM_COUNTERMODE_CENTERALIGNED3; // center aligned
+
+ if (HAL_TIM_PWM_Init(&TimHandle) != HAL_OK) {
+ return -1;
+ }
+
+ TIM_OC_InitTypeDef sConfig;
+ // Configure channels
+ sConfig.OCMode = TIM_OCMODE_PWM1;
+ sConfig.Pulse = obj->pulse / obj->prescaler;
+ sConfig.OCPolarity = TIM_OCPOLARITY_HIGH;
+ sConfig.OCFastMode = TIM_OCFAST_DISABLE;
+#if defined(TIM_OCIDLESTATE_RESET)
+ sConfig.OCIdleState = TIM_OCIDLESTATE_RESET;
+#endif
+#if defined(TIM_OCNIDLESTATE_RESET)
+ sConfig.OCNPolarity = TIM_OCNPOLARITY_HIGH;
+ sConfig.OCNIdleState = TIM_OCNIDLESTATE_RESET;
+#endif
+
+ int channel = 0;
+ switch (obj->channel) {
+ case 1:
+ channel = TIM_CHANNEL_1;
+ break;
+ case 2:
+ channel = TIM_CHANNEL_2;
+ break;
+ case 3:
+ channel = TIM_CHANNEL_3;
+ break;
+ case 4:
+ channel = TIM_CHANNEL_4;
+ break;
+ default:
+ return -1;
+ }
+
+ if (LL_TIM_CC_IsEnabledChannel(TimHandle.Instance, _TIM_ChannelConvert_HAL2LL(channel, obj)) == 0) {
+ // If channel is not enabled, proceed to channel configuration
+ if (HAL_TIM_PWM_ConfigChannel(&TimHandle, &sConfig, channel) != HAL_OK) {
+ return -1;
+ }
+ }
+
+ // Save for future use
+ obj->period = period_us;
+#if !defined(PWMOUT_INVERTED_NOT_SUPPORTED)
+ if (obj->inverted) {
+ HAL_TIMEx_PWMN_Start(&TimHandle, channel);
+ } else
+#endif
+ {
+ HAL_TIM_PWM_Start(&TimHandle, channel);
+ }
+
+ return 0;
+}
+
+// setting pwm to hardware pin - instead analogWrite()
+void _pwm_write(pwmout_t *obj, float value){
+ TIM_HandleTypeDef TimHandle;
+ int channel = 0;
+
+ TimHandle.Instance = (TIM_TypeDef *)(obj->pwm);
+
+ if (value < (float)0.0) {
+ value = 0.0;
+ } else if (value > (float)1.0) {
+ value = 1.0;
+ }
+
+ obj->pulse = (uint32_t)((float)obj->period * value + 0.5);
+
+ switch (obj->channel) {
+ case 1:
+ channel = TIM_CHANNEL_1;
+ break;
+ case 2:
+ channel = TIM_CHANNEL_2;
+ break;
+ case 3:
+ channel = TIM_CHANNEL_3;
+ break;
+ case 4:
+ channel = TIM_CHANNEL_4;
+ break;
+ default:
+ return;
+ }
+
+ // If channel already enabled, only update compare value to avoid glitch
+ __HAL_TIM_SET_COMPARE(&TimHandle, channel, obj->pulse / obj->prescaler);
+}
+
+// init low side pin
+// HardwareTimer* _initPinPWMLow(uint32_t PWM_freq, int ulPin)
+// {
+// PinName pin = digitalPinToPinName(ulPin);
+// TIM_TypeDef *Instance = (TIM_TypeDef *)pinmap_peripheral(pin, PinMap_PWM);
+// uint32_t index = get_timer_index(Instance);
+
+// if (HardwareTimer_Handle[index] == NULL) {
+// HardwareTimer_Handle[index]->__this = new HardwareTimer((TIM_TypeDef *)pinmap_peripheral(pin, PinMap_PWM));
+// HardwareTimer_Handle[index]->handle.Init.CounterMode = TIM_COUNTERMODE_CENTERALIGNED3;
+// HAL_TIM_Base_Init(&(HardwareTimer_Handle[index]->handle));
+// TIM_OC_InitTypeDef sConfigOC = TIM_OC_InitTypeDef();
+// sConfigOC.OCMode = TIM_OCMODE_PWM2;
+// sConfigOC.Pulse = 100;
+// sConfigOC.OCPolarity = TIM_OCPOLARITY_LOW;
+// sConfigOC.OCFastMode = TIM_OCFAST_DISABLE;
+// sConfigOC.OCNPolarity = TIM_OCNPOLARITY_HIGH;
+// sConfigOC.OCIdleState = TIM_OCIDLESTATE_SET;
+// sConfigOC.OCNIdleState = TIM_OCNIDLESTATE_RESET;
+// uint32_t channel = STM_PIN_CHANNEL(pinmap_function(pin, PinMap_PWM));
+// HAL_TIM_PWM_ConfigChannel(&(HardwareTimer_Handle[index]->handle), &sConfigOC, channel);
+// }
+// HardwareTimer *HT = (HardwareTimer *)(HardwareTimer_Handle[index]->__this);
+// uint32_t channel = STM_PIN_CHANNEL(pinmap_function(pin, PinMap_PWM));
+// HT->setMode(channel, TIMER_OUTPUT_COMPARE_PWM2, pin);
+// HT->setOverflow(PWM_freq, HERTZ_FORMAT);
+// HT->pause();
+// HT->refresh();
+// return HT;
+// }
+
+
+// align the timers to end the init
+void _alignPWMTimers(pwmout_t *t1, pwmout_t *t2){
+ TIM_HandleTypeDef TimHandle1, TimHandle2;
+ TimHandle1.Instance = (TIM_TypeDef *)(t1->pwm);
+ TimHandle2.Instance = (TIM_TypeDef *)(t2->pwm);
+ __HAL_TIM_DISABLE(&TimHandle1);
+ __HAL_TIM_DISABLE(&TimHandle2);
+ __HAL_TIM_ENABLE(&TimHandle1);
+ __HAL_TIM_ENABLE(&TimHandle2);
+}
+
+// align the timers to end the init
+void _alignPWMTimers(pwmout_t *t1, pwmout_t *t2, pwmout_t *t3){
+ TIM_HandleTypeDef TimHandle1, TimHandle2, TimHandle3;
+ TimHandle1.Instance = (TIM_TypeDef *)(t1->pwm);
+ TimHandle2.Instance = (TIM_TypeDef *)(t2->pwm);
+ TimHandle3.Instance = (TIM_TypeDef *)(t3->pwm);
+ __HAL_TIM_DISABLE(&TimHandle1);
+ __HAL_TIM_DISABLE(&TimHandle2);
+ __HAL_TIM_DISABLE(&TimHandle3);
+ __HAL_TIM_ENABLE(&TimHandle1);
+ __HAL_TIM_ENABLE(&TimHandle2);
+ __HAL_TIM_ENABLE(&TimHandle3);
+}
+
+// align the timers to end the init
+void _alignPWMTimers(pwmout_t *t1, pwmout_t *t2, pwmout_t *t3, pwmout_t *t4){
+ TIM_HandleTypeDef TimHandle1, TimHandle2, TimHandle3, TimHandle4;
+ TimHandle1.Instance = (TIM_TypeDef *)(t1->pwm);
+ TimHandle2.Instance = (TIM_TypeDef *)(t2->pwm);
+ TimHandle3.Instance = (TIM_TypeDef *)(t3->pwm);
+ TimHandle4.Instance = (TIM_TypeDef *)(t4->pwm);
+ __HAL_TIM_DISABLE(&TimHandle1);
+ __HAL_TIM_DISABLE(&TimHandle2);
+ __HAL_TIM_DISABLE(&TimHandle3);
+ __HAL_TIM_DISABLE(&TimHandle4);
+ __HAL_TIM_ENABLE(&TimHandle1);
+ __HAL_TIM_ENABLE(&TimHandle2);
+ __HAL_TIM_ENABLE(&TimHandle3);
+ __HAL_TIM_ENABLE(&TimHandle4);
+}
+
+// // configure hardware 6pwm interface only one timer with inverted channels
+// HardwareTimer* _initHardware6PWMInterface(uint32_t PWM_freq, float dead_zone, int pinA_h, int pinA_l, int pinB_h, int pinB_l, int pinC_h, int pinC_l)
+// {
+// PinName uhPinName = digitalPinToPinName(pinA_h);
+// PinName ulPinName = digitalPinToPinName(pinA_l);
+// PinName vhPinName = digitalPinToPinName(pinB_h);
+// PinName vlPinName = digitalPinToPinName(pinB_l);
+// PinName whPinName = digitalPinToPinName(pinC_h);
+// PinName wlPinName = digitalPinToPinName(pinC_l);
+
+// TIM_TypeDef *Instance = (TIM_TypeDef *)pinmap_peripheral(uhPinName, PinMap_PWM);
+
+// uint32_t index = get_timer_index(Instance);
+
+// if (HardwareTimer_Handle[index] == NULL) {
+// HardwareTimer_Handle[index]->__this = new HardwareTimer((TIM_TypeDef *)pinmap_peripheral(uhPinName, PinMap_PWM));
+// HardwareTimer_Handle[index]->handle.Init.CounterMode = TIM_COUNTERMODE_CENTERALIGNED3;
+// HAL_TIM_Base_Init(&(HardwareTimer_Handle[index]->handle));
+// ((HardwareTimer *)HardwareTimer_Handle[index]->__this)->setOverflow(PWM_freq, HERTZ_FORMAT);
+// }
+// HardwareTimer *HT = (HardwareTimer *)(HardwareTimer_Handle[index]->__this);
+
+// HT->setMode(STM_PIN_CHANNEL(pinmap_function(uhPinName, PinMap_PWM)), TIMER_OUTPUT_COMPARE_PWM1, uhPinName);
+// HT->setMode(STM_PIN_CHANNEL(pinmap_function(ulPinName, PinMap_PWM)), TIMER_OUTPUT_COMPARE_PWM1, ulPinName);
+// HT->setMode(STM_PIN_CHANNEL(pinmap_function(vhPinName, PinMap_PWM)), TIMER_OUTPUT_COMPARE_PWM1, vhPinName);
+// HT->setMode(STM_PIN_CHANNEL(pinmap_function(vlPinName, PinMap_PWM)), TIMER_OUTPUT_COMPARE_PWM1, vlPinName);
+// HT->setMode(STM_PIN_CHANNEL(pinmap_function(whPinName, PinMap_PWM)), TIMER_OUTPUT_COMPARE_PWM1, whPinName);
+// HT->setMode(STM_PIN_CHANNEL(pinmap_function(wlPinName, PinMap_PWM)), TIMER_OUTPUT_COMPARE_PWM1, wlPinName);
+
+// // dead time is set in nanoseconds
+// uint32_t dead_time_ns = (float)(1e9f/PWM_freq)*dead_zone;
+// uint32_t dead_time = __LL_TIM_CALC_DEADTIME(SystemCoreClock, LL_TIM_GetClockDivision(HT->getHandle()->Instance), dead_time_ns);
+// LL_TIM_OC_SetDeadTime(HT->getHandle()->Instance, dead_time); // deadtime is non linear!
+// LL_TIM_CC_EnableChannel(HT->getHandle()->Instance, LL_TIM_CHANNEL_CH1 | LL_TIM_CHANNEL_CH1N | LL_TIM_CHANNEL_CH2 | LL_TIM_CHANNEL_CH2N | LL_TIM_CHANNEL_CH3 | LL_TIM_CHANNEL_CH3N);
+
+// HT->pause();
+// HT->refresh();
+// HT->resume();
+// return HT;
+// }
+
+
+// // returns 0 if each pair of pwm channels has same channel
+// // returns 1 all the channels belong to the same timer - hardware inverted channels
+// // returns -1 if neither - avoid configuring - error!!!
+// int _interfaceType(const int pinA_h, const int pinA_l, const int pinB_h, const int pinB_l, const int pinC_h, const int pinC_l){
+// PinName nameAH = digitalPinToPinName(pinA_h);
+// PinName nameAL = digitalPinToPinName(pinA_l);
+// PinName nameBH = digitalPinToPinName(pinB_h);
+// PinName nameBL = digitalPinToPinName(pinB_l);
+// PinName nameCH = digitalPinToPinName(pinC_h);
+// PinName nameCL = digitalPinToPinName(pinC_l);
+// int tim1 = get_timer_index((TIM_TypeDef *)pinmap_peripheral(nameAH, PinMap_PWM));
+// int tim2 = get_timer_index((TIM_TypeDef *)pinmap_peripheral(nameAL, PinMap_PWM));
+// int tim3 = get_timer_index((TIM_TypeDef *)pinmap_peripheral(nameBH, PinMap_PWM));
+// int tim4 = get_timer_index((TIM_TypeDef *)pinmap_peripheral(nameBL, PinMap_PWM));
+// int tim5 = get_timer_index((TIM_TypeDef *)pinmap_peripheral(nameCH, PinMap_PWM));
+// int tim6 = get_timer_index((TIM_TypeDef *)pinmap_peripheral(nameCL, PinMap_PWM));
+// if(tim1 == tim2 && tim2==tim3 && tim3==tim4 && tim4==tim5 && tim5==tim6)
+// return _HARDWARE_6PWM; // hardware 6pwm interface - only on timer
+// else if(tim1 == tim2 && tim3==tim4 && tim5==tim6)
+// return _SOFTWARE_6PWM; // software 6pwm interface - each pair of high-low side same timer
+// else
+// return _ERROR_6PWM; // might be error avoid configuration
+// }
+
+
+
+// function setting the high pwm frequency to the supplied pins
+// - Stepper motor - 2PWM setting
+// - hardware speciffic
+void* _configure2PWM(long pwm_frequency,const int pinA, const int pinB) {
+ if( !pwm_frequency || !_isset(pwm_frequency) ) pwm_frequency = _PWM_FREQUENCY; // default frequency 25khz
+ else pwm_frequency = _constrain(pwm_frequency, 0, _PWM_FREQUENCY_MAX); // constrain to 50kHz max
+
+ PortentaDriverParams* params = new PortentaDriverParams();
+ params->pwm_frequency = pwm_frequency;
+
+ core_util_critical_section_enter();
+ _pwm_init(&(params->pins[0]), pinA, (long)pwm_frequency);
+ _pwm_init(&(params->pins[1]), pinB, (long)pwm_frequency);
+ // allign the timers
+ _alignPWMTimers(&(params->pins[0]), &(params->pins[1]));
+ core_util_critical_section_exit();
+ return params;
+}
+
+
+// function setting the high pwm frequency to the supplied pins
+// - BLDC motor - 3PWM setting
+// - hardware speciffic
+void* _configure3PWM(long pwm_frequency,const int pinA, const int pinB, const int pinC) {
+ if( !pwm_frequency || !_isset(pwm_frequency) ) pwm_frequency = _PWM_FREQUENCY; // default frequency 25khz
+ else pwm_frequency = _constrain(pwm_frequency, 0, _PWM_FREQUENCY_MAX); // constrain to 50kHz max
+
+ PortentaDriverParams* params = new PortentaDriverParams();
+ params->pwm_frequency = pwm_frequency;
+
+ core_util_critical_section_enter();
+ _pwm_init(&(params->pins[0]), pinA, (long)pwm_frequency);
+ _pwm_init(&(params->pins[1]), pinB, (long)pwm_frequency);
+ _pwm_init(&(params->pins[2]), pinC, (long)pwm_frequency);
+ // allign the timers
+ _alignPWMTimers(&(params->pins[0]), &(params->pins[1]), &(params->pins[2]));
+ core_util_critical_section_exit();
+
+ return params;
+}
+
+
+
+// function setting the high pwm frequency to the supplied pins
+// - Stepper motor - 4PWM setting
+// - hardware speciffic
+void* _configure4PWM(long pwm_frequency,const int pinA, const int pinB, const int pinC, const int pinD) {
+ if( !pwm_frequency || !_isset(pwm_frequency) ) pwm_frequency = _PWM_FREQUENCY; // default frequency 25khz
+ else pwm_frequency = _constrain(pwm_frequency, 0, _PWM_FREQUENCY_MAX); // constrain to 50kHz max
+
+ PortentaDriverParams* params = new PortentaDriverParams();
+ params->pwm_frequency = pwm_frequency;
+
+ core_util_critical_section_enter();
+ _pwm_init(&(params->pins[0]), pinA, (long)pwm_frequency);
+ _pwm_init(&(params->pins[1]), pinB, (long)pwm_frequency);
+ _pwm_init(&(params->pins[2]), pinC, (long)pwm_frequency);
+ _pwm_init(&(params->pins[3]), pinD, (long)pwm_frequency);
+ // allign the timers
+ _alignPWMTimers(&(params->pins[0]), &(params->pins[1]), &(params->pins[2]), &(params->pins[3]));
+ core_util_critical_section_exit();
+
+ return params;
+}
+
+
+
+// function setting the pwm duty cycle to the hardware
+// - Stepper motor - 2PWM setting
+//- hardware speciffic
+void _writeDutyCycle2PWM(float dc_a, float dc_b, void* params){
+ core_util_critical_section_enter();
+ _pwm_write(&(((PortentaDriverParams*)params)->pins[0]), (float)dc_a);
+ _pwm_write(&(((PortentaDriverParams*)params)->pins[1]), (float)dc_b);
+ core_util_critical_section_exit();
+}
+
+// function setting the pwm duty cycle to the hardware
+// - BLDC motor - 3PWM setting
+//- hardware speciffic
+void _writeDutyCycle3PWM(float dc_a, float dc_b, float dc_c, void* params){
+ core_util_critical_section_enter();
+ _pwm_write(&(((PortentaDriverParams*)params)->pins[0]), (float)dc_a);
+ _pwm_write(&(((PortentaDriverParams*)params)->pins[1]), (float)dc_b);
+ _pwm_write(&(((PortentaDriverParams*)params)->pins[2]), (float)dc_c);
+ core_util_critical_section_exit();
+}
+
+
+// function setting the pwm duty cycle to the hardware
+// - Stepper motor - 4PWM setting
+//- hardware speciffic
+void _writeDutyCycle4PWM(float dc_1a, float dc_1b, float dc_2a, float dc_2b, void* params){
+ core_util_critical_section_enter();
+ _pwm_write(&(((PortentaDriverParams*)params)->pins[0]), (float)dc_1a);
+ _pwm_write(&(((PortentaDriverParams*)params)->pins[1]), (float)dc_1b);
+ _pwm_write(&(((PortentaDriverParams*)params)->pins[2]), (float)dc_2a);
+ _pwm_write(&(((PortentaDriverParams*)params)->pins[3]), (float)dc_2b);
+ core_util_critical_section_exit();
+}
+
+
+// 6-PWM currently not supported, defer to generic, which also doesn't support it ;-)
+
+// Configuring PWM frequency, resolution and alignment
+// - BLDC driver - 6PWM setting
+// - hardware specific
+//void* _configure6PWM(long pwm_frequency, float dead_zone, const int pinA_h, const int pinA_l, const int pinB_h, const int pinB_l, const int pinC_h, const int pinC_l){
+ // if( !pwm_frequency || !_isset(pwm_frequency) ) pwm_frequency = _PWM_FREQUENCY; // default frequency 25khz
+ // else pwm_frequency = _constrain(pwm_frequency, 0, _PWM_FREQUENCY_MAX); // constrain to |%0kHz max
+ // // center-aligned frequency is uses two periods
+ // pwm_frequency *=2;
+
+ // // find configuration
+ // int config = _interfaceType(pinA_h, pinA_l, pinB_h, pinB_l, pinC_h, pinC_l);
+ // // configure accordingly
+ // switch(config){
+ // case _ERROR_6PWM:
+ // return -1; // fail
+ // break;
+ // case _HARDWARE_6PWM:
+ // _initHardware6PWMInterface(pwm_frequency, dead_zone, pinA_h, pinA_l, pinB_h, pinB_l, pinC_h, pinC_l);
+ // break;
+ // case _SOFTWARE_6PWM:
+ // HardwareTimer* HT1 = _initPinPWMHigh(pwm_frequency, pinA_h);
+ // _initPinPWMLow(pwm_frequency, pinA_l);
+ // HardwareTimer* HT2 = _initPinPWMHigh(pwm_frequency,pinB_h);
+ // _initPinPWMLow(pwm_frequency, pinB_l);
+ // HardwareTimer* HT3 = _initPinPWMHigh(pwm_frequency,pinC_h);
+ // _initPinPWMLow(pwm_frequency, pinC_l);
+ // _alignPWMTimers(HT1, HT2, HT3);
+ // break;
+ // }
+// return -1; // success
+// }
+
+// Function setting the duty cycle to the pwm pin (ex. analogWrite())
+// - BLDC driver - 6PWM setting
+// - hardware specific
+//void _writeDutyCycle6PWM(float dc_a, float dc_b, float dc_c, void* params){
+ // // find configuration
+ // int config = _interfaceType(pinA_h, pinA_l, pinB_h, pinB_l, pinC_h, pinC_l);
+ // // set pwm accordingly
+ // switch(config){
+ // case _HARDWARE_6PWM:
+ // _setPwm(pinA_h, _PWM_RANGE*dc_a, _PWM_RESOLUTION);
+ // _setPwm(pinB_h, _PWM_RANGE*dc_b, _PWM_RESOLUTION);
+ // _setPwm(pinC_h, _PWM_RANGE*dc_c, _PWM_RESOLUTION);
+ // break;
+ // case _SOFTWARE_6PWM:
+ // _setPwm(pinA_l, _constrain(dc_a + dead_zone/2, 0, 1)*_PWM_RANGE, _PWM_RESOLUTION);
+ // _setPwm(pinA_h, _constrain(dc_a - dead_zone/2, 0, 1)*_PWM_RANGE, _PWM_RESOLUTION);
+ // _setPwm(pinB_l, _constrain(dc_b + dead_zone/2, 0, 1)*_PWM_RANGE, _PWM_RESOLUTION);
+ // _setPwm(pinB_h, _constrain(dc_b - dead_zone/2, 0, 1)*_PWM_RANGE, _PWM_RESOLUTION);
+ // _setPwm(pinC_l, _constrain(dc_c + dead_zone/2, 0, 1)*_PWM_RANGE, _PWM_RESOLUTION);
+ // _setPwm(pinC_h, _constrain(dc_c - dead_zone/2, 0, 1)*_PWM_RANGE, _PWM_RESOLUTION);
+ // break;
+ // }
+//}
+#endif
\ No newline at end of file
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/drivers/hardware_specific/renesas/renesas.cpp b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/drivers/hardware_specific/renesas/renesas.cpp
new file mode 100644
index 0000000..2c9c9b2
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/drivers/hardware_specific/renesas/renesas.cpp
@@ -0,0 +1,604 @@
+
+#include "./renesas.h"
+
+#if defined(ARDUINO_UNOR4_WIFI) || defined(ARDUINO_UNOR4_MINIMA)
+
+
+#pragma message("")
+#pragma message("SimpleFOC: compiling for Arduino/Renesas (UNO R4)")
+#pragma message("")
+
+
+
+#include "communication/SimpleFOCDebug.h"
+#include "FspTimer.h"
+
+#define GPT_OPEN (0x00475054ULL)
+
+/*
+ We use the GPT timers, there are 2 channels (32 bit) + 6 channels (16 bit)
+ Each channel has 2 outputs (GTIOCAx and GTIOCBx) which can be complimentary.
+
+ So each timer channel can handle one half-bridge, using either a single (3-PWM) or
+ two complimentary PWM signals (6-PWM).
+
+ For 1-PWM through 4-PWM, we need as many channels as PWM signals, and we can use
+ either output A or B of the timer (we can set the polarity) - but not both.
+
+ For 6-PWM we need 3 channels, and use both outputs A and B of each channel, then
+ we can do hardware dead-time.
+ Or we can use seperate channels for high and low side, with software dead-time.
+ Each phase can be either hardware (1 channel) or software (2 channels) dead-time
+ individually, they don't all have to be one or the other.
+
+ Selected channels can be started together, so we can keep the phases in sync for
+ low-side current sensing and software 6-PWM.
+
+ The event system should permit low side current sensing without needing interrupts,
+ but this will be handled by the current sense driver.
+
+ Supported:
+ - arbitrary PWM frequencies between 1Hz (minimum we can set with our integer based API)
+ and around 48kHz (more would be possible but the range will be low)
+ - PWM range at 24kHz (default) is 1000
+ - PWM range at 48kHz is 500
+ - polarity setting is supported, in all modes
+ - phase state setting is supported, in 3-PWM, 6-PWM hardware dead-time and 6-PWM software dead-time
+
+ TODOs:
+ - change setDutyCycle to use register access for speed
+ - add event system support for low-side current sensing
+ - perhaps add support to reserve timers used also in
+ Arduino Pwm.h code, for compatibility with analogWrite()
+ - check if there is a better way for phase-state setting
+ */
+
+
+// track which channels are used
+bool channel_used[GPT_HOWMANY] = { false };
+
+
+struct RenesasTimerConfig {
+ timer_cfg_t timer_cfg;
+ gpt_instance_ctrl_t ctrl;
+ gpt_extended_cfg_t ext_cfg;
+ gpt_extended_pwm_cfg_t pwm_cfg;
+ gpt_io_pin_t duty_pin;
+};
+
+struct ClockDivAndRange {
+ timer_source_div_t clk_div;
+ uint32_t range;
+};
+
+ClockDivAndRange getClockDivAndRange(uint32_t pwm_frequency, uint8_t timer_channel) {
+ ClockDivAndRange result;
+ uint32_t max_count = (timer_channel < GTP32_HOWMANY)? 4294967295 : 65535;
+ uint32_t freq_hz = R_FSP_SystemClockHzGet(FSP_PRIV_CLOCK_PCLKD);
+ float range = (float) freq_hz / ((float) pwm_frequency * 2.0f);
+ if(range / 1.0 < max_count) {
+ result.range = (uint32_t) (range / 1.0);
+ result.clk_div = TIMER_SOURCE_DIV_1;
+ }
+ else if (range / 2.0 < max_count) {
+ result.range = (uint32_t) (range / 2.0);
+ result.clk_div = TIMER_SOURCE_DIV_2;
+ }
+ else if(range / 4.0 < max_count) {
+ result.range = (uint32_t) (range / 4.0);
+ result.clk_div = TIMER_SOURCE_DIV_4;
+ }
+ else if(range / 8.0 < max_count) {
+ result.range = (uint32_t) (range / 8.0 );
+ result.clk_div = TIMER_SOURCE_DIV_8;
+ }
+ else if(range / 16.0 < max_count) {
+ result.range = (uint32_t) (range / 16.0 );
+ result.clk_div = TIMER_SOURCE_DIV_16;
+ }
+ else if (range / 32.0 < max_count) {
+ result.range = (uint32_t) (range / 32.0 );
+ result.clk_div = TIMER_SOURCE_DIV_32;
+ }
+ else if(range / 64.0 < max_count) {
+ result.range = (uint32_t) (range / 64.0 );
+ result.clk_div = TIMER_SOURCE_DIV_64;
+ }
+ else if(range / 128.0 < max_count) {
+ result.range = (uint32_t) (range / 128.0 );
+ result.clk_div = TIMER_SOURCE_DIV_128;
+ }
+ else if(range / 256.0 < max_count) {
+ result.range = (uint32_t) (range / 256.0 );
+ result.clk_div = TIMER_SOURCE_DIV_256;
+ }
+ else if(range / 512.0 < max_count) {
+ result.range = (uint32_t) (range / 512.0 );
+ result.clk_div = TIMER_SOURCE_DIV_512;
+ }
+ else if(range / 1024.0 < max_count) {
+ result.range = (uint32_t) (range / 1024.0 );
+ result.clk_div = TIMER_SOURCE_DIV_1024;
+ }
+ else {
+ SimpleFOCDebug::println("DRV: PWM frequency too low");
+ }
+ return result;
+};
+
+
+bool configureTimerPin(RenesasHardwareDriverParams* params, uint8_t index, bool active_high, bool complementary = false, bool complementary_active_high = true) {
+ uint8_t pin = params->pins[index];
+ uint8_t pin_C;
+ std::array pinCfgs = getPinCfgs(pin, PIN_CFG_REQ_PWM);
+ std::array pinCfgs_C;
+ if(pinCfgs[0] == 0) {
+ SIMPLEFOC_DEBUG("DRV: no PWM on pin ", pin);
+ return false;
+ }
+ if (IS_PIN_AGT_PWM(pinCfgs[0])) {
+ SIMPLEFOC_DEBUG("DRV: AGT timer not supported");
+ return false;
+ }
+ // get the timer channel
+ uint8_t timer_channel = GET_CHANNEL(pinCfgs[0]);
+ // check its not used
+ if (channel_used[timer_channel]) {
+ SIMPLEFOC_DEBUG("DRV: channel in use: ", timer_channel);
+ return false;
+ }
+
+ if (complementary) {
+ pin_C = params->pins[index+1];
+ pinCfgs_C = getPinCfgs(pin_C, PIN_CFG_REQ_PWM);
+ if(pinCfgs_C[0] == 0) {
+ SIMPLEFOC_DEBUG("DRV: no PWM on pin ", pin_C);
+ return false;
+ }
+ if (IS_PIN_AGT_PWM(pinCfgs_C[0]) || GET_CHANNEL(pinCfgs_C[0])!=timer_channel) {
+ SIMPLEFOC_DEBUG("DRV: comp. channel different");
+ return false;
+ }
+ }
+ TimerPWMChannel_t pwm_output = IS_PWM_ON_A(pinCfgs[0]) ? CHANNEL_A : CHANNEL_B;
+ if (complementary) {
+ TimerPWMChannel_t pwm_output_C = IS_PWM_ON_A(pinCfgs_C[0]) ? CHANNEL_A : CHANNEL_B;
+ if (pwm_output_C != CHANNEL_A || pwm_output != CHANNEL_B) {
+ SIMPLEFOC_DEBUG("DRV: output A/B mismatch");
+ return false;
+ }
+ }
+
+ // configure GPIO pin
+ fsp_err_t err = R_IOPORT_PinCfg(&g_ioport_ctrl, g_pin_cfg[pin].pin, (uint32_t) (IOPORT_CFG_PERIPHERAL_PIN | IOPORT_PERIPHERAL_GPT1));
+ if ((err == FSP_SUCCESS) && complementary)
+ err = R_IOPORT_PinCfg(&g_ioport_ctrl, g_pin_cfg[pin_C].pin, (uint32_t) (IOPORT_CFG_PERIPHERAL_PIN | IOPORT_PERIPHERAL_GPT1));
+ if (err != FSP_SUCCESS) {
+ SIMPLEFOC_DEBUG("DRV: pin config failed");
+ return false;
+ }
+
+
+ // configure timer channel - frequency / top value
+ ClockDivAndRange timings = getClockDivAndRange(params->pwm_frequency, timer_channel);
+ #if defined(SIMPLEFOC_RENESAS_DEBUG)
+ SimpleFOCDebug::println("---PWM Config---");
+ SimpleFOCDebug::println("DRV: pwm pin: ", pin);
+ if (complementary)
+ SimpleFOCDebug::println("DRV: compl. pin: ", pin_C);
+ SimpleFOCDebug::println("DRV: pwm channel: ", timer_channel);
+ SimpleFOCDebug::print("DRV: pwm A/B: "); SimpleFOCDebug::println(complementary?"A+B":((pwm_output==CHANNEL_A)?"A":"B"));
+ SimpleFOCDebug::println("DRV: pwm freq: ", (int)params->pwm_frequency);
+ SimpleFOCDebug::println("DRV: pwm range: ", (int)timings.range);
+ SimpleFOCDebug::println("DRV: pwm clkdiv: ", timings.clk_div);
+ #endif
+
+ RenesasTimerConfig* t = new RenesasTimerConfig();
+ // configure timer channel - count mode
+ t->timer_cfg.channel = timer_channel;
+ t->timer_cfg.mode = TIMER_MODE_TRIANGLE_WAVE_SYMMETRIC_PWM;
+ t->timer_cfg.source_div = timings.clk_div;
+ t->timer_cfg.period_counts = timings.range;
+ t->timer_cfg.duty_cycle_counts = 0;
+ t->timer_cfg.p_callback = nullptr;
+ t->timer_cfg.p_context = nullptr;
+ t->timer_cfg.p_extend = &(t->ext_cfg);
+ t->timer_cfg.cycle_end_ipl = BSP_IRQ_DISABLED;
+ t->timer_cfg.cycle_end_irq = FSP_INVALID_VECTOR;
+
+ t->ext_cfg.p_pwm_cfg = &(t->pwm_cfg);
+ t->ext_cfg.capture_a_ipl = BSP_IRQ_DISABLED;
+ t->ext_cfg.capture_a_irq = FSP_INVALID_VECTOR;
+ t->ext_cfg.capture_b_ipl = BSP_IRQ_DISABLED;
+ t->ext_cfg.capture_b_irq = FSP_INVALID_VECTOR;
+ t->pwm_cfg.trough_ipl = BSP_IRQ_DISABLED;
+ t->pwm_cfg.trough_irq = FSP_INVALID_VECTOR;
+ t->pwm_cfg.poeg_link = GPT_POEG_LINK_POEG0;
+ t->pwm_cfg.output_disable = GPT_OUTPUT_DISABLE_NONE;
+ t->pwm_cfg.adc_trigger = GPT_ADC_TRIGGER_NONE;
+ t->pwm_cfg.dead_time_count_up = 0;
+ t->pwm_cfg.dead_time_count_down = 0;
+ t->pwm_cfg.adc_a_compare_match = 0;
+ t->pwm_cfg.adc_b_compare_match = 0;
+ t->pwm_cfg.interrupt_skip_source = GPT_INTERRUPT_SKIP_SOURCE_NONE;
+ t->pwm_cfg.interrupt_skip_count = GPT_INTERRUPT_SKIP_COUNT_0;
+ t->pwm_cfg.interrupt_skip_adc = GPT_INTERRUPT_SKIP_ADC_NONE;
+ t->pwm_cfg.gtioca_disable_setting = GPT_GTIOC_DISABLE_PROHIBITED;
+ t->pwm_cfg.gtiocb_disable_setting = GPT_GTIOC_DISABLE_PROHIBITED;
+ // configure dead-time if both outputs are used
+ if (complementary) {
+ uint32_t dt = params->dead_zone * timings.range;
+ t->pwm_cfg.dead_time_count_up = dt;
+ t->pwm_cfg.dead_time_count_down = dt;
+ }
+
+ // configure timer channel - outputs and polarity
+ t->ext_cfg.gtior_setting.gtior = 0L;
+ if (!complementary) {
+ if(pwm_output == CHANNEL_A) {
+ t->duty_pin = GPT_IO_PIN_GTIOCA;
+ t->ext_cfg.gtioca.output_enabled = true;
+ t->ext_cfg.gtiocb.output_enabled = false;
+ t->ext_cfg.gtior_setting.gtior_b.gtioa = 0x03 | (active_high ? 0x00 : 0x10);
+ t->ext_cfg.gtior_setting.gtior_b.oadflt = active_high ? 0x00 : 0x01;
+ // t->ext_cfg.gtior_setting.gtior_b.oahld = 0x0;
+ // t->ext_cfg.gtior_setting.gtior_b.oadf = 0x0;
+ // t->ext_cfg.gtior_setting.gtior_b.nfaen = 0x0;
+ }
+ else {
+ t->duty_pin = GPT_IO_PIN_GTIOCB;
+ t->ext_cfg.gtiocb.output_enabled = true;
+ t->ext_cfg.gtioca.output_enabled = false;
+ t->ext_cfg.gtior_setting.gtior_b.gtiob = 0x03 | (active_high ? 0x00 : 0x10);
+ t->ext_cfg.gtior_setting.gtior_b.obdflt = active_high ? 0x00 : 0x01;
+ }
+ }
+ else {
+ t->duty_pin = GPT_IO_PIN_GTIOCA_AND_GTIOCB;
+ t->ext_cfg.gtioca.output_enabled = true;
+ t->ext_cfg.gtiocb.output_enabled = true;
+ t->ext_cfg.gtior_setting.gtior_b.gtioa = 0x03 | (!complementary_active_high ? 0x00 : 0x10);
+ t->ext_cfg.gtior_setting.gtior_b.oadflt = !complementary_active_high ? 0x00 : 0x01;
+ t->ext_cfg.gtior_setting.gtior_b.gtiob = 0x03 | (active_high ? 0x00 : 0x10);
+ t->ext_cfg.gtior_setting.gtior_b.obdflt = active_high ? 0x00 : 0x01;
+ }
+ memset(&(t->ctrl), 0, sizeof(gpt_instance_ctrl_t));
+ err = R_GPT_Open(&(t->ctrl),&(t->timer_cfg));
+ if ((err != FSP_ERR_ALREADY_OPEN) && (err != FSP_SUCCESS)) {
+ SIMPLEFOC_DEBUG("DRV: open failed");
+ return false;
+ }
+ if (err == FSP_ERR_ALREADY_OPEN) {
+ SimpleFOCDebug::println("DRV: timer already open");
+ return false;
+ }
+
+ err = R_GPT_PeriodSet(&(t->ctrl), t->timer_cfg.period_counts);
+ if (err != FSP_SUCCESS) {
+ SIMPLEFOC_DEBUG("DRV: period set failed");
+ return false;
+ }
+ err = R_GPT_OutputEnable(&(t->ctrl), t->duty_pin);
+ if (err != FSP_SUCCESS) {
+ SIMPLEFOC_DEBUG("DRV: pin enable failed");
+ return false;
+ }
+
+ channel_used[timer_channel] = true;
+ params->timer_config[index] = t;
+ params->channels[index] = timer_channel;
+ if (complementary) {
+ params->timer_config[index+1] = t;
+ params->channels[index+1] = timer_channel;
+ }
+
+ return true;
+}
+
+
+// start the timer channels for the motor, synchronously
+bool startTimerChannels(RenesasHardwareDriverParams* params, int num_channels) {
+ uint32_t mask = 0;
+ for (int i = 0; i < num_channels; i++) {
+ // RenesasTimerConfig* t = params->timer_config[i];
+ // if (R_GPT_Start(&(t->ctrl)) != FSP_SUCCESS) {
+ // SIMPLEFOC_DEBUG("DRV: timer start failed");
+ // return false;
+ // }
+ mask |= (1 << params->channels[i]);
+#if defined(SIMPLEFOC_RENESAS_DEBUG)
+ SimpleFOCDebug::println("DRV: starting timer: ", params->channels[i]);
+#endif
+ }
+ params->timer_config[0]->ctrl.p_reg->GTSTR |= mask;
+ #if defined(SIMPLEFOC_RENESAS_DEBUG)
+ SimpleFOCDebug::println("DRV: timers started");
+ #endif
+ return true;
+}
+
+
+// check if the given pins are on the same timer channel
+bool isHardware6Pwm(const int pin1, const int pin2) {
+ std::array pinCfgs1 = getPinCfgs(pin1, PIN_CFG_REQ_PWM);
+ std::array pinCfgs2 = getPinCfgs(pin2, PIN_CFG_REQ_PWM);
+ if(pinCfgs1[0] == 0 || pinCfgs2[0] == 0)
+ return false;
+ if (IS_PIN_AGT_PWM(pinCfgs1[0]) || IS_PIN_AGT_PWM(pinCfgs2[0]))
+ return false;
+ uint8_t timer_channel1 = GET_CHANNEL(pinCfgs1[0]);
+ uint8_t timer_channel2 = GET_CHANNEL(pinCfgs2[0]);
+ return timer_channel1==timer_channel2;
+}
+
+
+
+void* _configure1PWM(long pwm_frequency, const int pinA) {
+ RenesasHardwareDriverParams* params = new RenesasHardwareDriverParams;
+ params->pins[0] = pinA;
+ params->pwm_frequency = (pwm_frequency==NOT_SET)?RENESAS_DEFAULT_PWM_FREQUENCY:pwm_frequency;
+ bool success = true;
+ success = configureTimerPin(params, 0, SIMPLEFOC_PWM_ACTIVE_HIGH);
+ if (success)
+ success = startTimerChannels(params, 1);
+ if (!success)
+ return SIMPLEFOC_DRIVER_INIT_FAILED;
+ return params;
+}
+
+
+void* _configure2PWM(long pwm_frequency,const int pinA, const int pinB) {
+ RenesasHardwareDriverParams* params = new RenesasHardwareDriverParams;
+ params->pins[0] = pinA; params->pins[1] = pinB;
+ params->pwm_frequency = (pwm_frequency==NOT_SET)?RENESAS_DEFAULT_PWM_FREQUENCY:pwm_frequency;
+ bool success = true;
+ success = configureTimerPin(params, 0, SIMPLEFOC_PWM_ACTIVE_HIGH);
+ success &= configureTimerPin(params, 1, SIMPLEFOC_PWM_ACTIVE_HIGH);
+ if (!success)
+ success &= startTimerChannels(params, 2);
+ if (!success)
+ return SIMPLEFOC_DRIVER_INIT_FAILED;
+ return params;
+}
+
+
+void* _configure3PWM(long pwm_frequency,const int pinA, const int pinB, const int pinC) {
+ RenesasHardwareDriverParams* params = new RenesasHardwareDriverParams;
+ params->pins[0] = pinA; params->pins[1] = pinB; params->pins[2] = pinC;
+ params->pwm_frequency = (pwm_frequency==NOT_SET)?RENESAS_DEFAULT_PWM_FREQUENCY:pwm_frequency;
+ bool success = true;
+ success = configureTimerPin(params, 0, SIMPLEFOC_PWM_ACTIVE_HIGH);
+ success &= configureTimerPin(params, 1, SIMPLEFOC_PWM_ACTIVE_HIGH);
+ success &= configureTimerPin(params, 2, SIMPLEFOC_PWM_ACTIVE_HIGH);
+ if (success)
+ success = startTimerChannels(params, 3);
+ if (!success)
+ return SIMPLEFOC_DRIVER_INIT_FAILED;
+ return params;
+}
+
+
+void* _configure4PWM(long pwm_frequency, const int pin1A, const int pin1B, const int pin2A, const int pin2B) {
+ RenesasHardwareDriverParams* params = new RenesasHardwareDriverParams;
+ params->pins[0] = pin1A; params->pins[1] = pin1B; params->pins[2] = pin2A; params->pins[3] = pin2B;
+ params->pwm_frequency = (pwm_frequency==NOT_SET)?RENESAS_DEFAULT_PWM_FREQUENCY:pwm_frequency;
+ bool success = true;
+ success = configureTimerPin(params, 0, SIMPLEFOC_PWM_ACTIVE_HIGH);
+ success &= configureTimerPin(params, 1, SIMPLEFOC_PWM_ACTIVE_HIGH);
+ success &= configureTimerPin(params, 2, SIMPLEFOC_PWM_ACTIVE_HIGH);
+ success &= configureTimerPin(params, 3, SIMPLEFOC_PWM_ACTIVE_HIGH);
+ if (success)
+ success = startTimerChannels(params, 4);
+ if (!success)
+ return SIMPLEFOC_DRIVER_INIT_FAILED;
+ return params;
+}
+
+
+void* _configure6PWM(long pwm_frequency, float dead_zone, const int pinA_h, const int pinA_l, const int pinB_h, const int pinB_l, const int pinC_h, const int pinC_l){
+ RenesasHardwareDriverParams* params = new RenesasHardwareDriverParams;
+ params->pins[0] = pinA_h; params->pins[1] = pinA_l; params->pins[2] = pinB_h; params->pins[3] = pinB_l; params->pins[4] = pinC_h; params->pins[5] = pinC_l;
+ params->pwm_frequency = (pwm_frequency==NOT_SET)?RENESAS_DEFAULT_PWM_FREQUENCY:pwm_frequency;
+ params->dead_zone = (dead_zone==NOT_SET)?RENESAS_DEFAULT_DEAD_ZONE:dead_zone;
+
+ bool success = true;
+ if (isHardware6Pwm(pinA_h, pinA_l))
+ success &= configureTimerPin(params, 0, SIMPLEFOC_PWM_HIGHSIDE_ACTIVE_HIGH, true, SIMPLEFOC_PWM_LOWSIDE_ACTIVE_HIGH);
+ else {
+ success &= configureTimerPin(params, 0, SIMPLEFOC_PWM_HIGHSIDE_ACTIVE_HIGH);
+ success &= configureTimerPin(params, 1, !SIMPLEFOC_PWM_LOWSIDE_ACTIVE_HIGH); // reverse polarity on low side gives desired active high/low behaviour
+ }
+
+ if (isHardware6Pwm(pinB_h, pinB_l))
+ success &= configureTimerPin(params, 2, SIMPLEFOC_PWM_HIGHSIDE_ACTIVE_HIGH, true, SIMPLEFOC_PWM_LOWSIDE_ACTIVE_HIGH);
+ else {
+ success &= configureTimerPin(params, 2, SIMPLEFOC_PWM_HIGHSIDE_ACTIVE_HIGH);
+ success &= configureTimerPin(params, 3, !SIMPLEFOC_PWM_LOWSIDE_ACTIVE_HIGH);
+ }
+
+ if (isHardware6Pwm(pinC_h, pinC_l))
+ success &= configureTimerPin(params, 4, SIMPLEFOC_PWM_HIGHSIDE_ACTIVE_HIGH, true, SIMPLEFOC_PWM_LOWSIDE_ACTIVE_HIGH);
+ else {
+ success &= configureTimerPin(params, 4, SIMPLEFOC_PWM_HIGHSIDE_ACTIVE_HIGH);
+ success &= configureTimerPin(params, 5, !SIMPLEFOC_PWM_LOWSIDE_ACTIVE_HIGH);
+ }
+
+ if (success)
+ success = startTimerChannels(params, 6);
+ if (!success)
+ return SIMPLEFOC_DRIVER_INIT_FAILED;
+ return params;
+}
+
+
+
+
+void _writeDutyCycle1PWM(float dc_a, void* params){
+ RenesasTimerConfig* t = ((RenesasHardwareDriverParams*)params)->timer_config[0];
+ uint32_t duty_cycle_counts = (uint32_t)(dc_a * (float)(t->timer_cfg.period_counts));
+ if (R_GPT_DutyCycleSet(&(t->ctrl), duty_cycle_counts, t->duty_pin) != FSP_SUCCESS) {
+ // error
+ }
+}
+
+
+void _writeDutyCycle2PWM(float dc_a, float dc_b, void* params){
+ RenesasTimerConfig* t = ((RenesasHardwareDriverParams*)params)->timer_config[0];
+ uint32_t duty_cycle_counts = (uint32_t)(dc_a * (float)(t->timer_cfg.period_counts));
+ if (R_GPT_DutyCycleSet(&(t->ctrl), duty_cycle_counts, t->duty_pin) != FSP_SUCCESS) {
+ // error
+ }
+ t = ((RenesasHardwareDriverParams*)params)->timer_config[1];
+ duty_cycle_counts = (uint32_t)(dc_b * (float)(t->timer_cfg.period_counts));
+ if (R_GPT_DutyCycleSet(&(t->ctrl), duty_cycle_counts, t->duty_pin) != FSP_SUCCESS) {
+ // error
+ }
+}
+
+
+void _writeDutyCycle3PWM(float dc_a, float dc_b, float dc_c, void* params){
+ RenesasTimerConfig* t = ((RenesasHardwareDriverParams*)params)->timer_config[0];
+ uint32_t duty_cycle_counts = (uint32_t)(dc_a * (float)(t->timer_cfg.period_counts));
+ if (R_GPT_DutyCycleSet(&(t->ctrl), duty_cycle_counts, t->duty_pin) != FSP_SUCCESS) {
+ // error
+ }
+ t = ((RenesasHardwareDriverParams*)params)->timer_config[1];
+ duty_cycle_counts = (uint32_t)(dc_b * (float)(t->timer_cfg.period_counts));
+ if (R_GPT_DutyCycleSet(&(t->ctrl), duty_cycle_counts, t->duty_pin) != FSP_SUCCESS) {
+ // error
+ }
+ t = ((RenesasHardwareDriverParams*)params)->timer_config[2];
+ duty_cycle_counts = (uint32_t)(dc_c * (float)(t->timer_cfg.period_counts));
+ if (R_GPT_DutyCycleSet(&(t->ctrl), duty_cycle_counts, t->duty_pin) != FSP_SUCCESS) {
+ // error
+ }
+}
+
+
+void _writeDutyCycle4PWM(float dc_1a, float dc_1b, float dc_2a, float dc_2b, void* params){
+ RenesasTimerConfig* t = ((RenesasHardwareDriverParams*)params)->timer_config[0];
+ uint32_t duty_cycle_counts = (uint32_t)(dc_1a * (float)(t->timer_cfg.period_counts));
+ if (R_GPT_DutyCycleSet(&(t->ctrl), duty_cycle_counts, t->duty_pin) != FSP_SUCCESS) {
+ // error
+ }
+ t = ((RenesasHardwareDriverParams*)params)->timer_config[1];
+ duty_cycle_counts = (uint32_t)(dc_1b * (float)(t->timer_cfg.period_counts));
+ if (R_GPT_DutyCycleSet(&(t->ctrl), duty_cycle_counts, t->duty_pin) != FSP_SUCCESS) {
+ // error
+ }
+ t = ((RenesasHardwareDriverParams*)params)->timer_config[2];
+ duty_cycle_counts = (uint32_t)(dc_2a * (float)(t->timer_cfg.period_counts));
+ if (R_GPT_DutyCycleSet(&(t->ctrl), duty_cycle_counts, t->duty_pin) != FSP_SUCCESS) {
+ // error
+ }
+ t = ((RenesasHardwareDriverParams*)params)->timer_config[3];
+ duty_cycle_counts = (uint32_t)(dc_2b * (float)(t->timer_cfg.period_counts));
+ if (R_GPT_DutyCycleSet(&(t->ctrl), duty_cycle_counts, t->duty_pin) != FSP_SUCCESS) {
+ // error
+ }
+}
+
+
+
+void _setSinglePhaseState(RenesasTimerConfig* hi, RenesasTimerConfig* lo, PhaseState state) {
+ gpt_gtior_setting_t gtior;
+ gtior.gtior = hi->ctrl.p_reg->GTIOR;
+ bool on = (state==PHASE_ON) || (state==PHASE_HI);
+
+ if (hi->duty_pin == GPT_IO_PIN_GTIOCA_AND_GTIOCB) {
+ bool ch = false;
+ if (gtior.gtior_b.obe != on) {
+ gtior.gtior_b.obe = on;
+ ch = true;
+ } // B is high side
+ on = (state==PHASE_ON) || (state==PHASE_LO);
+ if (gtior.gtior_b.oae != on) {
+ gtior.gtior_b.oae = on;
+ ch = true;
+ }
+ if (ch)
+ hi->ctrl.p_reg->GTIOR = gtior.gtior;
+ return;
+ }
+
+ if (hi->duty_pin == GPT_IO_PIN_GTIOCA) {
+ if (gtior.gtior_b.oae != on) {
+ gtior.gtior_b.oae = on;
+ hi->ctrl.p_reg->GTIOR = gtior.gtior;
+ }
+ }
+ else if (hi->duty_pin == GPT_IO_PIN_GTIOCB) {
+ if (gtior.gtior_b.obe != on) {
+ gtior.gtior_b.obe = on;
+ hi->ctrl.p_reg->GTIOR = gtior.gtior;
+ }
+ }
+
+ gtior.gtior = lo->ctrl.p_reg->GTIOR;
+ on = (state==PHASE_ON) || (state==PHASE_LO);
+ if (lo->duty_pin == GPT_IO_PIN_GTIOCA) {
+ if (gtior.gtior_b.oae != on) {
+ gtior.gtior_b.oae = on;
+ lo->ctrl.p_reg->GTIOR = gtior.gtior;
+ }
+ }
+ else if (lo->duty_pin == GPT_IO_PIN_GTIOCB) {
+ if (gtior.gtior_b.obe != on) {
+ gtior.gtior_b.obe = on;
+ lo->ctrl.p_reg->GTIOR = gtior.gtior;
+ }
+ }
+
+}
+
+
+void _writeDutyCycle6PWM(float dc_a, float dc_b, float dc_c, PhaseState *phase_state, void* params){
+ RenesasTimerConfig* t = ((RenesasHardwareDriverParams*)params)->timer_config[0];
+ RenesasTimerConfig* t1 = ((RenesasHardwareDriverParams*)params)->timer_config[1];
+ uint32_t dt = (uint32_t)(((RenesasHardwareDriverParams*)params)->dead_zone * (float)(t->timer_cfg.period_counts));
+ uint32_t duty_cycle_counts = (uint32_t)(dc_a * (float)(t->timer_cfg.period_counts));
+ bool hw_deadtime = ((RenesasHardwareDriverParams*)params)->channels[0] == ((RenesasHardwareDriverParams*)params)->channels[1];
+ uint32_t dt_act = (duty_cycle_counts>0 && !hw_deadtime)?dt:0;
+ _setSinglePhaseState(t, t1, phase_state[0]);
+ if (R_GPT_DutyCycleSet(&(t->ctrl), duty_cycle_counts - dt_act, t->duty_pin) != FSP_SUCCESS) {
+ // error
+ }
+ if (!hw_deadtime) {
+ if (R_GPT_DutyCycleSet(&(t1->ctrl), duty_cycle_counts + dt_act, t1->duty_pin) != FSP_SUCCESS) {
+ // error
+ }
+ }
+
+ t = ((RenesasHardwareDriverParams*)params)->timer_config[2];
+ t1 = ((RenesasHardwareDriverParams*)params)->timer_config[3];
+ duty_cycle_counts = (uint32_t)(dc_b * (float)(t->timer_cfg.period_counts));
+ hw_deadtime = ((RenesasHardwareDriverParams*)params)->channels[2] == ((RenesasHardwareDriverParams*)params)->channels[3];
+ dt_act = (duty_cycle_counts>0 && !hw_deadtime)?dt:0;
+ _setSinglePhaseState(t, t1, phase_state[1]);
+ if (R_GPT_DutyCycleSet(&(t->ctrl), duty_cycle_counts - dt_act, t->duty_pin) != FSP_SUCCESS) {
+ // error
+ }
+ if (!hw_deadtime) {
+ if (R_GPT_DutyCycleSet(&(t1->ctrl), duty_cycle_counts + dt_act, t1->duty_pin) != FSP_SUCCESS) {
+ // error
+ }
+ }
+
+ t = ((RenesasHardwareDriverParams*)params)->timer_config[4];
+ t1 = ((RenesasHardwareDriverParams*)params)->timer_config[5];
+ duty_cycle_counts = (uint32_t)(dc_c * (float)(t->timer_cfg.period_counts));
+ hw_deadtime = ((RenesasHardwareDriverParams*)params)->channels[4] == ((RenesasHardwareDriverParams*)params)->channels[5];
+ dt_act = (duty_cycle_counts>0 && !hw_deadtime)?dt:0;
+ _setSinglePhaseState(t, t1, phase_state[2]);
+ if (R_GPT_DutyCycleSet(&(t->ctrl), duty_cycle_counts, t->duty_pin) != FSP_SUCCESS) {
+ // error
+ }
+ if (!hw_deadtime) {
+ if (R_GPT_DutyCycleSet(&(t1->ctrl), duty_cycle_counts + dt_act, t1->duty_pin) != FSP_SUCCESS) {
+ // error
+ }
+ }
+
+}
+
+#endif
\ No newline at end of file
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/drivers/hardware_specific/renesas/renesas.h b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/drivers/hardware_specific/renesas/renesas.h
new file mode 100644
index 0000000..91bacdc
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/drivers/hardware_specific/renesas/renesas.h
@@ -0,0 +1,28 @@
+#pragma once
+
+
+#include "../../hardware_api.h"
+
+
+#if defined(ARDUINO_UNOR4_WIFI) || defined(ARDUINO_UNOR4_MINIMA)
+
+// uncomment to enable debug output from Renesas driver
+// can set this as build-flag in Arduino IDE or PlatformIO
+#define SIMPLEFOC_RENESAS_DEBUG
+
+#define RENESAS_DEFAULT_PWM_FREQUENCY 24000
+#define RENESAS_DEFAULT_DEAD_ZONE 0.05f
+
+struct RenesasTimerConfig;
+
+typedef struct RenesasHardwareDriverParams {
+ uint8_t pins[6];
+ uint8_t channels[6];
+ RenesasTimerConfig* timer_config[6];
+ long pwm_frequency;
+ float dead_zone;
+} RenesasHardwareDriverParams;
+
+
+
+#endif
\ No newline at end of file
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/drivers/hardware_specific/rp2040/rp2040_mcu.cpp b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/drivers/hardware_specific/rp2040/rp2040_mcu.cpp
new file mode 100644
index 0000000..6afbf34
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/drivers/hardware_specific/rp2040/rp2040_mcu.cpp
@@ -0,0 +1,249 @@
+
+/**
+ * Support for the RP2040 MCU, as found on the Raspberry Pi Pico.
+ */
+
+#include "./rp2040_mcu.h"
+
+
+#if defined(TARGET_RP2040)
+
+
+#pragma message("")
+#pragma message("SimpleFOC: compiling for RP2040")
+#pragma message("")
+
+#if !defined(SIMPLEFOC_DEBUG_RP2040)
+#define SIMPLEFOC_DEBUG_RP2040
+#endif
+
+#include "../../hardware_api.h"
+#include "hardware/pwm.h"
+#include "hardware/clocks.h"
+#if defined(USE_ARDUINO_PINOUT)
+#include
+#endif
+
+#define _PWM_FREQUENCY 24000
+#define _PWM_FREQUENCY_MAX 66000
+#define _PWM_FREQUENCY_MIN 1
+
+
+
+// until I can figure out if this can be quickly read from some register, keep it here.
+// it also serves as a marker for what slices are already used.
+uint16_t wrapvalues[NUM_PWM_SLICES];
+
+
+// TODO add checks which channels are already used...
+
+void setupPWM(int pin_nr, long pwm_frequency, bool invert, RP2040DriverParams* params, uint8_t index) {
+ #if defined(USE_ARDUINO_PINOUT)
+ uint pin = (uint)digitalPinToPinName(pin_nr); // we could check for -DBOARD_HAS_PIN_REMAP ?
+ #else
+ uint pin = (uint)pin_nr;
+ #endif
+ gpio_set_function(pin, GPIO_FUNC_PWM);
+ uint slice = pwm_gpio_to_slice_num(pin);
+ uint chan = pwm_gpio_to_channel(pin);
+ params->pins[index] = pin;
+ params->slice[index] = slice;
+ params->chan[index] = chan;
+ uint32_t sysclock_hz = frequency_count_khz(CLOCKS_FC0_SRC_VALUE_CLK_SYS) * 1000;
+ uint32_t factor = 4096 * 2 * pwm_frequency;
+ uint32_t div = sysclock_hz / factor;
+ if (sysclock_hz % factor !=0) div+=1;
+ if (div < 16) div = 16;
+ uint32_t wrapvalue = (sysclock_hz * 8) / div / pwm_frequency - 1;
+#ifdef SIMPLEFOC_DEBUG_RP2040
+ SimpleFOCDebug::print("Configuring pin ");
+ SimpleFOCDebug::print((int)pin);
+ SimpleFOCDebug::print(" slice ");
+ SimpleFOCDebug::print((int)slice);
+ SimpleFOCDebug::print(" channel ");
+ SimpleFOCDebug::print((int)chan);
+ SimpleFOCDebug::print(" frequency ");
+ SimpleFOCDebug::print((int)pwm_frequency);
+ SimpleFOCDebug::print(" divisor ");
+ SimpleFOCDebug::print((int)(div>>4));
+ SimpleFOCDebug::print(".");
+ SimpleFOCDebug::print((int)(div&0xF));
+ SimpleFOCDebug::print(" top value ");
+ SimpleFOCDebug::println((int)wrapvalue);
+#endif
+ if (wrapvalue < 999)
+ SimpleFOCDebug::println("Warning: PWM resolution is low.");
+ pwm_set_clkdiv_int_frac(slice, div>>4, div&0xF);
+ pwm_set_phase_correct(slice, true);
+ pwm_set_wrap(slice, wrapvalue);
+ wrapvalues[slice] = wrapvalue;
+ if (invert) {
+ if (chan==0)
+ hw_write_masked(&pwm_hw->slice[slice].csr, 0x1 << PWM_CH0_CSR_A_INV_LSB, PWM_CH0_CSR_A_INV_BITS);
+ else
+ hw_write_masked(&pwm_hw->slice[slice].csr, 0x1 << PWM_CH0_CSR_B_INV_LSB, PWM_CH0_CSR_B_INV_BITS);
+ }
+ pwm_set_chan_level(slice, chan, 0); // switch off initially
+}
+
+
+void syncSlices() {
+ for (uint i=0;ipwm_frequency = pwm_frequency;
+ setupPWM(pinA, pwm_frequency, !SIMPLEFOC_PWM_ACTIVE_HIGH, params, 0);
+ syncSlices();
+ return params;
+}
+
+
+
+void* _configure2PWM(long pwm_frequency, const int pinA, const int pinB) {
+ RP2040DriverParams* params = new RP2040DriverParams();
+ if( !pwm_frequency || !_isset(pwm_frequency) ) pwm_frequency = _PWM_FREQUENCY;
+ else pwm_frequency = _constrain(pwm_frequency, _PWM_FREQUENCY_MIN, _PWM_FREQUENCY_MAX);
+ params->pwm_frequency = pwm_frequency;
+ setupPWM(pinA, pwm_frequency, !SIMPLEFOC_PWM_ACTIVE_HIGH, params, 0);
+ setupPWM(pinB, pwm_frequency, !SIMPLEFOC_PWM_ACTIVE_HIGH, params, 1);
+ syncSlices();
+ return params;
+}
+
+
+
+void* _configure3PWM(long pwm_frequency, const int pinA, const int pinB, const int pinC) {
+ RP2040DriverParams* params = new RP2040DriverParams();
+ if( !pwm_frequency || !_isset(pwm_frequency) ) pwm_frequency = _PWM_FREQUENCY;
+ else pwm_frequency = _constrain(pwm_frequency, _PWM_FREQUENCY_MIN, _PWM_FREQUENCY_MAX);
+ params->pwm_frequency = pwm_frequency;
+ setupPWM(pinA, pwm_frequency, !SIMPLEFOC_PWM_ACTIVE_HIGH, params, 0);
+ setupPWM(pinB, pwm_frequency, !SIMPLEFOC_PWM_ACTIVE_HIGH, params, 1);
+ setupPWM(pinC, pwm_frequency, !SIMPLEFOC_PWM_ACTIVE_HIGH, params, 2);
+ syncSlices();
+ return params;
+}
+
+
+
+
+void* _configure4PWM(long pwm_frequency, const int pin1A, const int pin1B, const int pin2A, const int pin2B) {
+ RP2040DriverParams* params = new RP2040DriverParams();
+ if( !pwm_frequency || !_isset(pwm_frequency) ) pwm_frequency = _PWM_FREQUENCY;
+ else pwm_frequency = _constrain(pwm_frequency, _PWM_FREQUENCY_MIN, _PWM_FREQUENCY_MAX);
+ params->pwm_frequency = pwm_frequency;
+ setupPWM(pin1A, pwm_frequency, !SIMPLEFOC_PWM_ACTIVE_HIGH, params, 0);
+ setupPWM(pin1B, pwm_frequency, !SIMPLEFOC_PWM_ACTIVE_HIGH, params, 1);
+ setupPWM(pin2A, pwm_frequency, !SIMPLEFOC_PWM_ACTIVE_HIGH, params, 2);
+ setupPWM(pin2B, pwm_frequency, !SIMPLEFOC_PWM_ACTIVE_HIGH, params, 3);
+ syncSlices();
+ return params;
+}
+
+
+void* _configure6PWM(long pwm_frequency, float dead_zone, const int pinA_h, const int pinA_l, const int pinB_h, const int pinB_l, const int pinC_h, const int pinC_l) {
+ // non-PIO solution...
+ RP2040DriverParams* params = new RP2040DriverParams();
+ if( !pwm_frequency || !_isset(pwm_frequency) ) pwm_frequency = _PWM_FREQUENCY;
+ else pwm_frequency = _constrain(pwm_frequency, _PWM_FREQUENCY_MIN, _PWM_FREQUENCY_MAX);
+ params->pwm_frequency = pwm_frequency;
+ params->dead_zone = dead_zone;
+ setupPWM(pinA_h, pwm_frequency, !SIMPLEFOC_PWM_HIGHSIDE_ACTIVE_HIGH, params, 0);
+ setupPWM(pinB_h, pwm_frequency, !SIMPLEFOC_PWM_HIGHSIDE_ACTIVE_HIGH, params, 2);
+ setupPWM(pinC_h, pwm_frequency, !SIMPLEFOC_PWM_HIGHSIDE_ACTIVE_HIGH, params, 4);
+ setupPWM(pinA_l, pwm_frequency, SIMPLEFOC_PWM_LOWSIDE_ACTIVE_HIGH, params, 1);
+ setupPWM(pinB_l, pwm_frequency, SIMPLEFOC_PWM_LOWSIDE_ACTIVE_HIGH, params, 3);
+ setupPWM(pinC_l, pwm_frequency, SIMPLEFOC_PWM_LOWSIDE_ACTIVE_HIGH, params, 5);
+ syncSlices();
+ return params;
+}
+
+
+
+
+
+void writeDutyCycle(float val, uint slice, uint chan) {
+ pwm_set_chan_level(slice, chan, (wrapvalues[slice]+1) * val);
+}
+
+
+
+
+void _writeDutyCycle1PWM(float dc_a, void* params) {
+ writeDutyCycle(dc_a, ((RP2040DriverParams*)params)->slice[0], ((RP2040DriverParams*)params)->chan[0]);
+}
+
+
+
+
+void _writeDutyCycle2PWM(float dc_a, float dc_b, void* params) {
+ writeDutyCycle(dc_a, ((RP2040DriverParams*)params)->slice[0], ((RP2040DriverParams*)params)->chan[0]);
+ writeDutyCycle(dc_b, ((RP2040DriverParams*)params)->slice[1], ((RP2040DriverParams*)params)->chan[1]);
+}
+
+
+
+void _writeDutyCycle3PWM(float dc_a, float dc_b, float dc_c, void* params) {
+ writeDutyCycle(dc_a, ((RP2040DriverParams*)params)->slice[0], ((RP2040DriverParams*)params)->chan[0]);
+ writeDutyCycle(dc_b, ((RP2040DriverParams*)params)->slice[1], ((RP2040DriverParams*)params)->chan[1]);
+ writeDutyCycle(dc_c, ((RP2040DriverParams*)params)->slice[2], ((RP2040DriverParams*)params)->chan[2]);
+}
+
+
+
+void _writeDutyCycle4PWM(float dc_1a, float dc_1b, float dc_2a, float dc_2b, void* params) {
+ writeDutyCycle(dc_1a, ((RP2040DriverParams*)params)->slice[0], ((RP2040DriverParams*)params)->chan[0]);
+ writeDutyCycle(dc_1b, ((RP2040DriverParams*)params)->slice[1], ((RP2040DriverParams*)params)->chan[1]);
+ writeDutyCycle(dc_2a, ((RP2040DriverParams*)params)->slice[2], ((RP2040DriverParams*)params)->chan[2]);
+ writeDutyCycle(dc_2b, ((RP2040DriverParams*)params)->slice[3], ((RP2040DriverParams*)params)->chan[3]);
+}
+
+inline float swDti(float val, float dt) {
+ float ret = dt+val;
+ if (ret>1.0) ret = 1.0f;
+ return ret;
+}
+
+void _writeDutyCycle6PWM(float dc_a, float dc_b, float dc_c, PhaseState *phase_state, void* params) {
+ if (phase_state[0]==PhaseState::PHASE_ON || phase_state[0]==PhaseState::PHASE_HI)
+ writeDutyCycle(dc_a, ((RP2040DriverParams*)params)->slice[0], ((RP2040DriverParams*)params)->chan[0]);
+ else
+ writeDutyCycle(0.0f, ((RP2040DriverParams*)params)->slice[0], ((RP2040DriverParams*)params)->chan[0]);
+ if (phase_state[0]==PhaseState::PHASE_ON || phase_state[0]==PhaseState::PHASE_LO)
+ writeDutyCycle(swDti(dc_a, ((RP2040DriverParams*)params)->dead_zone), ((RP2040DriverParams*)params)->slice[1], ((RP2040DriverParams*)params)->chan[1]);
+ else
+ writeDutyCycle(0.0f, ((RP2040DriverParams*)params)->slice[1], ((RP2040DriverParams*)params)->chan[1]);
+
+ if (phase_state[1]==PhaseState::PHASE_ON || phase_state[1]==PhaseState::PHASE_HI)
+ writeDutyCycle(dc_b, ((RP2040DriverParams*)params)->slice[2], ((RP2040DriverParams*)params)->chan[2]);
+ else
+ writeDutyCycle(0.0f, ((RP2040DriverParams*)params)->slice[2], ((RP2040DriverParams*)params)->chan[2]);
+ if (phase_state[1]==PhaseState::PHASE_ON || phase_state[1]==PhaseState::PHASE_LO)
+ writeDutyCycle(swDti(dc_b, ((RP2040DriverParams*)params)->dead_zone), ((RP2040DriverParams*)params)->slice[3], ((RP2040DriverParams*)params)->chan[3]);
+ else
+ writeDutyCycle(0.0f, ((RP2040DriverParams*)params)->slice[3], ((RP2040DriverParams*)params)->chan[3]);
+
+ if (phase_state[2]==PhaseState::PHASE_ON || phase_state[2]==PhaseState::PHASE_HI)
+ writeDutyCycle(dc_c, ((RP2040DriverParams*)params)->slice[4], ((RP2040DriverParams*)params)->chan[4]);
+ else
+ writeDutyCycle(0.0f, ((RP2040DriverParams*)params)->slice[4], ((RP2040DriverParams*)params)->chan[4]);
+ if (phase_state[2]==PhaseState::PHASE_ON || phase_state[2]==PhaseState::PHASE_LO)
+ writeDutyCycle(swDti(dc_c, ((RP2040DriverParams*)params)->dead_zone), ((RP2040DriverParams*)params)->slice[5], ((RP2040DriverParams*)params)->chan[5]);
+ else
+ writeDutyCycle(0.0f, ((RP2040DriverParams*)params)->slice[5], ((RP2040DriverParams*)params)->chan[5]);
+
+ _UNUSED(phase_state);
+}
+
+#endif
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/drivers/hardware_specific/rp2040/rp2040_mcu.h b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/drivers/hardware_specific/rp2040/rp2040_mcu.h
new file mode 100644
index 0000000..bbfb387
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/drivers/hardware_specific/rp2040/rp2040_mcu.h
@@ -0,0 +1,22 @@
+
+
+#pragma once
+
+#include "Arduino.h"
+
+#if defined(TARGET_RP2040)
+
+
+
+typedef struct RP2040DriverParams {
+ int pins[6];
+ uint slice[6];
+ uint chan[6];
+ long pwm_frequency;
+ float dead_zone;
+} RP2040DriverParams;
+
+
+
+
+#endif
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/drivers/hardware_specific/samd/samd21_mcu.cpp b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/drivers/hardware_specific/samd/samd21_mcu.cpp
new file mode 100644
index 0000000..d59a309
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/drivers/hardware_specific/samd/samd21_mcu.cpp
@@ -0,0 +1,353 @@
+
+
+
+#include "./samd_mcu.h"
+
+
+#ifdef _SAMD21_
+
+
+#pragma message("")
+#pragma message("SimpleFOC: compiling for SAMD21")
+#pragma message("")
+
+
+#ifndef TCC3_CH0
+#define TCC3_CH0 NOT_ON_TIMER
+#endif
+#ifndef TCC3_CH1
+#define TCC3_CH1 NOT_ON_TIMER
+#endif
+#ifndef TCC3_CH2
+#define TCC3_CH2 NOT_ON_TIMER
+#endif
+#ifndef TCC3_CH3
+#define TCC3_CH3 NOT_ON_TIMER
+#endif
+#ifndef TCC3_CH4
+#define TCC3_CH4 NOT_ON_TIMER
+#endif
+#ifndef TCC3_CH5
+#define TCC3_CH5 NOT_ON_TIMER
+#endif
+#ifndef TCC3_CH6
+#define TCC3_CH6 NOT_ON_TIMER
+#endif
+#ifndef TCC3_CH7
+#define TCC3_CH7 NOT_ON_TIMER
+#endif
+#ifndef TC6_CH0
+#define TC6_CH0 NOT_ON_TIMER
+#endif
+#ifndef TC6_CH1
+#define TC6_CH1 NOT_ON_TIMER
+#endif
+#ifndef TC7_CH0
+#define TC7_CH0 NOT_ON_TIMER
+#endif
+#ifndef TC7_CH1
+#define TC7_CH1 NOT_ON_TIMER
+#endif
+
+
+
+#define NUM_WO_ASSOCIATIONS 48
+
+/*
+ * For SAM D21 A/B/C/D Variant Devices and SAM DA1 A/B Variant Devices
+ * Good for SAMD2xE, SAMD2xG and SAMD2xJ devices. Other SAMD21s currently not supported in arduino anyway?
+ *
+ * Note: only the pins which have timers associated are listed in this table.
+ * You can use the values from g_APinDescription.ulPort and g_APinDescription.ulPin to find the correct row in the table.
+ *
+ * See Microchip Technology datasheet DS40001882F-page 30
+ */
+struct wo_association WO_associations[] = {
+
+ { PORTA, 0, TCC2_CH0, 0, NOT_ON_TIMER, 0},
+ { PORTA, 1, TCC2_CH1, 1, NOT_ON_TIMER, 0},
+ { PORTA, 2, NOT_ON_TIMER, 0, TCC3_CH0, 0},
+ { PORTA, 3, NOT_ON_TIMER, 0, TCC3_CH1, 1},
+ // PB04, PB05, PB06, PB07 - no timers
+ { PORTB, 8, TC4_CH0, 0, TCC3_CH6, 6},
+ { PORTB, 9, TC4_CH1, 1, TCC3_CH7, 7},
+ { PORTA, 4, TCC0_CH0, 0, TCC3_CH2, 2},
+ { PORTA, 5, TCC0_CH1, 1, TCC3_CH3, 3},
+ { PORTA, 6, TCC1_CH0, 0, TCC3_CH4, 4},
+ { PORTA, 7, TCC1_CH1, 1, TCC3_CH5, 5},
+ { PORTA, 8, TCC0_CH0, 0, TCC1_CH2, 2},
+ { PORTA, 9, TCC0_CH1, 1, TCC1_CH3, 3},
+ { PORTA, 10, TCC1_CH0, 0, TCC0_CH2, 2},
+ { PORTA, 11, TCC1_CH1, 1, TCC0_CH3, 3},
+ { PORTB, 10, TC5_CH0, 0, TCC0_CH4, 4},
+ { PORTB, 11, TC5_CH1, 1, TCC0_CH5, 5},
+ { PORTB, 12, TC4_CH0, 0, TCC0_CH6, 6},
+ { PORTB, 13, TC4_CH1, 1, TCC0_CH7, 7},
+ { PORTB, 14, TC5_CH0, 0, NOT_ON_TIMER, 0},
+ { PORTB, 15, TC5_CH1, 1, NOT_ON_TIMER, 0},
+ { PORTA, 12, TCC2_CH0, 0, TCC0_CH6, 6},
+ { PORTA, 13, TCC2_CH1, 1, TCC0_CH7, 7},
+ { PORTA, 14, TC3_CH0, 0, TCC0_CH4, 4},
+ { PORTA, 15, TC3_CH1, 1, TCC0_CH5, 5},
+ { PORTA, 16, TCC2_CH0, 0, TCC0_CH6, 6},
+ { PORTA, 17, TCC2_CH1, 1, TCC0_CH7, 7},
+ { PORTA, 18, TC3_CH0, 0, TCC0_CH2, 2},
+ { PORTA, 19, TC3_CH1, 1, TCC0_CH3, 3},
+ { PORTB, 16, TC6_CH0, 0, TCC0_CH4, 4},
+ { PORTB, 17, TC6_CH1, 1, TCC0_CH5, 5},
+ { PORTA, 20, TC7_CH0, 0, TCC0_CH6, 6},
+ { PORTA, 21, TC7_CH1, 1, TCC0_CH7, 7},
+ { PORTA, 22, TC4_CH0, 0, TCC0_CH4, 4},
+ { PORTA, 23, TC4_CH1, 1, TCC0_CH5, 5},
+ { PORTA, 24, TC5_CH0, 0, TCC1_CH2, 2},
+ { PORTA, 25, TC5_CH1, 1, TCC1_CH3, 3},
+ { PORTB, 22, TC7_CH0, 0, TCC3_CH0, 0},
+ { PORTB, 23, TC7_CH1, 1, TCC3_CH1, 1},
+ { PORTA, 27, NOT_ON_TIMER, 0, TCC3_CH6, 6},
+ { PORTA, 28, NOT_ON_TIMER, 0, TCC3_CH7, 7},
+ { PORTA, 30, TCC1_CH0, 0, TCC3_CH4, 4},
+ { PORTA, 31, TCC1_CH1, 1, TCC3_CH5, 5},
+ { PORTB, 30, TCC0_CH0, 0, TCC1_CH2, 2},
+ { PORTB, 31, TCC0_CH1, 1, TCC1_CH3, 3},
+ { PORTB, 0, TC7_CH0, 0, NOT_ON_TIMER, 0},
+ { PORTB, 1, TC7_CH1, 1, NOT_ON_TIMER, 0},
+ { PORTB, 2, TC6_CH0, 0, TCC3_CH2, 2},
+ { PORTB, 3, TC6_CH1, 1, TCC3_CH3, 3}
+};
+wo_association ASSOCIATION_NOT_FOUND = { NOT_A_PORT, 0, NOT_ON_TIMER, 0, NOT_ON_TIMER, 0};
+
+
+
+struct wo_association& getWOAssociation(EPortType port, uint32_t pin) {
+ for (int i=0;i>pin_position)&0x01)==0x1?PIO_TIMER_ALT:PIO_TIMER;
+}
+
+
+
+
+
+void syncTCC(Tcc* TCCx) {
+ while (TCCx->SYNCBUSY.reg & TCC_SYNCBUSY_MASK); // Wait for synchronization of registers between the clock domains
+}
+
+
+
+/**
+ * Configure Clock 4 - we want all simplefoc PWMs to use the same clock. This ensures that
+ * any compatible pin combination can be used without having to worry about configuring different
+ * clocks.
+ */
+void configureSAMDClock() {
+
+ // TODO investigate using the FDPLL96M clock to get 96MHz timer clocks... this
+ // would enable 48KHz PWM clocks, and setting the frequency between 24Khz with resolution 2000, to 48KHz with resolution 1000
+
+ if (!SAMDClockConfigured) {
+ SAMDClockConfigured = true; // mark clock as configured
+ for (int i=0;iSTATUS.bit.SYNCBUSY); // Wait for synchronization
+
+ REG_GCLK_GENCTRL = GCLK_GENCTRL_IDC | // Set the duty cycle to 50/50 HIGH/LOW
+ GCLK_GENCTRL_GENEN | // Enable GCLK4
+ GCLK_GENCTRL_SRC_DFLL48M | // Set the 48MHz clock source
+ // GCLK_GENCTRL_SRC_FDPLL | // Set the 96MHz clock source
+ GCLK_GENCTRL_ID(4); // Select GCLK4
+ while (GCLK->STATUS.bit.SYNCBUSY); // Wait for synchronization
+
+#ifdef SIMPLEFOC_SAMD_DEBUG
+ SIMPLEFOC_DEBUG("SAMD: Configured clock...");
+#endif
+ }
+}
+
+
+
+
+/**
+ * Configure a TCC unit
+ * pwm_frequency is fixed at 24kHz for now. We could go slower, but going
+ * faster won't be possible without sacrificing resolution.
+ */
+void configureTCC(tccConfiguration& tccConfig, long pwm_frequency, bool negate, float hw6pwm) {
+
+ long pwm_resolution = (24000000) / pwm_frequency;
+ if (pwm_resolution>SIMPLEFOC_SAMD_MAX_PWM_RESOLUTION)
+ pwm_resolution = SIMPLEFOC_SAMD_MAX_PWM_RESOLUTION;
+ if (pwm_resolution>1) {
+ case 0: GCLK_CLKCTRL_ID_ofthistcc = GCLK_CLKCTRL_ID(GCM_TCC0_TCC1); break; //GCLK_CLKCTRL_ID_TCC0_TCC1;
+ case 1: GCLK_CLKCTRL_ID_ofthistcc = GCLK_CLKCTRL_ID(GCM_TCC2_TC3); break; //GCLK_CLKCTRL_ID_TCC2_TC3;
+ case 2: GCLK_CLKCTRL_ID_ofthistcc = GCLK_CLKCTRL_ID(GCM_TC4_TC5); break; //GCLK_CLKCTRL_ID_TC4_TC5;
+ case 3: GCLK_CLKCTRL_ID_ofthistcc = GCLK_CLKCTRL_ID(GCM_TC6_TC7); break;
+ default: return;
+ }
+
+ // Feed GCLK4 to TCC
+ REG_GCLK_CLKCTRL = (uint16_t) GCLK_CLKCTRL_CLKEN | // Enable GCLK4
+ GCLK_CLKCTRL_GEN_GCLK4 | // Select GCLK4
+ GCLK_CLKCTRL_ID_ofthistcc; // Feed GCLK4 to tcc
+ while (GCLK->STATUS.bit.SYNCBUSY); // Wait for synchronization
+
+ tccConfigured[tccConfig.tcc.tccn] = true;
+
+ if (tccConfig.tcc.tccn>=TCC_INST_NUM) {
+ Tc* tc = (Tc*)GetTC(tccConfig.tcc.chaninfo);
+ // disable
+ tc->COUNT8.CTRLA.bit.ENABLE = 0;
+ while ( tc->COUNT8.STATUS.bit.SYNCBUSY == 1 );
+ // unfortunately we need the 8-bit counter mode to use the PER register...
+ tc->COUNT8.CTRLA.reg |= TC_CTRLA_MODE_COUNT8 | TC_CTRLA_WAVEGEN_NPWM ;
+ while ( tc->COUNT8.STATUS.bit.SYNCBUSY == 1 );
+ // meaning prescaler of 8, since TC-Unit has no up/down mode, and has resolution of 250 rather than 1000...
+ tc->COUNT8.CTRLA.bit.PRESCALER = TC_CTRLA_PRESCALER_DIV8_Val ;
+ while ( tc->COUNT8.STATUS.bit.SYNCBUSY == 1 );
+ // period is 250, period cannot be higher than 256!
+ tc->COUNT8.PER.reg = SIMPLEFOC_SAMD_PWM_TC_RESOLUTION-1;
+ while ( tc->COUNT8.STATUS.bit.SYNCBUSY == 1 );
+ // initial duty cycle is 0
+ tc->COUNT8.CC[tccConfig.tcc.chan].reg = 0;
+ while ( tc->COUNT8.STATUS.bit.SYNCBUSY == 1 );
+ // enable
+ tc->COUNT8.CTRLA.bit.ENABLE = 1;
+ while ( tc->COUNT8.STATUS.bit.SYNCBUSY == 1 );
+#ifdef SIMPLEFOC_SAMD_DEBUG
+ SIMPLEFOC_DEBUG("SAMD: Initialized TC ", tccConfig.tcc.tccn);
+#endif
+ }
+ else {
+ Tcc* tcc = (Tcc*)GetTC(tccConfig.tcc.chaninfo);
+
+ uint8_t invenMask = ~(1<DRVCTRL.vec.INVEN = (tcc->DRVCTRL.vec.INVEN&invenMask)|invenVal;
+ syncTCC(tcc); // wait for sync
+
+ tcc->WAVE.reg |= TCC_WAVE_POL(0xF)|TCC_WAVEB_WAVEGENB_DSBOTH; // Set wave form configuration
+ while ( tcc->SYNCBUSY.bit.WAVE == 1 ); // wait for sync
+
+ if (hw6pwm>0.0) {
+ tcc->WEXCTRL.vec.DTIEN |= (1<WEXCTRL.bit.DTLS = hw6pwm*(pwm_resolution-1);
+ tcc->WEXCTRL.bit.DTHS = hw6pwm*(pwm_resolution-1);
+ syncTCC(tcc); // wait for sync
+ }
+
+ tcc->PER.reg = pwm_resolution - 1; // Set counter Top using the PER register
+ while ( tcc->SYNCBUSY.bit.PER == 1 ); // wait for sync
+
+ // set all channels to 0%
+ uint8_t chanCount = (tccConfig.tcc.tccn==1||tccConfig.tcc.tccn==2)?2:4;
+ for (int i=0;iCC[i].reg = 0; // start off at 0% duty cycle
+ uint32_t chanbit = 0x1<<(TCC_SYNCBUSY_CC0_Pos+i);
+ while ( (tcc->SYNCBUSY.reg & chanbit) > 0 );
+ }
+
+ // Enable TC
+ tcc->CTRLA.reg |= TCC_CTRLA_ENABLE | TCC_CTRLA_PRESCALER_DIV1; //48Mhz/1=48Mhz/2(up/down)=24MHz/1024=24KHz
+ while ( tcc->SYNCBUSY.bit.ENABLE == 1 ); // wait for sync
+
+#if defined(SIMPLEFOC_SAMD_DEBUG) && !defined(SIMPLEFOC_DISABLE_DEBUG)
+ SimpleFOCDebug::print("SAMD: Initialized TCC ");
+ SimpleFOCDebug::print(tccConfig.tcc.tccn);
+ SimpleFOCDebug::print("-");
+ SimpleFOCDebug::print(tccConfig.tcc.chan);
+ SimpleFOCDebug::print("[");
+ SimpleFOCDebug::print(tccConfig.wo);
+ SimpleFOCDebug::print("] pwm res ");
+ SimpleFOCDebug::print((int)pwm_resolution);
+ SimpleFOCDebug::println();
+#endif
+ }
+ }
+ else if (tccConfig.tcc.tccnCTRLA.bit.ENABLE = 0;
+ while ( tcc->SYNCBUSY.bit.ENABLE == 1 );
+
+ uint8_t invenMask = ~(1<DRVCTRL.vec.INVEN = (tcc->DRVCTRL.vec.INVEN&invenMask)|invenVal;
+ syncTCC(tcc); // wait for sync
+
+ if (hw6pwm>0.0) {
+ tcc->WEXCTRL.vec.DTIEN |= (1<WEXCTRL.bit.DTLS = hw6pwm*(pwm_resolution-1);
+ tcc->WEXCTRL.bit.DTHS = hw6pwm*(pwm_resolution-1);
+ syncTCC(tcc); // wait for sync
+ }
+
+ tcc->CTRLA.bit.ENABLE = 1;
+ while ( tcc->SYNCBUSY.bit.ENABLE == 1 );
+
+#if defined(SIMPLEFOC_SAMD_DEBUG) && !defined(SIMPLEFOC_DISABLE_DEBUG)
+ SimpleFOCDebug::print("SAMD: (Re-)Initialized TCC ");
+ SimpleFOCDebug::print(tccConfig.tcc.tccn);
+ SimpleFOCDebug::print("-");
+ SimpleFOCDebug::print(tccConfig.tcc.chan);
+ SimpleFOCDebug::print("[");
+ SimpleFOCDebug::print(tccConfig.wo);
+ SimpleFOCDebug::print("] pwm res ");
+ SimpleFOCDebug::print((int)pwm_resolution);
+ SimpleFOCDebug::println();
+#endif
+ }
+
+
+}
+
+
+
+
+
+void writeSAMDDutyCycle(tccConfiguration* info, float dc) {
+ uint8_t tccn = GetTCNumber(info->tcc.chaninfo);
+ uint8_t chan = GetTCChannelNumber(info->tcc.chaninfo);
+ if (tccntcc.chaninfo);
+ // set via CC
+// tcc->CC[chan].reg = (uint32_t)((SIMPLEFOC_SAMD_PWM_RESOLUTION-1) * dc);
+// uint32_t chanbit = 0x1<<(TCC_SYNCBUSY_CC0_Pos+chan);
+// while ( (tcc->SYNCBUSY.reg & chanbit) > 0 );
+ // set via CCB
+ //while ( (tcc->SYNCBUSY.vec.CC & (0x1< 0 );
+ tcc->CCB[chan].reg = (uint32_t)((info->pwm_res-1) * dc);
+// while ( (tcc->SYNCBUSY.vec.CCB & (0x1< 0 );
+// tcc->STATUS.vec.CCBV |= (0x1<SYNCBUSY.bit.STATUS > 0 );
+// tcc->CTRLBSET.reg |= TCC_CTRLBSET_CMD(TCC_CTRLBSET_CMD_UPDATE_Val);
+// while ( tcc->SYNCBUSY.bit.CTRLB > 0 );
+ }
+ else {
+ Tc* tc = (Tc*)GetTC(info->tcc.chaninfo);
+ tc->COUNT8.CC[chan].reg = (uint8_t)((SIMPLEFOC_SAMD_PWM_TC_RESOLUTION-1) * dc);
+ while ( tc->COUNT8.STATUS.bit.SYNCBUSY == 1 );
+ }
+}
+
+
+
+
+#endif
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/drivers/hardware_specific/samd/samd51_mcu.cpp b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/drivers/hardware_specific/samd/samd51_mcu.cpp
new file mode 100644
index 0000000..71bf0b8
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/drivers/hardware_specific/samd/samd51_mcu.cpp
@@ -0,0 +1,351 @@
+
+
+#include "./samd_mcu.h"
+
+
+#if defined(_SAMD51_)||defined(_SAME51_)
+
+
+#pragma message("")
+#pragma message("SimpleFOC: compiling for SAMD51/SAME51")
+#pragma message("")
+
+
+
+// expected frequency on DPLL, since we don't configure it ourselves. Typically this is the CPU frequency.
+// for custom boards or overclockers you can override it using this define.
+#ifndef SIMPLEFOC_SAMD51_DPLL_FREQ
+#define SIMPLEFOC_SAMD51_DPLL_FREQ 120000000
+#endif
+
+
+#ifndef TCC3_CH0
+#define TCC3_CH0 NOT_ON_TIMER
+#define TCC3_CH1 NOT_ON_TIMER
+#endif
+
+#ifndef TCC4_CH0
+#define TCC4_CH0 NOT_ON_TIMER
+#define TCC4_CH1 NOT_ON_TIMER
+#endif
+
+
+#ifndef TC4_CH0
+#define TC4_CH0 NOT_ON_TIMER
+#define TC4_CH1 NOT_ON_TIMER
+#endif
+
+#ifndef TC5_CH0
+#define TC5_CH0 NOT_ON_TIMER
+#define TC5_CH1 NOT_ON_TIMER
+#endif
+
+#ifndef TC6_CH0
+#define TC6_CH0 NOT_ON_TIMER
+#define TC6_CH1 NOT_ON_TIMER
+#endif
+
+#ifndef TC7_CH0
+#define TC7_CH0 NOT_ON_TIMER
+#define TC7_CH1 NOT_ON_TIMER
+#endif
+
+
+
+// TCC# Channels WO_NUM Counter size Fault Dithering Output matrix DTI SWAP Pattern generation
+// 0 6 8 24-bit Yes Yes Yes Yes Yes Yes
+// 1 4 8 24-bit Yes Yes Yes Yes Yes Yes
+// 2 3 3 16-bit Yes - Yes - - -
+// 3 2 2 16-bit Yes - - - - -
+// 4 2 2 16-bit Yes - - - - -
+
+
+#define NUM_WO_ASSOCIATIONS 72
+
+struct wo_association WO_associations[] = {
+
+ { PORTB, 9, TC4_CH1, 1, NOT_ON_TIMER, 0, NOT_ON_TIMER, 0},
+ { PORTA, 4, TC0_CH0, 0, NOT_ON_TIMER, 0, NOT_ON_TIMER, 0},
+ { PORTA, 5, TC0_CH1, 1, NOT_ON_TIMER, 0, NOT_ON_TIMER, 0},
+ { PORTA, 6, TC1_CH0, 0, NOT_ON_TIMER, 0, NOT_ON_TIMER, 0},
+ { PORTA, 7, TC1_CH1, 1, NOT_ON_TIMER, 0, NOT_ON_TIMER, 0},
+ { PORTC, 4, NOT_ON_TIMER, 0, TCC0_CH0, 0, NOT_ON_TIMER, 0},
+ // PC05, PC06, PC07 -> no timers
+ { PORTA, 8, TC0_CH0, 0, TCC0_CH0, 0, TCC1_CH0, 4},
+ { PORTA, 9, TC0_CH1, 1, TCC0_CH1, 1, TCC1_CH1, 5},
+ { PORTA, 10, TC1_CH0, 0, TCC0_CH2, 2, TCC1_CH2, 6},
+ { PORTA, 11, TC1_CH1, 1, TCC0_CH3, 3, TCC1_CH3, 7},
+ { PORTB, 10, TC5_CH0, 0, TCC0_CH4, 4, TCC1_CH0, 0},
+ { PORTB, 11, TC5_CH1, 1, TCC0_CH5, 5, TCC1_CH1, 1},
+ { PORTB, 12, TC4_CH0, 0, TCC3_CH0, 0, TCC0_CH0, 0},
+ { PORTB, 13, TC4_CH1, 1, TCC3_CH1, 1, TCC0_CH1, 1},
+ { PORTB, 14, TC5_CH0, 0, TCC4_CH0, 0, TCC0_CH2, 2},
+ { PORTB, 15, TC5_CH1, 1, TCC4_CH1, 1, TCC0_CH3, 3},
+ { PORTD, 8, NOT_ON_TIMER, 0, TCC0_CH1, 1, NOT_ON_TIMER, 0},
+ { PORTD, 9, NOT_ON_TIMER, 0, TCC0_CH2, 2, NOT_ON_TIMER, 0},
+ { PORTD, 10, NOT_ON_TIMER, 0, TCC0_CH3, 3, NOT_ON_TIMER, 0},
+ { PORTD, 11, NOT_ON_TIMER, 0, TCC0_CH4, 4, NOT_ON_TIMER, 0},
+ { PORTD, 12, NOT_ON_TIMER, 0, TCC0_CH5, 5, NOT_ON_TIMER, 0},
+ { PORTC, 10, NOT_ON_TIMER, 0, TCC0_CH0, 0, TCC1_CH0, 4},
+ { PORTC, 11, NOT_ON_TIMER, 0, TCC0_CH1, 1, TCC1_CH1, 5},
+ { PORTC, 12, NOT_ON_TIMER, 0, TCC0_CH2, 2, TCC1_CH2, 6},
+ { PORTC, 13, NOT_ON_TIMER, 0, TCC0_CH3, 3, TCC1_CH3, 7},
+ { PORTC, 14, NOT_ON_TIMER, 0, TCC0_CH4, 4, TCC1_CH0, 0},
+ { PORTC, 15, NOT_ON_TIMER, 0, TCC0_CH5, 5, TCC1_CH1, 1},
+ { PORTA, 12, TC2_CH0, 0, TCC0_CH0, 6, TCC1_CH2, 2},
+ { PORTA, 13, TC2_CH1, 1, TCC0_CH1, 7, TCC1_CH3, 3},
+ { PORTA, 14, TC3_CH0, 0, TCC2_CH0, 0, TCC1_CH2, 2},
+ { PORTA, 15, TC3_CH1, 1, TCC2_CH1, 1, TCC1_CH3, 3},
+ { PORTA, 16, TC2_CH0, 0, TCC1_CH0, 0, TCC0_CH4, 4},
+ { PORTA, 17, TC2_CH1, 1, TCC1_CH1, 1, TCC0_CH5, 5},
+ { PORTA, 18, TC3_CH0, 0, TCC1_CH2, 2, TCC0_CH0, 6},
+ { PORTA, 19, TC3_CH1, 1, TCC1_CH3, 3, TCC0_CH1, 7},
+ { PORTC, 16, NOT_ON_TIMER, 0, TCC0_CH0, 0, NOT_ON_TIMER, 0}, // PDEC0
+ { PORTC, 17, NOT_ON_TIMER, 0, TCC0_CH1, 1, NOT_ON_TIMER, 0}, // PDEC1
+ { PORTC, 18, NOT_ON_TIMER, 0, TCC0_CH2, 2, NOT_ON_TIMER, 0}, // PDEC2
+ { PORTC, 19, NOT_ON_TIMER, 0, TCC0_CH3, 3, NOT_ON_TIMER, 0},
+ { PORTC, 20, NOT_ON_TIMER, 0, TCC0_CH4, 4, NOT_ON_TIMER, 0},
+ { PORTC, 21, NOT_ON_TIMER, 0, TCC0_CH5, 5, NOT_ON_TIMER, 0},
+ { PORTC, 22, NOT_ON_TIMER, 0, TCC0_CH0, 6, NOT_ON_TIMER, 0},
+ { PORTC, 23, NOT_ON_TIMER, 0, TCC0_CH1, 7, NOT_ON_TIMER, 0},
+ { PORTD, 20, NOT_ON_TIMER, 0, TCC1_CH0, 0, NOT_ON_TIMER, 0},
+ { PORTD, 21, NOT_ON_TIMER, 0, TCC1_CH1, 1, NOT_ON_TIMER, 0},
+ { PORTB, 16, TC6_CH0, 0, TCC3_CH0, 0, TCC0_CH4, 4},
+ { PORTB, 17, TC6_CH1, 1, TCC3_CH1, 1, TCC0_CH5, 5},
+ { PORTB, 18, NOT_ON_TIMER, 0, TCC1_CH0, 0, NOT_ON_TIMER, 0}, // PDEC0
+ { PORTB, 19, NOT_ON_TIMER, 0, TCC1_CH1, 1, NOT_ON_TIMER, 0}, // PDEC1
+ { PORTB, 20, NOT_ON_TIMER, 0, TCC1_CH2, 2, NOT_ON_TIMER, 0}, // PDEC2
+ { PORTB, 21, NOT_ON_TIMER, 0, TCC1_CH3, 3, NOT_ON_TIMER, 0},
+ { PORTA, 20, TC7_CH0, 0, TCC1_CH0, 4, TCC0_CH0, 0},
+ { PORTA, 21, TC7_CH1, 1, TCC1_CH1, 5, TCC0_CH1, 1},
+ { PORTA, 22, TC4_CH0, 0, TCC1_CH2, 6, TCC0_CH2, 2},
+ { PORTA, 23, TC4_CH1, 1, TCC1_CH3, 7, TCC0_CH3, 3},
+ { PORTA, 24, TC5_CH0, 0, TCC2_CH2, 2, NOT_ON_TIMER, 0}, // PDEC0
+ { PORTA, 25, TC5_CH1, 1, NOT_ON_TIMER, 0, NOT_ON_TIMER, 0}, // PDEC1
+ { PORTB, 22, TC7_CH0, 0, NOT_ON_TIMER, 0, NOT_ON_TIMER, 0}, // PDEC2
+ { PORTB, 23, TC7_CH1, 1, NOT_ON_TIMER, 0, NOT_ON_TIMER, 0}, // PDEC0
+ { PORTB, 24, NOT_ON_TIMER, 0, NOT_ON_TIMER, 0, NOT_ON_TIMER, 0}, // PDEC1
+ { PORTB, 25, NOT_ON_TIMER, 0, NOT_ON_TIMER, 0, NOT_ON_TIMER, 0}, // PDEC2
+ { PORTB, 26, NOT_ON_TIMER, 0, TCC1_CH2, 2, NOT_ON_TIMER, 0},
+ { PORTB, 27, NOT_ON_TIMER, 0, TCC1_CH3, 3, NOT_ON_TIMER, 0},
+ { PORTB, 28, NOT_ON_TIMER, 0, TCC1_CH0, 4, NOT_ON_TIMER, 0},
+ { PORTB, 29, NOT_ON_TIMER, 0, TCC1_CH1, 5, NOT_ON_TIMER, 0},
+ // PC24-PC28, PA27, RESET -> no TC/TCC peripherals
+ { PORTA, 30, TC6_CH0, 0, TCC2_CH0, 0, NOT_ON_TIMER, 0},
+ { PORTA, 31, TC6_CH1, 1, TCC2_CH1, 1, NOT_ON_TIMER, 0},
+ { PORTB, 30, TC0_CH0, 0, TCC4_CH0, 0, TCC0_CH0, 6},
+ { PORTB, 31, TC0_CH1, 1, TCC4_CH1, 1, TCC0_CH1, 7},
+ // PC30, PC31 -> no TC/TCC peripherals
+ { PORTB, 0, TC7_CH0, 0, NOT_ON_TIMER, 0, NOT_ON_TIMER, 0},
+ { PORTB, 1, TC7_CH1, 1, NOT_ON_TIMER, 0, NOT_ON_TIMER, 0},
+ { PORTB, 2, TC6_CH0, 0, TCC2_CH2, 2, NOT_ON_TIMER, 0},
+
+};
+
+wo_association ASSOCIATION_NOT_FOUND = { NOT_A_PORT, 0, NOT_ON_TIMER, 0, NOT_ON_TIMER, 0, NOT_ON_TIMER, 0};
+
+#ifndef TCC3_CC_NUM
+uint8_t TCC_CHANNEL_COUNT[] = { TCC0_CC_NUM, TCC1_CC_NUM, TCC2_CC_NUM };
+#else
+uint8_t TCC_CHANNEL_COUNT[] = { TCC0_CC_NUM, TCC1_CC_NUM, TCC2_CC_NUM, TCC3_CC_NUM, TCC4_CC_NUM };
+#endif
+
+
+struct wo_association& getWOAssociation(EPortType port, uint32_t pin) {
+ for (int i=0;i>pin_position)&0x01)==0x1?PIO_TCC_PDEC:PIO_TIMER_ALT;
+}
+
+
+
+void syncTCC(Tcc* TCCx) {
+ while (TCCx->SYNCBUSY.reg & TCC_SYNCBUSY_MASK);
+}
+
+
+
+
+void writeSAMDDutyCycle(tccConfiguration* info, float dc) {
+ uint8_t tccn = GetTCNumber(info->tcc.chaninfo);
+ uint8_t chan = GetTCChannelNumber(info->tcc.chaninfo);
+ if (tccntcc.chaninfo);
+ // set via CCBUF
+// while ( (tcc->SYNCBUSY.vec.CC & (0x1< 0 );
+ tcc->CCBUF[chan].reg = (uint32_t)((info->pwm_res-1) * dc); // TODO pwm frequency!
+ }
+ else {
+ // we don't support the TC channels on SAMD51, isn't worth it.
+ }
+}
+
+
+#define DPLL_CLOCK_NUM 2 // use GCLK2
+#define PWM_CLOCK_NUM 3 // use GCLK3
+
+
+/**
+ * Configure Clock 4 - we want all simplefoc PWMs to use the same clock. This ensures that
+ * any compatible pin combination can be used without having to worry about configuring different
+ * clocks.
+ */
+void configureSAMDClock() {
+ if (!SAMDClockConfigured) {
+ SAMDClockConfigured = true; // mark clock as configured
+ for (int i=0;iGENCTRL[DPLL_CLOCK_NUM].reg = GCLK_GENCTRL_GENEN | GCLK_GENCTRL_DIV(1)
+ // | GCLK_GENCTRL_SRC(GCLK_GENCTRL_SRC_DFLL_Val);
+ // while (GCLK->SYNCBUSY.vec.GENCTRL&(0x1<PCHCTRL[1].reg = GCLK_PCHCTRL_GEN(DPLL_CLOCK_NUM)|GCLK_PCHCTRL_CHEN;
+ // while (GCLK->SYNCBUSY.vec.GENCTRL&(0x1<Dpll[0].DPLLCTRLA.bit.ENABLE = 0;
+ // while (OSCCTRL->Dpll[0].DPLLSYNCBUSY.reg!=0x0);
+
+ // OSCCTRL->Dpll[0].DPLLCTRLB.bit.REFCLK = OSCCTRL_DPLLCTRLB_REFCLK_GCLK_Val;
+ // while (OSCCTRL->Dpll[0].DPLLSYNCBUSY.reg!=0x0);
+ // OSCCTRL->Dpll[0].DPLLRATIO.reg = 3;
+ // while (OSCCTRL->Dpll[0].DPLLSYNCBUSY.reg!=0x0);
+
+ // OSCCTRL->Dpll[0].DPLLCTRLA.bit.ENABLE = 1;
+ // while (OSCCTRL->Dpll[0].DPLLSYNCBUSY.reg!=0x0);
+
+ GCLK->GENCTRL[PWM_CLOCK_NUM].bit.GENEN = 0;
+ while (GCLK->SYNCBUSY.vec.GENCTRL&(0x1<GENCTRL[PWM_CLOCK_NUM].reg = GCLK_GENCTRL_GENEN | GCLK_GENCTRL_DIV(1) | GCLK_GENCTRL_IDC
+ //| GCLK_GENCTRL_SRC(GCLK_GENCTRL_SRC_DFLL_Val);
+ | GCLK_GENCTRL_SRC(GCLK_GENCTRL_SRC_DPLL0_Val);
+ while (GCLK->SYNCBUSY.vec.GENCTRL&(0x1<PCHCTRL[GCLK_CLKCTRL_ID_ofthistcc].reg = GCLK_PCHCTRL_GEN(PWM_CLOCK_NUM)|GCLK_PCHCTRL_CHEN;
+ while (GCLK->SYNCBUSY.vec.GENCTRL&(0x1<CTRLA.bit.ENABLE = 0; //switch off tcc
+ while ( tcc->SYNCBUSY.bit.ENABLE == 1 ); // wait for sync
+
+ uint8_t invenMask = ~(1<DRVCTRL.vec.INVEN = (tcc->DRVCTRL.vec.INVEN&invenMask)|invenVal;
+ syncTCC(tcc); // wait for sync
+
+ // work out pwm resolution for desired frequency and constrain to max/min values
+ long pwm_resolution = (SIMPLEFOC_SAMD51_DPLL_FREQ/2) / pwm_frequency;
+ if (pwm_resolution>SIMPLEFOC_SAMD_MAX_PWM_RESOLUTION)
+ pwm_resolution = SIMPLEFOC_SAMD_MAX_PWM_RESOLUTION;
+ if (pwm_resolution0.0) {
+ tcc->WEXCTRL.vec.DTIEN |= (1<WEXCTRL.bit.DTLS = hw6pwm*(pwm_resolution-1);
+ tcc->WEXCTRL.bit.DTHS = hw6pwm*(pwm_resolution-1);
+ syncTCC(tcc); // wait for sync
+ }
+
+ if (!tccConfigured[tccConfig.tcc.tccn]) {
+ tcc->WAVE.reg |= TCC_WAVE_POL(0xF)|TCC_WAVE_WAVEGEN_DSTOP; // Set wave form configuration - TODO check this... why set like this?
+ while ( tcc->SYNCBUSY.bit.WAVE == 1 ); // wait for sync
+
+ tcc->PER.reg = pwm_resolution - 1; // Set counter Top using the PER register
+ while ( tcc->SYNCBUSY.bit.PER == 1 ); // wait for sync
+
+ // set all channels to 0%
+ for (int i=0;iCC[i].reg = 0; // start off at 0% duty cycle
+ uint32_t chanbit = 0x1<<(TCC_SYNCBUSY_CC0_Pos+i);
+ while ( (tcc->SYNCBUSY.reg & chanbit) > 0 );
+ }
+ }
+
+ // Enable TCC
+ tcc->CTRLA.reg |= TCC_CTRLA_ENABLE | TCC_CTRLA_PRESCALER_DIV1; //48Mhz/1=48Mhz/2(up/down)=24MHz/1024=24KHz
+ while ( tcc->SYNCBUSY.bit.ENABLE == 1 ); // wait for sync
+
+#if defined(SIMPLEFOC_SAMD_DEBUG) && !defined(SIMPLEFOC_DISABLE_DEBUG)
+ SimpleFOCDebug::print("SAMD: (Re-)Initialized TCC ");
+ SimpleFOCDebug::print(tccConfig.tcc.tccn);
+ SimpleFOCDebug::print("-");
+ SimpleFOCDebug::print(tccConfig.tcc.chan);
+ SimpleFOCDebug::print("[");
+ SimpleFOCDebug::print(tccConfig.wo);
+ SimpleFOCDebug::print("] pwm res ");
+ SimpleFOCDebug::print((int)pwm_resolution);
+ SimpleFOCDebug::println();
+#endif
+ }
+ else if (tccConfig.tcc.tccn>=TCC_INST_NUM) {
+ //Tc* tc = (Tc*)GetTC(tccConfig.tcc.chaninfo);
+
+ // disable
+ // tc->COUNT8.CTRLA.bit.ENABLE = 0;
+ // while ( tc->COUNT8.STATUS.bit.SYNCBUSY == 1 );
+ // // unfortunately we need the 8-bit counter mode to use the PER register...
+ // tc->COUNT8.CTRLA.reg |= TC_CTRLA_MODE_COUNT8 | TC_CTRLA_WAVEGEN_NPWM ;
+ // while ( tc->COUNT8.STATUS.bit.SYNCBUSY == 1 );
+ // // meaning prescaler of 8, since TC-Unit has no up/down mode, and has resolution of 250 rather than 1000...
+ // tc->COUNT8.CTRLA.bit.PRESCALER = TC_CTRLA_PRESCALER_DIV8_Val ;
+ // while ( tc->COUNT8.STATUS.bit.SYNCBUSY == 1 );
+ // // period is 250, period cannot be higher than 256!
+ // tc->COUNT8.PER.reg = SIMPLEFOC_SAMD_PWM_TC_RESOLUTION-1;
+ // while ( tc->COUNT8.STATUS.bit.SYNCBUSY == 1 );
+ // // initial duty cycle is 0
+ // tc->COUNT8.CC[tccConfig.tcc.chan].reg = 0;
+ // while ( tc->COUNT8.STATUS.bit.SYNCBUSY == 1 );
+ // // enable
+ // tc->COUNT8.CTRLA.bit.ENABLE = 1;
+ // while ( tc->COUNT8.STATUS.bit.SYNCBUSY == 1 );
+
+ #ifdef SIMPLEFOC_SAMD_DEBUG
+ SIMPLEFOC_DEBUG("SAMD: Not initialized: TC ", tccConfig.tcc.tccn);
+ SIMPLEFOC_DEBUG("SAMD: TC units not supported on SAMD51");
+ #endif
+ }
+
+ // set as configured
+ tccConfigured[tccConfig.tcc.tccn] = true;
+
+
+}
+
+
+
+
+
+#endif
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/drivers/hardware_specific/samd/samd_mcu.cpp b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/drivers/hardware_specific/samd/samd_mcu.cpp
new file mode 100644
index 0000000..f697891
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/drivers/hardware_specific/samd/samd_mcu.cpp
@@ -0,0 +1,914 @@
+
+
+
+#include "./samd_mcu.h"
+
+#if defined(_SAMD21_)||defined(_SAMD51_)||defined(_SAME51_)
+
+
+
+/**
+ * Global state
+ */
+tccConfiguration tccPinConfigurations[SIMPLEFOC_SAMD_MAX_TCC_PINCONFIGURATIONS];
+uint8_t numTccPinConfigurations = 0;
+bool SAMDClockConfigured = false;
+bool tccConfigured[TCC_INST_NUM+TC_INST_NUM];
+
+
+
+
+
+/**
+ * Attach the TCC to the pin
+ */
+bool attachTCC(tccConfiguration& tccConfig) {
+ if (numTccPinConfigurations>=SIMPLEFOC_SAMD_MAX_TCC_PINCONFIGURATIONS)
+ return false;
+ pinMode(tccConfig.pin, OUTPUT);
+
+ pinPeripheral(tccConfig.pin, tccConfig.peripheral);
+ tccPinConfigurations[numTccPinConfigurations++] = tccConfig;
+ return true;
+}
+
+
+
+
+
+int getPermutationNumber(int pins) {
+ int num = 1;
+ for (int i=0;i=TCC_INST_NUM)
+ return false;
+
+ if (pinAh.tcc.chan==pinBh.tcc.chan || pinAh.tcc.chan==pinBl.tcc.chan || pinAh.tcc.chan==pinCh.tcc.chan || pinAh.tcc.chan==pinCl.tcc.chan)
+ return false;
+ if (pinBh.tcc.chan==pinCh.tcc.chan || pinBh.tcc.chan==pinCl.tcc.chan)
+ return false;
+ if (pinAl.tcc.chan==pinBh.tcc.chan || pinAl.tcc.chan==pinBl.tcc.chan || pinAl.tcc.chan==pinCh.tcc.chan || pinAl.tcc.chan==pinCl.tcc.chan)
+ return false;
+ if (pinBl.tcc.chan==pinCh.tcc.chan || pinBl.tcc.chan==pinCl.tcc.chan)
+ return false;
+
+ if (pinAh.tcc.chan!=pinAl.tcc.chan || pinBh.tcc.chan!=pinBl.tcc.chan || pinCh.tcc.chan!=pinCl.tcc.chan)
+ return false;
+ if (pinAh.wo==pinAl.wo || pinBh.wo==pinBl.wo || pinCh.wo!=pinCl.wo)
+ return false;
+
+ return true;
+}
+
+
+
+
+bool checkPeripheralPermutationCompatible(tccConfiguration pins[], uint8_t num) {
+ for (int i=0;i=TCC_INST_NUM || pinAl.tcc.tccn>=TCC_INST_NUM || pinBh.tcc.tccn>=TCC_INST_NUM
+ || pinBl.tcc.tccn>=TCC_INST_NUM || pinCh.tcc.tccn>=TCC_INST_NUM || pinCl.tcc.tccn>=TCC_INST_NUM)
+ return false;
+
+ // check we're not in use
+ if (inUse(pinAh) || inUse(pinAl) || inUse(pinBh) || inUse(pinBl) || inUse(pinCh) || inUse(pinCl))
+ return false;
+
+ // check pins are all different tccs/channels
+ if (pinAh.tcc.chaninfo==pinBh.tcc.chaninfo || pinAh.tcc.chaninfo==pinBl.tcc.chaninfo || pinAh.tcc.chaninfo==pinCh.tcc.chaninfo || pinAh.tcc.chaninfo==pinCl.tcc.chaninfo)
+ return false;
+ if (pinAl.tcc.chaninfo==pinBh.tcc.chaninfo || pinAl.tcc.chaninfo==pinBl.tcc.chaninfo || pinAl.tcc.chaninfo==pinCh.tcc.chaninfo || pinAl.tcc.chaninfo==pinCl.tcc.chaninfo)
+ return false;
+ if (pinBh.tcc.chaninfo==pinCh.tcc.chaninfo || pinBh.tcc.chaninfo==pinCl.tcc.chaninfo)
+ return false;
+ if (pinBl.tcc.chaninfo==pinCh.tcc.chaninfo || pinBl.tcc.chaninfo==pinCl.tcc.chaninfo)
+ return false;
+
+ // check H/L pins are on same timer
+ if (pinAh.tcc.tccn!=pinAl.tcc.tccn || pinBh.tcc.tccn!=pinBl.tcc.tccn || pinCh.tcc.tccn!=pinCl.tcc.tccn)
+ return false;
+
+ // check H/L pins aren't on both the same timer and wo
+ if (pinAh.wo==pinAl.wo || pinBh.wo==pinBl.wo || pinCh.wo==pinCl.wo)
+ return false;
+
+ return true;
+}
+
+
+
+
+
+int checkHardware6PWM(const int pinA_h, const int pinA_l, const int pinB_h, const int pinB_l, const int pinC_h, const int pinC_l) {
+ for (int i=0;i<64;i++) {
+ tccConfiguration pinAh = getTCCChannelNr(pinA_h, getPeripheralOfPermutation(i, 0));
+ tccConfiguration pinAl = getTCCChannelNr(pinA_l, getPeripheralOfPermutation(i, 1));
+ tccConfiguration pinBh = getTCCChannelNr(pinB_h, getPeripheralOfPermutation(i, 2));
+ tccConfiguration pinBl = getTCCChannelNr(pinB_l, getPeripheralOfPermutation(i, 3));
+ tccConfiguration pinCh = getTCCChannelNr(pinC_h, getPeripheralOfPermutation(i, 4));
+ tccConfiguration pinCl = getTCCChannelNr(pinC_l, getPeripheralOfPermutation(i, 5));
+ if (checkPeripheralPermutationSameTCC6(pinAh, pinAl, pinBh, pinBl, pinCh, pinCl))
+ return i;
+ }
+ return -1;
+}
+
+
+
+
+int checkSoftware6PWM(const int pinA_h, const int pinA_l, const int pinB_h, const int pinB_l, const int pinC_h, const int pinC_l) {
+ for (int i=0;i<64;i++) {
+ tccConfiguration pinAh = getTCCChannelNr(pinA_h, getPeripheralOfPermutation(i, 0));
+ tccConfiguration pinAl = getTCCChannelNr(pinA_l, getPeripheralOfPermutation(i, 1));
+ tccConfiguration pinBh = getTCCChannelNr(pinB_h, getPeripheralOfPermutation(i, 2));
+ tccConfiguration pinBl = getTCCChannelNr(pinB_l, getPeripheralOfPermutation(i, 3));
+ tccConfiguration pinCh = getTCCChannelNr(pinC_h, getPeripheralOfPermutation(i, 4));
+ tccConfiguration pinCl = getTCCChannelNr(pinC_l, getPeripheralOfPermutation(i, 5));
+ if (checkPeripheralPermutationCompatible6(pinAh, pinAl, pinBh, pinBl, pinCh, pinCl))
+ return i;
+ }
+ return -1;
+}
+
+
+
+int scorePermutation(tccConfiguration pins[], uint8_t num) {
+ uint32_t usedtccs = 0;
+ for (int i=0;i>1;
+ }
+ for (int i=0;i>1;
+ }
+ return score;
+}
+
+
+
+
+
+
+
+
+int checkPermutations(uint8_t num, int pins[], bool (*checkFunc)(tccConfiguration[], uint8_t) ) {
+ tccConfiguration tccConfs[num];
+ int best = -1;
+ int bestscore = 1000000;
+ for (int i=0;i<(0x1<pwm_res = tccConfs[0].pwm_res;
+ getTccPinConfiguration(pinB)->pwm_res = tccConfs[1].pwm_res;
+#ifdef SIMPLEFOC_SAMD_DEBUG
+ SIMPLEFOC_DEBUG("SAMD: Configured TCCs...");
+#endif
+
+ SAMDHardwareDriverParams* params = new SAMDHardwareDriverParams {
+ .tccPinConfigurations = { getTccPinConfiguration(pinA), getTccPinConfiguration(pinB) },
+ .pwm_frequency = (uint32_t)pwm_frequency
+ }; // Someone with a stepper-setup who can test it?
+ return params;
+}
+
+
+
+
+
+
+
+
+
+
+
+
+/**
+ * Configuring PWM frequency, resolution and alignment
+ * - BLDC driver - 3PWM setting
+ * - hardware specific
+ *
+ * SAMD21 will support up to 2 BLDC motors in 3-PWM:
+ * one on TCC0 using 3 of the channels 0,1,2 or 3
+ * one on TCC3 using 3 of the channels 0,1,2 or 3
+ * i.e. 8 different pins can be used, but only 4 different signals (WO[x]) on those 8 pins
+ * WO[0] and WO[4] are the same
+ * WO[1] and WO[5] are the same
+ * WO[2] and WO[6] are the same
+ * WO[3] and WO[7] are the same
+ *
+ * If you're on the Arduino Nano33 IoT, please see the Nano33 IoT pinout diagram to see which TCC0/WO[x]
+ * signal is on which pin of the Nano. You can drive one motor on TCC0. For other boards, consult their documentation.
+ *
+ * Note:
+ * That's if we want to keep the signals strictly in sync.
+ *
+ * If we can accept out-of-sync PWMs on the different phases, we could drive up to 4 BLDCs in 3-PWM mode,
+ * using all the TCC channels. (TCC0 & TCC3 - 4 channels each, TCC1 & TCC2 - 2 channels each)
+ *
+ * All channels will use the same resolution, prescaler and clock, but they will have different start-times leading
+ * to misaligned signals.
+ *
+ *
+ * @param pwm_frequency - frequency in hertz - if applicable
+ * @param pinA pinA bldc driver
+ * @param pinB pinB bldc driver
+ * @param pinC pinC bldc driver
+ */
+void* _configure3PWM(long pwm_frequency, const int pinA, const int pinB, const int pinC) {
+#ifdef SIMPLEFOC_SAMD_DEBUG
+ printAllPinInfos();
+#endif
+ int pins[3] = { pinA, pinB, pinC };
+ int compatibility = checkPermutations(3, pins, checkPeripheralPermutationCompatible);
+ if (compatibility<0) {
+ // no result!
+#ifdef SIMPLEFOC_SAMD_DEBUG
+ SIMPLEFOC_DEBUG("SAMD: Bad pin combination!");
+#endif
+ return SIMPLEFOC_DRIVER_INIT_FAILED;
+ }
+
+ tccConfiguration tccConfs[3] = { getTCCChannelNr(pinA, getPeripheralOfPermutation(compatibility, 0)),
+ getTCCChannelNr(pinB, getPeripheralOfPermutation(compatibility, 1)),
+ getTCCChannelNr(pinC, getPeripheralOfPermutation(compatibility, 2)) };
+
+
+#ifdef SIMPLEFOC_SAMD_DEBUG
+ SIMPLEFOC_DEBUG("SAMD: Found configuration: score=", scorePermutation(tccConfs, 3));
+ printTCCConfiguration(tccConfs[0]);
+ printTCCConfiguration(tccConfs[1]);
+ printTCCConfiguration(tccConfs[2]);
+#endif
+
+ // attach pins to timer peripherals
+ attachTCC(tccConfs[0]); // in theory this can fail, but there is no way to signal it...
+ attachTCC(tccConfs[1]);
+ attachTCC(tccConfs[2]);
+#ifdef SIMPLEFOC_SAMD_DEBUG
+ SIMPLEFOC_DEBUG("SAMD: Attached pins...");
+#endif
+
+ // set up clock - Note: if we did this right it should be possible to get all TCC units synchronized?
+ // e.g. attach all the timers, start them, and then start the clock... but this would require API-changes in SimpleFOC...
+ configureSAMDClock();
+
+ if (pwm_frequency==NOT_SET) {
+ // use default frequency
+ pwm_frequency = SIMPLEFOC_SAMD_DEFAULT_PWM_FREQUENCY_HZ;
+ }
+
+ // configure the TCC (waveform, top-value, pre-scaler = frequency)
+ configureTCC(tccConfs[0], pwm_frequency);
+ configureTCC(tccConfs[1], pwm_frequency);
+ configureTCC(tccConfs[2], pwm_frequency);
+ getTccPinConfiguration(pinA)->pwm_res = tccConfs[0].pwm_res;
+ getTccPinConfiguration(pinB)->pwm_res = tccConfs[1].pwm_res;
+ getTccPinConfiguration(pinC)->pwm_res = tccConfs[2].pwm_res;
+#ifdef SIMPLEFOC_SAMD_DEBUG
+ SIMPLEFOC_DEBUG("SAMD: Configured TCCs...");
+#endif
+
+ return new SAMDHardwareDriverParams {
+ .tccPinConfigurations = { getTccPinConfiguration(pinA), getTccPinConfiguration(pinB), getTccPinConfiguration(pinC) },
+ .pwm_frequency = (uint32_t)pwm_frequency
+ };
+
+}
+
+
+
+
+
+
+
+
+/**
+ * Configuring PWM frequency, resolution and alignment
+ * - Stepper driver - 4PWM setting
+ * - hardware specific
+ *
+ * @param pwm_frequency - frequency in hertz - if applicable
+ * @param pin1A pin1A stepper driver
+ * @param pin1B pin1B stepper driver
+ * @param pin2A pin2A stepper driver
+ * @param pin2B pin2B stepper driver
+ */
+void* _configure4PWM(long pwm_frequency, const int pin1A, const int pin1B, const int pin2A, const int pin2B) {
+#ifdef SIMPLEFOC_SAMD_DEBUG
+ printAllPinInfos();
+#endif
+ int pins[4] = { pin1A, pin1B, pin2A, pin2B };
+ int compatibility = checkPermutations(4, pins, checkPeripheralPermutationCompatible);
+ if (compatibility<0) {
+ // no result!
+#ifdef SIMPLEFOC_SAMD_DEBUG
+ SIMPLEFOC_DEBUG("SAMD: Bad pin combination!");
+#endif
+ return SIMPLEFOC_DRIVER_INIT_FAILED;
+ }
+
+ tccConfiguration tccConfs[4] = { getTCCChannelNr(pin1A, getPeripheralOfPermutation(compatibility, 0)),
+ getTCCChannelNr(pin1B, getPeripheralOfPermutation(compatibility, 1)),
+ getTCCChannelNr(pin2A, getPeripheralOfPermutation(compatibility, 2)),
+ getTCCChannelNr(pin2B, getPeripheralOfPermutation(compatibility, 3)) };
+
+
+#ifdef SIMPLEFOC_SAMD_DEBUG
+ SIMPLEFOC_DEBUG("SAMD: Found configuration: score=", scorePermutation(tccConfs, 4));
+ printTCCConfiguration(tccConfs[0]);
+ printTCCConfiguration(tccConfs[1]);
+ printTCCConfiguration(tccConfs[2]);
+ printTCCConfiguration(tccConfs[3]);
+#endif
+
+ // attach pins to timer peripherals
+ attachTCC(tccConfs[0]); // in theory this can fail, but there is no way to signal it...
+ attachTCC(tccConfs[1]);
+ attachTCC(tccConfs[2]);
+ attachTCC(tccConfs[3]);
+#ifdef SIMPLEFOC_SAMD_DEBUG
+ SIMPLEFOC_DEBUG("SAMD: Attached pins...");
+#endif
+
+ // set up clock - Note: if we did this right it should be possible to get all TCC units synchronized?
+ // e.g. attach all the timers, start them, and then start the clock... but this would require API-changes in SimpleFOC...
+ configureSAMDClock();
+
+ if (pwm_frequency==NOT_SET) {
+ // use default frequency
+ pwm_frequency = SIMPLEFOC_SAMD_DEFAULT_PWM_FREQUENCY_HZ;
+ }
+
+ // configure the TCC (waveform, top-value, pre-scaler = frequency)
+ configureTCC(tccConfs[0], pwm_frequency);
+ configureTCC(tccConfs[1], pwm_frequency);
+ configureTCC(tccConfs[2], pwm_frequency);
+ configureTCC(tccConfs[3], pwm_frequency);
+ getTccPinConfiguration(pin1A)->pwm_res = tccConfs[0].pwm_res;
+ getTccPinConfiguration(pin2A)->pwm_res = tccConfs[1].pwm_res;
+ getTccPinConfiguration(pin1B)->pwm_res = tccConfs[2].pwm_res;
+ getTccPinConfiguration(pin2B)->pwm_res = tccConfs[3].pwm_res;
+#ifdef SIMPLEFOC_SAMD_DEBUG
+ SIMPLEFOC_DEBUG("SAMD: Configured TCCs...");
+#endif
+
+ return new SAMDHardwareDriverParams {
+ .tccPinConfigurations = { getTccPinConfiguration(pin1A), getTccPinConfiguration(pin1B), getTccPinConfiguration(pin2A), getTccPinConfiguration(pin2B) },
+ .pwm_frequency = (uint32_t)pwm_frequency
+ };
+}
+
+
+
+
+
+
+
+
+
+/**
+ * Configuring PWM frequency, resolution and alignment
+ * - BLDC driver - 6PWM setting
+ * - hardware specific
+ *
+ * SAMD21 will support up to 2 BLDC motors in 6-PWM:
+ * one on TCC0 using 3 of the channels 0,1,2 or 3
+ * one on TCC3 using 3 of the channels 0,1,2 or 3
+ * i.e. 6 out of 8 pins must be used, in the following high/low side pairs:
+ * WO[0] & WO[4] (high side & low side)
+ * WO[1] & WO[5]
+ * WO[2] & WO[6]
+ * WO[3] & WO[7]
+ *
+ * If you're on the Arduino Nano33 IoT, please see the Nano33 IoT pinout diagram to see which TCC0/WO[x]
+ * signal is on which pin of the Nano. You can drive 1 BLDC on TCC0. For other boards, consult their documentation.
+ *
+ *
+ * @param pwm_frequency - frequency in hertz - if applicable
+ * @param dead_zone duty cycle protection zone [0, 1] - both low and high side low - if applicable
+ * @param pinA_h pinA high-side bldc driver
+ * @param pinA_l pinA low-side bldc driver
+ * @param pinB_h pinA high-side bldc driver
+ * @param pinB_l pinA low-side bldc driver
+ * @param pinC_h pinA high-side bldc driver
+ * @param pinC_l pinA low-side bldc driver
+ *
+ * @return 0 if config good, -1 if failed
+ */
+void* _configure6PWM(long pwm_frequency, float dead_zone, const int pinA_h, const int pinA_l, const int pinB_h, const int pinB_l, const int pinC_h, const int pinC_l) {
+ // we want to use a TCC channel with 1 non-inverted and 1 inverted output for each phase, with dead-time insertion
+#ifdef SIMPLEFOC_SAMD_DEBUG
+ printAllPinInfos();
+#endif
+ int compatibility = checkHardware6PWM(pinA_h, pinA_l, pinB_h, pinB_l, pinC_h, pinC_l);
+ if (compatibility<0) {
+ compatibility = checkSoftware6PWM(pinA_h, pinA_l, pinB_h, pinB_l, pinC_h, pinC_l);
+ if (compatibility<0) {
+ // no result!
+#ifdef SIMPLEFOC_SAMD_DEBUG
+ SIMPLEFOC_DEBUG("SAMD: Bad pin combination!");
+#endif
+ return SIMPLEFOC_DRIVER_INIT_FAILED;
+ }
+ }
+
+ tccConfiguration pinAh = getTCCChannelNr(pinA_h, getPeripheralOfPermutation(compatibility, 0));
+ tccConfiguration pinAl = getTCCChannelNr(pinA_l, getPeripheralOfPermutation(compatibility, 1));
+ tccConfiguration pinBh = getTCCChannelNr(pinB_h, getPeripheralOfPermutation(compatibility, 2));
+ tccConfiguration pinBl = getTCCChannelNr(pinB_l, getPeripheralOfPermutation(compatibility, 3));
+ tccConfiguration pinCh = getTCCChannelNr(pinC_h, getPeripheralOfPermutation(compatibility, 4));
+ tccConfiguration pinCl = getTCCChannelNr(pinC_l, getPeripheralOfPermutation(compatibility, 5));
+
+#ifdef SIMPLEFOC_SAMD_DEBUG
+ SIMPLEFOC_DEBUG("SAMD: Found configuration: ");
+ printTCCConfiguration(pinAh);
+ printTCCConfiguration(pinAl);
+ printTCCConfiguration(pinBh);
+ printTCCConfiguration(pinBl);
+ printTCCConfiguration(pinCh);
+ printTCCConfiguration(pinCl);
+#endif
+
+ // attach pins to timer peripherals
+ bool allAttached = true;
+ allAttached |= attachTCC(pinAh); // in theory this can fail, but there is no way to signal it...
+ allAttached |= attachTCC(pinAl);
+ allAttached |= attachTCC(pinBh);
+ allAttached |= attachTCC(pinBl);
+ allAttached |= attachTCC(pinCh);
+ allAttached |= attachTCC(pinCl);
+ if (!allAttached)
+ return SIMPLEFOC_DRIVER_INIT_FAILED;
+#ifdef SIMPLEFOC_SAMD_DEBUG
+ SIMPLEFOC_DEBUG("SAMD: Attached pins...");
+#endif
+ // set up clock - if we did this right it should be possible to get all TCC units synchronized?
+ // e.g. attach all the timers, start them, and then start the clock... but this would require API changes in SimpleFOC driver API
+ configureSAMDClock();
+
+ if (pwm_frequency==NOT_SET) {
+ // use default frequency
+ pwm_frequency = SIMPLEFOC_SAMD_DEFAULT_PWM_FREQUENCY_HZ;
+ }
+
+ // configure the TCC(s)
+ configureTCC(pinAh, pwm_frequency, false, (pinAh.tcc.chaninfo==pinAl.tcc.chaninfo)?dead_zone:-1);
+ if ((pinAh.tcc.chaninfo!=pinAl.tcc.chaninfo))
+ configureTCC(pinAl, pwm_frequency, true, -1.0);
+ configureTCC(pinBh, pwm_frequency, false, (pinBh.tcc.chaninfo==pinBl.tcc.chaninfo)?dead_zone:-1);
+ if ((pinBh.tcc.chaninfo!=pinBl.tcc.chaninfo))
+ configureTCC(pinBl, pwm_frequency, true, -1.0);
+ configureTCC(pinCh, pwm_frequency, false, (pinCh.tcc.chaninfo==pinCl.tcc.chaninfo)?dead_zone:-1);
+ if ((pinCh.tcc.chaninfo!=pinCl.tcc.chaninfo))
+ configureTCC(pinCl, pwm_frequency, true, -1.0);
+ getTccPinConfiguration(pinA_h)->pwm_res = pinAh.pwm_res;
+ getTccPinConfiguration(pinA_l)->pwm_res = pinAh.pwm_res; // use the high phase resolution, in case we didn't set it
+ getTccPinConfiguration(pinB_h)->pwm_res = pinBh.pwm_res;
+ getTccPinConfiguration(pinB_l)->pwm_res = pinBh.pwm_res;
+ getTccPinConfiguration(pinC_h)->pwm_res = pinCh.pwm_res;
+ getTccPinConfiguration(pinC_l)->pwm_res = pinCh.pwm_res;
+#ifdef SIMPLEFOC_SAMD_DEBUG
+ SIMPLEFOC_DEBUG("SAMD: Configured TCCs...");
+#endif
+
+ return new SAMDHardwareDriverParams {
+ .tccPinConfigurations = { getTccPinConfiguration(pinA_h), getTccPinConfiguration(pinA_l), getTccPinConfiguration(pinB_h), getTccPinConfiguration(pinB_l), getTccPinConfiguration(pinC_h), getTccPinConfiguration(pinC_l) },
+ .pwm_frequency = (uint32_t)pwm_frequency,
+ .dead_zone = dead_zone,
+ };
+}
+
+
+
+
+/**
+ * Function setting the duty cycle to the pwm pin (ex. analogWrite())
+ * - Stepper driver - 2PWM setting
+ * - hardware specific
+ *
+ * @param dc_a duty cycle phase A [0, 1]
+ * @param dc_b duty cycle phase B [0, 1]
+ * @param pinA phase A hardware pin number
+ * @param pinB phase B hardware pin number
+ */
+void _writeDutyCycle2PWM(float dc_a, float dc_b, void* params) {
+ writeSAMDDutyCycle(((SAMDHardwareDriverParams*)params)->tccPinConfigurations[0], dc_a);
+ writeSAMDDutyCycle(((SAMDHardwareDriverParams*)params)->tccPinConfigurations[1], dc_b);
+ return;
+}
+
+
+
+
+
+/**
+ * Function setting the duty cycle to the pwm pin (ex. analogWrite())
+ * - BLDC driver - 3PWM setting
+ * - hardware specific
+ *
+ * @param dc_a duty cycle phase A [0, 1]
+ * @param dc_b duty cycle phase B [0, 1]
+ * @param dc_c duty cycle phase C [0, 1]
+ * @param pinA phase A hardware pin number
+ * @param pinB phase B hardware pin number
+ * @param pinC phase C hardware pin number
+ */
+void _writeDutyCycle3PWM(float dc_a, float dc_b, float dc_c, void* params) {
+ writeSAMDDutyCycle(((SAMDHardwareDriverParams*)params)->tccPinConfigurations[0], dc_a);
+ writeSAMDDutyCycle(((SAMDHardwareDriverParams*)params)->tccPinConfigurations[1], dc_b);
+ writeSAMDDutyCycle(((SAMDHardwareDriverParams*)params)->tccPinConfigurations[2], dc_c);
+ return;
+}
+
+
+
+
+/**
+ * Function setting the duty cycle to the pwm pin (ex. analogWrite())
+ * - Stepper driver - 4PWM setting
+ * - hardware specific
+ *
+ * @param dc_1a duty cycle phase 1A [0, 1]
+ * @param dc_1b duty cycle phase 1B [0, 1]
+ * @param dc_2a duty cycle phase 2A [0, 1]
+ * @param dc_2b duty cycle phase 2B [0, 1]
+ * @param pin1A phase 1A hardware pin number
+ * @param pin1B phase 1B hardware pin number
+ * @param pin2A phase 2A hardware pin number
+ * @param pin2B phase 2B hardware pin number
+ */
+void _writeDutyCycle4PWM(float dc_1a, float dc_1b, float dc_2a, float dc_2b, void* params){
+ writeSAMDDutyCycle(((SAMDHardwareDriverParams*)params)->tccPinConfigurations[0], dc_1a);
+ writeSAMDDutyCycle(((SAMDHardwareDriverParams*)params)->tccPinConfigurations[1], dc_1b);
+ writeSAMDDutyCycle(((SAMDHardwareDriverParams*)params)->tccPinConfigurations[2], dc_2a);
+ writeSAMDDutyCycle(((SAMDHardwareDriverParams*)params)->tccPinConfigurations[3], dc_2b);
+ return;
+}
+
+
+
+
+/**
+ * Function setting the duty cycle to the pwm pin (ex. analogWrite())
+ * - BLDC driver - 6PWM setting
+ * - hardware specific
+ *
+ * Note: dead-time must be setup in advance, so parameter "dead_zone" is ignored
+ * the low side pins are automatically driven by the SAMD DTI module, so it is enough to set the high-side
+ * duty cycle.
+ * No sanity checks are perfomed to ensure the pinA, pinB, pinC are the same pins you used in configure method...
+ * so use appropriately.
+ *
+ * @param dc_a duty cycle phase A [0, 1]
+ * @param dc_b duty cycle phase B [0, 1]
+ * @param dc_c duty cycle phase C [0, 1]
+ * @param dead_zone duty cycle protection zone [0, 1] - both low and high side low
+ * @param pinA_h phase A high-side hardware pin number
+ * @param pinA_l phase A low-side hardware pin number
+ * @param pinB_h phase B high-side hardware pin number
+ * @param pinB_l phase B low-side hardware pin number
+ * @param pinC_h phase C high-side hardware pin number
+ * @param pinC_l phase C low-side hardware pin number
+ *
+ */
+void _writeDutyCycle6PWM(float dc_a, float dc_b, float dc_c, PhaseState *phase_state, void* params){
+ SAMDHardwareDriverParams* p = (SAMDHardwareDriverParams*)params;
+ tccConfiguration* tcc1 = p->tccPinConfigurations[0];
+ tccConfiguration* tcc2 = p->tccPinConfigurations[1];
+ uint32_t pwm_res =p->tccPinConfigurations[0]->pwm_res;
+ if (tcc1->tcc.chaninfo!=tcc2->tcc.chaninfo) {
+ // low-side on a different pin of same TCC - do dead-time in software...
+ float ls = dc_a+(p->dead_zone * (pwm_res-1)); // TODO resolution!!!
+ if (ls>1.0) ls = 1.0f; // no off-time is better than too-short dead-time
+ writeSAMDDutyCycle(tcc1, dc_a);
+ writeSAMDDutyCycle(tcc2, ls);
+ }
+ else
+ writeSAMDDutyCycle(tcc1, dc_a); // dead-time is done is hardware, no need to set low side pin explicitly
+
+ tcc1 = p->tccPinConfigurations[2];
+ tcc2 = p->tccPinConfigurations[3];
+ if (tcc1->tcc.chaninfo!=tcc2->tcc.chaninfo) {
+ float ls = dc_b+(p->dead_zone * (pwm_res-1));
+ if (ls>1.0) ls = 1.0f; // no off-time is better than too-short dead-time
+ writeSAMDDutyCycle(tcc1, dc_b);
+ writeSAMDDutyCycle(tcc2, ls);
+ }
+ else
+ writeSAMDDutyCycle(tcc1, dc_b);
+
+ tcc1 = p->tccPinConfigurations[4];
+ tcc2 = p->tccPinConfigurations[5];
+ if (tcc1->tcc.chaninfo!=tcc2->tcc.chaninfo) {
+ float ls = dc_c+(p->dead_zone * (pwm_res-1));
+ if (ls>1.0) ls = 1.0f; // no off-time is better than too-short dead-time
+ writeSAMDDutyCycle(tcc1, dc_c);
+ writeSAMDDutyCycle(tcc2, ls);
+ }
+ else
+ writeSAMDDutyCycle(tcc1, dc_c);
+ return;
+
+ _UNUSED(phase_state);
+}
+
+
+
+
+#ifdef SIMPLEFOC_SAMD_DEBUG
+
+/**
+ * Prints a table of pin assignments for your SAMD MCU. Very useful since the
+ * board pinout descriptions and variant.cpp are usually quite wrong, and this
+ * saves you hours of cross-referencing with the datasheet.
+ */
+void printAllPinInfos() {
+ SimpleFOCDebug::println();
+ for (uint8_t pin=0;pin=TCC_INST_NUM)
+ SimpleFOCDebug::print(": TC Peripheral");
+ else
+ SimpleFOCDebug::print(": TCC Peripheral");
+ switch (info.peripheral) {
+ case PIO_TIMER:
+ SimpleFOCDebug::print(" E "); break;
+ case PIO_TIMER_ALT:
+ SimpleFOCDebug::print(" F "); break;
+#if defined(_SAMD51_)||defined(_SAME51_)
+ case PIO_TCC_PDEC:
+ SimpleFOCDebug::print(" G "); break;
+#endif
+ default:
+ SimpleFOCDebug::print(" ? "); break;
+ }
+ if (info.tcc.tccn>=0) {
+ SimpleFOCDebug::print(info.tcc.tccn);
+ SimpleFOCDebug::print("-");
+ SimpleFOCDebug::print(info.tcc.chan);
+ SimpleFOCDebug::print("[");
+ SimpleFOCDebug::print(info.wo);
+ SimpleFOCDebug::println("]");
+ }
+ else
+ SimpleFOCDebug::println(" None");
+}
+
+
+
+#endif
+
+#endif
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/drivers/hardware_specific/samd/samd_mcu.h b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/drivers/hardware_specific/samd/samd_mcu.h
new file mode 100644
index 0000000..74004d6
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/drivers/hardware_specific/samd/samd_mcu.h
@@ -0,0 +1,127 @@
+
+#ifndef SAMD_MCU_H
+#define SAMD_MCU_H
+
+
+// uncomment to enable debug output from SAMD driver
+// can set this as build-flag in Arduino IDE or PlatformIO
+// #define SIMPLEFOC_SAMD_DEBUG
+
+#include "../../hardware_api.h"
+
+
+#if defined(__SAME51J19A__) || defined(__ATSAME51J19A__)
+#ifndef _SAME51_
+#define _SAME51_
+#endif
+#endif
+
+
+#if defined(_SAMD21_)||defined(_SAMD51_)||defined(_SAME51_)
+
+
+#include "Arduino.h"
+#include "variant.h"
+#include "wiring_private.h"
+
+
+#ifndef SIMPLEFOC_SAMD_PWM_RESOLUTION
+#define SIMPLEFOC_SAMD_PWM_RESOLUTION 1000
+#endif
+
+#define SIMPLEFOC_SAMD_DEFAULT_PWM_FREQUENCY_HZ 24000
+// arbitrary maximum. On SAMD51 with 120MHz clock this means 2kHz minimum pwm frequency
+#define SIMPLEFOC_SAMD_MAX_PWM_RESOLUTION 30000
+// lets not go too low - 400 with clock speed of 120MHz on SAMD51 means 150kHz maximum PWM frequency...
+// 400 with 48MHz clock on SAMD21 means 60kHz maximum PWM frequency...
+#define SIMPLEFOC_SAMD_MIN_PWM_RESOLUTION 400
+// this is the most we can support on the TC units
+#define SIMPLEFOC_SAMD_PWM_TC_RESOLUTION 250
+
+#ifndef SIMPLEFOC_SAMD_MAX_TCC_PINCONFIGURATIONS
+#define SIMPLEFOC_SAMD_MAX_TCC_PINCONFIGURATIONS 24
+#endif
+
+
+
+struct tccConfiguration {
+ uint8_t pin;
+ EPioType peripheral; // 1=true, 0=false
+ uint8_t wo;
+ union tccChanInfo {
+ struct {
+ int8_t chan;
+ int8_t tccn;
+ };
+ uint16_t chaninfo;
+ } tcc;
+ uint16_t pwm_res;
+};
+
+
+
+
+
+
+struct wo_association {
+ EPortType port;
+ uint32_t pin;
+ ETCChannel tccE;
+ uint8_t woE;
+ ETCChannel tccF;
+ uint8_t woF;
+#if defined(_SAMD51_)||defined(_SAME51_)
+ ETCChannel tccG;
+ uint8_t woG;
+#endif
+};
+
+
+
+typedef struct SAMDHardwareDriverParams {
+ tccConfiguration* tccPinConfigurations[6];
+ uint32_t pwm_frequency;
+ float dead_zone;
+} SAMDHardwareDriverParams;
+
+
+
+
+#if defined(_SAMD21_)
+#define NUM_PIO_TIMER_PERIPHERALS 2
+#elif defined(_SAMD51_)||defined(_SAME51_)
+#define NUM_PIO_TIMER_PERIPHERALS 3
+#endif
+
+
+
+/**
+ * Global state
+ */
+extern struct wo_association WO_associations[];
+extern uint8_t TCC_CHANNEL_COUNT[];
+extern tccConfiguration tccPinConfigurations[SIMPLEFOC_SAMD_MAX_TCC_PINCONFIGURATIONS];
+extern uint8_t numTccPinConfigurations;
+extern bool SAMDClockConfigured;
+extern bool tccConfigured[TCC_INST_NUM+TC_INST_NUM];
+
+
+
+struct wo_association& getWOAssociation(EPortType port, uint32_t pin);
+void writeSAMDDutyCycle(tccConfiguration* info, float dc);
+void configureSAMDClock();
+void configureTCC(tccConfiguration& tccConfig, long pwm_frequency, bool negate=false, float hw6pwm=-1);
+__inline__ void syncTCC(Tcc* TCCx) __attribute__((always_inline, unused));
+EPioType getPeripheralOfPermutation(int permutation, int pin_position);
+
+#ifdef SIMPLEFOC_SAMD_DEBUG
+void printTCCConfiguration(tccConfiguration& info);
+void printAllPinInfos();
+#endif
+
+
+
+#endif
+
+
+#endif
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/drivers/hardware_specific/stm32/stm32_mcu.cpp b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/drivers/hardware_specific/stm32/stm32_mcu.cpp
new file mode 100644
index 0000000..4009281
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/drivers/hardware_specific/stm32/stm32_mcu.cpp
@@ -0,0 +1,1190 @@
+
+#include "../../hardware_api.h"
+#include "stm32_mcu.h"
+
+#if defined(_STM32_DEF_)
+
+#define SIMPLEFOC_STM32_DEBUG
+#pragma message("")
+#pragma message("SimpleFOC: compiling for STM32")
+#pragma message("")
+
+
+#ifdef SIMPLEFOC_STM32_DEBUG
+void printTimerCombination(int numPins, PinMap* timers[], int score);
+int getTimerNumber(int timerIndex);
+#endif
+
+
+
+
+#ifndef SIMPLEFOC_STM32_MAX_PINTIMERSUSED
+#define SIMPLEFOC_STM32_MAX_PINTIMERSUSED 12
+#endif
+int numTimerPinsUsed;
+PinMap* timerPinsUsed[SIMPLEFOC_STM32_MAX_PINTIMERSUSED];
+
+
+
+bool _getPwmState(void* params) {
+ // assume timers are synchronized and that there's at least one timer
+ HardwareTimer* pHT = ((STM32DriverParams*)params)->timers[0];
+ TIM_HandleTypeDef* htim = pHT->getHandle();
+
+ bool dir = __HAL_TIM_IS_TIM_COUNTING_DOWN(htim);
+
+ return dir;
+}
+
+
+// setting pwm to hardware pin - instead analogWrite()
+void _setPwm(HardwareTimer *HT, uint32_t channel, uint32_t value, int resolution)
+{
+ // TODO - remove commented code
+ // PinName pin = digitalPinToPinName(ulPin);
+ // TIM_TypeDef *Instance = (TIM_TypeDef *)pinmap_peripheral(pin, PinMap_PWM);
+ // uint32_t index = get_timer_index(Instance);
+ // HardwareTimer *HT = (HardwareTimer *)(HardwareTimer_Handle[index]->__this);
+
+ HT->setCaptureCompare(channel, value, (TimerCompareFormat_t)resolution);
+}
+
+
+
+
+int getLLChannel(PinMap* timer) {
+#if defined(TIM_CCER_CC1NE)
+ if (STM_PIN_INVERTED(timer->function)) {
+ switch (STM_PIN_CHANNEL(timer->function)) {
+ case 1: return LL_TIM_CHANNEL_CH1N;
+ case 2: return LL_TIM_CHANNEL_CH2N;
+ case 3: return LL_TIM_CHANNEL_CH3N;
+#if defined(LL_TIM_CHANNEL_CH4N)
+ case 4: return LL_TIM_CHANNEL_CH4N;
+#endif
+ default: return -1;
+ }
+ } else
+#endif
+ {
+ switch (STM_PIN_CHANNEL(timer->function)) {
+ case 1: return LL_TIM_CHANNEL_CH1;
+ case 2: return LL_TIM_CHANNEL_CH2;
+ case 3: return LL_TIM_CHANNEL_CH3;
+ case 4: return LL_TIM_CHANNEL_CH4;
+ default: return -1;
+ }
+ }
+ return -1;
+}
+
+
+
+
+
+// init pin pwm
+HardwareTimer* _initPinPWM(uint32_t PWM_freq, PinMap* timer) {
+ // sanity check
+ if (timer==NP)
+ return NP;
+ uint32_t index = get_timer_index((TIM_TypeDef*)timer->peripheral);
+ bool init = false;
+ if (HardwareTimer_Handle[index] == NULL) {
+ HardwareTimer_Handle[index]->__this = new HardwareTimer((TIM_TypeDef*)timer->peripheral);
+ HardwareTimer_Handle[index]->handle.Init.CounterMode = TIM_COUNTERMODE_CENTERALIGNED3;
+ HardwareTimer_Handle[index]->handle.Init.RepetitionCounter = 1;
+ HAL_TIM_Base_Init(&(HardwareTimer_Handle[index]->handle));
+ init = true;
+ }
+ HardwareTimer *HT = (HardwareTimer *)(HardwareTimer_Handle[index]->__this);
+ uint32_t channel = STM_PIN_CHANNEL(timer->function);
+ HT->pause();
+ if (init)
+ HT->setOverflow(PWM_freq, HERTZ_FORMAT);
+ HT->setMode(channel, TIMER_OUTPUT_COMPARE_PWM1, timer->pin);
+ #if SIMPLEFOC_PWM_ACTIVE_HIGH==false
+ LL_TIM_OC_SetPolarity(HT->getHandle()->Instance, getLLChannel(timer), LL_TIM_OCPOLARITY_LOW);
+ #endif
+#ifdef SIMPLEFOC_STM32_DEBUG
+ SIMPLEFOC_DEBUG("STM32-DRV: Configuring high timer ", (int)getTimerNumber(get_timer_index(HardwareTimer_Handle[index]->handle.Instance)));
+ SIMPLEFOC_DEBUG("STM32-DRV: Configuring high channel ", (int)channel);
+#endif
+ return HT;
+}
+
+
+
+
+
+
+
+// init high side pin
+HardwareTimer* _initPinPWMHigh(uint32_t PWM_freq, PinMap* timer) {
+ HardwareTimer* HT = _initPinPWM(PWM_freq, timer);
+ #if SIMPLEFOC_PWM_HIGHSIDE_ACTIVE_HIGH==false && SIMPLEFOC_PWM_ACTIVE_HIGH==true
+ LL_TIM_OC_SetPolarity(HT->getHandle()->Instance, getLLChannel(timer), LL_TIM_OCPOLARITY_LOW);
+ #endif
+ return HT;
+}
+
+// init low side pin
+HardwareTimer* _initPinPWMLow(uint32_t PWM_freq, PinMap* timer)
+{
+ uint32_t index = get_timer_index((TIM_TypeDef*)timer->peripheral);
+
+ bool init = false;
+ if (HardwareTimer_Handle[index] == NULL) {
+ HardwareTimer_Handle[index]->__this = new HardwareTimer((TIM_TypeDef*)timer->peripheral);
+ HardwareTimer_Handle[index]->handle.Init.CounterMode = TIM_COUNTERMODE_CENTERALIGNED3;
+ HardwareTimer_Handle[index]->handle.Init.RepetitionCounter = 1;
+ HAL_TIM_Base_Init(&(HardwareTimer_Handle[index]->handle));
+ init = true;
+ }
+ HardwareTimer *HT = (HardwareTimer *)(HardwareTimer_Handle[index]->__this);
+ uint32_t channel = STM_PIN_CHANNEL(timer->function);
+
+#ifdef SIMPLEFOC_STM32_DEBUG
+ SIMPLEFOC_DEBUG("STM32-DRV: Configuring low timer ", (int)getTimerNumber(get_timer_index(HardwareTimer_Handle[index]->handle.Instance)));
+ SIMPLEFOC_DEBUG("STM32-DRV: Configuring low channel ", (int)channel);
+#endif
+
+ HT->pause();
+ if (init)
+ HT->setOverflow(PWM_freq, HERTZ_FORMAT);
+ // sets internal fields of HT, but we can't set polarity here
+ HT->setMode(channel, TIMER_OUTPUT_COMPARE_PWM2, timer->pin);
+ #if SIMPLEFOC_PWM_LOWSIDE_ACTIVE_HIGH==false
+ LL_TIM_OC_SetPolarity(HT->getHandle()->Instance, getLLChannel(timer), LL_TIM_OCPOLARITY_LOW);
+ #endif
+ return HT;
+}
+
+
+
+// align the timers to end the init
+void _alignPWMTimers(HardwareTimer *HT1, HardwareTimer *HT2, HardwareTimer *HT3)
+{
+ HT1->pause();
+ HT1->refresh();
+ HT2->pause();
+ HT2->refresh();
+ HT3->pause();
+ HT3->refresh();
+ HT1->resume();
+ HT2->resume();
+ HT3->resume();
+}
+
+
+
+
+// align the timers to end the init
+void _alignPWMTimers(HardwareTimer *HT1, HardwareTimer *HT2, HardwareTimer *HT3, HardwareTimer *HT4)
+{
+ HT1->pause();
+ HT1->refresh();
+ HT2->pause();
+ HT2->refresh();
+ HT3->pause();
+ HT3->refresh();
+ HT4->pause();
+ HT4->refresh();
+ HT1->resume();
+ HT2->resume();
+ HT3->resume();
+ HT4->resume();
+}
+
+
+// align the timers to end the init
+void _stopTimers(HardwareTimer **timers_to_stop, int timer_num)
+{
+ // TODO - stop each timer only once
+ // stop timers
+ for (int i=0; i < timer_num; i++) {
+ if(timers_to_stop[i] == NP) return;
+ timers_to_stop[i]->pause();
+ timers_to_stop[i]->refresh();
+ #ifdef SIMPLEFOC_STM32_DEBUG
+ SIMPLEFOC_DEBUG("STM32-DRV: Stopping timer ", getTimerNumber(get_timer_index(timers_to_stop[i]->getHandle()->Instance)));
+ #endif
+ }
+}
+
+
+#if defined(STM32G4xx)
+// function finds the appropriate timer source trigger for the master/slave timer combination
+// returns -1 if no trigger source is found
+// currently supports the master timers to be from TIM1 to TIM4 and TIM8
+int _getInternalSourceTrigger(HardwareTimer* master, HardwareTimer* slave) { // put master and slave in temp variables to avoid arrows
+ TIM_TypeDef *TIM_master = master->getHandle()->Instance;
+ #if defined(TIM1) && defined(LL_TIM_TS_ITR0)
+ if (TIM_master == TIM1) return LL_TIM_TS_ITR0;// return TIM_TS_ITR0;
+ #endif
+ #if defined(TIM2) && defined(LL_TIM_TS_ITR1)
+ else if (TIM_master == TIM2) return LL_TIM_TS_ITR1;//return TIM_TS_ITR1;
+ #endif
+ #if defined(TIM3) && defined(LL_TIM_TS_ITR2)
+ else if (TIM_master == TIM3) return LL_TIM_TS_ITR2;//return TIM_TS_ITR2;
+ #endif
+ #if defined(TIM4) && defined(LL_TIM_TS_ITR3)
+ else if (TIM_master == TIM4) return LL_TIM_TS_ITR3;//return TIM_TS_ITR3;
+ #endif
+ #if defined(TIM5) && defined(LL_TIM_TS_ITR4)
+ else if (TIM_master == TIM5) return LL_TIM_TS_ITR4;//return TIM_TS_ITR4;
+ #endif
+ #if defined(TIM8) && defined(LL_TIM_TS_ITR5)
+ else if (TIM_master == TIM8) return LL_TIM_TS_ITR5;//return TIM_TS_ITR5;
+ #endif
+ return -1;
+}
+#elif defined(STM32F4xx) || defined(STM32F1xx) || defined(STM32L4xx) || defined(STM32F7xx)
+
+// function finds the appropriate timer source trigger for the master/slave timer combination
+// returns -1 if no trigger source is found
+// currently supports the master timers to be from TIM1 to TIM4 and TIM8
+int _getInternalSourceTrigger(HardwareTimer* master, HardwareTimer* slave) {
+ // put master and slave in temp variables to avoid arrows
+ TIM_TypeDef *TIM_master = master->getHandle()->Instance;
+ TIM_TypeDef *TIM_slave = slave->getHandle()->Instance;
+ #if defined(TIM1) && defined(LL_TIM_TS_ITR0)
+ if (TIM_master == TIM1){
+ #if defined(TIM2)
+ if(TIM_slave == TIM2) return LL_TIM_TS_ITR0;
+ #endif
+ #if defined(TIM3)
+ else if(TIM_slave == TIM3) return LL_TIM_TS_ITR0;
+ #endif
+ #if defined(TIM4)
+ else if(TIM_slave == TIM4) return LL_TIM_TS_ITR0;
+ #endif
+ #if defined(TIM8)
+ else if(TIM_slave == TIM8) return LL_TIM_TS_ITR0;
+ #endif
+ }
+ #endif
+ #if defined(TIM2) && defined(LL_TIM_TS_ITR1)
+ else if (TIM_master == TIM2){
+ #if defined(TIM1)
+ if(TIM_slave == TIM1) return LL_TIM_TS_ITR1;
+ #endif
+ #if defined(TIM3)
+ else if(TIM_slave == TIM3) return LL_TIM_TS_ITR1;
+ #endif
+ #if defined(TIM4)
+ else if(TIM_slave == TIM4) return LL_TIM_TS_ITR1;
+ #endif
+ #if defined(TIM8)
+ else if(TIM_slave == TIM8) return LL_TIM_TS_ITR1;
+ #endif
+ #if defined(TIM5)
+ else if(TIM_slave == TIM5) return LL_TIM_TS_ITR0;
+ #endif
+ }
+ #endif
+ #if defined(TIM3) && defined(LL_TIM_TS_ITR2)
+ else if (TIM_master == TIM3){
+ #if defined(TIM1)
+ if(TIM_slave == TIM1) return LL_TIM_TS_ITR2;
+ #endif
+ #if defined(TIM2)
+ else if(TIM_slave == TIM2) return LL_TIM_TS_ITR2;
+ #endif
+ #if defined(TIM4)
+ else if(TIM_slave == TIM4) return LL_TIM_TS_ITR2;
+ #endif
+ #if defined(TIM5)
+ else if(TIM_slave == TIM5) return LL_TIM_TS_ITR1;
+ #endif
+ }
+ #endif
+ #if defined(TIM4) && defined(LL_TIM_TS_ITR3)
+ else if (TIM_master == TIM4){
+ #if defined(TIM1)
+ if(TIM_slave == TIM1) return LL_TIM_TS_ITR3;
+ #endif
+ #if defined(TIM2)
+ else if(TIM_slave == TIM2) return LL_TIM_TS_ITR3;
+ #endif
+ #if defined(TIM3)
+ else if(TIM_slave == TIM3) return LL_TIM_TS_ITR3;
+ #endif
+ #if defined(TIM8)
+ else if(TIM_slave == TIM8) return LL_TIM_TS_ITR2;
+ #endif
+ #if defined(TIM5)
+ else if(TIM_slave == TIM5) return LL_TIM_TS_ITR1;
+ #endif
+ }
+ #endif
+ #if defined(TIM5)
+ else if (TIM_master == TIM5){
+ #if !defined(STM32L4xx) // only difference between F4,F1 and L4
+ #if defined(TIM1)
+ if(TIM_slave == TIM1) return LL_TIM_TS_ITR0;
+ #endif
+ #if defined(TIM3)
+ else if(TIM_slave == TIM3) return LL_TIM_TS_ITR2;
+ #endif
+ #endif
+ #if defined(TIM8)
+ if(TIM_slave == TIM8) return LL_TIM_TS_ITR3;
+ #endif
+ }
+ #endif
+ #if defined(TIM8)
+ else if (TIM_master == TIM8){
+ #if defined(TIM2)
+ if(TIM_slave==TIM2) return LL_TIM_TS_ITR1;
+ #endif
+ #if defined(TIM4)
+ else if(TIM_slave == TIM4) return LL_TIM_TS_ITR3;
+ #endif
+ #if defined(TIM5)
+ else if(TIM_slave == TIM5) return LL_TIM_TS_ITR3;
+ #endif
+ }
+ #endif
+ return -1; // combination not supported
+}
+#else
+// Alignment not supported for this architecture
+int _getInternalSourceTrigger(HardwareTimer* master, HardwareTimer* slave) {
+ return -1;
+}
+#endif
+
+void syncTimerFrequency(long pwm_frequency, HardwareTimer *timers[], uint8_t num_timers) {
+ uint32_t max_frequency = 0;
+ uint32_t min_frequency = UINT32_MAX;
+ for (size_t i=0; igetTimerClkFreq();
+ if (freq > max_frequency) {
+ max_frequency = freq;
+ } else if (freq < min_frequency) {
+ min_frequency = freq;
+ }
+ }
+ if (max_frequency==min_frequency) return;
+ uint32_t overflow_value = min_frequency/pwm_frequency;
+ for (size_t i=0; igetTimerClkFreq()/min_frequency;
+ #ifdef SIMPLEFOC_DEBUG
+ SIMPLEFOC_DEBUG("STM32-DRV: Setting prescale to ", (float)prescale_factor);
+ SIMPLEFOC_DEBUG("STM32-DRV: Setting Overflow to ", (float)overflow_value);
+ #endif
+ timers[i]->setPrescaleFactor(prescale_factor);
+ timers[i]->setOverflow(overflow_value,TICK_FORMAT);
+ timers[i]->refresh();
+ }
+}
+
+void _alignTimersNew() {
+ int numTimers = 0;
+ HardwareTimer *timers[numTimerPinsUsed];
+
+ // find the timers used
+ for (int i=0; iperipheral);
+ HardwareTimer *timer = (HardwareTimer *)(HardwareTimer_Handle[index]->__this);
+ bool found = false;
+ for (int j=0; j 1){
+ // find the master timer
+ int16_t master_index = -1;
+ int triggerEvent = -1;
+ for (int i=0; igetHandle()->Instance)) {
+ // check if timer already configured in TRGO update mode (used for ADC triggering)
+ // in that case we should not change its TRGO configuration
+ if(timers[i]->getHandle()->Instance->CR2 & LL_TIM_TRGO_UPDATE) continue;
+ // check if the timer has the supported internal trigger for other timers
+ for (int slave_i=0; slave_igetHandle()->Instance)));
+ #endif
+ // make the master timer generate ITRGx event
+ // if it was already configured in slave mode
+ LL_TIM_SetSlaveMode(timers[master_index]->getHandle()->Instance, LL_TIM_SLAVEMODE_DISABLED );
+ // Configure the master timer to send a trigger signal on enable
+ LL_TIM_SetTriggerOutput(timers[master_index]->getHandle()->Instance, LL_TIM_TRGO_ENABLE);
+ // configure other timers to get the input trigger from the master timer
+ for (int slave_index=0; slave_index < numTimers; slave_index++) {
+ if (slave_index == master_index)
+ continue;
+ // Configure the slave timer to be triggered by the master enable signal
+ LL_TIM_SetTriggerInput(timers[slave_index]->getHandle()->Instance, _getInternalSourceTrigger(timers[master_index], timers[slave_index]));
+ LL_TIM_SetSlaveMode(timers[slave_index]->getHandle()->Instance, LL_TIM_SLAVEMODE_TRIGGER);
+ }
+ }
+ }
+
+ // enable timer clock
+ for (int i=0; ipause();
+ // timers[i]->refresh();
+ #ifdef SIMPLEFOC_STM32_DEBUG
+ SIMPLEFOC_DEBUG("STM32-DRV: Restarting timer ", getTimerNumber(get_timer_index(timers[i]->getHandle()->Instance)));
+ #endif
+ }
+
+ for (int i=0; iresume();
+ }
+
+}
+
+
+
+// align the timers to end the init
+void _startTimers(HardwareTimer **timers_to_start, int timer_num)
+{
+ // // TODO - start each timer only once
+ // // start timers
+ // for (int i=0; i < timer_num; i++) {
+ // if(timers_to_start[i] == NP) return;
+ // timers_to_start[i]->resume();
+ // #ifdef SIMPLEFOC_STM32_DEBUG
+ // SIMPLEFOC_DEBUG("STM32-DRV: Starting timer ", getTimerNumber(get_timer_index(timers_to_start[i]->getHandle()->Instance)));
+ // #endif
+ // }
+ _alignTimersNew();
+}
+
+
+// configure hardware 6pwm for a complementary pair of channels
+STM32DriverParams* _initHardware6PWMPair(long PWM_freq, float dead_zone, PinMap* pinH, PinMap* pinL, STM32DriverParams* params, int paramsPos) {
+ // sanity check
+ if (pinH==NP || pinL==NP)
+ return (STM32DriverParams*)SIMPLEFOC_DRIVER_INIT_FAILED;
+
+#if defined(STM32L0xx) // L0 boards dont have hardware 6pwm interface
+ return SIMPLEFOC_DRIVER_INIT_FAILED; // return nothing
+#endif
+
+ uint32_t channel1 = STM_PIN_CHANNEL(pinH->function);
+ uint32_t channel2 = STM_PIN_CHANNEL(pinL->function);
+
+ // more sanity check
+ if (channel1!=channel2 || pinH->peripheral!=pinL->peripheral)
+ return (STM32DriverParams*)SIMPLEFOC_DRIVER_INIT_FAILED;
+
+ uint32_t index = get_timer_index((TIM_TypeDef*)pinH->peripheral);
+
+ if (HardwareTimer_Handle[index] == NULL) {
+ HardwareTimer_Handle[index]->__this = new HardwareTimer((TIM_TypeDef*)pinH->peripheral);
+ HardwareTimer_Handle[index]->handle.Init.CounterMode = TIM_COUNTERMODE_CENTERALIGNED3;
+ HardwareTimer_Handle[index]->handle.Init.RepetitionCounter = 1;
+ // HardwareTimer_Handle[index]->handle.Init.AutoReloadPreload = TIM_AUTORELOAD_PRELOAD_ENABLE;
+ HAL_TIM_Base_Init(&(HardwareTimer_Handle[index]->handle));
+ ((HardwareTimer *)HardwareTimer_Handle[index]->__this)->setOverflow((uint32_t)PWM_freq, HERTZ_FORMAT);
+ }
+ HardwareTimer *HT = (HardwareTimer *)(HardwareTimer_Handle[index]->__this);
+
+ HT->setMode(channel1, TIMER_OUTPUT_COMPARE_PWM1, pinH->pin);
+ HT->setMode(channel2, TIMER_OUTPUT_COMPARE_PWM1, pinL->pin);
+
+ // dead time is set in nanoseconds
+ uint32_t dead_time_ns = (float)(1e9f/PWM_freq)*dead_zone;
+ uint32_t dead_time = __LL_TIM_CALC_DEADTIME(SystemCoreClock, LL_TIM_GetClockDivision(HT->getHandle()->Instance), dead_time_ns);
+ if (dead_time>255) dead_time = 255;
+ if (dead_time==0 && dead_zone>0) {
+ dead_time = 255; // LL_TIM_CALC_DEADTIME returns 0 if dead_time_ns is too large
+ SIMPLEFOC_DEBUG("STM32-DRV: WARN: dead time too large, setting to max");
+ }
+ LL_TIM_OC_SetDeadTime(HT->getHandle()->Instance, dead_time); // deadtime is non linear!
+ #if SIMPLEFOC_PWM_HIGHSIDE_ACTIVE_HIGH==false
+ LL_TIM_OC_SetPolarity(HT->getHandle()->Instance, getLLChannel(pinH), LL_TIM_OCPOLARITY_LOW);
+ #endif
+ #if SIMPLEFOC_PWM_LOWSIDE_ACTIVE_HIGH==false
+ LL_TIM_OC_SetPolarity(HT->getHandle()->Instance, getLLChannel(pinL), LL_TIM_OCPOLARITY_LOW);
+ #endif
+ LL_TIM_CC_EnableChannel(HT->getHandle()->Instance, getLLChannel(pinH) | getLLChannel(pinL));
+ HT->pause();
+
+ // make sure timer output goes to LOW when timer channels are temporarily disabled
+ LL_TIM_SetOffStates(HT->getHandle()->Instance, LL_TIM_OSSI_DISABLE, LL_TIM_OSSR_ENABLE);
+
+ params->timers[paramsPos] = HT;
+ params->timers[paramsPos+1] = HT;
+ params->channels[paramsPos] = channel1;
+ params->channels[paramsPos+1] = channel2;
+ return params;
+}
+
+
+
+
+STM32DriverParams* _initHardware6PWMInterface(long PWM_freq, float dead_zone, PinMap* pinA_h, PinMap* pinA_l, PinMap* pinB_h, PinMap* pinB_l, PinMap* pinC_h, PinMap* pinC_l) {
+ STM32DriverParams* params = new STM32DriverParams {
+ .timers = { NP, NP, NP, NP, NP, NP },
+ .channels = { 0, 0, 0, 0, 0, 0 },
+ .pwm_frequency = PWM_freq,
+ .dead_zone = dead_zone,
+ .interface_type = _HARDWARE_6PWM
+ };
+
+ if (_initHardware6PWMPair(PWM_freq, dead_zone, pinA_h, pinA_l, params, 0) == SIMPLEFOC_DRIVER_INIT_FAILED)
+ return (STM32DriverParams*)SIMPLEFOC_DRIVER_INIT_FAILED;
+ if(_initHardware6PWMPair(PWM_freq, dead_zone, pinB_h, pinB_l, params, 2) == SIMPLEFOC_DRIVER_INIT_FAILED)
+ return (STM32DriverParams*)SIMPLEFOC_DRIVER_INIT_FAILED;
+ if (_initHardware6PWMPair(PWM_freq, dead_zone, pinC_h, pinC_l, params, 4) == SIMPLEFOC_DRIVER_INIT_FAILED)
+ return (STM32DriverParams*)SIMPLEFOC_DRIVER_INIT_FAILED;
+
+ return params;
+}
+
+
+
+
+
+
+/*
+ timer combination scoring function
+ assigns a score, and also checks the combination is valid
+ returns <0 if combination is invalid, >=0 if combination is valid. lower (but positive) score is better
+ for 6 pwm, hardware 6-pwm is preferred over software 6-pwm
+ hardware 6-pwm is possible if each low channel is the inverted counterpart of its high channel
+ inverted channels are not allowed except when using hardware 6-pwm (in theory they could be but lets not complicate things)
+*/
+int scoreCombination(int numPins, PinMap* pinTimers[]) {
+ // check already used - TODO move this to outer loop also...
+ for (int i=0; iperipheral == timerPinsUsed[i]->peripheral
+ && STM_PIN_CHANNEL(pinTimers[i]->function) == STM_PIN_CHANNEL(timerPinsUsed[i]->function))
+ return -2; // bad combination - timer channel already used
+ }
+
+ // TODO LPTIM and HRTIM should be ignored for now
+
+ // check for inverted channels
+ if (numPins < 6) {
+ for (int i=0; ifunction))
+ return -3; // bad combination - inverted channel used in non-hardware 6pwm
+ }
+ }
+ // check for duplicated channels
+ for (int i=0; iperipheral == pinTimers[j]->peripheral
+ && STM_PIN_CHANNEL(pinTimers[i]->function) == STM_PIN_CHANNEL(pinTimers[j]->function)
+ && STM_PIN_INVERTED(pinTimers[i]->function) == STM_PIN_INVERTED(pinTimers[j]->function))
+ return -4; // bad combination - duplicated channel
+ }
+ }
+ int score = 0;
+ for (int i=0; iperipheral == pinTimers[j]->peripheral)
+ found = true;
+ }
+ if (!found) score++;
+ }
+ if (numPins==6) {
+ // check for inverted channels - best: 1 timer, 3 channels, 3 matching inverted channels
+ // >1 timer, 3 channels, 3 matching inverted channels
+ // 1 timer, 6 channels (no inverted channels)
+ // >1 timer, 6 channels (no inverted channels)
+ // check for inverted high-side channels - TODO is this a configuration we should allow? what if all 3 high side channels are inverted and the low-side non-inverted?
+ if (STM_PIN_INVERTED(pinTimers[0]->function) || STM_PIN_INVERTED(pinTimers[2]->function) || STM_PIN_INVERTED(pinTimers[4]->function))
+ return -5; // bad combination - inverted channel used on high-side channel
+ if (pinTimers[0]->peripheral == pinTimers[1]->peripheral
+ && pinTimers[2]->peripheral == pinTimers[3]->peripheral
+ && pinTimers[4]->peripheral == pinTimers[5]->peripheral
+ && STM_PIN_CHANNEL(pinTimers[0]->function) == STM_PIN_CHANNEL(pinTimers[1]->function)
+ && STM_PIN_CHANNEL(pinTimers[2]->function) == STM_PIN_CHANNEL(pinTimers[3]->function)
+ && STM_PIN_CHANNEL(pinTimers[4]->function) == STM_PIN_CHANNEL(pinTimers[5]->function)
+ && STM_PIN_INVERTED(pinTimers[1]->function) && STM_PIN_INVERTED(pinTimers[3]->function) && STM_PIN_INVERTED(pinTimers[5]->function)) {
+ // hardware 6pwm, score <10
+
+ // TODO F37xxx doesn't support dead-time insertion, it has no TIM1/TIM8
+ // F301, F302 --> 6 channels, but only 1-3 have dead-time insertion
+ // TIM2/TIM3/TIM4/TIM5 don't do dead-time insertion
+ // TIM15/TIM16/TIM17 do dead-time insertion only on channel 1
+
+ // TODO check these defines
+ #if defined(STM32F4xx_HAL_TIM_H) || defined(STM32F3xx_HAL_TIM_H) || defined(STM32F2xx_HAL_TIM_H) || defined(STM32F1xx_HAL_TIM_H) || defined(STM32F100_HAL_TIM_H) || defined(STM32FG0x1_HAL_TIM_H) || defined(STM32G0x0_HAL_TIM_H)
+ if (STM_PIN_CHANNEL(pinTimers[0]->function)>3 || STM_PIN_CHANNEL(pinTimers[2]->function)>3 || STM_PIN_CHANNEL(pinTimers[4]->function)>3 )
+ return -8; // channel 4 does not have dead-time insertion
+ #endif
+ #ifdef STM32G4xx_HAL_TIM_H
+ if (STM_PIN_CHANNEL(pinTimers[0]->function)>4 || STM_PIN_CHANNEL(pinTimers[2]->function)>4 || STM_PIN_CHANNEL(pinTimers[4]->function)>4 )
+ return -8; // channels 5 & 6 do not have dead-time insertion
+ #endif
+ }
+ else {
+ // check for inverted low-side channels
+ if (STM_PIN_INVERTED(pinTimers[1]->function) || STM_PIN_INVERTED(pinTimers[3]->function) || STM_PIN_INVERTED(pinTimers[5]->function))
+ return -6; // bad combination - inverted channel used on low-side channel in software 6-pwm
+ if (pinTimers[0]->peripheral != pinTimers[1]->peripheral
+ || pinTimers[2]->peripheral != pinTimers[3]->peripheral
+ || pinTimers[4]->peripheral != pinTimers[5]->peripheral)
+ return -7; // bad combination - non-matching timers for H/L side in software 6-pwm
+ score += 10; // software 6pwm, score >10
+ }
+ }
+ return score;
+}
+
+
+
+
+int findIndexOfFirstPinMapEntry(int pin) {
+ PinName pinName = digitalPinToPinName(pin);
+ int i = 0;
+ while (PinMap_TIM[i].pin!=NC) {
+ if (pinName == PinMap_TIM[i].pin)
+ return i;
+ i++;
+ }
+ return -1;
+}
+
+
+int findIndexOfLastPinMapEntry(int pin) {
+ PinName pinName = digitalPinToPinName(pin);
+ int i = 0;
+ while (PinMap_TIM[i].pin!=NC) {
+ if ( pinName == (PinMap_TIM[i].pin & ~ALTX_MASK)
+ && pinName != (PinMap_TIM[i+1].pin & ~ALTX_MASK))
+ return i;
+ i++;
+ }
+ return -1;
+}
+
+
+
+
+
+
+#define NOT_FOUND 1000
+
+int findBestTimerCombination(int numPins, int index, int pins[], PinMap* pinTimers[]) {
+ PinMap* searchArray[numPins];
+ for (int j=0;j=0 && score= 0) {
+ #ifdef SIMPLEFOC_STM32_DEBUG
+ SimpleFOCDebug::print("STM32-DRV: best: ");
+ printTimerCombination(numPins, pinTimers, bestScore);
+ #endif
+ }
+ return bestScore;
+};
+
+
+
+void* _configure1PWM(long pwm_frequency, const int pinA) {
+ if (numTimerPinsUsed+1 > SIMPLEFOC_STM32_MAX_PINTIMERSUSED) {
+ SIMPLEFOC_DEBUG("STM32-DRV: ERR: too many pins used");
+ return (STM32DriverParams*)SIMPLEFOC_DRIVER_INIT_FAILED;
+ }
+
+ if( !pwm_frequency || !_isset(pwm_frequency) ) pwm_frequency = _PWM_FREQUENCY; // default frequency 25khz
+ else pwm_frequency = _constrain(pwm_frequency, 0, _PWM_FREQUENCY_MAX); // constrain to 50kHz max
+ // center-aligned frequency is uses two periods
+ pwm_frequency *=2;
+
+ int pins[1] = { pinA };
+ PinMap* pinTimers[1] = { NP };
+ if (findBestTimerCombination(1, pins, pinTimers)<0)
+ return (STM32DriverParams*)SIMPLEFOC_DRIVER_INIT_FAILED;
+
+ HardwareTimer* HT1 = _initPinPWM(pwm_frequency, pinTimers[0]);\
+ // align the timers
+ _alignTimersNew();
+
+ uint32_t channel1 = STM_PIN_CHANNEL(pinTimers[0]->function);
+
+ STM32DriverParams* params = new STM32DriverParams {
+ .timers = { HT1 },
+ .channels = { channel1 },
+ .pwm_frequency = pwm_frequency
+ };
+ timerPinsUsed[numTimerPinsUsed++] = pinTimers[0];
+ return params;
+}
+
+
+
+
+
+// function setting the high pwm frequency to the supplied pins
+// - Stepper motor - 2PWM setting
+// - hardware speciffic
+void* _configure2PWM(long pwm_frequency, const int pinA, const int pinB) {
+ if (numTimerPinsUsed+2 > SIMPLEFOC_STM32_MAX_PINTIMERSUSED) {
+ SIMPLEFOC_DEBUG("STM32-DRV: ERR: too many pins used");
+ return (STM32DriverParams*)SIMPLEFOC_DRIVER_INIT_FAILED;
+ }
+
+ if( !pwm_frequency || !_isset(pwm_frequency) ) pwm_frequency = _PWM_FREQUENCY; // default frequency 25khz
+ else pwm_frequency = _constrain(pwm_frequency, 0, _PWM_FREQUENCY_MAX); // constrain to 50kHz max
+ // center-aligned frequency is uses two periods
+ pwm_frequency *=2;
+
+ int pins[2] = { pinA, pinB };
+ PinMap* pinTimers[2] = { NP, NP };
+ if (findBestTimerCombination(2, pins, pinTimers)<0)
+ return (STM32DriverParams*)SIMPLEFOC_DRIVER_INIT_FAILED;
+
+ HardwareTimer* HT1 = _initPinPWM(pwm_frequency, pinTimers[0]);
+ HardwareTimer* HT2 = _initPinPWM(pwm_frequency, pinTimers[1]);
+ HardwareTimer *timers[2] = {HT1, HT2};
+ syncTimerFrequency(pwm_frequency, timers, 2);
+ // allign the timers
+ _alignPWMTimers(HT1, HT2, HT2);
+
+ uint32_t channel1 = STM_PIN_CHANNEL(pinTimers[0]->function);
+ uint32_t channel2 = STM_PIN_CHANNEL(pinTimers[1]->function);
+
+ STM32DriverParams* params = new STM32DriverParams {
+ .timers = { HT1, HT2 },
+ .channels = { channel1, channel2 },
+ .pwm_frequency = pwm_frequency
+ };
+ timerPinsUsed[numTimerPinsUsed++] = pinTimers[0];
+ timerPinsUsed[numTimerPinsUsed++] = pinTimers[1];
+ return params;
+}
+
+
+
+
+TIM_MasterConfigTypeDef sMasterConfig;
+TIM_SlaveConfigTypeDef sSlaveConfig;
+
+// function setting the high pwm frequency to the supplied pins
+// - BLDC motor - 3PWM setting
+// - hardware speciffic
+void* _configure3PWM(long pwm_frequency,const int pinA, const int pinB, const int pinC) {
+ if (numTimerPinsUsed+3 > SIMPLEFOC_STM32_MAX_PINTIMERSUSED) {
+ SIMPLEFOC_DEBUG("STM32-DRV: ERR: too many pins used");
+ return (STM32DriverParams*)SIMPLEFOC_DRIVER_INIT_FAILED;
+ }
+ if( !pwm_frequency || !_isset(pwm_frequency) ) pwm_frequency = _PWM_FREQUENCY; // default frequency 25khz
+ else pwm_frequency = _constrain(pwm_frequency, 0, _PWM_FREQUENCY_MAX); // constrain to 50kHz max
+ // center-aligned frequency is uses two periods
+ pwm_frequency *=2;
+
+ int pins[3] = { pinA, pinB, pinC };
+ PinMap* pinTimers[3] = { NP, NP, NP };
+ if (findBestTimerCombination(3, pins, pinTimers)<0)
+ return (STM32DriverParams*)SIMPLEFOC_DRIVER_INIT_FAILED;
+
+ HardwareTimer* HT1 = _initPinPWM(pwm_frequency, pinTimers[0]);
+ HardwareTimer* HT2 = _initPinPWM(pwm_frequency, pinTimers[1]);
+ HardwareTimer* HT3 = _initPinPWM(pwm_frequency, pinTimers[2]);
+
+ HardwareTimer *timers[3] = {HT1, HT2, HT3};
+ syncTimerFrequency(pwm_frequency, timers, 3);
+
+ uint32_t channel1 = STM_PIN_CHANNEL(pinTimers[0]->function);
+ uint32_t channel2 = STM_PIN_CHANNEL(pinTimers[1]->function);
+ uint32_t channel3 = STM_PIN_CHANNEL(pinTimers[2]->function);
+
+ STM32DriverParams* params = new STM32DriverParams {
+ .timers = { HT1, HT2, HT3 },
+ .channels = { channel1, channel2, channel3 },
+ .pwm_frequency = pwm_frequency
+ };
+ timerPinsUsed[numTimerPinsUsed++] = pinTimers[0];
+ timerPinsUsed[numTimerPinsUsed++] = pinTimers[1];
+ timerPinsUsed[numTimerPinsUsed++] = pinTimers[2];
+
+ _alignTimersNew();
+
+ return params;
+}
+
+
+
+// function setting the high pwm frequency to the supplied pins
+// - Stepper motor - 4PWM setting
+// - hardware speciffic
+void* _configure4PWM(long pwm_frequency,const int pinA, const int pinB, const int pinC, const int pinD) {
+ if (numTimerPinsUsed+4 > SIMPLEFOC_STM32_MAX_PINTIMERSUSED) {
+ SIMPLEFOC_DEBUG("STM32-DRV: ERR: too many pins used");
+ return (STM32DriverParams*)SIMPLEFOC_DRIVER_INIT_FAILED;
+ }
+ if( !pwm_frequency || !_isset(pwm_frequency) ) pwm_frequency = _PWM_FREQUENCY; // default frequency 25khz
+ else pwm_frequency = _constrain(pwm_frequency, 0, _PWM_FREQUENCY_MAX); // constrain to 50kHz max
+ // center-aligned frequency is uses two periods
+ pwm_frequency *=2;
+
+ int pins[4] = { pinA, pinB, pinC, pinD };
+ PinMap* pinTimers[4] = { NP, NP, NP, NP };
+ if (findBestTimerCombination(4, pins, pinTimers)<0)
+ return (STM32DriverParams*)SIMPLEFOC_DRIVER_INIT_FAILED;
+
+ HardwareTimer* HT1 = _initPinPWM(pwm_frequency, pinTimers[0]);
+ HardwareTimer* HT2 = _initPinPWM(pwm_frequency, pinTimers[1]);
+ HardwareTimer* HT3 = _initPinPWM(pwm_frequency, pinTimers[2]);
+ HardwareTimer* HT4 = _initPinPWM(pwm_frequency, pinTimers[3]);
+ HardwareTimer *timers[4] = {HT1, HT2, HT3, HT4};
+ syncTimerFrequency(pwm_frequency, timers, 4);
+ // allign the timers
+ _alignPWMTimers(HT1, HT2, HT3, HT4);
+
+ uint32_t channel1 = STM_PIN_CHANNEL(pinTimers[0]->function);
+ uint32_t channel2 = STM_PIN_CHANNEL(pinTimers[1]->function);
+ uint32_t channel3 = STM_PIN_CHANNEL(pinTimers[2]->function);
+ uint32_t channel4 = STM_PIN_CHANNEL(pinTimers[3]->function);
+
+ STM32DriverParams* params = new STM32DriverParams {
+ .timers = { HT1, HT2, HT3, HT4 },
+ .channels = { channel1, channel2, channel3, channel4 },
+ .pwm_frequency = pwm_frequency
+ };
+ timerPinsUsed[numTimerPinsUsed++] = pinTimers[0];
+ timerPinsUsed[numTimerPinsUsed++] = pinTimers[1];
+ timerPinsUsed[numTimerPinsUsed++] = pinTimers[2];
+ timerPinsUsed[numTimerPinsUsed++] = pinTimers[3];
+ return params;
+}
+
+
+
+// function setting the pwm duty cycle to the hardware
+// - DC motor - 1PWM setting
+// - hardware speciffic
+void _writeDutyCycle1PWM(float dc_a, void* params){
+ // transform duty cycle from [0,1] to [0,255]
+ _setPwm(((STM32DriverParams*)params)->timers[0], ((STM32DriverParams*)params)->channels[0], _PWM_RANGE*dc_a, _PWM_RESOLUTION);
+}
+
+
+
+// function setting the pwm duty cycle to the hardware
+// - Stepper motor - 2PWM setting
+//- hardware speciffic
+void _writeDutyCycle2PWM(float dc_a, float dc_b, void* params){
+ // transform duty cycle from [0,1] to [0,4095]
+ _setPwm(((STM32DriverParams*)params)->timers[0], ((STM32DriverParams*)params)->channels[0], _PWM_RANGE*dc_a, _PWM_RESOLUTION);
+ _setPwm(((STM32DriverParams*)params)->timers[1], ((STM32DriverParams*)params)->channels[1], _PWM_RANGE*dc_b, _PWM_RESOLUTION);
+}
+
+// function setting the pwm duty cycle to the hardware
+// - BLDC motor - 3PWM setting
+//- hardware speciffic
+void _writeDutyCycle3PWM(float dc_a, float dc_b, float dc_c, void* params){
+ // transform duty cycle from [0,1] to [0,4095]
+ _setPwm(((STM32DriverParams*)params)->timers[0], ((STM32DriverParams*)params)->channels[0], _PWM_RANGE*dc_a, _PWM_RESOLUTION);
+ _setPwm(((STM32DriverParams*)params)->timers[1], ((STM32DriverParams*)params)->channels[1], _PWM_RANGE*dc_b, _PWM_RESOLUTION);
+ _setPwm(((STM32DriverParams*)params)->timers[2], ((STM32DriverParams*)params)->channels[2], _PWM_RANGE*dc_c, _PWM_RESOLUTION);
+}
+
+
+// function setting the pwm duty cycle to the hardware
+// - Stepper motor - 4PWM setting
+//- hardware speciffic
+void _writeDutyCycle4PWM(float dc_1a, float dc_1b, float dc_2a, float dc_2b, void* params){
+ // transform duty cycle from [0,1] to [0,4095]
+ _setPwm(((STM32DriverParams*)params)->timers[0], ((STM32DriverParams*)params)->channels[0], _PWM_RANGE*dc_1a, _PWM_RESOLUTION);
+ _setPwm(((STM32DriverParams*)params)->timers[1], ((STM32DriverParams*)params)->channels[1], _PWM_RANGE*dc_1b, _PWM_RESOLUTION);
+ _setPwm(((STM32DriverParams*)params)->timers[2], ((STM32DriverParams*)params)->channels[2], _PWM_RANGE*dc_2a, _PWM_RESOLUTION);
+ _setPwm(((STM32DriverParams*)params)->timers[3], ((STM32DriverParams*)params)->channels[3], _PWM_RANGE*dc_2b, _PWM_RESOLUTION);
+}
+
+
+
+
+// Configuring PWM frequency, resolution and alignment
+// - BLDC driver - 6PWM setting
+// - hardware specific
+void* _configure6PWM(long pwm_frequency, float dead_zone, const int pinA_h, const int pinA_l, const int pinB_h, const int pinB_l, const int pinC_h, const int pinC_l){
+ if (numTimerPinsUsed+6 > SIMPLEFOC_STM32_MAX_PINTIMERSUSED) {
+ SIMPLEFOC_DEBUG("STM32-DRV: ERR: too many pins used");
+ return (STM32DriverParams*)SIMPLEFOC_DRIVER_INIT_FAILED;
+ }
+ if( !pwm_frequency || !_isset(pwm_frequency) ) pwm_frequency = _PWM_FREQUENCY; // default frequency 25khz
+ else pwm_frequency = _constrain(pwm_frequency, 0, _PWM_FREQUENCY_MAX); // constrain to |%0kHz max
+ // center-aligned frequency is uses two periods
+ pwm_frequency *=2;
+
+ // find configuration
+ int pins[6] = { pinA_h, pinA_l, pinB_h, pinB_l, pinC_h, pinC_l };
+ PinMap* pinTimers[6] = { NP, NP, NP, NP, NP, NP };
+ int score = findBestTimerCombination(6, pins, pinTimers);
+
+ STM32DriverParams* params;
+ // configure accordingly
+ if (score<0)
+ params = (STM32DriverParams*)SIMPLEFOC_DRIVER_INIT_FAILED;
+ else if (score<10) // hardware pwm
+ params = _initHardware6PWMInterface(pwm_frequency, dead_zone, pinTimers[0], pinTimers[1], pinTimers[2], pinTimers[3], pinTimers[4], pinTimers[5]);
+ else { // software pwm
+ HardwareTimer* HT1 = _initPinPWMHigh(pwm_frequency, pinTimers[0]);
+ HardwareTimer* HT2 = _initPinPWMLow(pwm_frequency, pinTimers[1]);
+ HardwareTimer* HT3 = _initPinPWMHigh(pwm_frequency, pinTimers[2]);
+ HardwareTimer* HT4 = _initPinPWMLow(pwm_frequency, pinTimers[3]);
+ HardwareTimer* HT5 = _initPinPWMHigh(pwm_frequency, pinTimers[4]);
+ HardwareTimer* HT6 = _initPinPWMLow(pwm_frequency, pinTimers[5]);
+ HardwareTimer *timers[6] = {HT1, HT2, HT3, HT4, HT5, HT6};
+ syncTimerFrequency(pwm_frequency, timers, 6);
+ uint32_t channel1 = STM_PIN_CHANNEL(pinTimers[0]->function);
+ uint32_t channel2 = STM_PIN_CHANNEL(pinTimers[1]->function);
+ uint32_t channel3 = STM_PIN_CHANNEL(pinTimers[2]->function);
+ uint32_t channel4 = STM_PIN_CHANNEL(pinTimers[3]->function);
+ uint32_t channel5 = STM_PIN_CHANNEL(pinTimers[4]->function);
+ uint32_t channel6 = STM_PIN_CHANNEL(pinTimers[5]->function);
+ params = new STM32DriverParams {
+ .timers = { HT1, HT2, HT3, HT4, HT5, HT6 },
+ .channels = { channel1, channel2, channel3, channel4, channel5, channel6 },
+ .pwm_frequency = pwm_frequency,
+ .dead_zone = dead_zone,
+ .interface_type = _SOFTWARE_6PWM
+ };
+ }
+ if (score>=0) {
+ for (int i=0; i<6; i++)
+ timerPinsUsed[numTimerPinsUsed++] = pinTimers[i];
+ _alignTimersNew();
+ }
+ return params; // success
+}
+
+
+
+void _setSinglePhaseState(PhaseState state, HardwareTimer *HT, int channel1,int channel2) {
+ _UNUSED(channel2);
+ switch (state) {
+ case PhaseState::PHASE_OFF:
+ // Due to a weird quirk in the arduino timer API, pauseChannel only disables the complementary channel (e.g. CC1NE).
+ // To actually make the phase floating, we must also set pwm to 0.
+ HT->pauseChannel(channel1);
+ break;
+ default:
+ HT->resumeChannel(channel1);
+ break;
+ }
+}
+
+
+// Function setting the duty cycle to the pwm pin (ex. analogWrite())
+// - BLDC driver - 6PWM setting
+// - hardware specific
+void _writeDutyCycle6PWM(float dc_a, float dc_b, float dc_c, PhaseState* phase_state, void* params){
+ switch(((STM32DriverParams*)params)->interface_type){
+ case _HARDWARE_6PWM:
+ // phase a
+ _setSinglePhaseState(phase_state[0], ((STM32DriverParams*)params)->timers[0], ((STM32DriverParams*)params)->channels[0], ((STM32DriverParams*)params)->channels[1]);
+ if(phase_state[0] == PhaseState::PHASE_OFF) dc_a = 0.0f;
+ _setPwm(((STM32DriverParams*)params)->timers[0], ((STM32DriverParams*)params)->channels[0], _PWM_RANGE*dc_a, _PWM_RESOLUTION);
+ // phase b
+ _setSinglePhaseState(phase_state[1], ((STM32DriverParams*)params)->timers[2], ((STM32DriverParams*)params)->channels[2], ((STM32DriverParams*)params)->channels[3]);
+ if(phase_state[1] == PhaseState::PHASE_OFF) dc_b = 0.0f;
+ _setPwm(((STM32DriverParams*)params)->timers[2], ((STM32DriverParams*)params)->channels[2], _PWM_RANGE*dc_b, _PWM_RESOLUTION);
+ // phase c
+ _setSinglePhaseState(phase_state[2], ((STM32DriverParams*)params)->timers[4], ((STM32DriverParams*)params)->channels[4], ((STM32DriverParams*)params)->channels[5]);
+ if(phase_state[2] == PhaseState::PHASE_OFF) dc_c = 0.0f;
+ _setPwm(((STM32DriverParams*)params)->timers[4], ((STM32DriverParams*)params)->channels[4], _PWM_RANGE*dc_c, _PWM_RESOLUTION);
+ break;
+ case _SOFTWARE_6PWM:
+ float dead_zone = ((STM32DriverParams*)params)->dead_zone / 2.0f;
+ if (phase_state[0] == PhaseState::PHASE_ON || phase_state[0] == PhaseState::PHASE_HI)
+ _setPwm(((STM32DriverParams*)params)->timers[0], ((STM32DriverParams*)params)->channels[0], _constrain(dc_a - dead_zone, 0.0f, 1.0f)*_PWM_RANGE, _PWM_RESOLUTION);
+ else
+ _setPwm(((STM32DriverParams*)params)->timers[0], ((STM32DriverParams*)params)->channels[0], 0.0f, _PWM_RESOLUTION);
+ if (phase_state[0] == PhaseState::PHASE_ON || phase_state[0] == PhaseState::PHASE_LO)
+ _setPwm(((STM32DriverParams*)params)->timers[1], ((STM32DriverParams*)params)->channels[1], _constrain(dc_a + dead_zone, 0.0f, 1.0f)*_PWM_RANGE, _PWM_RESOLUTION);
+ else
+ _setPwm(((STM32DriverParams*)params)->timers[1], ((STM32DriverParams*)params)->channels[1], 0.0f, _PWM_RESOLUTION);
+
+ if (phase_state[1] == PhaseState::PHASE_ON || phase_state[1] == PhaseState::PHASE_HI)
+ _setPwm(((STM32DriverParams*)params)->timers[2], ((STM32DriverParams*)params)->channels[2], _constrain(dc_b - dead_zone, 0.0f, 1.0f)*_PWM_RANGE, _PWM_RESOLUTION);
+ else
+ _setPwm(((STM32DriverParams*)params)->timers[2], ((STM32DriverParams*)params)->channels[2], 0.0f, _PWM_RESOLUTION);
+ if (phase_state[1] == PhaseState::PHASE_ON || phase_state[1] == PhaseState::PHASE_LO)
+ _setPwm(((STM32DriverParams*)params)->timers[3], ((STM32DriverParams*)params)->channels[3], _constrain(dc_b + dead_zone, 0.0f, 1.0f)*_PWM_RANGE, _PWM_RESOLUTION);
+ else
+ _setPwm(((STM32DriverParams*)params)->timers[3], ((STM32DriverParams*)params)->channels[3], 0.0f, _PWM_RESOLUTION);
+
+ if (phase_state[2] == PhaseState::PHASE_ON || phase_state[2] == PhaseState::PHASE_HI)
+ _setPwm(((STM32DriverParams*)params)->timers[4], ((STM32DriverParams*)params)->channels[4], _constrain(dc_c - dead_zone, 0.0f, 1.0f)*_PWM_RANGE, _PWM_RESOLUTION);
+ else
+ _setPwm(((STM32DriverParams*)params)->timers[4], ((STM32DriverParams*)params)->channels[4], 0.0f, _PWM_RESOLUTION);
+ if (phase_state[2] == PhaseState::PHASE_ON || phase_state[2] == PhaseState::PHASE_LO)
+ _setPwm(((STM32DriverParams*)params)->timers[5], ((STM32DriverParams*)params)->channels[5], _constrain(dc_c + dead_zone, 0.0f, 1.0f)*_PWM_RANGE, _PWM_RESOLUTION);
+ else
+ _setPwm(((STM32DriverParams*)params)->timers[5], ((STM32DriverParams*)params)->channels[5], 0.0f, _PWM_RESOLUTION);
+ break;
+ }
+ _UNUSED(phase_state);
+}
+
+
+
+#ifdef SIMPLEFOC_STM32_DEBUG
+
+int getTimerNumber(int timerIndex) {
+ #if defined(TIM1_BASE)
+ if (timerIndex==TIMER1_INDEX) return 1;
+ #endif
+ #if defined(TIM2_BASE)
+ if (timerIndex==TIMER2_INDEX) return 2;
+ #endif
+ #if defined(TIM3_BASE)
+ if (timerIndex==TIMER3_INDEX) return 3;
+ #endif
+ #if defined(TIM4_BASE)
+ if (timerIndex==TIMER4_INDEX) return 4;
+ #endif
+ #if defined(TIM5_BASE)
+ if (timerIndex==TIMER5_INDEX) return 5;
+ #endif
+ #if defined(TIM6_BASE)
+ if (timerIndex==TIMER6_INDEX) return 6;
+ #endif
+ #if defined(TIM7_BASE)
+ if (timerIndex==TIMER7_INDEX) return 7;
+ #endif
+ #if defined(TIM8_BASE)
+ if (timerIndex==TIMER8_INDEX) return 8;
+ #endif
+ #if defined(TIM9_BASE)
+ if (timerIndex==TIMER9_INDEX) return 9;
+ #endif
+ #if defined(TIM10_BASE)
+ if (timerIndex==TIMER10_INDEX) return 10;
+ #endif
+ #if defined(TIM11_BASE)
+ if (timerIndex==TIMER11_INDEX) return 11;
+ #endif
+ #if defined(TIM12_BASE)
+ if (timerIndex==TIMER12_INDEX) return 12;
+ #endif
+ #if defined(TIM13_BASE)
+ if (timerIndex==TIMER13_INDEX) return 13;
+ #endif
+ #if defined(TIM14_BASE)
+ if (timerIndex==TIMER14_INDEX) return 14;
+ #endif
+ #if defined(TIM15_BASE)
+ if (timerIndex==TIMER15_INDEX) return 15;
+ #endif
+ #if defined(TIM16_BASE)
+ if (timerIndex==TIMER16_INDEX) return 16;
+ #endif
+ #if defined(TIM17_BASE)
+ if (timerIndex==TIMER17_INDEX) return 17;
+ #endif
+ #if defined(TIM18_BASE)
+ if (timerIndex==TIMER18_INDEX) return 18;
+ #endif
+ #if defined(TIM19_BASE)
+ if (timerIndex==TIMER19_INDEX) return 19;
+ #endif
+ #if defined(TIM20_BASE)
+ if (timerIndex==TIMER20_INDEX) return 20;
+ #endif
+ #if defined(TIM21_BASE)
+ if (timerIndex==TIMER21_INDEX) return 21;
+ #endif
+ #if defined(TIM22_BASE)
+ if (timerIndex==TIMER22_INDEX) return 22;
+ #endif
+ return -1;
+}
+
+
+void printTimerCombination(int numPins, PinMap* timers[], int score) {
+ for (int i=0; iperipheral)));
+ SimpleFOCDebug::print("-CH");
+ SimpleFOCDebug::print(STM_PIN_CHANNEL(timers[i]->function));
+ if (STM_PIN_INVERTED(timers[i]->function))
+ SimpleFOCDebug::print("N");
+ }
+ SimpleFOCDebug::print(" ");
+ }
+ SimpleFOCDebug::println("score: ", score);
+}
+
+#endif
+
+#endif
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/drivers/hardware_specific/stm32/stm32_mcu.h b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/drivers/hardware_specific/stm32/stm32_mcu.h
new file mode 100644
index 0000000..411c43b
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/drivers/hardware_specific/stm32/stm32_mcu.h
@@ -0,0 +1,35 @@
+#ifndef STM32_DRIVER_MCU_DEF
+#define STM32_DRIVER_MCU_DEF
+#include "../../hardware_api.h"
+
+#if defined(_STM32_DEF_)
+
+// default pwm parameters
+#define _PWM_RESOLUTION 12 // 12bit
+#define _PWM_RANGE 4095.0f // 2^12 -1 = 4095
+#define _PWM_FREQUENCY 25000 // 25khz
+#define _PWM_FREQUENCY_MAX 50000 // 50khz
+
+// 6pwm parameters
+#define _HARDWARE_6PWM 1
+#define _SOFTWARE_6PWM 0
+#define _ERROR_6PWM -1
+
+
+typedef struct STM32DriverParams {
+ HardwareTimer* timers[6] = {NULL};
+ uint32_t channels[6];
+ long pwm_frequency;
+ float dead_zone;
+ uint8_t interface_type;
+} STM32DriverParams;
+
+// timer synchornisation functions
+void _stopTimers(HardwareTimer **timers_to_stop, int timer_num=6);
+void _startTimers(HardwareTimer **timers_to_start, int timer_num=6);
+
+// timer query functions
+bool _getPwmState(void* params);
+
+#endif
+#endif
\ No newline at end of file
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/drivers/hardware_specific/teensy/teensy3_mcu.cpp b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/drivers/hardware_specific/teensy/teensy3_mcu.cpp
new file mode 100644
index 0000000..fe14527
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/drivers/hardware_specific/teensy/teensy3_mcu.cpp
@@ -0,0 +1,227 @@
+#include "teensy_mcu.h"
+
+// if defined
+// - Teensy 3.0 MK20DX128
+// - Teensy 3.1/3.2 MK20DX256
+// - Teensy LC MKL26Z64
+// - Teensy 3.5 MK64FX512
+// - Teensy 3.6 MK66FX1M0
+#if defined(__arm__) && defined(CORE_TEENSY) && (defined(__MK20DX128__) || defined(__MK20DX256__) || defined(__MKL26Z64__) || defined(__MK64FX512__) || defined(__MK66FX1M0__))
+
+
+#pragma message("")
+#pragma message("SimpleFOC: compiling for Teensy 3.x")
+#pragma message("")
+
+// pin definition from https://github.com/PaulStoffregen/cores/blob/286511f3ec849a6c9e0ec8b73ad6a2fada52e44c/teensy3/pins_teensy.c#L627
+#if defined(__MK20DX128__)
+#define FTM0_CH0_PIN 22
+#define FTM0_CH1_PIN 23
+#define FTM0_CH2_PIN 9
+#define FTM0_CH3_PIN 10
+#define FTM0_CH4_PIN 6
+#define FTM0_CH5_PIN 20
+#define FTM0_CH6_PIN 21
+#define FTM0_CH7_PIN 5
+#define FTM1_CH0_PIN 3
+#define FTM1_CH1_PIN 4
+#elif defined(__MK20DX256__)
+#define FTM0_CH0_PIN 22
+#define FTM0_CH1_PIN 23
+#define FTM0_CH2_PIN 9
+#define FTM0_CH3_PIN 10
+#define FTM0_CH4_PIN 6
+#define FTM0_CH5_PIN 20
+#define FTM0_CH6_PIN 21
+#define FTM0_CH7_PIN 5
+#define FTM1_CH0_PIN 3
+#define FTM1_CH1_PIN 4
+#define FTM2_CH0_PIN 32
+#define FTM2_CH1_PIN 25
+#elif defined(__MKL26Z64__)
+#define FTM0_CH0_PIN 22
+#define FTM0_CH1_PIN 23
+#define FTM0_CH2_PIN 9
+#define FTM0_CH3_PIN 10
+#define FTM0_CH4_PIN 6
+#define FTM0_CH5_PIN 20
+#define FTM1_CH0_PIN 16
+#define FTM1_CH1_PIN 17
+#define FTM2_CH0_PIN 3
+#define FTM2_CH1_PIN 4
+#elif defined(__MK64FX512__)
+#define FTM0_CH0_PIN 22
+#define FTM0_CH1_PIN 23
+#define FTM0_CH2_PIN 9
+#define FTM0_CH3_PIN 10
+#define FTM0_CH4_PIN 6
+#define FTM0_CH5_PIN 20
+#define FTM0_CH6_PIN 21
+#define FTM0_CH7_PIN 5
+#define FTM1_CH0_PIN 3
+#define FTM1_CH1_PIN 4
+#define FTM2_CH0_PIN 29
+#define FTM2_CH1_PIN 30
+#define FTM3_CH0_PIN 2
+#define FTM3_CH1_PIN 14
+#define FTM3_CH2_PIN 7
+#define FTM3_CH3_PIN 8
+#define FTM3_CH4_PIN 35
+#define FTM3_CH5_PIN 36
+#define FTM3_CH6_PIN 37
+#define FTM3_CH7_PIN 38
+#elif defined(__MK66FX1M0__)
+#define FTM0_CH0_PIN 22
+#define FTM0_CH1_PIN 23
+#define FTM0_CH2_PIN 9
+#define FTM0_CH3_PIN 10
+#define FTM0_CH4_PIN 6
+#define FTM0_CH5_PIN 20
+#define FTM0_CH6_PIN 21
+#define FTM0_CH7_PIN 5
+#define FTM1_CH0_PIN 3
+#define FTM1_CH1_PIN 4
+#define FTM2_CH0_PIN 29
+#define FTM2_CH1_PIN 30
+#define FTM3_CH0_PIN 2
+#define FTM3_CH1_PIN 14
+#define FTM3_CH2_PIN 7
+#define FTM3_CH3_PIN 8
+#define FTM3_CH4_PIN 35
+#define FTM3_CH5_PIN 36
+#define FTM3_CH6_PIN 37
+#define FTM3_CH7_PIN 38
+#define TPM1_CH0_PIN 16
+#define TPM1_CH1_PIN 17
+#endif
+
+int _findTimer( const int Ah, const int Al, const int Bh, const int Bl, const int Ch, const int Cl){
+
+ if((Ah == FTM0_CH0_PIN && Al == FTM0_CH1_PIN) ||
+ (Ah == FTM0_CH2_PIN && Al == FTM0_CH3_PIN) ||
+ (Ah == FTM0_CH4_PIN && Al == FTM0_CH5_PIN) ){
+ if((Bh == FTM0_CH0_PIN && Bl == FTM0_CH1_PIN) ||
+ (Bh == FTM0_CH2_PIN && Bl == FTM0_CH3_PIN) ||
+ (Bh == FTM0_CH4_PIN && Bl == FTM0_CH5_PIN) ){
+ if((Ch == FTM0_CH0_PIN && Cl == FTM0_CH1_PIN) ||
+ (Ch == FTM0_CH2_PIN && Cl == FTM0_CH3_PIN) ||
+ (Ch == FTM0_CH4_PIN && Cl == FTM0_CH5_PIN) ){
+#ifdef SIMPLEFOC_TEENSY_DEBUG
+ SIMPLEFOC_DEBUG("TEENSY-DRV: Using timer FTM0.");
+#endif
+ // timer FTM0
+ return 0;
+ }
+ }
+ }
+
+#ifdef FTM3_CH0_PIN // if the board has FTM3 timer
+ if((Ah == FTM3_CH0_PIN && Al == FTM3_CH1_PIN) ||
+ (Ah == FTM3_CH2_PIN && Al == FTM3_CH3_PIN) ||
+ (Ah == FTM3_CH4_PIN && Al == FTM3_CH5_PIN) ){
+ if((Bh == FTM3_CH0_PIN && Bl == FTM3_CH1_PIN) ||
+ (Bh == FTM3_CH2_PIN && Bl == FTM3_CH3_PIN) ||
+ (Bh == FTM3_CH4_PIN && Bl == FTM3_CH5_PIN) ){
+ if((Ch == FTM3_CH0_PIN && Cl == FTM3_CH1_PIN) ||
+ (Ch == FTM3_CH2_PIN && Cl == FTM3_CH3_PIN) ||
+ (Ch == FTM3_CH4_PIN && Cl == FTM3_CH5_PIN) ){
+ // timer FTM3
+#ifdef SIMPLEFOC_TEENSY_DEBUG
+ SIMPLEFOC_DEBUG("TEENSY-DRV: Using timer FTM3.");
+#endif
+ return 3;
+ }
+ }
+ }
+#endif
+
+#ifdef SIMPLEFOC_TEENSY_DEBUG
+ SIMPLEFOC_DEBUG("TEENSY-DRV: ERR: Pins not on timers FTM0 or FTM3!");
+#endif
+ return -1;
+
+}
+
+
+// function setting the high pwm frequency to the supplied pins
+// - Stepper motor - 6PWM setting
+// - hardware specific
+void* _configure6PWM(long pwm_frequency, float dead_zone, const int pinA_h, const int pinA_l, const int pinB_h, const int pinB_l, const int pinC_h, const int pinC_l) {
+ if(!pwm_frequency || !_isset(pwm_frequency) ) pwm_frequency = _PWM_FREQUENCY; // default frequency 25khz
+ else pwm_frequency = _constrain(pwm_frequency, 0, _PWM_FREQUENCY_MAX); // constrain to 50kHz max
+ unsigned long pwm_freq = 2*pwm_frequency; // center-aligned pwm has 4 times lower freq
+ _setHighFrequency(pwm_freq, pinA_h);
+ _setHighFrequency(pwm_freq, pinA_l);
+ _setHighFrequency(pwm_freq, pinB_h);
+ _setHighFrequency(pwm_freq, pinB_l);
+ _setHighFrequency(pwm_freq, pinC_h);
+ _setHighFrequency(pwm_freq, pinC_l);
+
+ GenericDriverParams* params = new GenericDriverParams {
+ .pins = { pinA_h,pinA_l, pinB_h,pinB_l, pinC_h, pinC_l },
+ .pwm_frequency = pwm_frequency
+ };
+
+
+ int timer = _findTimer(pinA_h,pinA_l,pinB_h,pinB_l,pinC_h,pinC_l);
+ if(timer<0) return SIMPLEFOC_DRIVER_INIT_FAILED;
+
+ // find the best combination of prescalers and counter value
+ double dead_time = dead_zone/pwm_freq;
+ int prescaler = 1; // initial prescaler (1,4 or 16)
+ double count = 1; // inital count (1 - 63)
+ for (; prescaler<=16; prescaler*=4){
+ count = dead_time*((double)F_CPU)/((double)prescaler);
+ if(count < 64) break; // found the solution
+ }
+ count = _constrain(count, 1, 63);
+
+ // configure the timer
+ if(timer==0){
+ // Configure FTM0
+ // // inverting and deadtime insertion for FTM1
+ FTM0_COMBINE = 0x00121212; // 0x2 - complemetary mode, 0x1 - dead timer insertion enabled
+
+ // Deadtime config
+ FTM0_DEADTIME = (int)count; // set counter - 1-63
+ FTM0_DEADTIME |= ((prescaler>1) << 7) | ((prescaler>4) << 6); // set prescaler (0b01 - 1, 0b10 - 4, 0b11 - 16)
+
+ // configure center aligned PWM
+ FTM0_SC = 0x00000028; // 0x2 - center-alignment, 0x8 - fixed clock freq
+ }else if(timer==3){
+ // Configure FTM3
+ // inverting and deadtime insertion for FTM1
+ FTM3_COMBINE = 0x00121212; // 0x2 - complemetary mode, 0x1 - dead timer insertion enabled
+
+ // Deadtime config
+ FTM3_DEADTIME = (int)count; // set counter - 1-63
+ FTM3_DEADTIME |= ((prescaler>1) << 7) | ((prescaler>4) << 6); // set prescaler (0b01 - 1, 0b10 - 4, 0b11 - 16)
+
+ // configure center aligned PWM
+ FTM3_SC = 0x00000028; // 0x2 - center-alignment, 0x8 - fixed clock freq
+ }
+
+ return params;
+}
+
+
+
+// function setting the pwm duty cycle to the hardware
+// - Stepper motor - 6PWM setting
+// - hardware specific
+void _writeDutyCycle6PWM(float dc_a, float dc_b, float dc_c, PhaseState *phase_state, void* params){
+ _UNUSED(phase_state);
+ // transform duty cycle from [0,1] to [0,255]
+ // phase A
+ analogWrite(((GenericDriverParams*)params)->pins[0], 255.0f*dc_a);
+ analogWrite(((GenericDriverParams*)params)->pins[1], 255.0f*dc_a);
+
+ // phase B
+ analogWrite(((GenericDriverParams*)params)->pins[2], 255.0f*dc_b);
+ analogWrite(((GenericDriverParams*)params)->pins[3], 255.0f*dc_b);
+
+ // phase C
+ analogWrite(((GenericDriverParams*)params)->pins[4], 255.0f*dc_c);
+ analogWrite(((GenericDriverParams*)params)->pins[5], 255.0f*dc_c);
+}
+#endif
\ No newline at end of file
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/drivers/hardware_specific/teensy/teensy4_mcu.cpp b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/drivers/hardware_specific/teensy/teensy4_mcu.cpp
new file mode 100644
index 0000000..4710844
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/drivers/hardware_specific/teensy/teensy4_mcu.cpp
@@ -0,0 +1,666 @@
+#include "teensy4_mcu.h"
+#include "../../../communication/SimpleFOCDebug.h"
+
+// if defined
+// - Teensy 4.0
+// - Teensy 4.1
+#if defined(__arm__) && defined(CORE_TEENSY) && ( defined(__IMXRT1062__) || defined(ARDUINO_TEENSY40) || defined(ARDUINO_TEENSY41) || defined(ARDUINO_TEENSY_MICROMOD) )
+
+#pragma message("")
+#pragma message("SimpleFOC: compiling for Teensy 4.x")
+#pragma message("")
+
+// #define SIMPLEFOC_TEENSY4_FORCE_CENTER_ALIGNED_3PWM
+
+
+// function finding the TRIG event given the flexpwm timer and the submodule
+// returning -1 if the submodule is not valid or no trigger is available
+// allowing flexpwm1-4 and submodule 0-3
+//
+// the flags are defined in the imxrt.h file
+// https://github.com/PaulStoffregen/cores/blob/dd6aa8419ee173a0a6593eab669fbff54ed85f48/teensy4/imxrt.h#L9662-L9693
+int flexpwm_submodule_to_trig(IMXRT_FLEXPWM_t* flexpwm, int submodule){
+ if(submodule <0 && submodule > 3) return -1;
+ if(flexpwm == &IMXRT_FLEXPWM1){
+ return XBARA1_IN_FLEXPWM1_PWM1_OUT_TRIG0 + submodule;
+ }else if(flexpwm == &IMXRT_FLEXPWM2){
+ return XBARA1_IN_FLEXPWM2_PWM1_OUT_TRIG0 + submodule;
+ }else if(flexpwm == &IMXRT_FLEXPWM3){
+ return XBARA1_IN_FLEXPWM3_PWM1_OUT_TRIG0 + submodule;
+ }else if(flexpwm == &IMXRT_FLEXPWM4){
+ return XBARA1_IN_FLEXPWM4_PWM1_OUT_TRIG0 + submodule;
+ }
+ return -1;
+}
+
+// function finding the EXT_SYNC event given the flexpwm timer and the submodule
+// returning -1 if the submodule is not valid or no trigger is available
+// allowing flexpwm1-4 and submodule 0-3
+//
+// the flags are defined in the imxrt.h file
+// https://github.com/PaulStoffregen/cores/blob/dd6aa8419ee173a0a6593eab669fbff54ed85f48/teensy4/imxrt.h#L9757
+int flexpwm_submodule_to_ext_sync(IMXRT_FLEXPWM_t* flexpwm, int submodule){
+ if(submodule < 0 && submodule > 3) return -1;
+ if(flexpwm == &IMXRT_FLEXPWM1){
+ return XBARA1_OUT_FLEXPWM1_PWM0_EXT_SYNC + submodule;
+ }else if(flexpwm == &IMXRT_FLEXPWM2){
+ return XBARA1_OUT_FLEXPWM2_PWM0_EXT_SYNC + submodule;
+ }else if(flexpwm == &IMXRT_FLEXPWM3){
+ return XBARA1_OUT_FLEXPWM3_EXT_SYNC0 + submodule; // TODO verify why they are not called PWM0_EXT_SYNC but EXT_SYNC0
+ }else if(flexpwm == &IMXRT_FLEXPWM4){
+ return XBARA1_OUT_FLEXPWM4_EXT_SYNC0 + submodule; // TODO verify why they are not called PWM0_EXT_SYNC but EXT_SYNC0
+ }
+ return -1;
+}
+
+// function finding the flexpwm instance given the submodule
+int flexpwm_to_index(IMXRT_FLEXPWM_t* flexpwm){
+ if(flexpwm == &IMXRT_FLEXPWM1) return 1;
+ if(flexpwm == &IMXRT_FLEXPWM2) return 2;
+ if(flexpwm == &IMXRT_FLEXPWM3) return 3;
+ if(flexpwm == &IMXRT_FLEXPWM4) return 4;
+ return -1;
+}
+
+// The i.MXRT1062 uses one config register per two XBAR outputs, so a helper
+// function to make code more readable.
+void xbar_connect(unsigned int input, unsigned int output)
+{
+ if (input >= 88) return;
+ if (output >= 132) return;
+ volatile uint16_t *xbar = &XBARA1_SEL0 + (output / 2);
+ uint16_t val = *xbar;
+ if (!(output & 1)) {
+ val = (val & 0xFF00) | input;
+ } else {
+ val = (val & 0x00FF) | (input << 8);
+ }
+ *xbar = val;
+}
+
+void xbar_init() {
+ CCM_CCGR2 |= CCM_CCGR2_XBAR1(CCM_CCGR_ON); //turn clock on for xbara1
+}
+
+// function which finds the flexpwm instance for a pin
+// if it does not belong to the flexpwm timer it returns a null-pointer
+IMXRT_FLEXPWM_t* get_flexpwm(uint8_t pin){
+
+ const struct pwm_pin_info_struct *info;
+ info = pwm_pin_info + pin;
+ if (pin >= CORE_NUM_DIGITAL || info->type == 2) {
+#ifdef SIMPLEFOC_TEENSY_DEBUG
+ char s[60];
+ sprintf (s, "TEENSY-DRV: ERR: Pin: %d not Flextimer pin!", pin);
+ SIMPLEFOC_DEBUG(s);
+#endif
+ return nullptr;
+ }
+ // FlexPWM pin
+ IMXRT_FLEXPWM_t *flexpwm;
+ switch ((info->module >> 4) & 3) {
+ case 0: flexpwm = &IMXRT_FLEXPWM1; break;
+ case 1: flexpwm = &IMXRT_FLEXPWM2; break;
+ case 2: flexpwm = &IMXRT_FLEXPWM3; break;
+ default: flexpwm = &IMXRT_FLEXPWM4;
+ }
+ if(flexpwm != nullptr){
+#ifdef SIMPLEFOC_TEENSY_DEBUG
+ char s[60];
+ sprintf (s, "TEENSY-DRV: Pin: %d on Flextimer %d.", pin, ((info->module >> 4) & 3) + 1);
+ SIMPLEFOC_DEBUG(s);
+#endif
+ return flexpwm;
+ }
+ return nullptr;
+}
+
+
+// function which finds the timer submodule for a pin
+// if it does not belong to the submodule it returns a -1
+int get_submodule(uint8_t pin){
+
+ const struct pwm_pin_info_struct *info;
+ if (pin >= CORE_NUM_DIGITAL){
+#ifdef SIMPLEFOC_TEENSY_DEBUG
+ char s[60];
+ sprintf (s, "TEENSY-DRV: ERR: Pin: %d not Flextimer pin!", pin);
+ SIMPLEFOC_DEBUG(s);
+#endif
+ return -1;
+ }
+
+ info = pwm_pin_info + pin;
+ int sm1 = info->module&0x3;
+
+ if (sm1 >= 0 && sm1 < 4) {
+#ifdef SIMPLEFOC_TEENSY_DEBUG
+ char s[60];
+ sprintf (s, "TEENSY-DRV: Pin %d on submodule %d.", pin, sm1);
+ SIMPLEFOC_DEBUG(s);
+#endif
+ return sm1;
+ } else {
+#ifdef SIMPLEFOC_TEENSY_DEBUG
+ char s[50];
+ sprintf (s, "TEENSY-DRV: ERR: Pin: %d not in submodule!", pin);
+ SIMPLEFOC_DEBUG(s);
+#endif
+ return -1;
+ }
+}
+
+// function which finds the flexpwm instance for a pair of pins
+// if they do not belong to the same timer it returns a nullpointer
+IMXRT_FLEXPWM_t* get_flexpwm(uint8_t pin, uint8_t pin1){
+
+ const struct pwm_pin_info_struct *info;
+ if (pin >= CORE_NUM_DIGITAL || pin1 >= CORE_NUM_DIGITAL) {
+#ifdef SIMPLEFOC_TEENSY_DEBUG
+ char s[60];
+ sprintf (s, "TEENSY-DRV: ERR: Pins: %d, %d not Flextimer pins!", pin, pin1);
+ SIMPLEFOC_DEBUG(s);
+#endif
+ return nullptr;
+ }
+ info = pwm_pin_info + pin;
+ // FlexPWM pin
+ IMXRT_FLEXPWM_t *flexpwm1,*flexpwm2;
+ switch ((info->module >> 4) & 3) {
+ case 0: flexpwm1 = &IMXRT_FLEXPWM1; break;
+ case 1: flexpwm1 = &IMXRT_FLEXPWM2; break;
+ case 2: flexpwm1 = &IMXRT_FLEXPWM3; break;
+ default: flexpwm1 = &IMXRT_FLEXPWM4;
+ }
+
+ info = pwm_pin_info + pin1;
+ switch ((info->module >> 4) & 3) {
+ case 0: flexpwm2 = &IMXRT_FLEXPWM1; break;
+ case 1: flexpwm2 = &IMXRT_FLEXPWM2; break;
+ case 2: flexpwm2 = &IMXRT_FLEXPWM3; break;
+ default: flexpwm2 = &IMXRT_FLEXPWM4;
+ }
+ if(flexpwm1 == flexpwm2){
+ char s[60];
+ sprintf (s, "TEENSY-DRV: Pins: %d, %d on Flextimer %d.", pin, pin1, ((info->module >> 4) & 3) + 1);
+ SIMPLEFOC_DEBUG(s);
+ return flexpwm1;
+ } else {
+#ifdef SIMPLEFOC_TEENSY_DEBUG
+ char s[60];
+ sprintf (s, "TEENSY-DRV: ERR: Pins: %d, %d not in same Flextimer!", pin, pin1);
+ SIMPLEFOC_DEBUG(s);
+#endif
+ return nullptr;
+ }
+}
+
+
+// function which finds the timer submodule for a pair of pins
+// if they do not belong to the same submodule it returns a -1
+int get_submodule(uint8_t pin, uint8_t pin1){
+
+ const struct pwm_pin_info_struct *info;
+ if (pin >= CORE_NUM_DIGITAL || pin1 >= CORE_NUM_DIGITAL){
+#ifdef SIMPLEFOC_TEENSY_DEBUG
+ char s[60];
+ sprintf (s, "TEENSY-DRV: ERR: Pins: %d, %d not Flextimer pins!", pin, pin1);
+ SIMPLEFOC_DEBUG(s);
+#endif
+ return -1;
+ }
+
+ info = pwm_pin_info + pin;
+ int sm1 = info->module&0x3;
+ info = pwm_pin_info + pin1;
+ int sm2 = info->module&0x3;
+
+ if (sm1 == sm2) {
+ char s[60];
+ sprintf (s, "TEENSY-DRV: Pins: %d, %d on submodule %d.", pin, pin1, sm1);
+ SIMPLEFOC_DEBUG(s);
+ return sm1;
+ } else {
+#ifdef SIMPLEFOC_TEENSY_DEBUG
+ char s[50];
+ sprintf (s, "TEENSY-DRV: ERR: Pins: %d, %d not in same submodule!", pin, pin1);
+ SIMPLEFOC_DEBUG(s);
+#endif
+ return -1;
+ }
+}
+
+
+// function which finds the channel for flexpwm timer pin
+// 0 - X
+// 1 - A
+// 2 - B
+int get_channel(uint8_t pin){
+ const struct pwm_pin_info_struct *info;
+ info = pwm_pin_info + pin;
+ if (pin >= CORE_NUM_DIGITAL || info->type == 2){
+#ifdef SIMPLEFOC_TEENSY_DEBUG
+ char s[90];
+ sprintf (s, "TEENSY-DRV: ERR: Pin: %d not Flextimer pin!", pin);
+ SIMPLEFOC_DEBUG(s);
+#endif
+ return -1;
+ }
+#ifdef SIMPLEFOC_TEENSY_DEBUG
+ char s[60];
+ sprintf (s, "TEENSY-DRV: Pin: %d on channel %s.", pin, info->channel==0 ? "X" : info->channel==1 ? "A" : "B");
+ SIMPLEFOC_DEBUG(s);
+#endif
+ return info->channel;
+}
+
+// function which finds the timer submodule for a pair of pins
+// if they do not belong to the same submodule it returns a -1
+int get_inverted_channel(uint8_t pin, uint8_t pin1){
+
+ if (pin >= CORE_NUM_DIGITAL || pin1 >= CORE_NUM_DIGITAL){
+#ifdef SIMPLEFOC_TEENSY_DEBUG
+ char s[60];
+ sprintf (s, "TEENSY-DRV: ERR: Pins: %d, %d not Flextimer pins!", pin, pin1);
+ SIMPLEFOC_DEBUG(s);
+#endif
+ return -1;
+ }
+
+ int ch1 = get_channel(pin);
+ int ch2 = get_channel(pin1);
+
+ if (ch1 != 1) {
+#ifdef SIMPLEFOC_TEENSY_DEBUG
+ char s[60];
+ sprintf (s, "TEENSY-DRV: ERR: Pin: %d on channel %s - only A supported", pin1, ch1==2 ? "B" : "X");
+ SIMPLEFOC_DEBUG(s);
+#endif
+ return -1;
+ } else if (ch2 != 2) {
+#ifdef SIMPLEFOC_TEENSY_DEBUG
+ char s[60];
+ sprintf (s, "TEENSY-DRV: ERR: Inverted pin: %d on channel %s - only B supported", pin1, ch2==1 ? "A" : "X");
+ SIMPLEFOC_DEBUG(s);
+#endif
+ return -1;
+ } else {
+#ifdef SIMPLEFOC_TEENSY_DEBUG
+ char s[60];
+ sprintf (s, "TEENSY-DRV: Pin: %d on channel B inverted.", pin1);
+ SIMPLEFOC_DEBUG(s);
+#endif
+return ch2;
+ }
+}
+
+// Helper to set up A/B pair on a FlexPWM submodule.
+// can configure sync, prescale and B inversion.
+// sets the desired frequency of the PWM
+// sets the center-aligned pwm
+void setup_pwm_pair (IMXRT_FLEXPWM_t * flexpwm, int submodule, bool ext_sync, const long frequency, float dead_zone )
+{
+ int submodule_mask = 1 << submodule ;
+ flexpwm->MCTRL &= ~ FLEXPWM_MCTRL_RUN (submodule_mask) ; // stop it if its already running
+ flexpwm->MCTRL |= FLEXPWM_MCTRL_CLDOK (submodule_mask) ; // clear load OK
+
+
+ // calculate the counter and prescaler for the desired pwm frequency
+ uint32_t newdiv = (uint32_t)((float)F_BUS_ACTUAL / frequency + 0.5f);
+ uint32_t prescale = 0;
+ //printf(" div=%lu\n", newdiv);
+ while (newdiv > 65535 && prescale < 7) {
+ newdiv = newdiv >> 1;
+ prescale = prescale + 1;
+ }
+ if (newdiv > 65535) {
+ newdiv = 65535;
+ } else if (newdiv < 2) {
+ newdiv = 2;
+ }
+
+ // the halfcycle of the PWM
+ int half_cycle = int(newdiv/2.0f);
+ int dead_time = int(dead_zone*half_cycle); //default dead-time - 2%
+ int mid_pwm = int((half_cycle)/2.0f);
+
+ // if the timer should be externally synced with the master timer
+ int sel = ext_sync ? 3 : 0;
+
+ // setup the timer
+ // https://github.com/PaulStoffregen/cores/blob/master/teensy4/imxrt.h
+ flexpwm->SM[submodule].CTRL2 = FLEXPWM_SMCTRL2_WAITEN | FLEXPWM_SMCTRL2_DBGEN |
+ FLEXPWM_SMCTRL2_FRCEN | FLEXPWM_SMCTRL2_INIT_SEL(sel) | FLEXPWM_SMCTRL2_FORCE_SEL(6);
+ flexpwm->SM[submodule].CTRL = FLEXPWM_SMCTRL_FULL | FLEXPWM_SMCTRL_HALF | FLEXPWM_SMCTRL_PRSC(prescale) ;
+ // https://github.com/PaulStoffregen/cores/blob/70ba01accd728abe75ebfc8dcd8b3d3a8f3e3f25/teensy4/imxrt.h#L4948
+ flexpwm->SM[submodule].OCTRL = 0; //FLEXPWM_SMOCTRL_POLA | FLEXPWM_SMOCTRL_POLB;//channel_to_invert==2 ? 0 : FLEXPWM_SMOCTRL_POLA | FLEXPWM_SMOCTRL_POLB ;
+ if (!ext_sync) flexpwm->SM[submodule].TCTRL = FLEXPWM_SMTCTRL_OUT_TRIG_EN (0b000010) ; // sync trig out on VAL1 match if master timer
+ flexpwm->SM[submodule].DTCNT0 = dead_time ; // should try this out (deadtime control)
+ flexpwm->SM[submodule].DTCNT1 = dead_time ; // should try this out (deadtime control)
+ flexpwm->SM[submodule].INIT = -half_cycle; // count from -HALFCYCLE to +HALFCYCLE
+ flexpwm->SM[submodule].VAL0 = 0;
+ flexpwm->SM[submodule].VAL1 = half_cycle ;
+ flexpwm->SM[submodule].VAL2 = -mid_pwm ;
+ flexpwm->SM[submodule].VAL3 = +mid_pwm ;
+
+ flexpwm->MCTRL |= FLEXPWM_MCTRL_LDOK (submodule_mask) ; // loading reenabled
+ flexpwm->MCTRL |= FLEXPWM_MCTRL_RUN (submodule_mask) ; // start it running
+}
+
+
+// Helper to set up a FlexPWM submodule.
+// can configure sync, prescale
+// sets the desired frequency of the PWM
+// sets the center-aligned pwm
+void setup_pwm_timer_submodule (IMXRT_FLEXPWM_t * flexpwm, int submodule, bool ext_sync, const long frequency)
+{
+ int submodule_mask = 1 << submodule ;
+ flexpwm->MCTRL &= ~ FLEXPWM_MCTRL_RUN (submodule_mask) ; // stop it if its already running
+ flexpwm->MCTRL |= FLEXPWM_MCTRL_CLDOK (submodule_mask) ; // clear load OK
+
+ // calculate the counter and prescaler for the desired pwm frequency
+ uint32_t newdiv = (uint32_t)((float)F_BUS_ACTUAL / frequency + 0.5f);
+ uint32_t prescale = 0;
+ //printf(" div=%lu\n", newdiv);
+ while (newdiv > 65535 && prescale < 7) {
+ newdiv = newdiv >> 1;
+ prescale = prescale + 1;
+ }
+ if (newdiv > 65535) {
+ newdiv = 65535;
+ } else if (newdiv < 2) {
+ newdiv = 2;
+ }
+
+ // the halfcycle of the PWM
+ int half_cycle = int(newdiv/2.0f);
+
+ // if the timer should be externally synced with the master timer
+ int sel = ext_sync ? 3 : 0;
+
+ // setup the timer
+ // https://github.com/PaulStoffregen/cores/blob/master/teensy4/imxrt.h
+ flexpwm->SM[submodule].CTRL2 = FLEXPWM_SMCTRL2_INDEP | FLEXPWM_SMCTRL2_WAITEN | FLEXPWM_SMCTRL2_DBGEN |
+ FLEXPWM_SMCTRL2_FRCEN | FLEXPWM_SMCTRL2_INIT_SEL(sel) | FLEXPWM_SMCTRL2_FORCE_SEL(6);
+ flexpwm->SM[submodule].CTRL = FLEXPWM_SMCTRL_FULL | FLEXPWM_SMCTRL_HALF | FLEXPWM_SMCTRL_PRSC(prescale) ;
+ // https://github.com/PaulStoffregen/cores/blob/70ba01accd728abe75ebfc8dcd8b3d3a8f3e3f25/teensy4/imxrt.h#L4948
+ flexpwm->SM[submodule].OCTRL = 0; //FLEXPWM_SMOCTRL_POLA | FLEXPWM_SMOCTRL_POLB;//channel_to_invert==2 ? 0 : FLEXPWM_SMOCTRL_POLA | FLEXPWM_SMOCTRL_POLB ;
+ if (!ext_sync) flexpwm->SM[submodule].TCTRL = FLEXPWM_SMTCTRL_OUT_TRIG_EN (0b000010) ; // sync trig out on VAL1 match if master timer
+ flexpwm->SM[submodule].DTCNT0 = 0 ;
+ flexpwm->SM[submodule].DTCNT1 = 0 ;
+ flexpwm->SM[submodule].INIT = -half_cycle; // count from -HALFCYCLE to +HALFCYCLE
+ flexpwm->SM[submodule].VAL0 = 0;
+ flexpwm->SM[submodule].VAL1 = half_cycle;
+ flexpwm->SM[submodule].VAL2 = 0 ;
+ flexpwm->SM[submodule].VAL3 = 0 ;
+ flexpwm->SM[submodule].VAL2 = 0 ;
+ flexpwm->SM[submodule].VAL3 = 0 ;
+
+ flexpwm->MCTRL |= FLEXPWM_MCTRL_LDOK (submodule_mask) ; // loading reenabled
+ flexpwm->MCTRL |= FLEXPWM_MCTRL_RUN (submodule_mask) ; // start it running
+}
+
+
+// staring the PWM on A and B channels of the submodule
+void startup_pwm_pair (IMXRT_FLEXPWM_t * flexpwm, int submodule, int channel)
+{
+ int submodule_mask = 1 << submodule ;
+
+ if(channel==1) flexpwm->OUTEN |= FLEXPWM_OUTEN_PWMA_EN (submodule_mask); // enable A output
+ else if(channel==2) flexpwm->OUTEN |= FLEXPWM_OUTEN_PWMB_EN (submodule_mask); // enable B output
+}
+
+
+
+// staring the PWM on A and B channels of the submodule
+void startup_pwm_pair (IMXRT_FLEXPWM_t * flexpwm, int submodule)
+{
+ int submodule_mask = 1 << submodule ;
+
+ flexpwm->OUTEN |= FLEXPWM_OUTEN_PWMA_EN (submodule_mask); // enable A output
+ flexpwm->OUTEN |= FLEXPWM_OUTEN_PWMB_EN (submodule_mask); // enable B output
+}
+
+
+
+// PWM setting on the high and low pair of the PWM channels
+void write_pwm_pair(IMXRT_FLEXPWM_t * flexpwm, int submodule, float duty){
+ int half_cycle = int(flexpwm->SM[submodule].VAL1);
+ int mid_pwm = int((half_cycle)/2.0f);
+ int count_pwm = int(mid_pwm*(duty*2-1)) + mid_pwm;
+
+ flexpwm->SM[submodule].VAL2 = -count_pwm; // A on
+ flexpwm->SM[submodule].VAL3 = count_pwm ; // A off
+ flexpwm->MCTRL |= FLEXPWM_MCTRL_LDOK (1<additional_params;
+ _UNUSED(phase_state);
+ write_pwm_pair (p->flextimers[0], p->submodules[0], dc_a);
+ write_pwm_pair (p->flextimers[1], p->submodules[1], dc_b);
+ write_pwm_pair (p->flextimers[2], p->submodules[2], dc_c);
+}
+
+void write_pwm_on_pin(IMXRT_FLEXPWM_t *p, unsigned int submodule, uint8_t channel, float duty)
+{
+ uint16_t mask = 1 << submodule;
+ uint32_t half_cycle = p->SM[submodule].VAL1;
+ int mid_pwm = int((half_cycle)/2.0f);
+ int cval = int(mid_pwm*(duty*2-1)) + mid_pwm;
+
+ //printf("flexpwmWrite, p=%08lX, sm=%d, ch=%c, cval=%ld\n",
+ //(uint32_t)p, submodule, channel == 0 ? 'X' : (channel == 1 ? 'A' : 'B'), cval);
+ p->MCTRL |= FLEXPWM_MCTRL_CLDOK(mask);
+ switch (channel) {
+ case 0: // X
+ p->SM[submodule].VAL0 = half_cycle - cval;
+ p->OUTEN |= FLEXPWM_OUTEN_PWMX_EN(mask);
+ //printf(" write channel X\n");
+ break;
+ case 1: // A
+ p->SM[submodule].VAL2 = -cval;
+ p->SM[submodule].VAL3 = cval;
+ p->OUTEN |= FLEXPWM_OUTEN_PWMA_EN(mask);
+ //printf(" write channel A\n");
+ break;
+ case 2: // B
+ p->SM[submodule].VAL4 = -cval;
+ p->SM[submodule].VAL5 = cval;
+ p->OUTEN |= FLEXPWM_OUTEN_PWMB_EN(mask);
+ //printf(" write channel B\n");
+ }
+ p->MCTRL |= FLEXPWM_MCTRL_LDOK(mask);
+}
+
+#ifdef SIMPLEFOC_TEENSY4_FORCE_CENTER_ALIGNED_3PWM
+
+// function setting the high pwm frequency to the supplied pins
+// - BLDC motor - 3PWM setting
+// - hardware speciffic
+// in generic case dont do anything
+ void* _configureCenterAligned3PMW(long pwm_frequency,const int pinA, const int pinB, const int pinC) {
+
+ if(!pwm_frequency || !_isset(pwm_frequency) ) pwm_frequency = _PWM_FREQUENCY; // default frequency 25khz
+ else pwm_frequency = _constrain(pwm_frequency, 0, _PWM_FREQUENCY_MAX); // constrain to 50kHz max
+
+ IMXRT_FLEXPWM_t *flexpwmA,*flexpwmB,*flexpwmC;
+ int submoduleA,submoduleB,submoduleC;
+ flexpwmA = get_flexpwm(pinA);
+ submoduleA = get_submodule(pinA);
+ flexpwmB = get_flexpwm(pinB);
+ submoduleB = get_submodule(pinB);
+ flexpwmC = get_flexpwm(pinC);
+ submoduleC = get_submodule(pinC);
+ int channelA = get_channel(pinA);
+ int channelB = get_channel(pinB);
+ int channelC = get_channel(pinC);
+
+
+ // if pins belong to the flextimers and they only use submodules A and B
+ // we can configure the center-aligned pwm
+ if((flexpwmA != nullptr) && (flexpwmB != nullptr) && (flexpwmC != nullptr) && (channelA > 0) && (channelB > 0) && (channelC > 0) ){
+ #ifdef SIMPLEFOC_TEENSY_DEBUG
+ SIMPLEFOC_DEBUG("TEENSY-DRV: All pins on Flexpwm A or B channels - Configuring center-aligned pwm!");
+ #endif
+
+ // Configure FlexPWM units
+ setup_pwm_timer_submodule (flexpwmA, submoduleA, true, pwm_frequency) ; // others externally synced
+ setup_pwm_timer_submodule (flexpwmB, submoduleB, true, pwm_frequency) ; // others externally synced
+ setup_pwm_timer_submodule (flexpwmC, submoduleC, false, pwm_frequency) ; // this is the master, internally synced
+ delayMicroseconds (100) ;
+
+
+ #ifdef SIMPLEFOC_TEENSY_DEBUG
+ char buff[100];
+ sprintf(buff, "TEENSY-CS: Syncing to Master FlexPWM: %d, Submodule: %d", flexpwm_to_index(flexpwmC), submoduleC);
+ SIMPLEFOC_DEBUG(buff);
+ sprintf(buff, "TEENSY-CS: Slave timers FlexPWM: %d, Submodule: %d and FlexPWM: %d, Submodule: %d", flexpwm_to_index(flexpwmA), submoduleA, flexpwm_to_index(flexpwmB), submoduleB);
+ SIMPLEFOC_DEBUG(buff);
+ #endif
+
+ // // turn on XBAR1 clock for all but stop mode
+ xbar_init() ;
+
+ // // Connect trigger to synchronize all timers
+ xbar_connect (flexpwm_submodule_to_trig(flexpwmC, submoduleC), flexpwm_submodule_to_ext_sync(flexpwmA, submoduleA)) ;
+ xbar_connect (flexpwm_submodule_to_trig(flexpwmC, submoduleC), flexpwm_submodule_to_ext_sync(flexpwmB, submoduleB)) ;
+
+ TeensyDriverParams* params = new TeensyDriverParams {
+ .pins = { pinA, pinB, pinC },
+ .pwm_frequency = pwm_frequency,
+ .additional_params = new Teensy4DriverParams {
+ .flextimers = { flexpwmA, flexpwmB, flexpwmC},
+ .submodules = { submoduleA, submoduleB, submoduleC},
+ .channels = {channelA, channelB, channelC},
+ }
+ };
+
+ startup_pwm_pair (flexpwmA, submoduleA, channelA) ;
+ startup_pwm_pair (flexpwmB, submoduleB, channelB) ;
+ startup_pwm_pair (flexpwmC, submoduleC, channelC) ;
+
+ // // config the pins 2/3/6/9/8/7 as their FLEXPWM alternates.
+ *portConfigRegister(pinA) = pwm_pin_info[pinA].muxval ;
+ *portConfigRegister(pinB) = pwm_pin_info[pinB].muxval ;
+ *portConfigRegister(pinC) = pwm_pin_info[pinC].muxval ;
+
+ return params;
+ }else{
+ #ifdef SIMPLEFOC_TEENSY_DEBUG
+ SIMPLEFOC_DEBUG("TEENSY-DRV: Not all pins on Flexpwm A and B channels - cannot configure center-aligned pwm!");
+ #endif
+ return SIMPLEFOC_DRIVER_INIT_FAILED;
+ }
+
+}
+
+// function setting the pwm duty cycle to the hardware
+// - Stepper motor - 6PWM setting
+// - hardware specific
+void _writeCenterAligned3PMW(float dc_a, float dc_b, float dc_c, void* params){
+ Teensy4DriverParams* p = (Teensy4DriverParams*)((TeensyDriverParams*)params)->additional_params;
+ write_pwm_on_pin (p->flextimers[0], p->submodules[0], p->channels[0], dc_a);
+ write_pwm_on_pin (p->flextimers[1], p->submodules[1], p->channels[1], dc_b);
+ write_pwm_on_pin (p->flextimers[2], p->submodules[2], p->channels[2], dc_c);
+}
+
+#endif
+
+#endif
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/drivers/hardware_specific/teensy/teensy4_mcu.h b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/drivers/hardware_specific/teensy/teensy4_mcu.h
new file mode 100644
index 0000000..aed6482
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/drivers/hardware_specific/teensy/teensy4_mcu.h
@@ -0,0 +1,125 @@
+#ifndef TEENSY4_MCU_DRIVER_H
+#define TEENSY4_MCU_DRIVER_H
+
+#include "teensy_mcu.h"
+
+// if defined
+// - Teensy 4.0
+// - Teensy 4.1
+#if defined(__arm__) && defined(CORE_TEENSY) && ( defined(__IMXRT1062__) || defined(ARDUINO_TEENSY40) || defined(ARDUINO_TEENSY41) || defined(ARDUINO_TEENSY_MICROMOD) )
+
+// teensy 4 driver configuration parameters
+typedef struct Teensy4DriverParams {
+ IMXRT_FLEXPWM_t* flextimers[3] = {NULL};
+ int submodules[3];
+ int channels[6];
+ float dead_zone;
+} Teensy4DriverParams;
+
+
+// pin definition from https://github.com/PaulStoffregen/cores/blob/master/teensy4/pwm.c
+struct pwm_pin_info_struct {
+ uint8_t type; // 0=no pwm, 1=flexpwm, 2=quad
+ uint8_t module; // 0-3, 0-3
+ uint8_t channel; // 0=X, 1=A, 2=B
+ uint8_t muxval; //
+};
+#define M(a, b) ((((a) - 1) << 4) | (b))
+#if defined(__IMXRT1062__)
+const struct pwm_pin_info_struct pwm_pin_info[] = {
+ {1, M(1, 1), 0, 4}, // FlexPWM1_1_X 0 // AD_B0_03
+ {1, M(1, 0), 0, 4}, // FlexPWM1_0_X 1 // AD_B0_02
+ {1, M(4, 2), 1, 1}, // FlexPWM4_2_A 2 // EMC_04
+ {1, M(4, 2), 2, 1}, // FlexPWM4_2_B 3 // EMC_05
+ {1, M(2, 0), 1, 1}, // FlexPWM2_0_A 4 // EMC_06
+ {1, M(2, 1), 1, 1}, // FlexPWM2_1_A 5 // EMC_08
+ {1, M(2, 2), 1, 2}, // FlexPWM2_2_A 6 // B0_10
+ {1, M(1, 3), 2, 6}, // FlexPWM1_3_B 7 // B1_01
+ {1, M(1, 3), 1, 6}, // FlexPWM1_3_A 8 // B1_00
+ {1, M(2, 2), 2, 2}, // FlexPWM2_2_B 9 // B0_11
+ {2, M(1, 0), 0, 1}, // QuadTimer1_0 10 // B0_00
+ {2, M(1, 2), 0, 1}, // QuadTimer1_2 11 // B0_02
+ {2, M(1, 1), 0, 1}, // QuadTimer1_1 12 // B0_01
+ {2, M(2, 0), 0, 1}, // QuadTimer2_0 13 // B0_03
+ {2, M(3, 2), 0, 1}, // QuadTimer3_2 14 // AD_B1_02
+ {2, M(3, 3), 0, 1}, // QuadTimer3_3 15 // AD_B1_03
+ {0, M(1, 0), 0, 0},
+ {0, M(1, 0), 0, 0},
+ {2, M(3, 1), 0, 1}, // QuadTimer3_1 18 // AD_B1_01
+ {2, M(3, 0), 0, 1}, // QuadTimer3_0 19 // AD_B1_00
+ {0, M(1, 0), 0, 0},
+ {0, M(1, 0), 0, 0},
+ {1, M(4, 0), 1, 1}, // FlexPWM4_0_A 22 // AD_B1_08
+ {1, M(4, 1), 1, 1}, // FlexPWM4_1_A 23 // AD_B1_09
+ {1, M(1, 2), 0, 4}, // FlexPWM1_2_X 24 // AD_B0_12
+ {1, M(1, 3), 0, 4}, // FlexPWM1_3_X 25 // AD_B0_13
+ {0, M(1, 0), 0, 0},
+ {0, M(1, 0), 0, 0},
+ {1, M(3, 1), 2, 1}, // FlexPWM3_1_B 28 // EMC_32
+ {1, M(3, 1), 1, 1}, // FlexPWM3_1_A 29 // EMC_31
+ {0, M(1, 0), 0, 0},
+ {0, M(1, 0), 0, 0},
+ {0, M(1, 0), 0, 0},
+ {1, M(2, 0), 2, 1}, // FlexPWM2_0_B 33 // EMC_07
+#ifdef ARDUINO_TEENSY40
+ {1, M(1, 1), 2, 1}, // FlexPWM1_1_B 34 // SD_B0_03
+ {1, M(1, 1), 1, 1}, // FlexPWM1_1_A 35 // SD_B0_02
+ {1, M(1, 0), 2, 1}, // FlexPWM1_0_B 36 // SD_B0_01
+ {1, M(1, 0), 1, 1}, // FlexPWM1_0_A 37 // SD_B0_00
+ {1, M(1, 2), 2, 1}, // FlexPWM1_2_B 38 // SD_B0_05
+ {1, M(1, 2), 1, 1}, // FlexPWM1_2_A 39 // SD_B0_04
+#endif
+#ifdef ARDUINO_TEENSY41
+ {0, M(1, 0), 0, 0},
+ {0, M(1, 0), 0, 0},
+ {1, M(2, 3), 1, 6}, // FlexPWM2_3_A 36 // B1_00
+ {1, M(2, 3), 2, 6}, // FlexPWM2_3_B 37 // B1_01
+ {0, M(1, 0), 0, 0},
+ {0, M(1, 0), 0, 0},
+ {0, M(1, 0), 0, 0},
+ {0, M(1, 0), 0, 0},
+ {1, M(1, 1), 2, 1}, // FlexPWM1_1_B 42 // SD_B0_03
+ {1, M(1, 1), 1, 1}, // FlexPWM1_1_A 43 // SD_B0_02
+ {1, M(1, 0), 2, 1}, // FlexPWM1_0_B 44 // SD_B0_01
+ {1, M(1, 0), 1, 1}, // FlexPWM1_0_A 45 // SD_B0_00
+ {1, M(1, 2), 2, 1}, // FlexPWM1_2_B 46 // SD_B0_05
+ {1, M(1, 2), 1, 1}, // FlexPWM1_2_A 47 // SD_B0_04
+ {0, M(1, 0), 0, 0}, // duplicate FlexPWM1_0_B
+ {0, M(1, 0), 0, 0}, // duplicate FlexPWM1_2_A
+ {0, M(1, 0), 0, 0}, // duplicate FlexPWM1_2_B
+ {1, M(3, 3), 2, 1}, // FlexPWM3_3_B 51 // EMC_22
+ {0, M(1, 0), 0, 0}, // duplicate FlexPWM1_1_B
+ {0, M(1, 0), 0, 0}, // duplicate FlexPWM1_1_A
+ {1, M(3, 0), 1, 1}, // FlexPWM3_0_A 54 // EMC_29
+#endif
+#ifdef ARDUINO_TEENSY_MICROMOD
+ {1, M(1, 1), 2, 1}, // FlexPWM1_1_B 34 // SD_B0_03
+ {1, M(1, 1), 1, 1}, // FlexPWM1_1_A 35 // SD_B0_02
+ {1, M(1, 0), 2, 1}, // FlexPWM1_0_B 36 // SD_B0_01
+ {1, M(1, 0), 1, 1}, // FlexPWM1_0_A 37 // SD_B0_00
+ {1, M(1, 2), 1, 1}, // FlexPWM1_2_A 38 // SD_B0_04
+ {1, M(1, 2), 2, 1}, // FlexPWM1_2_B 39 // SD_B0_05
+ {2, M(2, 1), 0, 1}, // QuadTimer2_1 40 // B0_04
+ {2, M(2, 2), 0, 1}, // QuadTimer2_2 41 // B0_05
+ {0, M(1, 0), 0, 0}, // duplicate QuadTimer3_0
+ {0, M(1, 0), 0, 0}, // duplicate QuadTimer3_1
+ {0, M(1, 0), 0, 0}, // duplicate QuadTimer3_2
+ {2, M(4, 0), 0, 1}, // QuadTimer4_0 45 // B0_09
+#endif
+};
+
+// function finding the flexpwm instance given the submodule
+int flexpwm_to_index(IMXRT_FLEXPWM_t* flexpwm);
+// find the trigger TRG0 for the given timer and submodule
+int flexpwm_submodule_to_trig(IMXRT_FLEXPWM_t* flexpwm, int submodule);
+// find the external trigger for the given timer and submodule
+int flexpwm_submodule_to_ext_sync(IMXRT_FLEXPWM_t* flexpwm, int submodule);
+// function to connecting the triggers
+void xbar_connect(unsigned int input, unsigned int output);
+// function to initialize the xbar
+void xbar_init();
+
+#endif
+
+#endif
+#endif
\ No newline at end of file
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/drivers/hardware_specific/teensy/teensy_mcu.cpp b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/drivers/hardware_specific/teensy/teensy_mcu.cpp
new file mode 100644
index 0000000..196f07f
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/drivers/hardware_specific/teensy/teensy_mcu.cpp
@@ -0,0 +1,151 @@
+#include "teensy_mcu.h"
+
+#if defined(__arm__) && defined(CORE_TEENSY)
+
+#include "../../../communication/SimpleFOCDebug.h"
+
+// configure High PWM frequency
+void _setHighFrequency(const long freq, const int pin){
+ analogWrite(pin, 0);
+ analogWriteFrequency(pin, freq);
+}
+
+
+// function setting the high pwm frequency to the supplied pins
+// - Stepper motor - 2PWM setting
+// - hardware specific
+void* _configure1PWM(long pwm_frequency, const int pinA) {
+ if(!pwm_frequency || !_isset(pwm_frequency) ) pwm_frequency = _PWM_FREQUENCY; // default frequency 25khz
+ else pwm_frequency = _constrain(pwm_frequency, 0, _PWM_FREQUENCY_MAX); // constrain to 50kHz max
+ _setHighFrequency(pwm_frequency, pinA);
+ TeensyDriverParams* params = new TeensyDriverParams {
+ .pins = { pinA },
+ .pwm_frequency = pwm_frequency,
+ .additional_params = nullptr
+ };
+ return params;
+}
+
+
+// function setting the high pwm frequency to the supplied pins
+// - Stepper motor - 2PWM setting
+// - hardware specific
+void* _configure2PWM(long pwm_frequency, const int pinA, const int pinB) {
+ if(!pwm_frequency || !_isset(pwm_frequency) ) pwm_frequency = _PWM_FREQUENCY; // default frequency 25khz
+ else pwm_frequency = _constrain(pwm_frequency, 0, _PWM_FREQUENCY_MAX); // constrain to 50kHz max
+ _setHighFrequency(pwm_frequency, pinA);
+ _setHighFrequency(pwm_frequency, pinB);
+ TeensyDriverParams* params = new TeensyDriverParams {
+ .pins = { pinA, pinB },
+ .pwm_frequency = pwm_frequency,
+ .additional_params = nullptr
+ };
+ return params;
+}
+
+// inital weak implementation of the center aligned 3pwm configuration
+// teensy 4 and 3 have center aligned pwm
+__attribute__((weak)) void* _configureCenterAligned3PMW(long pwm_frequency, const int pinA, const int pinB, const int pinC) {
+ return SIMPLEFOC_DRIVER_INIT_FAILED;
+}
+
+// function setting the high pwm frequency to the supplied pins
+// - BLDC motor - 3PWM setting
+// - hardware specific
+void* _configure3PWM(long pwm_frequency,const int pinA, const int pinB, const int pinC) {
+ if(!pwm_frequency || !_isset(pwm_frequency) ) pwm_frequency = _PWM_FREQUENCY; // default frequency 25khz
+ else pwm_frequency = _constrain(pwm_frequency, 0, _PWM_FREQUENCY_MAX); // constrain to 50kHz max
+
+ // try configuring center aligned pwm
+ void* p = _configureCenterAligned3PMW(pwm_frequency, pinA, pinB, pinC);
+ if(p != SIMPLEFOC_DRIVER_INIT_FAILED){
+ return p; // if center aligned pwm is available return the params
+ }else{ // if center aligned pwm is not available use fast pwm
+ SIMPLEFOC_DEBUG("TEENSY-DRV: Configuring 3PWM with fast pwm. Please consider using center aligned pwm for better performance!");
+ _setHighFrequency(pwm_frequency, pinA);
+ _setHighFrequency(pwm_frequency, pinB);
+ _setHighFrequency(pwm_frequency, pinC);
+ TeensyDriverParams* params = new TeensyDriverParams {
+ .pins = { pinA, pinB, pinC },
+ .pwm_frequency = pwm_frequency,
+ .additional_params = nullptr
+ };
+ return params;
+ }
+}
+
+// function setting the high pwm frequency to the supplied pins
+// - Stepper motor - 4PWM setting
+// - hardware specific
+void* _configure4PWM(long pwm_frequency, const int pinA, const int pinB, const int pinC, const int pinD) {
+ if(!pwm_frequency || !_isset(pwm_frequency) ) pwm_frequency = _PWM_FREQUENCY; // default frequency 25khz
+ else pwm_frequency = _constrain(pwm_frequency, 0, _PWM_FREQUENCY_MAX); // constrain to 50kHz max
+ _setHighFrequency(pwm_frequency, pinA);
+ _setHighFrequency(pwm_frequency, pinB);
+ _setHighFrequency(pwm_frequency, pinC);
+ _setHighFrequency(pwm_frequency, pinD);
+ TeensyDriverParams* params = new TeensyDriverParams {
+ .pins = { pinA, pinB, pinC, pinD },
+ .pwm_frequency = pwm_frequency,
+ .additional_params = nullptr
+ };
+ return params;
+}
+
+
+// function setting the pwm duty cycle to the hardware
+// - Stepper motor - 2PWM setting
+// - hardware specific
+void _writeDutyCycle1PWM(float dc_a, void* params) {
+ // transform duty cycle from [0,1] to [0,255]
+ analogWrite(((TeensyDriverParams*)params)->pins[0], 255.0f*dc_a);
+}
+
+
+// function setting the pwm duty cycle to the hardware
+// - Stepper motor - 2PWM setting
+// - hardware specific
+void _writeDutyCycle2PWM(float dc_a, float dc_b, void* params) {
+ // transform duty cycle from [0,1] to [0,255]
+ analogWrite(((TeensyDriverParams*)params)->pins[0], 255.0f*dc_a);
+ analogWrite(((TeensyDriverParams*)params)->pins[1], 255.0f*dc_b);
+}
+
+// inital weak implementation of the center aligned 3pwm configuration
+// teensy 4 and 3 have center aligned pwm implementation of this function
+__attribute__((weak)) void _writeCenterAligned3PMW(float dc_a, float dc_b, float dc_c, void* params){
+ _UNUSED(dc_a);
+ _UNUSED(dc_b);
+ _UNUSED(dc_c);
+ _UNUSED(params);
+}
+
+
+// function setting the pwm duty cycle to the hardware
+// - BLDC motor - 3PWM setting
+// - hardware specific
+void _writeDutyCycle3PWM(float dc_a, float dc_b, float dc_c, void* params){
+
+ TeensyDriverParams* p = (TeensyDriverParams*)params;
+ if(p->additional_params != nullptr){
+ _writeCenterAligned3PMW(dc_a, dc_b, dc_c, p);
+ }else{
+ // transform duty cycle from [0,1] to [0,255]
+ analogWrite(p->pins[0], 255.0f*dc_a);
+ analogWrite(p->pins[1], 255.0f*dc_b);
+ analogWrite(p->pins[2], 255.0f*dc_c);
+ }
+}
+
+// function setting the pwm duty cycle to the hardware
+// - Stepper motor - 4PWM setting
+// - hardware specific
+void _writeDutyCycle4PWM(float dc_1a, float dc_1b, float dc_2a, float dc_2b, void* params){
+ // transform duty cycle from [0,1] to [0,255]
+ analogWrite(((TeensyDriverParams*)params)->pins[0], 255.0f*dc_1a);
+ analogWrite(((TeensyDriverParams*)params)->pins[1], 255.0f*dc_1b);
+ analogWrite(((TeensyDriverParams*)params)->pins[2], 255.0f*dc_2a);
+ analogWrite(((TeensyDriverParams*)params)->pins[3], 255.0f*dc_2b);
+}
+
+#endif
\ No newline at end of file
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/drivers/hardware_specific/teensy/teensy_mcu.h b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/drivers/hardware_specific/teensy/teensy_mcu.h
new file mode 100644
index 0000000..266f4b6
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/drivers/hardware_specific/teensy/teensy_mcu.h
@@ -0,0 +1,27 @@
+#ifndef TEENSY_MCU_DRIVER_H
+#define TEENSY_MCU_DRIVER_H
+
+#include "../../hardware_api.h"
+
+#if defined(__arm__) && defined(CORE_TEENSY)
+
+#define _PWM_FREQUENCY 25000 // 25khz
+#define _PWM_FREQUENCY_MAX 50000 // 50khz
+
+// debugging output
+#define SIMPLEFOC_TEENSY_DEBUG
+
+typedef struct TeensyDriverParams {
+ int pins[6] = {(int)NOT_SET};
+ long pwm_frequency;
+ void* additional_params;
+} TeensyDriverParams;
+
+// configure High PWM frequency
+void _setHighFrequency(const long freq, const int pin);
+
+void* _configureCenterAligned3PMW(long pwm_frequency, const int pinA, const int pinB, const int pinC);
+void _writeCenterAligned3PMW(float dc_a, float dc_b, float dc_c, void* params);
+
+#endif
+#endif
\ No newline at end of file
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/sensors/Encoder.cpp b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/sensors/Encoder.cpp
new file mode 100644
index 0000000..fa4b8e7
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/sensors/Encoder.cpp
@@ -0,0 +1,229 @@
+#include "Encoder.h"
+
+
+/*
+ Encoder(int encA, int encB , int cpr, int index)
+ - encA, encB - encoder A and B pins
+ - cpr - counts per rotation number (cpm=ppm*4)
+ - index pin - (optional input)
+*/
+
+Encoder::Encoder(int _encA, int _encB , float _ppr, int _index){
+
+ // Encoder measurement structure init
+ // hardware pins
+ pinA = _encA;
+ pinB = _encB;
+ // counter setup
+ pulse_counter = 0;
+ pulse_timestamp = 0;
+
+ cpr = _ppr;
+ A_active = 0;
+ B_active = 0;
+ I_active = 0;
+ // index pin
+ index_pin = _index; // its 0 if not used
+
+ // velocity calculation variables
+ prev_Th = 0;
+ pulse_per_second = 0;
+ prev_pulse_counter = 0;
+ prev_timestamp_us = _micros();
+
+ // extern pullup as default
+ pullup = Pullup::USE_EXTERN;
+ // enable quadrature encoder by default
+ quadrature = Quadrature::ON;
+}
+
+// Encoder interrupt callback functions
+// A channel
+void Encoder::handleA() {
+ bool A = digitalRead(pinA);
+ switch (quadrature){
+ case Quadrature::ON:
+ // CPR = 4xPPR
+ if ( A != A_active ) {
+ pulse_counter += (A_active == B_active) ? 1 : -1;
+ pulse_timestamp = _micros();
+ A_active = A;
+ }
+ break;
+ case Quadrature::OFF:
+ // CPR = PPR
+ if(A && !digitalRead(pinB)){
+ pulse_counter++;
+ pulse_timestamp = _micros();
+ }
+ break;
+ }
+}
+// B channel
+void Encoder::handleB() {
+ bool B = digitalRead(pinB);
+ switch (quadrature){
+ case Quadrature::ON:
+ // // CPR = 4xPPR
+ if ( B != B_active ) {
+ pulse_counter += (A_active != B_active) ? 1 : -1;
+ pulse_timestamp = _micros();
+ B_active = B;
+ }
+ break;
+ case Quadrature::OFF:
+ // CPR = PPR
+ if(B && !digitalRead(pinA)){
+ pulse_counter--;
+ pulse_timestamp = _micros();
+ }
+ break;
+ }
+}
+
+// Index channel
+void Encoder::handleIndex() {
+ if(hasIndex()){
+ bool I = digitalRead(index_pin);
+ if(I && !I_active){
+ index_found = true;
+ // align encoder on each index
+ long tmp = pulse_counter;
+ // corrent the counter value
+ pulse_counter = round((double)pulse_counter/(double)cpr)*cpr;
+ // preserve relative speed
+ prev_pulse_counter += pulse_counter - tmp;
+ }
+ I_active = I;
+ }
+}
+
+
+// Sensor update function. Safely copy volatile interrupt variables into Sensor base class state variables.
+void Encoder::update() {
+ // Copy volatile variables in minimal-duration blocking section to ensure no interrupts are missed
+ noInterrupts();
+ angle_prev_ts = pulse_timestamp;
+ long copy_pulse_counter = pulse_counter;
+ interrupts();
+ // TODO: numerical precision issue here if the pulse_counter overflows the angle will be lost
+ full_rotations = copy_pulse_counter / (int)cpr;
+ angle_prev = _2PI * ((copy_pulse_counter) % ((int)cpr)) / ((float)cpr);
+}
+
+/*
+ Shaft angle calculation
+*/
+float Encoder::getSensorAngle(){
+ return _2PI * (pulse_counter) / ((float)cpr);
+}
+
+
+
+/*
+ Shaft velocity calculation
+ function using mixed time and frequency measurement technique
+*/
+float Encoder::getVelocity(){
+ // Copy volatile variables in minimal-duration blocking section to ensure no interrupts are missed
+ noInterrupts();
+ long copy_pulse_counter = pulse_counter;
+ long copy_pulse_timestamp = pulse_timestamp;
+ interrupts();
+ // timestamp
+ long timestamp_us = _micros();
+ // sampling time calculation
+ float Ts = (timestamp_us - prev_timestamp_us) * 1e-6f;
+ // quick fix for strange cases (micros overflow)
+ if(Ts <= 0 || Ts > 0.5f) Ts = 1e-3f;
+
+ // time from last impulse
+ float Th = (timestamp_us - copy_pulse_timestamp) * 1e-6f;
+ long dN = copy_pulse_counter - prev_pulse_counter;
+
+ // Pulse per second calculation (Eq.3.)
+ // dN - impulses received
+ // Ts - sampling time - time in between function calls
+ // Th - time from last impulse
+ // Th_1 - time form last impulse of the previous call
+ // only increment if some impulses received
+ float dt = Ts + prev_Th - Th;
+ pulse_per_second = (dN != 0 && dt > Ts/2) ? dN / dt : pulse_per_second;
+
+ // if more than 0.05f passed in between impulses
+ if ( Th > 0.1f) pulse_per_second = 0;
+
+ // velocity calculation
+ float velocity = pulse_per_second / ((float)cpr) * (_2PI);
+
+ // save variables for next pass
+ prev_timestamp_us = timestamp_us;
+ // save velocity calculation variables
+ prev_Th = Th;
+ prev_pulse_counter = copy_pulse_counter;
+ return velocity;
+}
+
+// getter for index pin
+// return -1 if no index
+int Encoder::needsSearch(){
+ return hasIndex() && !index_found;
+}
+
+// private function used to determine if encoder has index
+int Encoder::hasIndex(){
+ return index_pin != 0;
+}
+
+
+// encoder initialisation of the hardware pins
+// and calculation variables
+void Encoder::init(){
+
+ // Encoder - check if pullup needed for your encoder
+ if(pullup == Pullup::USE_INTERN){
+ pinMode(pinA, INPUT_PULLUP);
+ pinMode(pinB, INPUT_PULLUP);
+ if(hasIndex()) pinMode(index_pin,INPUT_PULLUP);
+ }else{
+ pinMode(pinA, INPUT);
+ pinMode(pinB, INPUT);
+ if(hasIndex()) pinMode(index_pin,INPUT);
+ }
+
+ // counter setup
+ pulse_counter = 0;
+ pulse_timestamp = _micros();
+ // velocity calculation variables
+ prev_Th = 0;
+ pulse_per_second = 0;
+ prev_pulse_counter = 0;
+ prev_timestamp_us = _micros();
+
+ // initial cpr = PPR
+ // change it if the mode is quadrature
+ if(quadrature == Quadrature::ON) cpr = 4*cpr;
+
+ // we don't call Sensor::init() here because init is handled in Encoder class.
+}
+
+// function enabling hardware interrupts of the for the callback provided
+// if callback is not provided then the interrupt is not enabled
+void Encoder::enableInterrupts(void (*doA)(), void(*doB)(), void(*doIndex)()){
+ // attach interrupt if functions provided
+ switch(quadrature){
+ case Quadrature::ON:
+ // A callback and B callback
+ if(doA != nullptr) attachInterrupt(digitalPinToInterrupt(pinA), doA, CHANGE);
+ if(doB != nullptr) attachInterrupt(digitalPinToInterrupt(pinB), doB, CHANGE);
+ break;
+ case Quadrature::OFF:
+ // A callback and B callback
+ if(doA != nullptr) attachInterrupt(digitalPinToInterrupt(pinA), doA, RISING);
+ if(doB != nullptr) attachInterrupt(digitalPinToInterrupt(pinB), doB, RISING);
+ break;
+ }
+
+ // if index used initialize the index interrupt
+ if(hasIndex() && doIndex != nullptr) attachInterrupt(digitalPinToInterrupt(index_pin), doIndex, CHANGE);
+}
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/sensors/Encoder.h b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/sensors/Encoder.h
new file mode 100644
index 0000000..af6a5ab
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/sensors/Encoder.h
@@ -0,0 +1,91 @@
+#ifndef ENCODER_LIB_H
+#define ENCODER_LIB_H
+
+#include "Arduino.h"
+#include "../common/foc_utils.h"
+#include "../common/time_utils.h"
+#include "../common/base_classes/Sensor.h"
+
+
+/**
+ * Quadrature mode configuration structure
+ */
+enum Quadrature : uint8_t {
+ ON = 0x00, //!< Enable quadrature mode CPR = 4xPPR
+ OFF = 0x01 //!< Disable quadrature mode / CPR = PPR
+};
+
+class Encoder: public Sensor{
+ public:
+ /**
+ Encoder class constructor
+ @param encA encoder B pin
+ @param encB encoder B pin
+ @param ppr impulses per rotation (cpr=ppr*4)
+ @param index index pin number (optional input)
+ */
+ Encoder(int encA, int encB , float ppr, int index = 0);
+
+ /** encoder initialise pins */
+ void init() override;
+ /**
+ * function enabling hardware interrupts for the encoder channels with provided callback functions
+ * if callback is not provided then the interrupt is not enabled
+ *
+ * @param doA pointer to the A channel interrupt handler function
+ * @param doB pointer to the B channel interrupt handler function
+ * @param doIndex pointer to the Index channel interrupt handler function
+ *
+ */
+ void enableInterrupts(void (*doA)() = nullptr, void(*doB)() = nullptr, void(*doIndex)() = nullptr);
+
+ // Encoder interrupt callback functions
+ /** A channel callback function */
+ void handleA();
+ /** B channel callback function */
+ void handleB();
+ /** Index channel callback function */
+ void handleIndex();
+
+
+ // pins A and B
+ int pinA; //!< encoder hardware pin A
+ int pinB; //!< encoder hardware pin B
+ int index_pin; //!< index pin
+
+ // Encoder configuration
+ Pullup pullup; //!< Configuration parameter internal or external pullups
+ Quadrature quadrature;//!< Configuration parameter enable or disable quadrature mode
+ float cpr;//!< encoder cpr number
+
+ // Abstract functions of the Sensor class implementation
+ /** get current angle (rad) */
+ float getSensorAngle() override;
+ /** get current angular velocity (rad/s) */
+ float getVelocity() override;
+ virtual void update() override;
+
+ /**
+ * returns 0 if it does need search for absolute zero
+ * 0 - encoder without index
+ * 1 - ecoder with index
+ */
+ int needsSearch() override;
+
+ private:
+ int hasIndex(); //!< function returning 1 if encoder has index pin and 0 if not.
+
+ volatile long pulse_counter;//!< current pulse counter
+ volatile long pulse_timestamp;//!< last impulse timestamp in us
+ volatile int A_active; //!< current active states of A channel
+ volatile int B_active; //!< current active states of B channel
+ volatile int I_active; //!< current active states of Index channel
+ volatile bool index_found = false; //!< flag stating that the index has been found
+
+ // velocity calculation variables
+ float prev_Th, pulse_per_second;
+ volatile long prev_pulse_counter, prev_timestamp_us;
+};
+
+
+#endif
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/sensors/GenericSensor.cpp b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/sensors/GenericSensor.cpp
new file mode 100644
index 0000000..3d4025f
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/sensors/GenericSensor.cpp
@@ -0,0 +1,26 @@
+#include "GenericSensor.h"
+
+
+/*
+ GenericSensor( float (*readCallback)() )
+ - readCallback - pointer to the function which reads the sensor angle.
+*/
+
+GenericSensor::GenericSensor(float (*readCallback)(), void (*initCallback)()){
+ // if function provided add it to the
+ if(readCallback != nullptr) this->readCallback = readCallback;
+ if(initCallback != nullptr) this->initCallback = initCallback;
+}
+
+void GenericSensor::init(){
+ // if init callback specified run it
+ if(initCallback != nullptr) this->initCallback();
+ this->Sensor::init(); // call base class init
+}
+
+/*
+ Shaft angle calculation
+*/
+float GenericSensor::getSensorAngle(){
+ return this->readCallback();
+}
\ No newline at end of file
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/sensors/GenericSensor.h b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/sensors/GenericSensor.h
new file mode 100644
index 0000000..ba0dfe5
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/sensors/GenericSensor.h
@@ -0,0 +1,31 @@
+#ifndef GENERIC_SENSOR_LIB_H
+#define GENERIC_SENSOR_LIB_H
+
+#include "Arduino.h"
+#include "../common/foc_utils.h"
+#include "../common/time_utils.h"
+#include "../common/base_classes/Sensor.h"
+
+
+class GenericSensor: public Sensor{
+ public:
+ /**
+ GenericSensor class constructor
+ * @param readCallback pointer to the function reading the sensor angle
+ * @param initCallback pointer to the function initialising the sensor
+ */
+ GenericSensor(float (*readCallback)() = nullptr, void (*initCallback)() = nullptr);
+
+ float (*readCallback)() = nullptr; //!< function pointer to sensor reading
+ void (*initCallback)() = nullptr; //!< function pointer to sensor initialisation
+
+ void init() override;
+
+ // Abstract functions of the Sensor class implementation
+ /** get current angle (rad) */
+ float getSensorAngle() override;
+
+};
+
+
+#endif
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/sensors/HallSensor.cpp b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/sensors/HallSensor.cpp
new file mode 100644
index 0000000..64c5e48
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/sensors/HallSensor.cpp
@@ -0,0 +1,181 @@
+#include "HallSensor.h"
+
+
+/*
+ HallSensor(int hallA, int hallB , int cpr, int index)
+ - hallA, hallB, hallC - HallSensor A, B and C pins
+ - pp - pole pairs
+*/
+HallSensor::HallSensor(int _hallA, int _hallB, int _hallC, int _pp){
+
+ // hardware pins
+ pinA = _hallA;
+ pinB = _hallB;
+ pinC = _hallC;
+
+ // hall has 6 segments per electrical revolution
+ cpr = _pp * 6;
+
+ // extern pullup as default
+ pullup = Pullup::USE_EXTERN;
+}
+
+// HallSensor interrupt callback functions
+// A channel
+void HallSensor::handleA() {
+ A_active= digitalRead(pinA);
+ updateState();
+}
+// B channel
+void HallSensor::handleB() {
+ B_active = digitalRead(pinB);
+ updateState();
+}
+
+// C channel
+void HallSensor::handleC() {
+ C_active = digitalRead(pinC);
+ updateState();
+}
+
+/**
+ * Updates the state and sector following an interrupt
+ */
+void HallSensor::updateState() {
+ int8_t new_hall_state = C_active + (B_active << 1) + (A_active << 2);
+
+ // glitch avoidance #1 - sometimes we get an interrupt but pins haven't changed
+ if (new_hall_state == hall_state) return;
+
+ long new_pulse_timestamp = _micros();
+ hall_state = new_hall_state;
+
+ int8_t new_electric_sector = ELECTRIC_SECTORS[hall_state];
+ int8_t electric_sector_dif = new_electric_sector - electric_sector;
+ if (electric_sector_dif > 3) {
+ //underflow
+ direction = Direction::CCW;
+ electric_rotations += direction;
+ } else if (electric_sector_dif < (-3)) {
+ //overflow
+ direction = Direction::CW;
+ electric_rotations += direction;
+ } else {
+ direction = (new_electric_sector > electric_sector)? Direction::CW : Direction::CCW;
+ }
+ electric_sector = new_electric_sector;
+
+ // glitch avoidance #2 changes in direction can cause velocity spikes. Possible improvements needed in this area
+ if (direction == old_direction) {
+ // not oscilating or just changed direction
+ pulse_diff = new_pulse_timestamp - pulse_timestamp;
+ } else {
+ pulse_diff = 0;
+ }
+
+ pulse_timestamp = new_pulse_timestamp;
+ total_interrupts++;
+ old_direction = direction;
+ if (onSectorChange != nullptr) onSectorChange(electric_sector);
+}
+
+/**
+ * Optionally set a function callback to be fired when sector changes
+ * void onSectorChange(int sector) {
+ * ... // for debug or call driver directly?
+ * }
+ * sensor.attachSectorCallback(onSectorChange);
+ */
+void HallSensor::attachSectorCallback(void (*_onSectorChange)(int sector)) {
+ onSectorChange = _onSectorChange;
+}
+
+
+
+// Sensor update function. Safely copy volatile interrupt variables into Sensor base class state variables.
+void HallSensor::update() {
+ // Copy volatile variables in minimal-duration blocking section to ensure no interrupts are missed
+ if (use_interrupt){
+ noInterrupts();
+ }else{
+ A_active = digitalRead(pinA);
+ B_active = digitalRead(pinB);
+ C_active = digitalRead(pinC);
+ updateState();
+ }
+
+ angle_prev_ts = pulse_timestamp;
+ long last_electric_rotations = electric_rotations;
+ int8_t last_electric_sector = electric_sector;
+ if (use_interrupt) interrupts();
+ angle_prev = ((float)((last_electric_rotations * 6 + last_electric_sector) % cpr) / (float)cpr) * _2PI ;
+ full_rotations = (int32_t)((last_electric_rotations * 6 + last_electric_sector) / cpr);
+}
+
+
+
+/*
+ Shaft angle calculation
+ TODO: numerical precision issue here if the electrical rotation overflows the angle will be lost
+*/
+float HallSensor::getSensorAngle() {
+ return ((float)(electric_rotations * 6 + electric_sector) / (float)cpr) * _2PI ;
+}
+
+/*
+ Shaft velocity calculation
+ function using mixed time and frequency measurement technique
+*/
+float HallSensor::getVelocity(){
+ noInterrupts();
+ long last_pulse_timestamp = pulse_timestamp;
+ long last_pulse_diff = pulse_diff;
+ interrupts();
+ if (last_pulse_diff == 0 || ((long)(_micros() - last_pulse_timestamp) > last_pulse_diff*2) ) { // last velocity isn't accurate if too old
+ return 0;
+ } else {
+ return direction * (_2PI / (float)cpr) / (last_pulse_diff / 1000000.0f);
+ }
+
+}
+
+// HallSensor initialisation of the hardware pins
+// and calculation variables
+void HallSensor::init(){
+ // initialise the electrical rotations to 0
+ electric_rotations = 0;
+
+ // HallSensor - check if pullup needed for your HallSensor
+ if(pullup == Pullup::USE_INTERN){
+ pinMode(pinA, INPUT_PULLUP);
+ pinMode(pinB, INPUT_PULLUP);
+ pinMode(pinC, INPUT_PULLUP);
+ }else{
+ pinMode(pinA, INPUT);
+ pinMode(pinB, INPUT);
+ pinMode(pinC, INPUT);
+ }
+
+ // init hall_state
+ A_active = digitalRead(pinA);
+ B_active = digitalRead(pinB);
+ C_active = digitalRead(pinC);
+ updateState();
+
+ pulse_timestamp = _micros();
+
+ // we don't call Sensor::init() here because init is handled in HallSensor class.
+}
+
+// function enabling hardware interrupts for the callback provided
+// if callback is not provided then the interrupt is not enabled
+void HallSensor::enableInterrupts(void (*doA)(), void(*doB)(), void(*doC)()){
+ // attach interrupt if functions provided
+
+ // A, B and C callback
+ if(doA != nullptr) attachInterrupt(digitalPinToInterrupt(pinA), doA, CHANGE);
+ if(doB != nullptr) attachInterrupt(digitalPinToInterrupt(pinB), doB, CHANGE);
+ if(doC != nullptr) attachInterrupt(digitalPinToInterrupt(pinC), doC, CHANGE);
+
+ use_interrupt = true;
+}
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/sensors/HallSensor.h b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/sensors/HallSensor.h
new file mode 100644
index 0000000..94053e0
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/sensors/HallSensor.h
@@ -0,0 +1,100 @@
+#ifndef HALL_SENSOR_LIB_H
+#define HALL_SENSOR_LIB_H
+
+#include "Arduino.h"
+#include "../common/base_classes/Sensor.h"
+#include "../common/foc_utils.h"
+#include "../common/time_utils.h"
+
+// seq 1 > 5 > 4 > 6 > 2 > 3 > 1 000 001 010 011 100 101 110 111
+const int8_t ELECTRIC_SECTORS[8] = { -1, 0, 4, 5, 2, 1, 3 , -1 };
+
+class HallSensor: public Sensor{
+ public:
+ /**
+ HallSensor class constructor
+ @param encA HallSensor A pin
+ @param encB HallSensor B pin
+ @param encC HallSensor C pin
+ @param pp pole pairs (e.g hoverboard motor has 15pp and small gimbals often have 7pp)
+ @param index index pin number (optional input)
+ */
+ HallSensor(int encA, int encB, int encC, int pp);
+
+ /** HallSensor initialise pins */
+ void init();
+ /**
+ * function enabling hardware interrupts for the HallSensor channels with provided callback functions
+ * if callback is not provided then the interrupt is not enabled
+ *
+ * @param doA pointer to the A channel interrupt handler function
+ * @param doB pointer to the B channel interrupt handler function
+ * @param doIndex pointer to the Index channel interrupt handler function
+ *
+ */
+ void enableInterrupts(void (*doA)() = nullptr, void(*doB)() = nullptr, void(*doC)() = nullptr);
+
+ // HallSensor interrupt callback functions
+ /** A channel callback function */
+ void handleA();
+ /** B channel callback function */
+ void handleB();
+ /** C channel callback function */
+ void handleC();
+
+
+ // pins A and B
+ int pinA; //!< HallSensor hardware pin A
+ int pinB; //!< HallSensor hardware pin B
+ int pinC; //!< HallSensor hardware pin C
+ int use_interrupt; //!< True if interrupts have been attached
+
+ // HallSensor configuration
+ Pullup pullup; //!< Configuration parameter internal or external pullups
+ int cpr;//!< HallSensor cpr number
+
+ // Abstract functions of the Sensor class implementation
+ /** Interrupt-safe update */
+ void update() override;
+ /** get current angle (rad) */
+ float getSensorAngle() override;
+ /** get current angular velocity (rad/s) */
+ float getVelocity() override;
+
+ // whether last step was CW (+1) or CCW (-1).
+ Direction direction;
+ Direction old_direction;
+
+ void attachSectorCallback(void (*onSectorChange)(int a) = nullptr);
+
+ // the current 3bit state of the hall sensors
+ volatile int8_t hall_state;
+ // the current sector of the sensor. Each sector is 60deg electrical
+ volatile int8_t electric_sector;
+ // the number of electric rotations
+ volatile long electric_rotations;
+ // this is sometimes useful to identify interrupt issues (e.g. weak or no pullup resulting in 1000s of interrupts)
+ volatile long total_interrupts;
+
+ // variable used to filter outliers - rad/s
+ float velocity_max = 1000.0f;
+
+ private:
+
+ Direction decodeDirection(int oldState, int newState);
+ void updateState();
+
+ volatile unsigned long pulse_timestamp;//!< last impulse timestamp in us
+ volatile int A_active; //!< current active states of A channel
+ volatile int B_active; //!< current active states of B channel
+ volatile int C_active; //!< current active states of C channel
+
+ // function pointer for on sector change call back
+ void (*onSectorChange)(int sector) = nullptr;
+
+ volatile long pulse_diff;
+
+};
+
+
+#endif
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/sensors/MagneticSensorAnalog.cpp b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/sensors/MagneticSensorAnalog.cpp
new file mode 100644
index 0000000..d4adad6
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/sensors/MagneticSensorAnalog.cpp
@@ -0,0 +1,42 @@
+#include "MagneticSensorAnalog.h"
+
+/** MagneticSensorAnalog(uint8_t _pinAnalog, int _min, int _max)
+ * @param _pinAnalog the pin that is reading the pwm from magnetic sensor
+ * @param _min_raw_count the smallest expected reading. Whilst you might expect it to be 0 it is often ~15. Getting this wrong results in a small click once per revolution
+ * @param _max_raw_count the largest value read. whilst you might expect it to be 2^10 = 1023 it is often ~ 1020. Note: For ESP32 (with 12bit ADC the value will be nearer 4096)
+ */
+MagneticSensorAnalog::MagneticSensorAnalog(uint8_t _pinAnalog, int _min_raw_count, int _max_raw_count){
+
+ pinAnalog = _pinAnalog;
+
+ cpr = _max_raw_count - _min_raw_count;
+ min_raw_count = _min_raw_count;
+ max_raw_count = _max_raw_count;
+
+ if(pullup == Pullup::USE_INTERN){
+ pinMode(pinAnalog, INPUT_PULLUP);
+ }else{
+ pinMode(pinAnalog, INPUT);
+ }
+
+}
+
+
+void MagneticSensorAnalog::init(){
+ raw_count = getRawCount();
+
+ this->Sensor::init(); // call base class init
+}
+
+// Shaft angle calculation
+// angle is in radians [rad]
+float MagneticSensorAnalog::getSensorAngle(){
+ // raw data from the sensor
+ raw_count = getRawCount();
+ return ( (float) (raw_count) / (float)cpr) * _2PI;
+}
+
+// function reading the raw counter of the magnetic sensor
+int MagneticSensorAnalog::getRawCount(){
+ return analogRead(pinAnalog);
+}
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/sensors/MagneticSensorAnalog.h b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/sensors/MagneticSensorAnalog.h
new file mode 100644
index 0000000..6f787b9
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/sensors/MagneticSensorAnalog.h
@@ -0,0 +1,51 @@
+#ifndef MAGNETICSENSORANALOG_LIB_H
+#define MAGNETICSENSORANALOG_LIB_H
+
+#include "Arduino.h"
+#include "../common/base_classes/Sensor.h"
+#include "../common/foc_utils.h"
+#include "../common/time_utils.h"
+
+/**
+ * This sensor has been tested with AS5600 running in 'analog mode'. This is where output pin of AS6000 is connected to an analog pin on your microcontroller.
+ * This approach is very simple but you may more accurate results with MagneticSensorI2C if that is also supported as its skips the DAC -> ADC conversion (ADC supports MagneticSensorI2C)
+ */
+class MagneticSensorAnalog: public Sensor{
+ public:
+ /**
+ * MagneticSensorAnalog class constructor
+ * @param _pinAnalog the pin to read the PWM signal
+ */
+ MagneticSensorAnalog(uint8_t _pinAnalog, int _min = 0, int _max = 0);
+
+
+ /** sensor initialise pins */
+ void init();
+
+ int pinAnalog; //!< encoder hardware pin A
+
+ // Encoder configuration
+ Pullup pullup;
+
+ // implementation of abstract functions of the Sensor class
+ /** get current angle (rad) */
+ float getSensorAngle() override;
+ /** raw count (typically in range of 0-1023), useful for debugging resolution issues */
+ int raw_count;
+
+ private:
+ int min_raw_count;
+ int max_raw_count;
+ int cpr;
+ int read();
+
+ /**
+ * Function getting current angle register value
+ * it uses angle_register variable
+ */
+ int getRawCount();
+
+};
+
+
+#endif
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/sensors/MagneticSensorI2C.cpp b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/sensors/MagneticSensorI2C.cpp
new file mode 100644
index 0000000..2b3db0c
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/sensors/MagneticSensorI2C.cpp
@@ -0,0 +1,170 @@
+#include "MagneticSensorI2C.h"
+
+/** Typical configuration for the 12bit AMS AS5600 magnetic sensor over I2C interface */
+MagneticSensorI2CConfig_s AS5600_I2C = {
+ .chip_address = 0x36,
+ .bit_resolution = 12,
+ .angle_register = 0x0C,
+ .data_start_bit = 11
+};
+
+/** Typical configuration for the 12bit AMS AS5048 magnetic sensor over I2C interface */
+MagneticSensorI2CConfig_s AS5048_I2C = {
+ .chip_address = 0x40, // highly configurable. if A1 and A2 are held low, this is probable value
+ .bit_resolution = 14,
+ .angle_register = 0xFE,
+ .data_start_bit = 15
+};
+
+/** Typical configuration for the 12bit MT6701 magnetic sensor over I2C interface */
+MagneticSensorI2CConfig_s MT6701_I2C = {
+ .chip_address = 0x06,
+ .bit_resolution = 14,
+ .angle_register = 0x03,
+ .data_start_bit = 15
+};
+
+
+// MagneticSensorI2C(uint8_t _chip_address, float _cpr, uint8_t _angle_register_msb)
+// @param _chip_address I2C chip address
+// @param _bit_resolution bit resolution of the sensor
+// @param _angle_register_msb angle read register
+// @param _bits_used_msb number of used bits in msb
+MagneticSensorI2C::MagneticSensorI2C(uint8_t _chip_address, int _bit_resolution, uint8_t _angle_register_msb, int _bits_used_msb){
+ // chip I2C address
+ chip_address = _chip_address;
+ // angle read register of the magnetic sensor
+ angle_register_msb = _angle_register_msb;
+ // register maximum value (counts per revolution)
+ cpr = _powtwo(_bit_resolution);
+
+ // depending on the sensor architecture there are different combinations of
+ // LSB and MSB register used bits
+ // AS5600 uses 0..7 LSB and 8..11 MSB
+ // AS5048 uses 0..5 LSB and 6..13 MSB
+ // MT6701 uses 0..5 LSB and 9..15 MSB
+ // used bits in LSB
+ lsb_used = _bit_resolution - _bits_used_msb;
+ // extraction masks
+ lsb_mask = (uint8_t)( (2 << lsb_used) - 1 );
+ msb_mask = (uint8_t)( (2 << _bits_used_msb) - 1 );
+ wire = &Wire;
+}
+
+MagneticSensorI2C::MagneticSensorI2C(MagneticSensorI2CConfig_s config){
+ chip_address = config.chip_address;
+
+ // angle read register of the magnetic sensor
+ angle_register_msb = config.angle_register;
+ // register maximum value (counts per revolution)
+ cpr = _powtwo(config.bit_resolution);
+
+ int bits_used_msb = config.data_start_bit - 7;
+ lsb_used = config.bit_resolution - bits_used_msb;
+ // extraction masks
+ lsb_mask = (uint8_t)( (2 << lsb_used) - 1 );
+ msb_mask = (uint8_t)( (2 << bits_used_msb) - 1 );
+ wire = &Wire;
+}
+
+MagneticSensorI2C MagneticSensorI2C::AS5600() {
+ return {AS5600_I2C};
+}
+
+void MagneticSensorI2C::init(TwoWire* _wire){
+
+ wire = _wire;
+
+ // I2C communication begin
+ wire->begin();
+
+ this->Sensor::init(); // call base class init
+}
+
+// Shaft angle calculation
+// angle is in radians [rad]
+float MagneticSensorI2C::getSensorAngle(){
+ // (number of full rotations)*2PI + current sensor angle
+ return ( getRawCount() / (float)cpr) * _2PI ;
+}
+
+
+
+// function reading the raw counter of the magnetic sensor
+int MagneticSensorI2C::getRawCount(){
+ return (int)MagneticSensorI2C::read(angle_register_msb);
+}
+
+// I2C functions
+/*
+* Read a register from the sensor
+* Takes the address of the register as a uint8_t
+* Returns the value of the register
+*/
+int MagneticSensorI2C::read(uint8_t angle_reg_msb) {
+ // read the angle register first MSB then LSB
+ byte readArray[2];
+ uint16_t readValue = 0;
+ // notify the device that is aboout to be read
+ wire->beginTransmission(chip_address);
+ wire->write(angle_reg_msb);
+ currWireError = wire->endTransmission(false);
+
+ // read the data msb and lsb
+ wire->requestFrom(chip_address, (uint8_t)2);
+ for (byte i=0; i < 2; i++) {
+ readArray[i] = wire->read();
+ }
+
+ // depending on the sensor architecture there are different combinations of
+ // LSB and MSB register used bits
+ // AS5600 uses 0..7 LSB and 8..11 MSB
+ // AS5048 uses 0..5 LSB and 6..13 MSB
+ // MT6701 uses 0..5 LSB and 6..13 MSB
+ readValue = ( readArray[1] & lsb_mask );
+ readValue += ( ( readArray[0] & msb_mask ) << lsb_used );
+ return readValue;
+}
+
+/*
+* Checks whether other devices have locked the bus. Can clear SDA locks.
+* This should be called before sensor.init() on devices that suffer i2c slaves locking sda
+* e.g some stm32 boards with AS5600 chips
+* Takes the sda_pin and scl_pin
+* Returns 0 for OK, 1 for other master and 2 for unfixable sda locked LOW
+*/
+int MagneticSensorI2C::checkBus(byte sda_pin, byte scl_pin) {
+
+ pinMode(scl_pin, INPUT_PULLUP);
+ pinMode(sda_pin, INPUT_PULLUP);
+ delay(250);
+
+ if (digitalRead(scl_pin) == LOW) {
+ // Someone else has claimed master!");
+ return 1;
+ }
+
+ if(digitalRead(sda_pin) == LOW) {
+ // slave is communicating and awaiting clocks, we are blocked
+ pinMode(scl_pin, OUTPUT);
+ for (byte i = 0; i < 16; i++) {
+ // toggle clock for 2 bytes of data
+ digitalWrite(scl_pin, LOW);
+ delayMicroseconds(20);
+ digitalWrite(scl_pin, HIGH);
+ delayMicroseconds(20);
+ }
+ pinMode(sda_pin, INPUT);
+ delayMicroseconds(20);
+ if (digitalRead(sda_pin) == LOW) {
+ // SDA still blocked
+ return 2;
+ }
+ _delay(1000);
+ }
+ // SDA is clear (HIGH)
+ pinMode(sda_pin, INPUT);
+ pinMode(scl_pin, INPUT);
+
+ return 0;
+}
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/sensors/MagneticSensorI2C.h b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/sensors/MagneticSensorI2C.h
new file mode 100644
index 0000000..f8b189f
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/sensors/MagneticSensorI2C.h
@@ -0,0 +1,84 @@
+#ifndef MAGNETICSENSORI2C_LIB_H
+#define MAGNETICSENSORI2C_LIB_H
+
+#include "Arduino.h"
+#include
+#include "../common/base_classes/Sensor.h"
+#include "../common/foc_utils.h"
+#include "../common/time_utils.h"
+
+struct MagneticSensorI2CConfig_s {
+ int chip_address;
+ int bit_resolution;
+ int angle_register;
+ int data_start_bit;
+};
+// some predefined structures
+extern MagneticSensorI2CConfig_s AS5600_I2C,AS5048_I2C;
+
+#if defined(TARGET_RP2040)
+#define SDA I2C_SDA
+#define SCL I2C_SCL
+#endif
+
+
+class MagneticSensorI2C: public Sensor{
+ public:
+ /**
+ * MagneticSensorI2C class constructor
+ * @param chip_address I2C chip address
+ * @param bits number of bits of the sensor resolution
+ * @param angle_register_msb angle read register msb
+ * @param _bits_used_msb number of used bits in msb
+ */
+ MagneticSensorI2C(uint8_t _chip_address, int _bit_resolution, uint8_t _angle_register_msb, int _msb_bits_used);
+
+ /**
+ * MagneticSensorI2C class constructor
+ * @param config I2C config
+ */
+ MagneticSensorI2C(MagneticSensorI2CConfig_s config);
+
+ static MagneticSensorI2C AS5600();
+
+ /** sensor initialise pins */
+ void init(TwoWire* _wire = &Wire);
+
+ // implementation of abstract functions of the Sensor class
+ /** get current angle (rad) */
+ float getSensorAngle() override;
+
+ /** experimental function to check and fix SDA locked LOW issues */
+ int checkBus(byte sda_pin , byte scl_pin );
+
+ /** current error code from Wire endTransmission() call **/
+ uint8_t currWireError = 0;
+
+ private:
+ float cpr; //!< Maximum range of the magnetic sensor
+ uint16_t lsb_used; //!< Number of bits used in LSB register
+ uint8_t lsb_mask;
+ uint8_t msb_mask;
+
+ // I2C variables
+ uint8_t angle_register_msb; //!< I2C angle register to read
+ uint8_t chip_address; //!< I2C chip select pins
+
+ // I2C functions
+ /** Read one I2C register value */
+ int read(uint8_t angle_register_msb);
+
+ /**
+ * Function getting current angle register value
+ * it uses angle_register variable
+ */
+ int getRawCount();
+
+ /* the two wire instance for this sensor */
+ TwoWire* wire;
+
+
+};
+
+
+#endif
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/sensors/MagneticSensorPWM.cpp b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/sensors/MagneticSensorPWM.cpp
new file mode 100644
index 0000000..04b7cc7
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/sensors/MagneticSensorPWM.cpp
@@ -0,0 +1,117 @@
+#include "MagneticSensorPWM.h"
+#include "Arduino.h"
+
+/** MagneticSensorPWM(uint8_t _pinPWM, int _min, int _max)
+ * @param _pinPWM the pin that is reading the pwm from magnetic sensor
+ * @param _min_raw_count the smallest expected reading
+ * @param _max_raw_count the largest expected reading
+ */
+MagneticSensorPWM::MagneticSensorPWM(uint8_t _pinPWM, int _min_raw_count, int _max_raw_count){
+
+ pinPWM = _pinPWM;
+
+ cpr = _max_raw_count - _min_raw_count + 1;
+ min_raw_count = _min_raw_count;
+ max_raw_count = _max_raw_count;
+
+ // define if the sensor uses interrupts
+ is_interrupt_based = false;
+
+ // define as not set
+ last_call_us = _micros();
+}
+
+
+/** MagneticSensorPWM(uint8_t _pinPWM, int freqHz, int _total_pwm_clocks, int _min_pwm_clocks, int _max_pwm_clocks)
+ *
+ * Constructor that computes the min and max raw counts based on the PWM frequency and the number of PWM clocks in one period
+ *
+ * @param _pinPWM the pin that is reading the pwm from magnetic sensor
+ * @param freqHz the frequency of the PWM signal, in Hz, e.g. 115, 230, 460 or 920 for the AS5600, depending on the PWM frequency setting
+ * @param _total_pwm_clocks the total number of PWM clocks in one period, e.g. 4351 for the AS5600
+ * @param _min_pwm_clocks the 0 value returned by the sensor, in PWM clocks, e.g. 128 for the AS5600
+ * @param _max_pwm_clocks the largest value returned by the sensor, in PWM clocks, e.g. 4223 for the AS5600
+ */
+MagneticSensorPWM::MagneticSensorPWM(uint8_t _pinPWM, int freqHz, int _total_pwm_clocks, int _min_pwm_clocks, int _max_pwm_clocks){
+
+ pinPWM = _pinPWM;
+
+ min_raw_count = lroundf(1000000.0f/freqHz/_total_pwm_clocks*_min_pwm_clocks);
+ max_raw_count = lroundf(1000000.0f/freqHz/_total_pwm_clocks*_max_pwm_clocks);
+ cpr = max_raw_count - min_raw_count + 1;
+
+ // define if the sensor uses interrupts
+ is_interrupt_based = false;
+
+ min_elapsed_time = 1.0f/freqHz; // set the minimum time between two readings
+
+ // define as not set
+ last_call_us = _micros();
+}
+
+
+
+void MagneticSensorPWM::init(){
+
+ // initial hardware
+ pinMode(pinPWM, INPUT);
+ raw_count = getRawCount();
+ pulse_timestamp = _micros();
+
+ this->Sensor::init(); // call base class init
+}
+
+// Sensor update function. Safely copy volatile interrupt variables into Sensor base class state variables.
+void MagneticSensorPWM::update() {
+ if (is_interrupt_based)
+ noInterrupts();
+ Sensor::update();
+ angle_prev_ts = pulse_timestamp; // Timestamp of actual sample, before the time-consuming PWM communication
+ if (is_interrupt_based)
+ interrupts();
+}
+
+// get current angle (rad)
+float MagneticSensorPWM::getSensorAngle(){
+ // raw data from sensor
+ raw_count = getRawCount();
+ if (raw_count > max_raw_count) raw_count = max_raw_count;
+ if (raw_count < min_raw_count) raw_count = min_raw_count;
+ return( (float) (raw_count - min_raw_count) / (float)cpr) * _2PI;
+}
+
+
+// read the raw counter of the magnetic sensor
+int MagneticSensorPWM::getRawCount(){
+ if (!is_interrupt_based){ // if it's not interrupt based read the value in a blocking way
+ pulse_timestamp = _micros(); // ideally this should be done right at the rising edge of the pulse
+ pulse_length_us = pulseIn(pinPWM, HIGH, timeout_us); // 1200us timeout, should this be configurable?
+ }
+ return pulse_length_us;
+}
+
+
+void MagneticSensorPWM::handlePWM() {
+ // unsigned long now_us = ticks();
+ unsigned long now_us = _micros();
+
+ // if falling edge, calculate the pulse length
+ if (!digitalRead(pinPWM)) {
+ pulse_length_us = now_us - last_call_us;
+ pulse_timestamp = last_call_us; // angle was sampled at the rising edge of the pulse, so use that timestamp
+ }
+
+ // save the currrent timestamp for the next call
+ last_call_us = now_us;
+ is_interrupt_based = true; // set the flag to true
+}
+
+// function enabling hardware interrupts of the for the callback provided
+// if callback is not provided then the interrupt is not enabled
+void MagneticSensorPWM::enableInterrupt(void (*doPWM)()){
+ // declare it's interrupt based
+ is_interrupt_based = true;
+
+ // enable interrupts on pwm input pin
+ attachInterrupt(digitalPinToInterrupt(pinPWM), doPWM, CHANGE);
+}
\ No newline at end of file
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/sensors/MagneticSensorPWM.h b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/sensors/MagneticSensorPWM.h
new file mode 100644
index 0000000..a5fd7e6
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/sensors/MagneticSensorPWM.h
@@ -0,0 +1,75 @@
+#ifndef MAGNETICSENSORPWM_LIB_H
+#define MAGNETICSENSORPWM_LIB_H
+
+#include "Arduino.h"
+#include "../common/base_classes/Sensor.h"
+#include "../common/foc_utils.h"
+#include "../common/time_utils.h"
+
+// This sensor has been tested with AS5048a running in PWM mode.
+
+class MagneticSensorPWM: public Sensor{
+ public:
+ /** MagneticSensorPWM(uint8_t _pinPWM, int _min, int _max)
+ * @param _pinPWM the pin that is reading the pwm from magnetic sensor
+ * @param _min_raw_count the smallest expected reading
+ * @param _max_raw_count the largest expected reading
+ */
+ MagneticSensorPWM(uint8_t _pinPWM,int _min = 0, int _max = 0);
+ /** MagneticSensorPWM(uint8_t _pinPWM, int freqHz, int _total_pwm_clocks, int _min_pwm_clocks, int _max_pwm_clocks)
+ *
+ * Constructor that computes the min and max raw counts based on the PWM frequency and the number of PWM clocks in one period
+ *
+ * @param _pinPWM the pin that is reading the pwm from magnetic sensor
+ * @param freqHz the frequency of the PWM signal, in Hz, e.g. 115, 230, 460 or 920 for the AS5600, depending on the PWM frequency setting
+ * @param _total_pwm_clocks the total number of PWM clocks in one period, e.g. 4351 for the AS5600
+ * @param _min_pwm_clocks the 0 value returned by the sensor, in PWM clocks, e.g. 128 for the AS5600
+ * @param _max_pwm_clocks the largest value returned by the sensor, in PWM clocks, e.g. 4223 for the AS5600
+ */
+ MagneticSensorPWM(uint8_t _pinPWM, int freqHz, int _total_pwm_clocks, int _min_pwm_clocks, int _max_pwm_clocks);
+
+ // initialize the sensor hardware
+ void init();
+
+ int pinPWM;
+
+ // Interrupt-safe update
+ void update() override;
+
+ // get current angle (rad)
+ float getSensorAngle() override;
+
+ // pwm handler
+ void handlePWM();
+ void enableInterrupt(void (*doPWM)());
+ unsigned long pulse_length_us;
+
+ unsigned int timeout_us = 1200;
+
+ private:
+ // raw count (typically in range of 0-1023)
+ int raw_count;
+ int min_raw_count;
+ int max_raw_count;
+ int cpr;
+
+ // flag saying if the readings are interrupt based or not
+ bool is_interrupt_based;
+
+ int read();
+
+ /**
+ * Function getting current angle register value
+ * it uses angle_register variable
+ */
+ int getRawCount();
+
+ // time tracking variables
+ unsigned long last_call_us;
+ // unsigned long pulse_length_us;
+ unsigned long pulse_timestamp;
+
+
+};
+
+#endif
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/sensors/MagneticSensorSPI.cpp b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/sensors/MagneticSensorSPI.cpp
new file mode 100644
index 0000000..52febc3
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/sensors/MagneticSensorSPI.cpp
@@ -0,0 +1,161 @@
+
+#include "MagneticSensorSPI.h"
+
+/** Typical configuration for the 14bit AMS AS5147 magnetic sensor over SPI interface */
+MagneticSensorSPIConfig_s AS5147_SPI = {
+ .spi_mode = SPI_MODE1,
+ .clock_speed = 1000000,
+ .bit_resolution = 14,
+ .angle_register = 0x3FFF,
+ .data_start_bit = 13,
+ .command_rw_bit = 14,
+ .command_parity_bit = 15
+};
+// AS5048 and AS5047 are the same as AS5147
+MagneticSensorSPIConfig_s AS5048_SPI = AS5147_SPI;
+MagneticSensorSPIConfig_s AS5047_SPI = AS5147_SPI;
+
+/** Typical configuration for the 14bit MonolithicPower MA730 magnetic sensor over SPI interface */
+MagneticSensorSPIConfig_s MA730_SPI = {
+ .spi_mode = SPI_MODE0,
+ .clock_speed = 1000000,
+ .bit_resolution = 14,
+ .angle_register = 0x0000,
+ .data_start_bit = 15,
+ .command_rw_bit = 0, // not required
+ .command_parity_bit = 0 // parity not implemented
+};
+
+
+// MagneticSensorSPI(int cs, float _bit_resolution, int _angle_register)
+// cs - SPI chip select pin
+// _bit_resolution sensor resolution bit number
+// _angle_register - (optional) angle read register - default 0x3FFF
+MagneticSensorSPI::MagneticSensorSPI(int cs, int _bit_resolution, int _angle_register){
+
+ chip_select_pin = cs;
+ // angle read register of the magnetic sensor
+ angle_register = _angle_register ? _angle_register : DEF_ANGLE_REGISTER;
+ // register maximum value (counts per revolution)
+ cpr = _powtwo(_bit_resolution);
+ spi_mode = SPI_MODE1;
+ clock_speed = 1000000;
+ bit_resolution = _bit_resolution;
+
+ command_parity_bit = 15; // for backwards compatibilty
+ command_rw_bit = 14; // for backwards compatibilty
+ data_start_bit = 13; // for backwards compatibilty
+}
+
+MagneticSensorSPI::MagneticSensorSPI(MagneticSensorSPIConfig_s config, int cs){
+ chip_select_pin = cs;
+ // angle read register of the magnetic sensor
+ angle_register = config.angle_register ? config.angle_register : DEF_ANGLE_REGISTER;
+ // register maximum value (counts per revolution)
+ cpr = _powtwo(config.bit_resolution);
+ spi_mode = config.spi_mode;
+ clock_speed = config.clock_speed;
+ bit_resolution = config.bit_resolution;
+
+ command_parity_bit = config.command_parity_bit; // for backwards compatibilty
+ command_rw_bit = config.command_rw_bit; // for backwards compatibilty
+ data_start_bit = config.data_start_bit; // for backwards compatibilty
+}
+
+void MagneticSensorSPI::init(SPIClass* _spi){
+ spi = _spi;
+ // 1MHz clock (AMS should be able to accept up to 10MHz)
+ settings = SPISettings(clock_speed, MSBFIRST, spi_mode);
+ //setup pins
+ pinMode(chip_select_pin, OUTPUT);
+ //SPI has an internal SPI-device counter, it is possible to call "begin()" from different devices
+ spi->begin();
+ // do any architectures need to set the clock divider for SPI? Why was this in the code?
+ //spi->setClockDivider(SPI_CLOCK_DIV8);
+ digitalWrite(chip_select_pin, HIGH);
+
+ this->Sensor::init(); // call base class init
+}
+
+// Shaft angle calculation
+// angle is in radians [rad]
+float MagneticSensorSPI::getSensorAngle(){
+ return (getRawCount() / (float)cpr) * _2PI;
+}
+
+// function reading the raw counter of the magnetic sensor
+int MagneticSensorSPI::getRawCount(){
+ return (int)MagneticSensorSPI::read(angle_register);
+}
+
+// SPI functions
+/**
+ * Utility function used to calculate even parity of word
+ */
+byte MagneticSensorSPI::spiCalcEvenParity(word value){
+ byte cnt = 0;
+ byte i;
+
+ for (i = 0; i < 16; i++)
+ {
+ if (value & 0x1) cnt++;
+ value >>= 1;
+ }
+ return cnt & 0x1;
+}
+
+ /*
+ * Read a register from the sensor
+ * Takes the address of the register as a 16 bit word
+ * Returns the value of the register
+ */
+word MagneticSensorSPI::read(word angle_register){
+
+ word command = angle_register;
+
+ if (command_rw_bit > 0) {
+ command = angle_register | (1 << command_rw_bit);
+ }
+ if (command_parity_bit > 0) {
+ //Add a parity bit on the the MSB
+ command |= ((word)spiCalcEvenParity(command) << command_parity_bit);
+ }
+
+ //SPI - begin transaction
+ spi->beginTransaction(settings);
+
+ //Send the command
+ digitalWrite(chip_select_pin, LOW);
+ spi->transfer16(command);
+ digitalWrite(chip_select_pin,HIGH);
+
+#if defined(ESP_H) && defined(ARDUINO_ARCH_ESP32) // if ESP32 board
+ delayMicroseconds(50); // why do we need to delay 50us on ESP32? In my experience no extra delays are needed, on any of the architectures I've tested...
+#else
+ delayMicroseconds(1); // delay 1us, the minimum time possible in plain arduino. 350ns is the required time for AMS sensors, 80ns for MA730, MA702
+#endif
+
+ //Now read the response
+ digitalWrite(chip_select_pin, LOW);
+ word register_value = spi->transfer16(0x00);
+ digitalWrite(chip_select_pin, HIGH);
+
+ //SPI - end transaction
+ spi->endTransaction();
+
+ register_value = register_value >> (1 + data_start_bit - bit_resolution); //this should shift data to the rightmost bits of the word
+
+ const static word data_mask = 0xFFFF >> (16 - bit_resolution);
+
+ return register_value & data_mask; // Return the data, stripping the non data (e.g parity) bits
+}
+
+/**
+ * Closes the SPI connection
+ * SPI has an internal SPI-device counter, for each init()-call the close() function must be called exactly 1 time
+ */
+void MagneticSensorSPI::close(){
+ spi->end();
+}
+
+
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/sensors/MagneticSensorSPI.h b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/sensors/MagneticSensorSPI.h
new file mode 100644
index 0000000..03ebde4
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/Simple FOC/src/sensors/MagneticSensorSPI.h
@@ -0,0 +1,84 @@
+#ifndef MAGNETICSENSORSPI_LIB_H
+#define MAGNETICSENSORSPI_LIB_H
+
+
+#include "Arduino.h"
+#include
+#include "../common/base_classes/Sensor.h"
+#include "../common/foc_utils.h"
+#include "../common/time_utils.h"
+
+#define DEF_ANGLE_REGISTER 0x3FFF
+
+struct MagneticSensorSPIConfig_s {
+ int spi_mode;
+ long clock_speed;
+ int bit_resolution;
+ int angle_register;
+ int data_start_bit;
+ int command_rw_bit;
+ int command_parity_bit;
+};
+// typical configuration structures
+extern MagneticSensorSPIConfig_s AS5147_SPI,AS5048_SPI,AS5047_SPI, MA730_SPI;
+
+class MagneticSensorSPI: public Sensor{
+ public:
+ /**
+ * MagneticSensorSPI class constructor
+ * @param cs SPI chip select pin
+ * @param bit_resolution sensor resolution bit number
+ * @param angle_register (optional) angle read register - default 0x3FFF
+ */
+ MagneticSensorSPI(int cs, int bit_resolution, int angle_register = 0);
+ /**
+ * MagneticSensorSPI class constructor
+ * @param config SPI config
+ * @param cs SPI chip select pin
+ */
+ MagneticSensorSPI(MagneticSensorSPIConfig_s config, int cs);
+
+ /** sensor initialise pins */
+ void init(SPIClass* _spi = &SPI);
+
+ // implementation of abstract functions of the Sensor class
+ /** get current angle (rad) */
+ float getSensorAngle() override;
+
+ // returns the spi mode (phase/polarity of read/writes) i.e one of SPI_MODE0 | SPI_MODE1 | SPI_MODE2 | SPI_MODE3
+ int spi_mode;
+
+ /* returns the speed of the SPI clock signal */
+ long clock_speed;
+
+
+ private:
+ float cpr; //!< Maximum range of the magnetic sensor
+ // spi variables
+ int angle_register; //!< SPI angle register to read
+ int chip_select_pin; //!< SPI chip select pin
+ SPISettings settings; //!< SPI settings variable
+ // spi functions
+ /** Stop SPI communication */
+ void close();
+ /** Read one SPI register value */
+ word read(word angle_register);
+ /** Calculate parity value */
+ byte spiCalcEvenParity(word value);
+
+ /**
+ * Function getting current angle register value
+ * it uses angle_register variable
+ */
+ int getRawCount();
+
+ int bit_resolution; //!< the number of bites of angle data
+ int command_parity_bit; //!< the bit where parity flag is stored in command
+ int command_rw_bit; //!< the bit where read/write flag is stored in command
+ int data_start_bit; //!< the the position of first bit
+
+ SPIClass* spi;
+};
+
+
+#endif
diff --git a/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/integrity.dat b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/integrity.dat
new file mode 100644
index 0000000..a54095b
--- /dev/null
+++ b/embedded/CANFDMigrate/.pio/libdeps/seeed_xiao_esp32s3/integrity.dat
@@ -0,0 +1,2 @@
+fbiego/ESP32Time@^2.0.6
+askuric/Simple FOC@^2.3.4
\ No newline at end of file
diff --git a/embedded/CANFDMigrate/.project b/embedded/CANFDMigrate/.project
new file mode 100644
index 0000000..cc9733d
--- /dev/null
+++ b/embedded/CANFDMigrate/.project
@@ -0,0 +1,32 @@
+
+
+ 01-Blink2
+
+
+
+
+
+ org.eclipse.cdt.managedbuilder.core.genmakebuilder
+ clean,full,incremental,
+
+
+
+
+ org.eclipse.cdt.managedbuilder.core.ScannerConfigBuilder
+ full,incremental,
+
+
+
+
+
+ com.st.stm32cube.ide.mcu.MCUProjectNature
+ com.st.stm32cube.ide.mcu.MCUCubeProjectNature
+ org.eclipse.cdt.core.cnature
+ com.st.stm32cube.ide.mcu.MCUCubeIdeServicesRevAev2ProjectNature
+ com.st.stm32cube.ide.mcu.MCUAdvancedStructureProjectNature
+ com.st.stm32cube.ide.mcu.MCUSingleCpuProjectNature
+ com.st.stm32cube.ide.mcu.MCURootProjectNature
+ org.eclipse.cdt.managedbuilder.core.managedBuildNature
+ org.eclipse.cdt.managedbuilder.core.ScannerConfigNature
+
+
diff --git a/embedded/CANFDMigrate/CANFDMigrate.ioc b/embedded/CANFDMigrate/CANFDMigrate.ioc
new file mode 100644
index 0000000..3fad87a
--- /dev/null
+++ b/embedded/CANFDMigrate/CANFDMigrate.ioc
@@ -0,0 +1,217 @@
+#MicroXplorer Configuration settings - do not modify
+CAD.formats=
+CAD.pinconfig=
+CAD.provider=
+FDCAN2.CalculateBaudRateNominal=1000000
+FDCAN2.CalculateTimeBitNominal=1000
+FDCAN2.CalculateTimeQuantumNominal=20.833333333333332
+FDCAN2.DataPrescaler=2
+FDCAN2.DataSyncJumpWidth=5
+FDCAN2.DataTimeSeg1=18
+FDCAN2.DataTimeSeg2=5
+FDCAN2.IPParameters=CalculateTimeQuantumNominal,CalculateTimeBitNominal,CalculateBaudRateNominal,NominalPrescaler,NominalTimeSeg1,NominalTimeSeg2,NominalSyncJumpWidth,DataTimeSeg1,DataTimeSeg2,DataPrescaler,DataSyncJumpWidth
+FDCAN2.NominalPrescaler=1
+FDCAN2.NominalSyncJumpWidth=7
+FDCAN2.NominalTimeSeg1=40
+FDCAN2.NominalTimeSeg2=7
+FDCAN3.CalculateBaudRateNominal=1000000
+FDCAN3.CalculateTimeBitNominal=1000
+FDCAN3.CalculateTimeQuantumNominal=20.833333333333332
+FDCAN3.DataPrescaler=2
+FDCAN3.DataSyncJumpWidth=5
+FDCAN3.DataTimeSeg1=18
+FDCAN3.DataTimeSeg2=5
+FDCAN3.IPParameters=CalculateTimeQuantumNominal,CalculateTimeBitNominal,CalculateBaudRateNominal,NominalPrescaler,NominalTimeSeg1,NominalTimeSeg2,NominalSyncJumpWidth,DataTimeSeg1,DataPrescaler,DataSyncJumpWidth,DataTimeSeg2
+FDCAN3.NominalPrescaler=1
+FDCAN3.NominalSyncJumpWidth=7
+FDCAN3.NominalTimeSeg1=40
+FDCAN3.NominalTimeSeg2=7
+File.Version=6
+GPIO.groupedBy=
+KeepUserPlacement=false
+Mcu.CPN=STM32G474CEU6
+Mcu.Family=STM32G4
+Mcu.IP0=FDCAN2
+Mcu.IP1=FDCAN3
+Mcu.IP2=NVIC
+Mcu.IP3=RCC
+Mcu.IP4=RTC
+Mcu.IP5=SYS
+Mcu.IP6=USART2
+Mcu.IP7=USB
+Mcu.IP8=USB_DEVICE
+Mcu.IPNb=9
+Mcu.Name=STM32G474C(B-C-E)Ux
+Mcu.Package=UFQFPN48
+Mcu.Pin0=PC14-OSC32_IN
+Mcu.Pin1=PC15-OSC32_OUT
+Mcu.Pin10=PA11
+Mcu.Pin11=PA12
+Mcu.Pin12=PA13
+Mcu.Pin13=PA14
+Mcu.Pin14=PA15
+Mcu.Pin15=VP_RTC_VS_RTC_Activate
+Mcu.Pin16=VP_SYS_VS_Systick
+Mcu.Pin17=VP_SYS_VS_DBSignals
+Mcu.Pin18=VP_USB_DEVICE_VS_USB_DEVICE_CDC_FS
+Mcu.Pin2=PF0-OSC_IN
+Mcu.Pin3=PF1-OSC_OUT
+Mcu.Pin4=PA2
+Mcu.Pin5=PA3
+Mcu.Pin6=PB12
+Mcu.Pin7=PB13
+Mcu.Pin8=PC6
+Mcu.Pin9=PA8
+Mcu.PinsNb=19
+Mcu.ThirdPartyNb=0
+Mcu.UserConstants=
+Mcu.UserName=STM32G474CEUx
+MxCube.Version=6.9.2
+MxDb.Version=DB.6.0.92
+NVIC.BusFault_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false
+NVIC.DebugMonitor_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false
+NVIC.FDCAN2_IT0_IRQn=true\:0\:0\:false\:false\:true\:true\:true\:true
+NVIC.FDCAN2_IT1_IRQn=true\:0\:0\:false\:false\:true\:true\:true\:true
+NVIC.FDCAN3_IT0_IRQn=true\:0\:0\:false\:false\:true\:true\:true\:true
+NVIC.FDCAN3_IT1_IRQn=true\:0\:0\:false\:false\:true\:true\:true\:true
+NVIC.ForceEnableDMAVector=true
+NVIC.HardFault_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false
+NVIC.MemoryManagement_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false
+NVIC.NonMaskableInt_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false
+NVIC.PendSV_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false
+NVIC.PriorityGroup=NVIC_PRIORITYGROUP_4
+NVIC.SVCall_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false
+NVIC.SysTick_IRQn=true\:15\:0\:false\:false\:true\:false\:true\:false
+NVIC.USB_LP_IRQn=true\:0\:0\:false\:false\:true\:false\:true\:true
+NVIC.UsageFault_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false
+PA11.Mode=Device
+PA11.Signal=USB_DM
+PA12.Mode=Device
+PA12.Signal=USB_DP
+PA13.Mode=Serial_Wire
+PA13.Signal=SYS_JTMS-SWDIO
+PA14.Mode=Serial_Wire
+PA14.Signal=SYS_JTCK-SWCLK
+PA15.Mode=FDCAN_Activate
+PA15.Signal=FDCAN3_TX
+PA2.Mode=Asynchronous
+PA2.Signal=USART2_TX
+PA3.Mode=Asynchronous
+PA3.Signal=USART2_RX
+PA8.Mode=FDCAN_Activate
+PA8.Signal=FDCAN3_RX
+PB12.Mode=FDCAN_Activate
+PB12.Signal=FDCAN2_RX
+PB13.Mode=FDCAN_Activate
+PB13.Signal=FDCAN2_TX
+PC14-OSC32_IN.Mode=LSE-External-Oscillator
+PC14-OSC32_IN.Signal=RCC_OSC32_IN
+PC15-OSC32_OUT.Mode=LSE-External-Oscillator
+PC15-OSC32_OUT.Signal=RCC_OSC32_OUT
+PC6.GPIOParameters=GPIO_Label
+PC6.GPIO_Label=LED
+PC6.Locked=true
+PC6.Signal=GPIO_Output
+PF0-OSC_IN.Mode=HSE-External-Oscillator
+PF0-OSC_IN.Signal=RCC_OSC_IN
+PF1-OSC_OUT.Mode=HSE-External-Oscillator
+PF1-OSC_OUT.Signal=RCC_OSC_OUT
+PinOutPanel.RotationAngle=0
+ProjectManager.AskForMigrate=true
+ProjectManager.BackupPrevious=false
+ProjectManager.CompilerLinker=GCC
+ProjectManager.CompilerOptimize=6
+ProjectManager.ComputerToolchain=false
+ProjectManager.CoupleFile=true
+ProjectManager.CustomerFirmwarePackage=
+ProjectManager.DefaultFWLocation=true
+ProjectManager.DeletePrevious=true
+ProjectManager.DeviceId=STM32G474CEUx
+ProjectManager.FirmwarePackage=STM32Cube FW_G4 V1.5.1
+ProjectManager.FreePins=false
+ProjectManager.HalAssertFull=false
+ProjectManager.HeapSize=0x200
+ProjectManager.KeepUserCode=true
+ProjectManager.LastFirmware=true
+ProjectManager.LibraryCopy=1
+ProjectManager.MainLocation=Core/Src
+ProjectManager.NoMain=false
+ProjectManager.PreviousToolchain=STM32CubeIDE
+ProjectManager.ProjectBuild=false
+ProjectManager.ProjectFileName=01-Blink2.ioc
+ProjectManager.ProjectName=01-Blink2
+ProjectManager.ProjectStructure=
+ProjectManager.RegisterCallBack=
+ProjectManager.StackSize=0x400
+ProjectManager.TargetToolchain=STM32CubeIDE
+ProjectManager.ToolChainLocation=
+ProjectManager.UAScriptAfterPath=
+ProjectManager.UAScriptBeforePath=
+ProjectManager.UnderRoot=true
+ProjectManager.functionlistsort=1-SystemClock_Config-RCC-false-HAL-false,2-MX_GPIO_Init-GPIO-false-HAL-true,3-MX_RTC_Init-RTC-false-HAL-true,4-MX_FDCAN2_Init-FDCAN2-false-HAL-true,5-MX_FDCAN3_Init-FDCAN3-false-HAL-true,6-MX_USART2_UART_Init-USART2-false-HAL-true,7-MX_USB_Device_Init-USB_DEVICE-false-HAL-false
+RCC.ADC12Freq_Value=48000000
+RCC.ADC345Freq_Value=48000000
+RCC.AHBFreq_Value=48000000
+RCC.APB1Freq_Value=48000000
+RCC.APB1TimFreq_Value=48000000
+RCC.APB2Freq_Value=48000000
+RCC.APB2TimFreq_Value=48000000
+RCC.CRSFreq_Value=48000000
+RCC.CortexFreq_Value=48000000
+RCC.EXTERNAL_CLOCK_VALUE=12288000
+RCC.FCLKCortexFreq_Value=48000000
+RCC.FDCANCLockSelection=RCC_FDCANCLKSOURCE_PLL
+RCC.FDCANFreq_Value=48000000
+RCC.FamilyName=M
+RCC.HCLKFreq_Value=48000000
+RCC.HRTIM1Freq_Value=48000000
+RCC.HSE_VALUE=8000000
+RCC.HSI48_VALUE=48000000
+RCC.HSI_VALUE=16000000
+RCC.I2C1Freq_Value=48000000
+RCC.I2C2Freq_Value=48000000
+RCC.I2C3Freq_Value=48000000
+RCC.I2C4Freq_Value=48000000
+RCC.I2SFreq_Value=48000000
+RCC.IPParameters=ADC12Freq_Value,ADC345Freq_Value,AHBFreq_Value,APB1Freq_Value,APB1TimFreq_Value,APB2Freq_Value,APB2TimFreq_Value,CRSFreq_Value,CortexFreq_Value,EXTERNAL_CLOCK_VALUE,FCLKCortexFreq_Value,FDCANCLockSelection,FDCANFreq_Value,FamilyName,HCLKFreq_Value,HRTIM1Freq_Value,HSE_VALUE,HSI48_VALUE,HSI_VALUE,I2C1Freq_Value,I2C2Freq_Value,I2C3Freq_Value,I2C4Freq_Value,I2SFreq_Value,LPTIM1Freq_Value,LPUART1Freq_Value,LSCOPinFreq_Value,LSI_VALUE,MCO1PinFreq_Value,PLLN,PLLPoutputFreq_Value,PLLQoutputFreq_Value,PLLRCLKFreq_Value,PLLSourceVirtual,PWRFreq_Value,QSPIFreq_Value,RNGFreq_Value,RTCClockSelection,RTCFreq_Value,SAI1Freq_Value,SYSCLKFreq_VALUE,SYSCLKSource,UART4Freq_Value,USART1Freq_Value,USART2Freq_Value,USART3Freq_Value,USBFreq_Value,VCOInputFreq_Value,VCOOutputFreq_Value
+RCC.LPTIM1Freq_Value=48000000
+RCC.LPUART1Freq_Value=48000000
+RCC.LSCOPinFreq_Value=32000
+RCC.LSI_VALUE=32000
+RCC.MCO1PinFreq_Value=16000000
+RCC.PLLN=12
+RCC.PLLPoutputFreq_Value=48000000
+RCC.PLLQoutputFreq_Value=48000000
+RCC.PLLRCLKFreq_Value=48000000
+RCC.PLLSourceVirtual=RCC_PLLSOURCE_HSE
+RCC.PWRFreq_Value=48000000
+RCC.QSPIFreq_Value=48000000
+RCC.RNGFreq_Value=48000000
+RCC.RTCClockSelection=RCC_RTCCLKSOURCE_LSE
+RCC.RTCFreq_Value=32768
+RCC.SAI1Freq_Value=48000000
+RCC.SYSCLKFreq_VALUE=48000000
+RCC.SYSCLKSource=RCC_SYSCLKSOURCE_PLLCLK
+RCC.UART4Freq_Value=48000000
+RCC.USART1Freq_Value=48000000
+RCC.USART2Freq_Value=48000000
+RCC.USART3Freq_Value=48000000
+RCC.USBFreq_Value=48000000
+RCC.VCOInputFreq_Value=8000000
+RCC.VCOOutputFreq_Value=96000000
+USART2.IPParameters=VirtualMode-Asynchronous
+USART2.VirtualMode-Asynchronous=VM_ASYNC
+USB_DEVICE.CLASS_NAME_FS=CDC
+USB_DEVICE.IPParameters=VirtualMode,VirtualModeFS,CLASS_NAME_FS
+USB_DEVICE.VirtualMode=Cdc
+USB_DEVICE.VirtualModeFS=Cdc_FS
+VP_RTC_VS_RTC_Activate.Mode=RTC_Enabled
+VP_RTC_VS_RTC_Activate.Signal=RTC_VS_RTC_Activate
+VP_SYS_VS_DBSignals.Mode=DisableDeadBatterySignals
+VP_SYS_VS_DBSignals.Signal=SYS_VS_DBSignals
+VP_SYS_VS_Systick.Mode=SysTick
+VP_SYS_VS_Systick.Signal=SYS_VS_Systick
+VP_USB_DEVICE_VS_USB_DEVICE_CDC_FS.Mode=CDC_FS
+VP_USB_DEVICE_VS_USB_DEVICE_CDC_FS.Signal=USB_DEVICE_VS_USB_DEVICE_CDC_FS
+board=custom
+isbadioc=false
diff --git a/embedded/CANFDMigrate/Core/Inc/fdcan.h b/embedded/CANFDMigrate/Core/Inc/fdcan.h
new file mode 100644
index 0000000..f22c52f
--- /dev/null
+++ b/embedded/CANFDMigrate/Core/Inc/fdcan.h
@@ -0,0 +1,55 @@
+/* USER CODE BEGIN Header */
+/**
+ ******************************************************************************
+ * @file fdcan.h
+ * @brief This file contains all the function prototypes for
+ * the fdcan.c file
+ ******************************************************************************
+ * @attention
+ *
+ * Copyright (c) 2025 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software is licensed under terms that can be found in the LICENSE file
+ * in the root directory of this software component.
+ * If no LICENSE file comes with this software, it is provided AS-IS.
+ *
+ ******************************************************************************
+ */
+/* USER CODE END Header */
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __FDCAN_H__
+#define __FDCAN_H__
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+#include "main.h"
+
+/* USER CODE BEGIN Includes */
+
+/* USER CODE END Includes */
+
+extern FDCAN_HandleTypeDef hfdcan2;
+
+extern FDCAN_HandleTypeDef hfdcan3;
+
+/* USER CODE BEGIN Private defines */
+
+/* USER CODE END Private defines */
+
+void MX_FDCAN2_Init(void);
+void MX_FDCAN3_Init(void);
+
+/* USER CODE BEGIN Prototypes */
+
+/* USER CODE END Prototypes */
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __FDCAN_H__ */
+
diff --git a/embedded/CANFDMigrate/Core/Inc/gpio.h b/embedded/CANFDMigrate/Core/Inc/gpio.h
new file mode 100644
index 0000000..8ba7de1
--- /dev/null
+++ b/embedded/CANFDMigrate/Core/Inc/gpio.h
@@ -0,0 +1,49 @@
+/* USER CODE BEGIN Header */
+/**
+ ******************************************************************************
+ * @file gpio.h
+ * @brief This file contains all the function prototypes for
+ * the gpio.c file
+ ******************************************************************************
+ * @attention
+ *
+ * Copyright (c) 2025 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software is licensed under terms that can be found in the LICENSE file
+ * in the root directory of this software component.
+ * If no LICENSE file comes with this software, it is provided AS-IS.
+ *
+ ******************************************************************************
+ */
+/* USER CODE END Header */
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __GPIO_H__
+#define __GPIO_H__
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+#include "main.h"
+
+/* USER CODE BEGIN Includes */
+
+/* USER CODE END Includes */
+
+/* USER CODE BEGIN Private defines */
+
+/* USER CODE END Private defines */
+
+void MX_GPIO_Init(void);
+
+/* USER CODE BEGIN Prototypes */
+
+/* USER CODE END Prototypes */
+
+#ifdef __cplusplus
+}
+#endif
+#endif /*__ GPIO_H__ */
+
diff --git a/embedded/CANFDMigrate/Core/Inc/main.h b/embedded/CANFDMigrate/Core/Inc/main.h
new file mode 100644
index 0000000..12f1c21
--- /dev/null
+++ b/embedded/CANFDMigrate/Core/Inc/main.h
@@ -0,0 +1,76 @@
+/* USER CODE BEGIN Header */
+/**
+ ******************************************************************************
+ * @file : main.h
+ * @brief : Header for main.c file.
+ * This file contains the common defines of the application.
+ ******************************************************************************
+ * @attention
+ *
+ * Copyright (c) 2025 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software is licensed under terms that can be found in the LICENSE file
+ * in the root directory of this software component.
+ * If no LICENSE file comes with this software, it is provided AS-IS.
+ *
+ ******************************************************************************
+ */
+/* USER CODE END Header */
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __MAIN_H
+#define __MAIN_H
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32g4xx_hal.h"
+
+/* Private includes ----------------------------------------------------------*/
+/* USER CODE BEGIN Includes */
+
+/* USER CODE END Includes */
+
+/* Exported types ------------------------------------------------------------*/
+/* USER CODE BEGIN ET */
+
+/* USER CODE END ET */
+
+/* Exported constants --------------------------------------------------------*/
+/* USER CODE BEGIN EC */
+
+/* USER CODE END EC */
+
+/* Exported macro ------------------------------------------------------------*/
+/* USER CODE BEGIN EM */
+
+/* USER CODE END EM */
+
+/* Exported functions prototypes ---------------------------------------------*/
+void Error_Handler(void);
+
+/* USER CODE BEGIN EFP */
+
+/* USER CODE END EFP */
+
+/* Private defines -----------------------------------------------------------*/
+#define LED_Pin GPIO_PIN_6
+#define LED_GPIO_Port GPIOC
+#define PHASE_A_PIN GPIO_PIN_6
+#define PHASE_B_PIN GPIO_PIN_7
+#define PHASE_C_PIN GPIO_PIN_9
+#define MOT_EN_PIN GPIO_PIN_1
+#define MOTOR_PORT GPIOB
+
+/* USER CODE BEGIN Private defines */
+
+/* USER CODE END Private defines */
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __MAIN_H */
diff --git a/embedded/CANFDMigrate/Core/Inc/rtc.h b/embedded/CANFDMigrate/Core/Inc/rtc.h
new file mode 100644
index 0000000..fb81e10
--- /dev/null
+++ b/embedded/CANFDMigrate/Core/Inc/rtc.h
@@ -0,0 +1,52 @@
+/* USER CODE BEGIN Header */
+/**
+ ******************************************************************************
+ * @file rtc.h
+ * @brief This file contains all the function prototypes for
+ * the rtc.c file
+ ******************************************************************************
+ * @attention
+ *
+ * Copyright (c) 2025 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software is licensed under terms that can be found in the LICENSE file
+ * in the root directory of this software component.
+ * If no LICENSE file comes with this software, it is provided AS-IS.
+ *
+ ******************************************************************************
+ */
+/* USER CODE END Header */
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __RTC_H__
+#define __RTC_H__
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+#include "main.h"
+
+/* USER CODE BEGIN Includes */
+
+/* USER CODE END Includes */
+
+extern RTC_HandleTypeDef hrtc;
+
+/* USER CODE BEGIN Private defines */
+
+/* USER CODE END Private defines */
+
+void MX_RTC_Init(void);
+
+/* USER CODE BEGIN Prototypes */
+
+/* USER CODE END Prototypes */
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __RTC_H__ */
+
diff --git a/embedded/CANFDMigrate/Core/Inc/spi.h b/embedded/CANFDMigrate/Core/Inc/spi.h
new file mode 100644
index 0000000..bc75c0f
--- /dev/null
+++ b/embedded/CANFDMigrate/Core/Inc/spi.h
@@ -0,0 +1,52 @@
+/* USER CODE BEGIN Header */
+/**
+ ******************************************************************************
+ * @file spi.h
+ * @brief This file contains all the function prototypes for
+ * the spi.c file
+ ******************************************************************************
+ * @attention
+ *
+ * Copyright (c) 2025 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software is licensed under terms that can be found in the LICENSE file
+ * in the root directory of this software component.
+ * If no LICENSE file comes with this software, it is provided AS-IS.
+ *
+ ******************************************************************************
+ */
+/* USER CODE END Header */
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __SPI_H__
+#define __SPI_H__
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+#include "main.h"
+
+/* USER CODE BEGIN Includes */
+
+/* USER CODE END Includes */
+
+extern SPI_HandleTypeDef hspi1;
+
+/* USER CODE BEGIN Private defines */
+
+/* USER CODE END Private defines */
+
+void MX_SPI1_Init(void);
+
+/* USER CODE BEGIN Prototypes */
+
+/* USER CODE END Prototypes */
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __SPI_H__ */
+
diff --git a/embedded/CANFDMigrate/Core/Inc/stm32g4xx_hal_conf.h b/embedded/CANFDMigrate/Core/Inc/stm32g4xx_hal_conf.h
new file mode 100644
index 0000000..6723163
--- /dev/null
+++ b/embedded/CANFDMigrate/Core/Inc/stm32g4xx_hal_conf.h
@@ -0,0 +1,380 @@
+/* USER CODE BEGIN Header */
+/**
+ ******************************************************************************
+ * @file stm32g4xx_hal_conf.h
+ * @author MCD Application Team
+ * @brief HAL configuration file
+ ******************************************************************************
+ * @attention
+ *
+ * Copyright (c) 2019 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software is licensed under terms that can be found in the LICENSE file
+ * in the root directory of this software component.
+ * If no LICENSE file comes with this software, it is provided AS-IS.
+ *
+ ******************************************************************************
+ */
+/* USER CODE END Header */
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef STM32G4xx_HAL_CONF_H
+#define STM32G4xx_HAL_CONF_H
+
+#ifdef __cplusplus
+ extern "C" {
+#endif
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+
+/* ########################## Module Selection ############################## */
+/**
+ * @brief This is the list of modules to be used in the HAL driver
+ */
+
+#define HAL_MODULE_ENABLED
+
+ /*#define HAL_ADC_MODULE_ENABLED */
+/*#define HAL_COMP_MODULE_ENABLED */
+/*#define HAL_CORDIC_MODULE_ENABLED */
+/*#define HAL_CRC_MODULE_ENABLED */
+/*#define HAL_CRYP_MODULE_ENABLED */
+/*#define HAL_DAC_MODULE_ENABLED */
+#define HAL_FDCAN_MODULE_ENABLED
+/*#define HAL_FMAC_MODULE_ENABLED */
+/*#define HAL_HRTIM_MODULE_ENABLED */
+/*#define HAL_IRDA_MODULE_ENABLED */
+/*#define HAL_IWDG_MODULE_ENABLED */
+/*#define HAL_I2C_MODULE_ENABLED */
+/*#define HAL_I2S_MODULE_ENABLED */
+/*#define HAL_LPTIM_MODULE_ENABLED */
+/*#define HAL_NAND_MODULE_ENABLED */
+/*#define HAL_NOR_MODULE_ENABLED */
+/*#define HAL_OPAMP_MODULE_ENABLED */
+#define HAL_PCD_MODULE_ENABLED
+/*#define HAL_QSPI_MODULE_ENABLED */
+/*#define HAL_RNG_MODULE_ENABLED */
+#define HAL_RTC_MODULE_ENABLED
+/*#define HAL_SAI_MODULE_ENABLED */
+/*#define HAL_SMARTCARD_MODULE_ENABLED */
+/*#define HAL_SMBUS_MODULE_ENABLED */
+/*#define HAL_SPI_MODULE_ENABLED */
+/*#define HAL_SRAM_MODULE_ENABLED */
+/*#define HAL_TIM_MODULE_ENABLED */
+#define HAL_UART_MODULE_ENABLED
+/*#define HAL_USART_MODULE_ENABLED */
+/*#define HAL_WWDG_MODULE_ENABLED */
+#define HAL_GPIO_MODULE_ENABLED
+#define HAL_EXTI_MODULE_ENABLED
+#define HAL_DMA_MODULE_ENABLED
+#define HAL_RCC_MODULE_ENABLED
+#define HAL_FLASH_MODULE_ENABLED
+#define HAL_PWR_MODULE_ENABLED
+#define HAL_CORTEX_MODULE_ENABLED
+
+/* ########################## Register Callbacks selection ############################## */
+/**
+ * @brief This is the list of modules where register callback can be used
+ */
+#define USE_HAL_ADC_REGISTER_CALLBACKS 0U
+#define USE_HAL_COMP_REGISTER_CALLBACKS 0U
+#define USE_HAL_CORDIC_REGISTER_CALLBACKS 0U
+#define USE_HAL_CRYP_REGISTER_CALLBACKS 0U
+#define USE_HAL_DAC_REGISTER_CALLBACKS 0U
+#define USE_HAL_EXTI_REGISTER_CALLBACKS 0U
+#define USE_HAL_FDCAN_REGISTER_CALLBACKS 0U
+#define USE_HAL_FMAC_REGISTER_CALLBACKS 0U
+#define USE_HAL_HRTIM_REGISTER_CALLBACKS 0U
+#define USE_HAL_I2C_REGISTER_CALLBACKS 0U
+#define USE_HAL_I2S_REGISTER_CALLBACKS 0U
+#define USE_HAL_IRDA_REGISTER_CALLBACKS 0U
+#define USE_HAL_LPTIM_REGISTER_CALLBACKS 0U
+#define USE_HAL_NAND_REGISTER_CALLBACKS 0U
+#define USE_HAL_NOR_REGISTER_CALLBACKS 0U
+#define USE_HAL_OPAMP_REGISTER_CALLBACKS 0U
+#define USE_HAL_PCD_REGISTER_CALLBACKS 0U
+#define USE_HAL_QSPI_REGISTER_CALLBACKS 0U
+#define USE_HAL_RNG_REGISTER_CALLBACKS 0U
+#define USE_HAL_RTC_REGISTER_CALLBACKS 0U
+#define USE_HAL_SAI_REGISTER_CALLBACKS 0U
+#define USE_HAL_SMARTCARD_REGISTER_CALLBACKS 0U
+#define USE_HAL_SMBUS_REGISTER_CALLBACKS 0U
+#define USE_HAL_SPI_REGISTER_CALLBACKS 0U
+#define USE_HAL_SRAM_REGISTER_CALLBACKS 0U
+#define USE_HAL_TIM_REGISTER_CALLBACKS 0U
+#define USE_HAL_UART_REGISTER_CALLBACKS 0U
+#define USE_HAL_USART_REGISTER_CALLBACKS 0U
+#define USE_HAL_WWDG_REGISTER_CALLBACKS 0U
+
+/* ########################## Oscillator Values adaptation ####################*/
+/**
+ * @brief Adjust the value of External High Speed oscillator (HSE) used in your application.
+ * This value is used by the RCC HAL module to compute the system frequency
+ * (when HSE is used as system clock source, directly or through the PLL).
+ */
+#if !defined (HSE_VALUE)
+ #define HSE_VALUE (8000000UL) /*!< Value of the External oscillator in Hz */
+#endif /* HSE_VALUE */
+
+#if !defined (HSE_STARTUP_TIMEOUT)
+ #define HSE_STARTUP_TIMEOUT (100UL) /*!< Time out for HSE start up, in ms */
+#endif /* HSE_STARTUP_TIMEOUT */
+
+/**
+ * @brief Internal High Speed oscillator (HSI) value.
+ * This value is used by the RCC HAL module to compute the system frequency
+ * (when HSI is used as system clock source, directly or through the PLL).
+ */
+#if !defined (HSI_VALUE)
+ #define HSI_VALUE (16000000UL) /*!< Value of the Internal oscillator in Hz*/
+#endif /* HSI_VALUE */
+
+/**
+ * @brief Internal High Speed oscillator (HSI48) value for USB FS and RNG.
+ * This internal oscillator is mainly dedicated to provide a high precision clock to
+ * the USB peripheral by means of a special Clock Recovery System (CRS) circuitry.
+ * When the CRS is not used, the HSI48 RC oscillator runs on it default frequency
+ * which is subject to manufacturing process variations.
+ */
+#if !defined (HSI48_VALUE)
+ #define HSI48_VALUE (48000000UL) /*!< Value of the Internal High Speed oscillator for USB FS/RNG in Hz.
+ The real value my vary depending on manufacturing process variations.*/
+#endif /* HSI48_VALUE */
+
+/**
+ * @brief Internal Low Speed oscillator (LSI) value.
+ */
+#if !defined (LSI_VALUE)
+/*!< Value of the Internal Low Speed oscillator in Hz
+The real value may vary depending on the variations in voltage and temperature.*/
+#define LSI_VALUE (32000UL) /*!< LSI Typical Value in Hz*/
+#endif /* LSI_VALUE */
+/**
+ * @brief External Low Speed oscillator (LSE) value.
+ * This value is used by the UART, RTC HAL module to compute the system frequency
+ */
+#if !defined (LSE_VALUE)
+#define LSE_VALUE (32768UL) /*!< Value of the External Low Speed oscillator in Hz */
+#endif /* LSE_VALUE */
+
+#if !defined (LSE_STARTUP_TIMEOUT)
+#define LSE_STARTUP_TIMEOUT (5000UL) /*!< Time out for LSE start up, in ms */
+#endif /* LSE_STARTUP_TIMEOUT */
+
+/**
+ * @brief External clock source for I2S and SAI peripherals
+ * This value is used by the I2S and SAI HAL modules to compute the I2S and SAI clock source
+ * frequency, this source is inserted directly through I2S_CKIN pad.
+ */
+#if !defined (EXTERNAL_CLOCK_VALUE)
+#define EXTERNAL_CLOCK_VALUE (12288000UL) /*!< Value of the External oscillator in Hz*/
+#endif /* EXTERNAL_CLOCK_VALUE */
+
+/* Tip: To avoid modifying this file each time you need to use different HSE,
+ === you can define the HSE value in your toolchain compiler preprocessor. */
+
+/* ########################### System Configuration ######################### */
+/**
+ * @brief This is the HAL system configuration section
+ */
+
+#define VDD_VALUE (3300UL) /*!< Value of VDD in mv */
+#define TICK_INT_PRIORITY (15UL) /*!< tick interrupt priority (lowest by default) */
+#define USE_RTOS 0U
+#define PREFETCH_ENABLE 0U
+#define INSTRUCTION_CACHE_ENABLE 1U
+#define DATA_CACHE_ENABLE 1U
+
+/* ########################## Assert Selection ############################## */
+/**
+ * @brief Uncomment the line below to expanse the "assert_param" macro in the
+ * HAL drivers code
+ */
+/* #define USE_FULL_ASSERT 1U */
+
+/* ################## SPI peripheral configuration ########################## */
+
+/* CRC FEATURE: Use to activate CRC feature inside HAL SPI Driver
+ * Activated: CRC code is present inside driver
+ * Deactivated: CRC code cleaned from driver
+ */
+
+#define USE_SPI_CRC 0U
+
+/* Includes ------------------------------------------------------------------*/
+/**
+ * @brief Include module's header file
+ */
+
+#ifdef HAL_RCC_MODULE_ENABLED
+#include "stm32g4xx_hal_rcc.h"
+#endif /* HAL_RCC_MODULE_ENABLED */
+
+#ifdef HAL_GPIO_MODULE_ENABLED
+#include "stm32g4xx_hal_gpio.h"
+#endif /* HAL_GPIO_MODULE_ENABLED */
+
+#ifdef HAL_DMA_MODULE_ENABLED
+#include "stm32g4xx_hal_dma.h"
+#endif /* HAL_DMA_MODULE_ENABLED */
+
+#ifdef HAL_CORTEX_MODULE_ENABLED
+#include "stm32g4xx_hal_cortex.h"
+#endif /* HAL_CORTEX_MODULE_ENABLED */
+
+#ifdef HAL_ADC_MODULE_ENABLED
+#include "stm32g4xx_hal_adc.h"
+#endif /* HAL_ADC_MODULE_ENABLED */
+
+#ifdef HAL_COMP_MODULE_ENABLED
+#include "stm32g4xx_hal_comp.h"
+#endif /* HAL_COMP_MODULE_ENABLED */
+
+#ifdef HAL_CORDIC_MODULE_ENABLED
+#include "stm32g4xx_hal_cordic.h"
+#endif /* HAL_CORDIC_MODULE_ENABLED */
+
+#ifdef HAL_CRC_MODULE_ENABLED
+#include "stm32g4xx_hal_crc.h"
+#endif /* HAL_CRC_MODULE_ENABLED */
+
+#ifdef HAL_CRYP_MODULE_ENABLED
+#include "stm32g4xx_hal_cryp.h"
+#endif /* HAL_CRYP_MODULE_ENABLED */
+
+#ifdef HAL_DAC_MODULE_ENABLED
+#include "stm32g4xx_hal_dac.h"
+#endif /* HAL_DAC_MODULE_ENABLED */
+
+#ifdef HAL_EXTI_MODULE_ENABLED
+#include "stm32g4xx_hal_exti.h"
+#endif /* HAL_EXTI_MODULE_ENABLED */
+
+#ifdef HAL_FDCAN_MODULE_ENABLED
+#include "stm32g4xx_hal_fdcan.h"
+#endif /* HAL_FDCAN_MODULE_ENABLED */
+
+#ifdef HAL_FLASH_MODULE_ENABLED
+#include "stm32g4xx_hal_flash.h"
+#endif /* HAL_FLASH_MODULE_ENABLED */
+
+#ifdef HAL_FMAC_MODULE_ENABLED
+#include "stm32g4xx_hal_fmac.h"
+#endif /* HAL_FMAC_MODULE_ENABLED */
+
+#ifdef HAL_HRTIM_MODULE_ENABLED
+#include "stm32g4xx_hal_hrtim.h"
+#endif /* HAL_HRTIM_MODULE_ENABLED */
+
+#ifdef HAL_IRDA_MODULE_ENABLED
+#include "stm32g4xx_hal_irda.h"
+#endif /* HAL_IRDA_MODULE_ENABLED */
+
+#ifdef HAL_IWDG_MODULE_ENABLED
+#include "stm32g4xx_hal_iwdg.h"
+#endif /* HAL_IWDG_MODULE_ENABLED */
+
+#ifdef HAL_I2C_MODULE_ENABLED
+#include "stm32g4xx_hal_i2c.h"
+#endif /* HAL_I2C_MODULE_ENABLED */
+
+#ifdef HAL_I2S_MODULE_ENABLED
+#include "stm32g4xx_hal_i2s.h"
+#endif /* HAL_I2S_MODULE_ENABLED */
+
+#ifdef HAL_LPTIM_MODULE_ENABLED
+#include "stm32g4xx_hal_lptim.h"
+#endif /* HAL_LPTIM_MODULE_ENABLED */
+
+#ifdef HAL_NAND_MODULE_ENABLED
+#include "stm32g4xx_hal_nand.h"
+#endif /* HAL_NAND_MODULE_ENABLED */
+
+#ifdef HAL_NOR_MODULE_ENABLED
+#include "stm32g4xx_hal_nor.h"
+#endif /* HAL_NOR_MODULE_ENABLED */
+
+#ifdef HAL_OPAMP_MODULE_ENABLED
+#include "stm32g4xx_hal_opamp.h"
+#endif /* HAL_OPAMP_MODULE_ENABLED */
+
+#ifdef HAL_PCD_MODULE_ENABLED
+#include "stm32g4xx_hal_pcd.h"
+#endif /* HAL_PCD_MODULE_ENABLED */
+
+#ifdef HAL_PWR_MODULE_ENABLED
+#include "stm32g4xx_hal_pwr.h"
+#endif /* HAL_PWR_MODULE_ENABLED */
+
+#ifdef HAL_QSPI_MODULE_ENABLED
+#include "stm32g4xx_hal_qspi.h"
+#endif /* HAL_QSPI_MODULE_ENABLED */
+
+#ifdef HAL_RNG_MODULE_ENABLED
+#include "stm32g4xx_hal_rng.h"
+#endif /* HAL_RNG_MODULE_ENABLED */
+
+#ifdef HAL_RTC_MODULE_ENABLED
+#include "stm32g4xx_hal_rtc.h"
+#endif /* HAL_RTC_MODULE_ENABLED */
+
+#ifdef HAL_SAI_MODULE_ENABLED
+#include "stm32g4xx_hal_sai.h"
+#endif /* HAL_SAI_MODULE_ENABLED */
+
+#ifdef HAL_SMARTCARD_MODULE_ENABLED
+#include "stm32g4xx_hal_smartcard.h"
+#endif /* HAL_SMARTCARD_MODULE_ENABLED */
+
+#ifdef HAL_SMBUS_MODULE_ENABLED
+#include "stm32g4xx_hal_smbus.h"
+#endif /* HAL_SMBUS_MODULE_ENABLED */
+
+#ifdef HAL_SPI_MODULE_ENABLED
+#include "stm32g4xx_hal_spi.h"
+#endif /* HAL_SPI_MODULE_ENABLED */
+
+#ifdef HAL_SRAM_MODULE_ENABLED
+#include "stm32g4xx_hal_sram.h"
+#endif /* HAL_SRAM_MODULE_ENABLED */
+
+#ifdef HAL_TIM_MODULE_ENABLED
+#include "stm32g4xx_hal_tim.h"
+#endif /* HAL_TIM_MODULE_ENABLED */
+
+#ifdef HAL_UART_MODULE_ENABLED
+#include "stm32g4xx_hal_uart.h"
+#endif /* HAL_UART_MODULE_ENABLED */
+
+#ifdef HAL_USART_MODULE_ENABLED
+#include "stm32g4xx_hal_usart.h"
+#endif /* HAL_USART_MODULE_ENABLED */
+
+#ifdef HAL_WWDG_MODULE_ENABLED
+#include "stm32g4xx_hal_wwdg.h"
+#endif /* HAL_WWDG_MODULE_ENABLED */
+
+/* Exported macro ------------------------------------------------------------*/
+#ifdef USE_FULL_ASSERT
+/**
+ * @brief The assert_param macro is used for function's parameters check.
+ * @param expr: If expr is false, it calls assert_failed function
+ * which reports the name of the source file and the source
+ * line number of the call that failed.
+ * If expr is true, it returns no value.
+ * @retval None
+ */
+#define assert_param(expr) ((expr) ? (void)0U : assert_failed((uint8_t *)__FILE__, __LINE__))
+/* Exported functions ------------------------------------------------------- */
+void assert_failed(uint8_t *file, uint32_t line);
+#else
+#define assert_param(expr) ((void)0U)
+#endif /* USE_FULL_ASSERT */
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* STM32G4xx_HAL_CONF_H */
diff --git a/embedded/CANFDMigrate/Core/Inc/stm32g4xx_it.h b/embedded/CANFDMigrate/Core/Inc/stm32g4xx_it.h
new file mode 100644
index 0000000..b126231
--- /dev/null
+++ b/embedded/CANFDMigrate/Core/Inc/stm32g4xx_it.h
@@ -0,0 +1,71 @@
+/* USER CODE BEGIN Header */
+/**
+ ******************************************************************************
+ * @file stm32g4xx_it.h
+ * @brief This file contains the headers of the interrupt handlers.
+ ******************************************************************************
+ * @attention
+ *
+ * Copyright (c) 2025 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software is licensed under terms that can be found in the LICENSE file
+ * in the root directory of this software component.
+ * If no LICENSE file comes with this software, it is provided AS-IS.
+ *
+ ******************************************************************************
+ */
+/* USER CODE END Header */
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32G4xx_IT_H
+#define __STM32G4xx_IT_H
+
+#ifdef __cplusplus
+ extern "C" {
+#endif
+
+/* Private includes ----------------------------------------------------------*/
+/* USER CODE BEGIN Includes */
+
+/* USER CODE END Includes */
+
+/* Exported types ------------------------------------------------------------*/
+/* USER CODE BEGIN ET */
+
+/* USER CODE END ET */
+
+/* Exported constants --------------------------------------------------------*/
+/* USER CODE BEGIN EC */
+
+/* USER CODE END EC */
+
+/* Exported macro ------------------------------------------------------------*/
+/* USER CODE BEGIN EM */
+
+/* USER CODE END EM */
+
+/* Exported functions prototypes ---------------------------------------------*/
+void NMI_Handler(void);
+void HardFault_Handler(void);
+void MemManage_Handler(void);
+void BusFault_Handler(void);
+void UsageFault_Handler(void);
+void SVC_Handler(void);
+void DebugMon_Handler(void);
+void PendSV_Handler(void);
+void SysTick_Handler(void);
+void USB_LP_IRQHandler(void);
+void FDCAN2_IT0_IRQHandler(void);
+void FDCAN2_IT1_IRQHandler(void);
+void FDCAN3_IT0_IRQHandler(void);
+void FDCAN3_IT1_IRQHandler(void);
+/* USER CODE BEGIN EFP */
+
+/* USER CODE END EFP */
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __STM32G4xx_IT_H */
diff --git a/embedded/CANFDMigrate/Core/Inc/usart.h b/embedded/CANFDMigrate/Core/Inc/usart.h
new file mode 100644
index 0000000..a0cfef0
--- /dev/null
+++ b/embedded/CANFDMigrate/Core/Inc/usart.h
@@ -0,0 +1,52 @@
+/* USER CODE BEGIN Header */
+/**
+ ******************************************************************************
+ * @file usart.h
+ * @brief This file contains all the function prototypes for
+ * the usart.c file
+ ******************************************************************************
+ * @attention
+ *
+ * Copyright (c) 2025 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software is licensed under terms that can be found in the LICENSE file
+ * in the root directory of this software component.
+ * If no LICENSE file comes with this software, it is provided AS-IS.
+ *
+ ******************************************************************************
+ */
+/* USER CODE END Header */
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __USART_H__
+#define __USART_H__
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+#include "main.h"
+
+/* USER CODE BEGIN Includes */
+
+/* USER CODE END Includes */
+
+extern UART_HandleTypeDef huart2;
+
+/* USER CODE BEGIN Private defines */
+
+/* USER CODE END Private defines */
+
+void MX_USART2_UART_Init(void);
+
+/* USER CODE BEGIN Prototypes */
+
+/* USER CODE END Prototypes */
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __USART_H__ */
+
diff --git a/embedded/CANFDMigrate/Core/Src/fdcan.c b/embedded/CANFDMigrate/Core/Src/fdcan.c
new file mode 100644
index 0000000..d452137
--- /dev/null
+++ b/embedded/CANFDMigrate/Core/Src/fdcan.c
@@ -0,0 +1,255 @@
+/* USER CODE BEGIN Header */
+/**
+ ******************************************************************************
+ * @file fdcan.c
+ * @brief This file provides code for the configuration
+ * of the FDCAN instances.
+ ******************************************************************************
+ * @attention
+ *
+ * Copyright (c) 2025 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software is licensed under terms that can be found in the LICENSE file
+ * in the root directory of this software component.
+ * If no LICENSE file comes with this software, it is provided AS-IS.
+ *
+ ******************************************************************************
+ */
+/* USER CODE END Header */
+/* Includes ------------------------------------------------------------------*/
+#include "fdcan.h"
+
+/* USER CODE BEGIN 0 */
+
+/* USER CODE END 0 */
+
+FDCAN_HandleTypeDef hfdcan2;
+FDCAN_HandleTypeDef hfdcan3;
+
+/* FDCAN2 init function */
+void MX_FDCAN2_Init(void)
+{
+
+ /* USER CODE BEGIN FDCAN2_Init 0 */
+
+ /* USER CODE END FDCAN2_Init 0 */
+
+ /* USER CODE BEGIN FDCAN2_Init 1 */
+
+ /* USER CODE END FDCAN2_Init 1 */
+ hfdcan2.Instance = FDCAN2;
+ hfdcan2.Init.ClockDivider = FDCAN_CLOCK_DIV1;
+ hfdcan2.Init.FrameFormat = FDCAN_FRAME_CLASSIC;
+ hfdcan2.Init.Mode = FDCAN_MODE_NORMAL;
+ hfdcan2.Init.AutoRetransmission = ENABLE;
+ hfdcan2.Init.TransmitPause = DISABLE;
+ hfdcan2.Init.ProtocolException = ENABLE;
+ hfdcan2.Init.NominalPrescaler = 1;
+ hfdcan2.Init.NominalSyncJumpWidth = 7;
+ hfdcan2.Init.NominalTimeSeg1 = 40;
+ hfdcan2.Init.NominalTimeSeg2 = 7;
+ hfdcan2.Init.DataPrescaler = 2;
+ hfdcan2.Init.DataSyncJumpWidth = 5;
+ hfdcan2.Init.DataTimeSeg1 = 18;
+ hfdcan2.Init.DataTimeSeg2 = 5;
+ hfdcan2.Init.StdFiltersNbr = 0;
+ hfdcan2.Init.ExtFiltersNbr = 0;
+ hfdcan2.Init.TxFifoQueueMode = FDCAN_TX_FIFO_OPERATION;
+ if (HAL_FDCAN_Init(&hfdcan2) != HAL_OK)
+ {
+ Error_Handler();
+ }
+ /* USER CODE BEGIN FDCAN2_Init 2 */
+
+ /* USER CODE END FDCAN2_Init 2 */
+
+}
+/* FDCAN3 init function */
+void MX_FDCAN3_Init(void)
+{
+
+ /* USER CODE BEGIN FDCAN3_Init 0 */
+
+ /* USER CODE END FDCAN3_Init 0 */
+
+ /* USER CODE BEGIN FDCAN3_Init 1 */
+
+ /* USER CODE END FDCAN3_Init 1 */
+ hfdcan3.Instance = FDCAN3;
+ hfdcan3.Init.ClockDivider = FDCAN_CLOCK_DIV1;
+ hfdcan3.Init.FrameFormat = FDCAN_FRAME_CLASSIC;
+ hfdcan3.Init.Mode = FDCAN_MODE_NORMAL;
+ hfdcan3.Init.AutoRetransmission = ENABLE;
+ hfdcan3.Init.TransmitPause = DISABLE;
+ hfdcan3.Init.ProtocolException = ENABLE;
+ hfdcan3.Init.NominalPrescaler = 1;
+ hfdcan3.Init.NominalSyncJumpWidth = 7;
+ hfdcan3.Init.NominalTimeSeg1 = 40;
+ hfdcan3.Init.NominalTimeSeg2 = 7;
+ hfdcan3.Init.DataPrescaler = 2;
+ hfdcan3.Init.DataSyncJumpWidth = 5;
+ hfdcan3.Init.DataTimeSeg1 = 18;
+ hfdcan3.Init.DataTimeSeg2 = 5;
+ hfdcan3.Init.StdFiltersNbr = 0;
+ hfdcan3.Init.ExtFiltersNbr = 0;
+ hfdcan3.Init.TxFifoQueueMode = FDCAN_TX_FIFO_OPERATION;
+ if (HAL_FDCAN_Init(&hfdcan3) != HAL_OK)
+ {
+ Error_Handler();
+ }
+ /* USER CODE BEGIN FDCAN3_Init 2 */
+
+ /* USER CODE END FDCAN3_Init 2 */
+
+}
+
+static uint32_t HAL_RCC_FDCAN_CLK_ENABLED=0;
+
+void HAL_FDCAN_MspInit(FDCAN_HandleTypeDef* fdcanHandle)
+{
+
+ GPIO_InitTypeDef GPIO_InitStruct = {0};
+ RCC_PeriphCLKInitTypeDef PeriphClkInit = {0};
+ if(fdcanHandle->Instance==FDCAN2)
+ {
+ /* USER CODE BEGIN FDCAN2_MspInit 0 */
+
+ /* USER CODE END FDCAN2_MspInit 0 */
+
+ /** Initializes the peripherals clocks
+ */
+ PeriphClkInit.PeriphClockSelection = RCC_PERIPHCLK_FDCAN;
+ PeriphClkInit.FdcanClockSelection = RCC_FDCANCLKSOURCE_PLL;
+ if (HAL_RCCEx_PeriphCLKConfig(&PeriphClkInit) != HAL_OK)
+ {
+ Error_Handler();
+ }
+
+ /* FDCAN2 clock enable */
+ HAL_RCC_FDCAN_CLK_ENABLED++;
+ if(HAL_RCC_FDCAN_CLK_ENABLED==1){
+ __HAL_RCC_FDCAN_CLK_ENABLE();
+ }
+
+ __HAL_RCC_GPIOB_CLK_ENABLE();
+ /**FDCAN2 GPIO Configuration
+ PB12 ------> FDCAN2_RX
+ PB13 ------> FDCAN2_TX
+ */
+ GPIO_InitStruct.Pin = GPIO_PIN_12|GPIO_PIN_13;
+ GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
+ GPIO_InitStruct.Pull = GPIO_NOPULL;
+ GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
+ GPIO_InitStruct.Alternate = GPIO_AF9_FDCAN2;
+ HAL_GPIO_Init(GPIOB, &GPIO_InitStruct);
+
+ /* FDCAN2 interrupt Init */
+ HAL_NVIC_SetPriority(FDCAN2_IT0_IRQn, 0, 0);
+ HAL_NVIC_EnableIRQ(FDCAN2_IT0_IRQn);
+ HAL_NVIC_SetPriority(FDCAN2_IT1_IRQn, 0, 0);
+ HAL_NVIC_EnableIRQ(FDCAN2_IT1_IRQn);
+ /* USER CODE BEGIN FDCAN2_MspInit 1 */
+
+ /* USER CODE END FDCAN2_MspInit 1 */
+ }
+ else if(fdcanHandle->Instance==FDCAN3)
+ {
+ /* USER CODE BEGIN FDCAN3_MspInit 0 */
+
+ /* USER CODE END FDCAN3_MspInit 0 */
+
+ /** Initializes the peripherals clocks
+ */
+ PeriphClkInit.PeriphClockSelection = RCC_PERIPHCLK_FDCAN;
+ PeriphClkInit.FdcanClockSelection = RCC_FDCANCLKSOURCE_PLL;
+ if (HAL_RCCEx_PeriphCLKConfig(&PeriphClkInit) != HAL_OK)
+ {
+ Error_Handler();
+ }
+
+ /* FDCAN3 clock enable */
+ HAL_RCC_FDCAN_CLK_ENABLED++;
+ if(HAL_RCC_FDCAN_CLK_ENABLED==1){
+ __HAL_RCC_FDCAN_CLK_ENABLE();
+ }
+
+ __HAL_RCC_GPIOA_CLK_ENABLE();
+ /**FDCAN3 GPIO Configuration
+ PA8 ------> FDCAN3_RX
+ PA15 ------> FDCAN3_TX
+ */
+ GPIO_InitStruct.Pin = GPIO_PIN_8|GPIO_PIN_15;
+ GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
+ GPIO_InitStruct.Pull = GPIO_NOPULL;
+ GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
+ GPIO_InitStruct.Alternate = GPIO_AF11_FDCAN3;
+ HAL_GPIO_Init(GPIOA, &GPIO_InitStruct);
+
+ /* FDCAN3 interrupt Init */
+ HAL_NVIC_SetPriority(FDCAN3_IT0_IRQn, 0, 0);
+ HAL_NVIC_EnableIRQ(FDCAN3_IT0_IRQn);
+ HAL_NVIC_SetPriority(FDCAN3_IT1_IRQn, 0, 0);
+ HAL_NVIC_EnableIRQ(FDCAN3_IT1_IRQn);
+ /* USER CODE BEGIN FDCAN3_MspInit 1 */
+
+ /* USER CODE END FDCAN3_MspInit 1 */
+ }
+}
+
+void HAL_FDCAN_MspDeInit(FDCAN_HandleTypeDef* fdcanHandle)
+{
+
+ if(fdcanHandle->Instance==FDCAN2)
+ {
+ /* USER CODE BEGIN FDCAN2_MspDeInit 0 */
+
+ /* USER CODE END FDCAN2_MspDeInit 0 */
+ /* Peripheral clock disable */
+ HAL_RCC_FDCAN_CLK_ENABLED--;
+ if(HAL_RCC_FDCAN_CLK_ENABLED==0){
+ __HAL_RCC_FDCAN_CLK_DISABLE();
+ }
+
+ /**FDCAN2 GPIO Configuration
+ PB12 ------> FDCAN2_RX
+ PB13 ------> FDCAN2_TX
+ */
+ HAL_GPIO_DeInit(GPIOB, GPIO_PIN_12|GPIO_PIN_13);
+
+ /* FDCAN2 interrupt Deinit */
+ HAL_NVIC_DisableIRQ(FDCAN2_IT0_IRQn);
+ HAL_NVIC_DisableIRQ(FDCAN2_IT1_IRQn);
+ /* USER CODE BEGIN FDCAN2_MspDeInit 1 */
+
+ /* USER CODE END FDCAN2_MspDeInit 1 */
+ }
+ else if(fdcanHandle->Instance==FDCAN3)
+ {
+ /* USER CODE BEGIN FDCAN3_MspDeInit 0 */
+
+ /* USER CODE END FDCAN3_MspDeInit 0 */
+ /* Peripheral clock disable */
+ HAL_RCC_FDCAN_CLK_ENABLED--;
+ if(HAL_RCC_FDCAN_CLK_ENABLED==0){
+ __HAL_RCC_FDCAN_CLK_DISABLE();
+ }
+
+ /**FDCAN3 GPIO Configuration
+ PA8 ------> FDCAN3_RX
+ PA15 ------> FDCAN3_TX
+ */
+ HAL_GPIO_DeInit(GPIOA, GPIO_PIN_8|GPIO_PIN_15);
+
+ /* FDCAN3 interrupt Deinit */
+ HAL_NVIC_DisableIRQ(FDCAN3_IT0_IRQn);
+ HAL_NVIC_DisableIRQ(FDCAN3_IT1_IRQn);
+ /* USER CODE BEGIN FDCAN3_MspDeInit 1 */
+
+ /* USER CODE END FDCAN3_MspDeInit 1 */
+ }
+}
+
+/* USER CODE BEGIN 1 */
+
+/* USER CODE END 1 */
diff --git a/embedded/CANFDMigrate/Core/Src/gpio.c b/embedded/CANFDMigrate/Core/Src/gpio.c
new file mode 100644
index 0000000..3a81262
--- /dev/null
+++ b/embedded/CANFDMigrate/Core/Src/gpio.c
@@ -0,0 +1,67 @@
+/* USER CODE BEGIN Header */
+/**
+ ******************************************************************************
+ * @file gpio.c
+ * @brief This file provides code for the configuration
+ * of all used GPIO pins.
+ ******************************************************************************
+ * @attention
+ *
+ * Copyright (c) 2025 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software is licensed under terms that can be found in the LICENSE file
+ * in the root directory of this software component.
+ * If no LICENSE file comes with this software, it is provided AS-IS.
+ *
+ ******************************************************************************
+ */
+/* USER CODE END Header */
+
+/* Includes ------------------------------------------------------------------*/
+#include "gpio.h"
+
+/* USER CODE BEGIN 0 */
+
+/* USER CODE END 0 */
+
+/*----------------------------------------------------------------------------*/
+/* Configure GPIO */
+/*----------------------------------------------------------------------------*/
+/* USER CODE BEGIN 1 */
+
+/* USER CODE END 1 */
+
+/** Configure pins as
+ * Analog
+ * Input
+ * Output
+ * EVENT_OUT
+ * EXTI
+*/
+void MX_GPIO_Init(void)
+{
+
+ GPIO_InitTypeDef GPIO_InitStruct = {0};
+
+ /* GPIO Ports Clock Enable */
+ __HAL_RCC_GPIOC_CLK_ENABLE();
+ __HAL_RCC_GPIOF_CLK_ENABLE();
+ __HAL_RCC_GPIOA_CLK_ENABLE();
+ __HAL_RCC_GPIOB_CLK_ENABLE();
+
+ /*Configure GPIO pin Output Level */
+ HAL_GPIO_WritePin(LED_GPIO_Port, LED_Pin, GPIO_PIN_RESET);
+
+ /*Configure GPIO pin : PtPin */
+ GPIO_InitStruct.Pin = LED_Pin;
+ GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP;
+ GPIO_InitStruct.Pull = GPIO_NOPULL;
+ GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
+ HAL_GPIO_Init(LED_GPIO_Port, &GPIO_InitStruct);
+
+}
+
+/* USER CODE BEGIN 2 */
+
+/* USER CODE END 2 */
diff --git a/embedded/CANFDMigrate/Core/Src/main.c b/embedded/CANFDMigrate/Core/Src/main.c
new file mode 100644
index 0000000..63c6ab3
--- /dev/null
+++ b/embedded/CANFDMigrate/Core/Src/main.c
@@ -0,0 +1,315 @@
+/* USER CODE BEGIN Header */
+/**
+ ******************************************************************************
+ * @file : main.c
+ * @brief : Main program body
+ ******************************************************************************
+ * @attention
+ *
+ * Copyright (c) 2025 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software is licensed under terms that can be found in the LICENSE file
+ * in the root directory of this software component.
+ * If no LICENSE file comes with this software, it is provided AS-IS.
+ *
+ ******************************************************************************
+ */
+/* USER CODE END Header */
+/* Includes ------------------------------------------------------------------*/
+#include "main.h"
+#include "fdcan.h"
+#include "rtc.h"
+#include "usart.h"
+#include "usb_device.h"
+#include "gpio.h"
+
+/* Private includes ----------------------------------------------------------*/
+/* USER CODE BEGIN Includes */
+
+/* USER CODE END Includes */
+
+/* Private typedef -----------------------------------------------------------*/
+/* USER CODE BEGIN PTD */
+
+/* USER CODE END PTD */
+
+/* Private define ------------------------------------------------------------*/
+/* USER CODE BEGIN PD */
+
+/* USER CODE END PD */
+
+/* Private macro -------------------------------------------------------------*/
+/* USER CODE BEGIN PM */
+
+/* USER CODE END PM */
+
+/* Private variables ---------------------------------------------------------*/
+
+/* USER CODE BEGIN PV */
+extern FDCAN_HandleTypeDef hfdcan2;
+extern FDCAN_HandleTypeDef hfdcan3;
+
+FDCAN_FilterTypeDef sFilterConfig;
+FDCAN_TxHeaderTypeDef TxHeader;
+FDCAN_RxHeaderTypeDef RxHeader;
+uint8_t TxData_C2_To_C3[64];
+uint8_t RxData_C3[8];
+volatile int txDone = 0;
+
+/* USER CODE END PV */
+
+/* Private function prototypes -----------------------------------------------*/
+void SystemClock_Config(void);
+/* USER CODE BEGIN PFP */
+static void check_can_bus(FDCAN_HandleTypeDef *hfdcan)
+{
+ FDCAN_ProtocolStatusTypeDef protocolStatus = {};
+
+ HAL_FDCAN_GetProtocolStatus(hfdcan, &protocolStatus);
+ if (protocolStatus.BusOff) {
+ CLEAR_BIT(hfdcan->Instance->CCCR, FDCAN_CCCR_INIT);
+ }
+}
+
+void HAL_FDCAN_ErrorStatusCallback(FDCAN_HandleTypeDef *hfdcan, uint32_t ErrorStatusITs)
+{
+ if (hfdcan == &hfdcan2) {
+ if ((ErrorStatusITs & FDCAN_IT_BUS_OFF) != RESET) {
+ check_can_bus(hfdcan);
+ }
+ }
+}
+/* USER CODE END PFP */
+
+/* Private user code ---------------------------------------------------------*/
+/* USER CODE BEGIN 0 */
+
+/* USER CODE END 0 */
+
+/**
+ * @brief The application entry point.
+ * @retval int
+ */
+int main(void)
+{
+ /* USER CODE BEGIN 1 */
+
+ /* USER CODE END 1 */
+
+ /* MCU Configuration--------------------------------------------------------*/
+
+ /* Reset of all peripherals, Initializes the Flash interface and the Systick. */
+ HAL_Init();
+
+ /* USER CODE BEGIN Init */
+
+ /* USER CODE END Init */
+
+ /* Configure the system clock */
+ SystemClock_Config();
+
+ /* USER CODE BEGIN SysInit */
+
+ /* USER CODE END SysInit */
+
+ /* Initialize all configured peripherals */
+ MX_GPIO_Init();
+ MX_RTC_Init();
+ MX_FDCAN2_Init();
+ MX_FDCAN3_Init();
+ MX_USART2_UART_Init();
+ MX_USB_Device_Init();
+ /* USER CODE BEGIN 2 */
+ TxHeader.Identifier = 0x123; // Standard ID
+ TxHeader.IdType = FDCAN_STANDARD_ID;
+ TxHeader.TxFrameType = FDCAN_DATA_FRAME;
+ TxHeader.DataLength = FDCAN_DLC_BYTES_8;
+ TxHeader.ErrorStateIndicator = FDCAN_ESI_ACTIVE;
+ TxHeader.BitRateSwitch = FDCAN_BRS_OFF;
+ TxHeader.FDFormat = FDCAN_FD_CAN;
+ TxHeader.TxEventFifoControl = FDCAN_NO_TX_EVENTS;
+ TxHeader.MessageMarker = 0;
+ TxData_C2_To_C3[0]=0b10101010;
+ for(uint8_t i=1;i<64;i++){
+ TxData_C2_To_C3[i]=2*i+2;
+ }
+//
+ sFilterConfig.IdType = FDCAN_STANDARD_ID;
+ sFilterConfig.FilterIndex = 0;
+ sFilterConfig.FilterType = FDCAN_FILTER_MASK;
+ sFilterConfig.FilterConfig = FDCAN_FILTER_TO_RXFIFO0;
+ sFilterConfig.FilterID1 = 0x123;
+ sFilterConfig.FilterID2 = 0x123;
+
+ if (HAL_FDCAN_ConfigFilter(&hfdcan2, &sFilterConfig) != HAL_OK
+ || HAL_FDCAN_ConfigFilter(&hfdcan3, &sFilterConfig) != HAL_OK) {
+ Error_Handler();
+ }
+
+ HAL_FDCAN_ConfigTxDelayCompensation(&hfdcan2, 38, 0);
+ HAL_FDCAN_EnableTxDelayCompensation(&hfdcan2);
+
+
+ HAL_FDCAN_ActivateNotification(
+ &hfdcan2,
+ FDCAN_IT_RX_FIFO0_NEW_MESSAGE | // RX FIFO0 new message
+ FDCAN_IT_TX_COMPLETE | // TX completed and acknowledged
+ FDCAN_IT_ERROR_WARNING | // error warning limit reached
+ FDCAN_IT_BUS_OFF | // bus-off state
+ FDCAN_IT_ARB_PROTOCOL_ERROR, // protocol error detected
+ 0
+ );
+ HAL_FDCAN_ActivateNotification(
+ &hfdcan3,
+ FDCAN_IT_RX_FIFO0_NEW_MESSAGE | // RX FIFO0 new message
+ FDCAN_IT_TX_COMPLETE | // TX completed and acknowledged
+ FDCAN_IT_ERROR_WARNING | // error warning limit reached
+ FDCAN_IT_BUS_OFF | // bus-off state
+ FDCAN_IT_ARB_PROTOCOL_ERROR, // protocol error detected
+ 0
+ );
+
+ HAL_FDCAN_Start(&hfdcan2);
+ HAL_FDCAN_Start(&hfdcan3);
+
+
+
+ /* USER CODE END 2 */
+
+ /* Infinite loop */
+ /* USER CODE BEGIN WHILE */
+
+ while (1)
+ {
+ HAL_GPIO_TogglePin(LED_GPIO_Port, LED_Pin);
+ if (HAL_FDCAN_AddMessageToTxFifoQ(&hfdcan2, &TxHeader, TxData_C2_To_C3) != HAL_OK) {
+ Error_Handler();
+ }
+
+
+ while (HAL_FDCAN_IsTxBufferMessagePending(&hfdcan2, FDCAN_TX_BUFFER0)) {
+ HAL_Delay(100);
+ FDCAN_ProtocolStatusTypeDef status;
+ HAL_FDCAN_GetProtocolStatus(&hfdcan2, &status);
+ printf("Hello from USB CDC! Tick: %lu\r\n", HAL_GetTick());
+ printf("BusOff: %d, Activity: %d, LastErrorCode: %d, RX FIFO Fill: %lu\n",
+ status.BusOff, status.Activity, status.LastErrorCode,
+ HAL_FDCAN_GetRxFifoFillLevel(&hfdcan2, FDCAN_RX_FIFO0));
+ };
+
+ }
+
+}
+
+/**
+ * @brief System Clock Configuration
+ * @retval None
+ */
+void SystemClock_Config(void)
+{
+ RCC_OscInitTypeDef RCC_OscInitStruct = {0};
+ RCC_ClkInitTypeDef RCC_ClkInitStruct = {0};
+
+ /** Configure the main internal regulator output voltage
+ */
+ HAL_PWREx_ControlVoltageScaling(PWR_REGULATOR_VOLTAGE_SCALE1);
+
+ /** Configure LSE Drive Capability
+ */
+ HAL_PWR_EnableBkUpAccess();
+ __HAL_RCC_LSEDRIVE_CONFIG(RCC_LSEDRIVE_LOW);
+
+ /** Initializes the RCC Oscillators according to the specified parameters
+ * in the RCC_OscInitTypeDef structure.
+ */
+ RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSE|RCC_OSCILLATORTYPE_LSE;
+ RCC_OscInitStruct.HSEState = RCC_HSE_ON;
+ RCC_OscInitStruct.LSEState = RCC_LSE_ON;
+ RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON;
+ RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSE;
+ RCC_OscInitStruct.PLL.PLLM = RCC_PLLM_DIV1;
+ RCC_OscInitStruct.PLL.PLLN = 12;
+ RCC_OscInitStruct.PLL.PLLP = RCC_PLLP_DIV2;
+ RCC_OscInitStruct.PLL.PLLQ = RCC_PLLQ_DIV2;
+ RCC_OscInitStruct.PLL.PLLR = RCC_PLLR_DIV2;
+ if (HAL_RCC_OscConfig(&RCC_OscInitStruct) != HAL_OK)
+ {
+ Error_Handler();
+ }
+
+ /** Initializes the CPU, AHB and APB buses clocks
+ */
+ RCC_ClkInitStruct.ClockType = RCC_CLOCKTYPE_HCLK|RCC_CLOCKTYPE_SYSCLK
+ |RCC_CLOCKTYPE_PCLK1|RCC_CLOCKTYPE_PCLK2;
+ RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK;
+ RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1;
+ RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV1;
+ RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV1;
+
+ if (HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_1) != HAL_OK)
+ {
+ Error_Handler();
+ }
+}
+
+/* USER CODE BEGIN 4 */
+
+
+
+void HAL_FDCAN_TxBufferCompleteCallback(FDCAN_HandleTypeDef *hfdcan, uint32_t BufferIndexes)
+{
+ if(hfdcan == &hfdcan2) {
+ txDone = 1;
+ }
+}
+
+int _write(int file, char *ptr, int len) {
+ CDC_Transmit_FS((uint8_t*)ptr, len);
+ return len;
+}
+
+void HAL_FDCAN_RxFifo0Callback(FDCAN_HandleTypeDef *hfdcan, uint32_t RxFifo0ITs){
+ HAL_FDCAN_GetRxMessage(hfdcan, FDCAN_RX_FIFO0, &RxHeader, RxData_C3);
+ // if(RxData[0]){
+ // digitalWrite(PC2, 1);
+ // }
+ // else{
+ // digitalWrite(PC2, 0);
+ // }
+ printf("HIHI I HEAR YOU!");
+
+}
+/* USER CODE END 4 */
+
+/**
+ * @brief This function is executed in case of error occurrence.
+ * @retval None
+ */
+void Error_Handler(void)
+{
+ /* USER CODE BEGIN Error_Handler_Debug */
+ /* User can add his own implementation to report the HAL error return state */
+ __disable_irq();
+ while (1)
+ {
+ }
+ /* USER CODE END Error_Handler_Debug */
+}
+
+#ifdef USE_FULL_ASSERT
+/**
+ * @brief Reports the name of the source file and the source line number
+ * where the assert_param error has occurred.
+ * @param file: pointer to the source file name
+ * @param line: assert_param error line source number
+ * @retval None
+ */
+void assert_failed(uint8_t *file, uint32_t line)
+{
+ /* USER CODE BEGIN 6 */
+ /* User can add his own implementation to report the file name and line number,
+ ex: printf("Wrong parameters value: file %s on line %d\r\n", file, line) */
+ /* USER CODE END 6 */
+}
+#endif /* USE_FULL_ASSERT */
diff --git a/embedded/CANFDMigrate/Core/Src/rtc.c b/embedded/CANFDMigrate/Core/Src/rtc.c
new file mode 100644
index 0000000..20ca727
--- /dev/null
+++ b/embedded/CANFDMigrate/Core/Src/rtc.c
@@ -0,0 +1,109 @@
+/* USER CODE BEGIN Header */
+/**
+ ******************************************************************************
+ * @file rtc.c
+ * @brief This file provides code for the configuration
+ * of the RTC instances.
+ ******************************************************************************
+ * @attention
+ *
+ * Copyright (c) 2025 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software is licensed under terms that can be found in the LICENSE file
+ * in the root directory of this software component.
+ * If no LICENSE file comes with this software, it is provided AS-IS.
+ *
+ ******************************************************************************
+ */
+/* USER CODE END Header */
+/* Includes ------------------------------------------------------------------*/
+#include "rtc.h"
+
+/* USER CODE BEGIN 0 */
+
+/* USER CODE END 0 */
+
+RTC_HandleTypeDef hrtc;
+
+/* RTC init function */
+void MX_RTC_Init(void)
+{
+
+ /* USER CODE BEGIN RTC_Init 0 */
+
+ /* USER CODE END RTC_Init 0 */
+
+ /* USER CODE BEGIN RTC_Init 1 */
+
+ /* USER CODE END RTC_Init 1 */
+
+ /** Initialize RTC Only
+ */
+ hrtc.Instance = RTC;
+ hrtc.Init.HourFormat = RTC_HOURFORMAT_24;
+ hrtc.Init.AsynchPrediv = 127;
+ hrtc.Init.SynchPrediv = 255;
+ hrtc.Init.OutPut = RTC_OUTPUT_DISABLE;
+ hrtc.Init.OutPutRemap = RTC_OUTPUT_REMAP_NONE;
+ hrtc.Init.OutPutPolarity = RTC_OUTPUT_POLARITY_HIGH;
+ hrtc.Init.OutPutType = RTC_OUTPUT_TYPE_OPENDRAIN;
+ hrtc.Init.OutPutPullUp = RTC_OUTPUT_PULLUP_NONE;
+ if (HAL_RTC_Init(&hrtc) != HAL_OK)
+ {
+ Error_Handler();
+ }
+ /* USER CODE BEGIN RTC_Init 2 */
+
+ /* USER CODE END RTC_Init 2 */
+
+}
+
+void HAL_RTC_MspInit(RTC_HandleTypeDef* rtcHandle)
+{
+
+ RCC_PeriphCLKInitTypeDef PeriphClkInit = {0};
+ if(rtcHandle->Instance==RTC)
+ {
+ /* USER CODE BEGIN RTC_MspInit 0 */
+
+ /* USER CODE END RTC_MspInit 0 */
+
+ /** Initializes the peripherals clocks
+ */
+ PeriphClkInit.PeriphClockSelection = RCC_PERIPHCLK_RTC;
+ PeriphClkInit.RTCClockSelection = RCC_RTCCLKSOURCE_LSE;
+ if (HAL_RCCEx_PeriphCLKConfig(&PeriphClkInit) != HAL_OK)
+ {
+ Error_Handler();
+ }
+
+ /* RTC clock enable */
+ __HAL_RCC_RTC_ENABLE();
+ __HAL_RCC_RTCAPB_CLK_ENABLE();
+ /* USER CODE BEGIN RTC_MspInit 1 */
+
+ /* USER CODE END RTC_MspInit 1 */
+ }
+}
+
+void HAL_RTC_MspDeInit(RTC_HandleTypeDef* rtcHandle)
+{
+
+ if(rtcHandle->Instance==RTC)
+ {
+ /* USER CODE BEGIN RTC_MspDeInit 0 */
+
+ /* USER CODE END RTC_MspDeInit 0 */
+ /* Peripheral clock disable */
+ __HAL_RCC_RTC_DISABLE();
+ __HAL_RCC_RTCAPB_CLK_DISABLE();
+ /* USER CODE BEGIN RTC_MspDeInit 1 */
+
+ /* USER CODE END RTC_MspDeInit 1 */
+ }
+}
+
+/* USER CODE BEGIN 1 */
+
+/* USER CODE END 1 */
diff --git a/embedded/CANFDMigrate/Core/Src/spi.c b/embedded/CANFDMigrate/Core/Src/spi.c
new file mode 100644
index 0000000..9168488
--- /dev/null
+++ b/embedded/CANFDMigrate/Core/Src/spi.c
@@ -0,0 +1,121 @@
+/* USER CODE BEGIN Header */
+/**
+ ******************************************************************************
+ * @file spi.c
+ * @brief This file provides code for the configuration
+ * of the SPI instances.
+ ******************************************************************************
+ * @attention
+ *
+ * Copyright (c) 2025 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software is licensed under terms that can be found in the LICENSE file
+ * in the root directory of this software component.
+ * If no LICENSE file comes with this software, it is provided AS-IS.
+ *
+ ******************************************************************************
+ */
+/* USER CODE END Header */
+/* Includes ------------------------------------------------------------------*/
+#include "spi.h"
+
+/* USER CODE BEGIN 0 */
+
+/* USER CODE END 0 */
+
+SPI_HandleTypeDef hspi1;
+
+/* SPI1 init function */
+void MX_SPI1_Init(void)
+{
+
+ /* USER CODE BEGIN SPI1_Init 0 */
+
+ /* USER CODE END SPI1_Init 0 */
+
+ /* USER CODE BEGIN SPI1_Init 1 */
+
+ /* USER CODE END SPI1_Init 1 */
+ hspi1.Instance = SPI1;
+ hspi1.Init.Mode = SPI_MODE_MASTER;
+ hspi1.Init.Direction = SPI_DIRECTION_2LINES;
+ hspi1.Init.DataSize = SPI_DATASIZE_4BIT;
+ hspi1.Init.CLKPolarity = SPI_POLARITY_HIGH;
+ hspi1.Init.CLKPhase = SPI_PHASE_2EDGE;
+ hspi1.Init.NSS = SPI_NSS_SOFT;
+ hspi1.Init.BaudRatePrescaler = SPI_BAUDRATEPRESCALER_2;
+ hspi1.Init.FirstBit = SPI_FIRSTBIT_MSB;
+ hspi1.Init.TIMode = SPI_TIMODE_DISABLE;
+ hspi1.Init.CRCCalculation = SPI_CRCCALCULATION_DISABLE;
+ hspi1.Init.CRCPolynomial = 7;
+ hspi1.Init.CRCLength = SPI_CRC_LENGTH_DATASIZE;
+ hspi1.Init.NSSPMode = SPI_NSS_PULSE_DISABLE;
+ if (HAL_SPI_Init(&hspi1) != HAL_OK)
+ {
+ Error_Handler();
+ }
+ /* USER CODE BEGIN SPI1_Init 2 */
+
+ /* USER CODE END SPI1_Init 2 */
+
+}
+
+void HAL_SPI_MspInit(SPI_HandleTypeDef* spiHandle)
+{
+
+ GPIO_InitTypeDef GPIO_InitStruct = {0};
+ if(spiHandle->Instance==SPI1)
+ {
+ /* USER CODE BEGIN SPI1_MspInit 0 */
+
+ /* USER CODE END SPI1_MspInit 0 */
+ /* SPI1 clock enable */
+ __HAL_RCC_SPI1_CLK_ENABLE();
+
+ __HAL_RCC_GPIOA_CLK_ENABLE();
+ /**SPI1 GPIO Configuration
+ PA5 ------> SPI1_SCK
+ PA6 ------> SPI1_MISO
+ PA7 ------> SPI1_MOSI
+ */
+ GPIO_InitStruct.Pin = GPIO_PIN_5|GPIO_PIN_6|GPIO_PIN_7;
+ GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
+ GPIO_InitStruct.Pull = GPIO_NOPULL;
+ GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
+ GPIO_InitStruct.Alternate = GPIO_AF5_SPI1;
+ HAL_GPIO_Init(GPIOA, &GPIO_InitStruct);
+
+ /* USER CODE BEGIN SPI1_MspInit 1 */
+
+ /* USER CODE END SPI1_MspInit 1 */
+ }
+}
+
+void HAL_SPI_MspDeInit(SPI_HandleTypeDef* spiHandle)
+{
+
+ if(spiHandle->Instance==SPI1)
+ {
+ /* USER CODE BEGIN SPI1_MspDeInit 0 */
+
+ /* USER CODE END SPI1_MspDeInit 0 */
+ /* Peripheral clock disable */
+ __HAL_RCC_SPI1_CLK_DISABLE();
+
+ /**SPI1 GPIO Configuration
+ PA5 ------> SPI1_SCK
+ PA6 ------> SPI1_MISO
+ PA7 ------> SPI1_MOSI
+ */
+ HAL_GPIO_DeInit(GPIOA, GPIO_PIN_5|GPIO_PIN_6|GPIO_PIN_7);
+
+ /* USER CODE BEGIN SPI1_MspDeInit 1 */
+
+ /* USER CODE END SPI1_MspDeInit 1 */
+ }
+}
+
+/* USER CODE BEGIN 1 */
+
+/* USER CODE END 1 */
diff --git a/embedded/CANFDMigrate/Core/Src/stm32g4xx_hal_msp.c b/embedded/CANFDMigrate/Core/Src/stm32g4xx_hal_msp.c
new file mode 100644
index 0000000..240a99a
--- /dev/null
+++ b/embedded/CANFDMigrate/Core/Src/stm32g4xx_hal_msp.c
@@ -0,0 +1,86 @@
+/* USER CODE BEGIN Header */
+/**
+ ******************************************************************************
+ * @file stm32g4xx_hal_msp.c
+ * @brief This file provides code for the MSP Initialization
+ * and de-Initialization codes.
+ ******************************************************************************
+ * @attention
+ *
+ * Copyright (c) 2025 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software is licensed under terms that can be found in the LICENSE file
+ * in the root directory of this software component.
+ * If no LICENSE file comes with this software, it is provided AS-IS.
+ *
+ ******************************************************************************
+ */
+/* USER CODE END Header */
+
+/* Includes ------------------------------------------------------------------*/
+#include "main.h"
+
+/* USER CODE BEGIN Includes */
+
+/* USER CODE END Includes */
+
+/* Private typedef -----------------------------------------------------------*/
+/* USER CODE BEGIN TD */
+
+/* USER CODE END TD */
+
+/* Private define ------------------------------------------------------------*/
+/* USER CODE BEGIN Define */
+
+/* USER CODE END Define */
+
+/* Private macro -------------------------------------------------------------*/
+/* USER CODE BEGIN Macro */
+
+/* USER CODE END Macro */
+
+/* Private variables ---------------------------------------------------------*/
+/* USER CODE BEGIN PV */
+
+/* USER CODE END PV */
+
+/* Private function prototypes -----------------------------------------------*/
+/* USER CODE BEGIN PFP */
+
+/* USER CODE END PFP */
+
+/* External functions --------------------------------------------------------*/
+/* USER CODE BEGIN ExternalFunctions */
+
+/* USER CODE END ExternalFunctions */
+
+/* USER CODE BEGIN 0 */
+
+/* USER CODE END 0 */
+/**
+ * Initializes the Global MSP.
+ */
+void HAL_MspInit(void)
+{
+ /* USER CODE BEGIN MspInit 0 */
+
+ /* USER CODE END MspInit 0 */
+
+ __HAL_RCC_SYSCFG_CLK_ENABLE();
+ __HAL_RCC_PWR_CLK_ENABLE();
+
+ /* System interrupt init*/
+
+ /** Disable the internal Pull-Up in Dead Battery pins of UCPD peripheral
+ */
+ HAL_PWREx_DisableUCPDDeadBattery();
+
+ /* USER CODE BEGIN MspInit 1 */
+
+ /* USER CODE END MspInit 1 */
+}
+
+/* USER CODE BEGIN 1 */
+
+/* USER CODE END 1 */
diff --git a/embedded/CANFDMigrate/Core/Src/stm32g4xx_it.c b/embedded/CANFDMigrate/Core/Src/stm32g4xx_it.c
new file mode 100644
index 0000000..1a26b0f
--- /dev/null
+++ b/embedded/CANFDMigrate/Core/Src/stm32g4xx_it.c
@@ -0,0 +1,275 @@
+/* USER CODE BEGIN Header */
+/**
+ ******************************************************************************
+ * @file stm32g4xx_it.c
+ * @brief Interrupt Service Routines.
+ ******************************************************************************
+ * @attention
+ *
+ * Copyright (c) 2025 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software is licensed under terms that can be found in the LICENSE file
+ * in the root directory of this software component.
+ * If no LICENSE file comes with this software, it is provided AS-IS.
+ *
+ ******************************************************************************
+ */
+/* USER CODE END Header */
+
+/* Includes ------------------------------------------------------------------*/
+#include "main.h"
+#include "stm32g4xx_it.h"
+/* Private includes ----------------------------------------------------------*/
+/* USER CODE BEGIN Includes */
+/* USER CODE END Includes */
+
+/* Private typedef -----------------------------------------------------------*/
+/* USER CODE BEGIN TD */
+
+/* USER CODE END TD */
+
+/* Private define ------------------------------------------------------------*/
+/* USER CODE BEGIN PD */
+
+/* USER CODE END PD */
+
+/* Private macro -------------------------------------------------------------*/
+/* USER CODE BEGIN PM */
+
+/* USER CODE END PM */
+
+/* Private variables ---------------------------------------------------------*/
+/* USER CODE BEGIN PV */
+
+/* USER CODE END PV */
+
+/* Private function prototypes -----------------------------------------------*/
+/* USER CODE BEGIN PFP */
+
+/* USER CODE END PFP */
+
+/* Private user code ---------------------------------------------------------*/
+/* USER CODE BEGIN 0 */
+
+/* USER CODE END 0 */
+
+/* External variables --------------------------------------------------------*/
+extern PCD_HandleTypeDef hpcd_USB_FS;
+extern FDCAN_HandleTypeDef hfdcan2;
+extern FDCAN_HandleTypeDef hfdcan3;
+/* USER CODE BEGIN EV */
+
+/* USER CODE END EV */
+
+/******************************************************************************/
+/* Cortex-M4 Processor Interruption and Exception Handlers */
+/******************************************************************************/
+/**
+ * @brief This function handles Non maskable interrupt.
+ */
+void NMI_Handler(void)
+{
+ /* USER CODE BEGIN NonMaskableInt_IRQn 0 */
+
+ /* USER CODE END NonMaskableInt_IRQn 0 */
+ /* USER CODE BEGIN NonMaskableInt_IRQn 1 */
+ while (1)
+ {
+ }
+ /* USER CODE END NonMaskableInt_IRQn 1 */
+}
+
+/**
+ * @brief This function handles Hard fault interrupt.
+ */
+void HardFault_Handler(void)
+{
+ /* USER CODE BEGIN HardFault_IRQn 0 */
+
+ /* USER CODE END HardFault_IRQn 0 */
+ while (1)
+ {
+ /* USER CODE BEGIN W1_HardFault_IRQn 0 */
+ /* USER CODE END W1_HardFault_IRQn 0 */
+ }
+}
+
+/**
+ * @brief This function handles Memory management fault.
+ */
+void MemManage_Handler(void)
+{
+ /* USER CODE BEGIN MemoryManagement_IRQn 0 */
+
+ /* USER CODE END MemoryManagement_IRQn 0 */
+ while (1)
+ {
+ /* USER CODE BEGIN W1_MemoryManagement_IRQn 0 */
+ /* USER CODE END W1_MemoryManagement_IRQn 0 */
+ }
+}
+
+/**
+ * @brief This function handles Prefetch fault, memory access fault.
+ */
+void BusFault_Handler(void)
+{
+ /* USER CODE BEGIN BusFault_IRQn 0 */
+
+ /* USER CODE END BusFault_IRQn 0 */
+ while (1)
+ {
+ /* USER CODE BEGIN W1_BusFault_IRQn 0 */
+ /* USER CODE END W1_BusFault_IRQn 0 */
+ }
+}
+
+/**
+ * @brief This function handles Undefined instruction or illegal state.
+ */
+void UsageFault_Handler(void)
+{
+ /* USER CODE BEGIN UsageFault_IRQn 0 */
+
+ /* USER CODE END UsageFault_IRQn 0 */
+ while (1)
+ {
+ /* USER CODE BEGIN W1_UsageFault_IRQn 0 */
+ /* USER CODE END W1_UsageFault_IRQn 0 */
+ }
+}
+
+/**
+ * @brief This function handles System service call via SWI instruction.
+ */
+void SVC_Handler(void)
+{
+ /* USER CODE BEGIN SVCall_IRQn 0 */
+
+ /* USER CODE END SVCall_IRQn 0 */
+ /* USER CODE BEGIN SVCall_IRQn 1 */
+
+ /* USER CODE END SVCall_IRQn 1 */
+}
+
+/**
+ * @brief This function handles Debug monitor.
+ */
+void DebugMon_Handler(void)
+{
+ /* USER CODE BEGIN DebugMonitor_IRQn 0 */
+
+ /* USER CODE END DebugMonitor_IRQn 0 */
+ /* USER CODE BEGIN DebugMonitor_IRQn 1 */
+
+ /* USER CODE END DebugMonitor_IRQn 1 */
+}
+
+/**
+ * @brief This function handles Pendable request for system service.
+ */
+void PendSV_Handler(void)
+{
+ /* USER CODE BEGIN PendSV_IRQn 0 */
+
+ /* USER CODE END PendSV_IRQn 0 */
+ /* USER CODE BEGIN PendSV_IRQn 1 */
+
+ /* USER CODE END PendSV_IRQn 1 */
+}
+
+/**
+ * @brief This function handles System tick timer.
+ */
+void SysTick_Handler(void)
+{
+ /* USER CODE BEGIN SysTick_IRQn 0 */
+
+ /* USER CODE END SysTick_IRQn 0 */
+ HAL_IncTick();
+ /* USER CODE BEGIN SysTick_IRQn 1 */
+
+ /* USER CODE END SysTick_IRQn 1 */
+}
+
+/******************************************************************************/
+/* STM32G4xx Peripheral Interrupt Handlers */
+/* Add here the Interrupt Handlers for the used peripherals. */
+/* For the available peripheral interrupt handler names, */
+/* please refer to the startup file (startup_stm32g4xx.s). */
+/******************************************************************************/
+
+/**
+ * @brief This function handles USB low priority interrupt remap.
+ */
+void USB_LP_IRQHandler(void)
+{
+ /* USER CODE BEGIN USB_LP_IRQn 0 */
+
+ /* USER CODE END USB_LP_IRQn 0 */
+ HAL_PCD_IRQHandler(&hpcd_USB_FS);
+ /* USER CODE BEGIN USB_LP_IRQn 1 */
+
+ /* USER CODE END USB_LP_IRQn 1 */
+}
+
+/**
+ * @brief This function handles FDCAN2 interrupt 0.
+ */
+void FDCAN2_IT0_IRQHandler(void)
+{
+ /* USER CODE BEGIN FDCAN2_IT0_IRQn 0 */
+
+ /* USER CODE END FDCAN2_IT0_IRQn 0 */
+ HAL_FDCAN_IRQHandler(&hfdcan2);
+ /* USER CODE BEGIN FDCAN2_IT0_IRQn 1 */
+
+ /* USER CODE END FDCAN2_IT0_IRQn 1 */
+}
+
+/**
+ * @brief This function handles FDCAN2 interrupt 1.
+ */
+void FDCAN2_IT1_IRQHandler(void)
+{
+ /* USER CODE BEGIN FDCAN2_IT1_IRQn 0 */
+
+ /* USER CODE END FDCAN2_IT1_IRQn 0 */
+ HAL_FDCAN_IRQHandler(&hfdcan2);
+ /* USER CODE BEGIN FDCAN2_IT1_IRQn 1 */
+
+ /* USER CODE END FDCAN2_IT1_IRQn 1 */
+}
+
+/**
+ * @brief This function handles FDCAN3 interrupt 0.
+ */
+void FDCAN3_IT0_IRQHandler(void)
+{
+ /* USER CODE BEGIN FDCAN3_IT0_IRQn 0 */
+
+ /* USER CODE END FDCAN3_IT0_IRQn 0 */
+ HAL_FDCAN_IRQHandler(&hfdcan3);
+ /* USER CODE BEGIN FDCAN3_IT0_IRQn 1 */
+
+ /* USER CODE END FDCAN3_IT0_IRQn 1 */
+}
+
+/**
+ * @brief This function handles FDCAN3 interrupt 1.
+ */
+void FDCAN3_IT1_IRQHandler(void)
+{
+ /* USER CODE BEGIN FDCAN3_IT1_IRQn 0 */
+
+ /* USER CODE END FDCAN3_IT1_IRQn 0 */
+ HAL_FDCAN_IRQHandler(&hfdcan3);
+ /* USER CODE BEGIN FDCAN3_IT1_IRQn 1 */
+
+ /* USER CODE END FDCAN3_IT1_IRQn 1 */
+}
+
+/* USER CODE BEGIN 1 */
+
+/* USER CODE END 1 */
diff --git a/embedded/CANFDMigrate/Core/Src/syscalls.c b/embedded/CANFDMigrate/Core/Src/syscalls.c
new file mode 100644
index 0000000..8884b5a
--- /dev/null
+++ b/embedded/CANFDMigrate/Core/Src/syscalls.c
@@ -0,0 +1,176 @@
+/**
+ ******************************************************************************
+ * @file syscalls.c
+ * @author Auto-generated by STM32CubeIDE
+ * @brief STM32CubeIDE Minimal System calls file
+ *
+ * For more information about which c-functions
+ * need which of these lowlevel functions
+ * please consult the Newlib libc-manual
+ ******************************************************************************
+ * @attention
+ *
+ * Copyright (c) 2020-2025 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software is licensed under terms that can be found in the LICENSE file
+ * in the root directory of this software component.
+ * If no LICENSE file comes with this software, it is provided AS-IS.
+ *
+ ******************************************************************************
+ */
+
+/* Includes */
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+
+
+/* Variables */
+extern int __io_putchar(int ch) __attribute__((weak));
+extern int __io_getchar(void) __attribute__((weak));
+
+
+char *__env[1] = { 0 };
+char **environ = __env;
+
+
+/* Functions */
+void initialise_monitor_handles()
+{
+}
+
+int _getpid(void)
+{
+ return 1;
+}
+
+int _kill(int pid, int sig)
+{
+ (void)pid;
+ (void)sig;
+ errno = EINVAL;
+ return -1;
+}
+
+void _exit (int status)
+{
+ _kill(status, -1);
+ while (1) {} /* Make sure we hang here */
+}
+
+__attribute__((weak)) int _read(int file, char *ptr, int len)
+{
+ (void)file;
+ int DataIdx;
+
+ for (DataIdx = 0; DataIdx < len; DataIdx++)
+ {
+ *ptr++ = __io_getchar();
+ }
+
+ return len;
+}
+
+__attribute__((weak)) int _write(int file, char *ptr, int len)
+{
+ (void)file;
+ int DataIdx;
+
+ for (DataIdx = 0; DataIdx < len; DataIdx++)
+ {
+ __io_putchar(*ptr++);
+ }
+ return len;
+}
+
+int _close(int file)
+{
+ (void)file;
+ return -1;
+}
+
+
+int _fstat(int file, struct stat *st)
+{
+ (void)file;
+ st->st_mode = S_IFCHR;
+ return 0;
+}
+
+int _isatty(int file)
+{
+ (void)file;
+ return 1;
+}
+
+int _lseek(int file, int ptr, int dir)
+{
+ (void)file;
+ (void)ptr;
+ (void)dir;
+ return 0;
+}
+
+int _open(char *path, int flags, ...)
+{
+ (void)path;
+ (void)flags;
+ /* Pretend like we always fail */
+ return -1;
+}
+
+int _wait(int *status)
+{
+ (void)status;
+ errno = ECHILD;
+ return -1;
+}
+
+int _unlink(char *name)
+{
+ (void)name;
+ errno = ENOENT;
+ return -1;
+}
+
+int _times(struct tms *buf)
+{
+ (void)buf;
+ return -1;
+}
+
+int _stat(char *file, struct stat *st)
+{
+ (void)file;
+ st->st_mode = S_IFCHR;
+ return 0;
+}
+
+int _link(char *old, char *new)
+{
+ (void)old;
+ (void)new;
+ errno = EMLINK;
+ return -1;
+}
+
+int _fork(void)
+{
+ errno = EAGAIN;
+ return -1;
+}
+
+int _execve(char *name, char **argv, char **env)
+{
+ (void)name;
+ (void)argv;
+ (void)env;
+ errno = ENOMEM;
+ return -1;
+}
diff --git a/embedded/CANFDMigrate/Core/Src/sysmem.c b/embedded/CANFDMigrate/Core/Src/sysmem.c
new file mode 100644
index 0000000..5d9f7e6
--- /dev/null
+++ b/embedded/CANFDMigrate/Core/Src/sysmem.c
@@ -0,0 +1,79 @@
+/**
+ ******************************************************************************
+ * @file sysmem.c
+ * @author Generated by STM32CubeIDE
+ * @brief STM32CubeIDE System Memory calls file
+ *
+ * For more information about which C functions
+ * need which of these lowlevel functions
+ * please consult the newlib libc manual
+ ******************************************************************************
+ * @attention
+ *
+ * Copyright (c) 2025 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software is licensed under terms that can be found in the LICENSE file
+ * in the root directory of this software component.
+ * If no LICENSE file comes with this software, it is provided AS-IS.
+ *
+ ******************************************************************************
+ */
+
+/* Includes */
+#include
+#include
+
+/**
+ * Pointer to the current high watermark of the heap usage
+ */
+static uint8_t *__sbrk_heap_end = NULL;
+
+/**
+ * @brief _sbrk() allocates memory to the newlib heap and is used by malloc
+ * and others from the C library
+ *
+ * @verbatim
+ * ############################################################################
+ * # .data # .bss # newlib heap # MSP stack #
+ * # # # # Reserved by _Min_Stack_Size #
+ * ############################################################################
+ * ^-- RAM start ^-- _end _estack, RAM end --^
+ * @endverbatim
+ *
+ * This implementation starts allocating at the '_end' linker symbol
+ * The '_Min_Stack_Size' linker symbol reserves a memory for the MSP stack
+ * The implementation considers '_estack' linker symbol to be RAM end
+ * NOTE: If the MSP stack, at any point during execution, grows larger than the
+ * reserved size, please increase the '_Min_Stack_Size'.
+ *
+ * @param incr Memory size
+ * @return Pointer to allocated memory
+ */
+void *_sbrk(ptrdiff_t incr)
+{
+ extern uint8_t _end; /* Symbol defined in the linker script */
+ extern uint8_t _estack; /* Symbol defined in the linker script */
+ extern uint32_t _Min_Stack_Size; /* Symbol defined in the linker script */
+ const uint32_t stack_limit = (uint32_t)&_estack - (uint32_t)&_Min_Stack_Size;
+ const uint8_t *max_heap = (uint8_t *)stack_limit;
+ uint8_t *prev_heap_end;
+
+ /* Initialize heap end at first call */
+ if (NULL == __sbrk_heap_end)
+ {
+ __sbrk_heap_end = &_end;
+ }
+
+ /* Protect heap from growing into the reserved MSP stack */
+ if (__sbrk_heap_end + incr > max_heap)
+ {
+ errno = ENOMEM;
+ return (void *)-1;
+ }
+
+ prev_heap_end = __sbrk_heap_end;
+ __sbrk_heap_end += incr;
+
+ return (void *)prev_heap_end;
+}
diff --git a/embedded/CANFDMigrate/Core/Src/system_stm32g4xx.c b/embedded/CANFDMigrate/Core/Src/system_stm32g4xx.c
new file mode 100644
index 0000000..d20700b
--- /dev/null
+++ b/embedded/CANFDMigrate/Core/Src/system_stm32g4xx.c
@@ -0,0 +1,285 @@
+/**
+ ******************************************************************************
+ * @file system_stm32g4xx.c
+ * @author MCD Application Team
+ * @brief CMSIS Cortex-M4 Device Peripheral Access Layer System Source File
+ *
+ * This file provides two functions and one global variable to be called from
+ * user application:
+ * - SystemInit(): This function is called at startup just after reset and
+ * before branch to main program. This call is made inside
+ * the "startup_stm32g4xx.s" file.
+ *
+ * - SystemCoreClock variable: Contains the core clock (HCLK), it can be used
+ * by the user application to setup the SysTick
+ * timer or configure other parameters.
+ *
+ * - SystemCoreClockUpdate(): Updates the variable SystemCoreClock and must
+ * be called whenever the core clock is changed
+ * during program execution.
+ *
+ * After each device reset the HSI (16 MHz) is used as system clock source.
+ * Then SystemInit() function is called, in "startup_stm32g4xx.s" file, to
+ * configure the system clock before to branch to main program.
+ *
+ * This file configures the system clock as follows:
+ *=============================================================================
+ *-----------------------------------------------------------------------------
+ * System Clock source | HSI
+ *-----------------------------------------------------------------------------
+ * SYSCLK(Hz) | 16000000
+ *-----------------------------------------------------------------------------
+ * HCLK(Hz) | 16000000
+ *-----------------------------------------------------------------------------
+ * AHB Prescaler | 1
+ *-----------------------------------------------------------------------------
+ * APB1 Prescaler | 1
+ *-----------------------------------------------------------------------------
+ * APB2 Prescaler | 1
+ *-----------------------------------------------------------------------------
+ * PLL_M | 1
+ *-----------------------------------------------------------------------------
+ * PLL_N | 16
+ *-----------------------------------------------------------------------------
+ * PLL_P | 7
+ *-----------------------------------------------------------------------------
+ * PLL_Q | 2
+ *-----------------------------------------------------------------------------
+ * PLL_R | 2
+ *-----------------------------------------------------------------------------
+ * Require 48MHz for RNG | Disabled
+ *-----------------------------------------------------------------------------
+ *=============================================================================
+ ******************************************************************************
+ * @attention
+ *
+ * Copyright (c) 2019 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software is licensed under terms that can be found in the LICENSE file
+ * in the root directory of this software component.
+ * If no LICENSE file comes with this software, it is provided AS-IS.
+ *
+ ******************************************************************************
+ */
+
+/** @addtogroup CMSIS
+ * @{
+ */
+
+/** @addtogroup stm32g4xx_system
+ * @{
+ */
+
+/** @addtogroup STM32G4xx_System_Private_Includes
+ * @{
+ */
+
+#include "stm32g4xx.h"
+
+#if !defined (HSE_VALUE)
+ #define HSE_VALUE 24000000U /*!< Value of the External oscillator in Hz */
+#endif /* HSE_VALUE */
+
+#if !defined (HSI_VALUE)
+ #define HSI_VALUE 16000000U /*!< Value of the Internal oscillator in Hz*/
+#endif /* HSI_VALUE */
+
+/**
+ * @}
+ */
+
+/** @addtogroup STM32G4xx_System_Private_TypesDefinitions
+ * @{
+ */
+
+/**
+ * @}
+ */
+
+/** @addtogroup STM32G4xx_System_Private_Defines
+ * @{
+ */
+
+/************************* Miscellaneous Configuration ************************/
+/* Note: Following vector table addresses must be defined in line with linker
+ configuration. */
+/*!< Uncomment the following line if you need to relocate the vector table
+ anywhere in Flash or Sram, else the vector table is kept at the automatic
+ remap of boot address selected */
+/* #define USER_VECT_TAB_ADDRESS */
+
+#if defined(USER_VECT_TAB_ADDRESS)
+/*!< Uncomment the following line if you need to relocate your vector Table
+ in Sram else user remap will be done in Flash. */
+/* #define VECT_TAB_SRAM */
+#if defined(VECT_TAB_SRAM)
+#define VECT_TAB_BASE_ADDRESS SRAM_BASE /*!< Vector Table base address field.
+ This value must be a multiple of 0x200. */
+#define VECT_TAB_OFFSET 0x00000000U /*!< Vector Table base offset field.
+ This value must be a multiple of 0x200. */
+#else
+#define VECT_TAB_BASE_ADDRESS FLASH_BASE /*!< Vector Table base address field.
+ This value must be a multiple of 0x200. */
+#define VECT_TAB_OFFSET 0x00000000U /*!< Vector Table base offset field.
+ This value must be a multiple of 0x200. */
+#endif /* VECT_TAB_SRAM */
+#endif /* USER_VECT_TAB_ADDRESS */
+/******************************************************************************/
+/**
+ * @}
+ */
+
+/** @addtogroup STM32G4xx_System_Private_Macros
+ * @{
+ */
+
+/**
+ * @}
+ */
+
+/** @addtogroup STM32G4xx_System_Private_Variables
+ * @{
+ */
+ /* The SystemCoreClock variable is updated in three ways:
+ 1) by calling CMSIS function SystemCoreClockUpdate()
+ 2) by calling HAL API function HAL_RCC_GetHCLKFreq()
+ 3) each time HAL_RCC_ClockConfig() is called to configure the system clock frequency
+ Note: If you use this function to configure the system clock; then there
+ is no need to call the 2 first functions listed above, since SystemCoreClock
+ variable is updated automatically.
+ */
+ uint32_t SystemCoreClock = HSI_VALUE;
+
+ const uint8_t AHBPrescTable[16] = {0U, 0U, 0U, 0U, 0U, 0U, 0U, 0U, 1U, 2U, 3U, 4U, 6U, 7U, 8U, 9U};
+ const uint8_t APBPrescTable[8] = {0U, 0U, 0U, 0U, 1U, 2U, 3U, 4U};
+
+/**
+ * @}
+ */
+
+/** @addtogroup STM32G4xx_System_Private_FunctionPrototypes
+ * @{
+ */
+
+/**
+ * @}
+ */
+
+/** @addtogroup STM32G4xx_System_Private_Functions
+ * @{
+ */
+
+/**
+ * @brief Setup the microcontroller system.
+ * @param None
+ * @retval None
+ */
+
+void SystemInit(void)
+{
+ /* FPU settings ------------------------------------------------------------*/
+ #if (__FPU_PRESENT == 1) && (__FPU_USED == 1)
+ SCB->CPACR |= ((3UL << (10*2))|(3UL << (11*2))); /* set CP10 and CP11 Full Access */
+ #endif
+
+ /* Configure the Vector Table location add offset address ------------------*/
+#if defined(USER_VECT_TAB_ADDRESS)
+ SCB->VTOR = VECT_TAB_BASE_ADDRESS | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal SRAM */
+#endif /* USER_VECT_TAB_ADDRESS */
+}
+
+/**
+ * @brief Update SystemCoreClock variable according to Clock Register Values.
+ * The SystemCoreClock variable contains the core clock (HCLK), it can
+ * be used by the user application to setup the SysTick timer or configure
+ * other parameters.
+ *
+ * @note Each time the core clock (HCLK) changes, this function must be called
+ * to update SystemCoreClock variable value. Otherwise, any configuration
+ * based on this variable will be incorrect.
+ *
+ * @note - The system frequency computed by this function is not the real
+ * frequency in the chip. It is calculated based on the predefined
+ * constant and the selected clock source:
+ *
+ * - If SYSCLK source is HSI, SystemCoreClock will contain the HSI_VALUE(**)
+ *
+ * - If SYSCLK source is HSE, SystemCoreClock will contain the HSE_VALUE(***)
+ *
+ * - If SYSCLK source is PLL, SystemCoreClock will contain the HSE_VALUE(***)
+ * or HSI_VALUE(*) multiplied/divided by the PLL factors.
+ *
+ * (**) HSI_VALUE is a constant defined in stm32g4xx_hal.h file (default value
+ * 16 MHz) but the real value may vary depending on the variations
+ * in voltage and temperature.
+ *
+ * (***) HSE_VALUE is a constant defined in stm32g4xx_hal.h file (default value
+ * 24 MHz), user has to ensure that HSE_VALUE is same as the real
+ * frequency of the crystal used. Otherwise, this function may
+ * have wrong result.
+ *
+ * - The result of this function could be not correct when using fractional
+ * value for HSE crystal.
+ *
+ * @param None
+ * @retval None
+ */
+void SystemCoreClockUpdate(void)
+{
+ uint32_t tmp, pllvco, pllr, pllsource, pllm;
+
+ /* Get SYSCLK source -------------------------------------------------------*/
+ switch (RCC->CFGR & RCC_CFGR_SWS)
+ {
+ case 0x04: /* HSI used as system clock source */
+ SystemCoreClock = HSI_VALUE;
+ break;
+
+ case 0x08: /* HSE used as system clock source */
+ SystemCoreClock = HSE_VALUE;
+ break;
+
+ case 0x0C: /* PLL used as system clock source */
+ /* PLL_VCO = (HSE_VALUE or HSI_VALUE / PLLM) * PLLN
+ SYSCLK = PLL_VCO / PLLR
+ */
+ pllsource = (RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC);
+ pllm = ((RCC->PLLCFGR & RCC_PLLCFGR_PLLM) >> 4) + 1U ;
+ if (pllsource == 0x02UL) /* HSI used as PLL clock source */
+ {
+ pllvco = (HSI_VALUE / pllm);
+ }
+ else /* HSE used as PLL clock source */
+ {
+ pllvco = (HSE_VALUE / pllm);
+ }
+ pllvco = pllvco * ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> 8);
+ pllr = (((RCC->PLLCFGR & RCC_PLLCFGR_PLLR) >> 25) + 1U) * 2U;
+ SystemCoreClock = pllvco/pllr;
+ break;
+
+ default:
+ break;
+ }
+ /* Compute HCLK clock frequency --------------------------------------------*/
+ /* Get HCLK prescaler */
+ tmp = AHBPrescTable[((RCC->CFGR & RCC_CFGR_HPRE) >> 4)];
+ /* HCLK clock frequency */
+ SystemCoreClock >>= tmp;
+}
+
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+
diff --git a/embedded/CANFDMigrate/Core/Src/usart.c b/embedded/CANFDMigrate/Core/Src/usart.c
new file mode 100644
index 0000000..8823d1d
--- /dev/null
+++ b/embedded/CANFDMigrate/Core/Src/usart.c
@@ -0,0 +1,140 @@
+/* USER CODE BEGIN Header */
+/**
+ ******************************************************************************
+ * @file usart.c
+ * @brief This file provides code for the configuration
+ * of the USART instances.
+ ******************************************************************************
+ * @attention
+ *
+ * Copyright (c) 2025 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software is licensed under terms that can be found in the LICENSE file
+ * in the root directory of this software component.
+ * If no LICENSE file comes with this software, it is provided AS-IS.
+ *
+ ******************************************************************************
+ */
+/* USER CODE END Header */
+/* Includes ------------------------------------------------------------------*/
+#include "usart.h"
+
+/* USER CODE BEGIN 0 */
+
+/* USER CODE END 0 */
+
+UART_HandleTypeDef huart2;
+
+/* USART2 init function */
+
+void MX_USART2_UART_Init(void)
+{
+
+ /* USER CODE BEGIN USART2_Init 0 */
+
+ /* USER CODE END USART2_Init 0 */
+
+ /* USER CODE BEGIN USART2_Init 1 */
+
+ /* USER CODE END USART2_Init 1 */
+ huart2.Instance = USART2;
+ huart2.Init.BaudRate = 115200;
+ huart2.Init.WordLength = UART_WORDLENGTH_8B;
+ huart2.Init.StopBits = UART_STOPBITS_1;
+ huart2.Init.Parity = UART_PARITY_NONE;
+ huart2.Init.Mode = UART_MODE_TX_RX;
+ huart2.Init.HwFlowCtl = UART_HWCONTROL_NONE;
+ huart2.Init.OverSampling = UART_OVERSAMPLING_16;
+ huart2.Init.OneBitSampling = UART_ONE_BIT_SAMPLE_DISABLE;
+ huart2.Init.ClockPrescaler = UART_PRESCALER_DIV1;
+ huart2.AdvancedInit.AdvFeatureInit = UART_ADVFEATURE_NO_INIT;
+ if (HAL_UART_Init(&huart2) != HAL_OK)
+ {
+ Error_Handler();
+ }
+ if (HAL_UARTEx_SetTxFifoThreshold(&huart2, UART_TXFIFO_THRESHOLD_1_8) != HAL_OK)
+ {
+ Error_Handler();
+ }
+ if (HAL_UARTEx_SetRxFifoThreshold(&huart2, UART_RXFIFO_THRESHOLD_1_8) != HAL_OK)
+ {
+ Error_Handler();
+ }
+ if (HAL_UARTEx_DisableFifoMode(&huart2) != HAL_OK)
+ {
+ Error_Handler();
+ }
+ /* USER CODE BEGIN USART2_Init 2 */
+
+ /* USER CODE END USART2_Init 2 */
+
+}
+
+void HAL_UART_MspInit(UART_HandleTypeDef* uartHandle)
+{
+
+ GPIO_InitTypeDef GPIO_InitStruct = {0};
+ RCC_PeriphCLKInitTypeDef PeriphClkInit = {0};
+ if(uartHandle->Instance==USART2)
+ {
+ /* USER CODE BEGIN USART2_MspInit 0 */
+
+ /* USER CODE END USART2_MspInit 0 */
+
+ /** Initializes the peripherals clocks
+ */
+ PeriphClkInit.PeriphClockSelection = RCC_PERIPHCLK_USART2;
+ PeriphClkInit.Usart2ClockSelection = RCC_USART2CLKSOURCE_PCLK1;
+ if (HAL_RCCEx_PeriphCLKConfig(&PeriphClkInit) != HAL_OK)
+ {
+ Error_Handler();
+ }
+
+ /* USART2 clock enable */
+ __HAL_RCC_USART2_CLK_ENABLE();
+
+ __HAL_RCC_GPIOA_CLK_ENABLE();
+ /**USART2 GPIO Configuration
+ PA2 ------> USART2_TX
+ PA3 ------> USART2_RX
+ */
+ GPIO_InitStruct.Pin = GPIO_PIN_2|GPIO_PIN_3;
+ GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
+ GPIO_InitStruct.Pull = GPIO_NOPULL;
+ GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
+ GPIO_InitStruct.Alternate = GPIO_AF7_USART2;
+ HAL_GPIO_Init(GPIOA, &GPIO_InitStruct);
+
+ /* USER CODE BEGIN USART2_MspInit 1 */
+
+ /* USER CODE END USART2_MspInit 1 */
+ }
+}
+
+void HAL_UART_MspDeInit(UART_HandleTypeDef* uartHandle)
+{
+
+ if(uartHandle->Instance==USART2)
+ {
+ /* USER CODE BEGIN USART2_MspDeInit 0 */
+
+ /* USER CODE END USART2_MspDeInit 0 */
+ /* Peripheral clock disable */
+ __HAL_RCC_USART2_CLK_DISABLE();
+
+ /**USART2 GPIO Configuration
+ PA2 ------> USART2_TX
+ PA3 ------> USART2_RX
+ */
+ HAL_GPIO_DeInit(GPIOA, GPIO_PIN_2|GPIO_PIN_3);
+
+ /* USER CODE BEGIN USART2_MspDeInit 1 */
+
+ /* USER CODE END USART2_MspDeInit 1 */
+ }
+}
+
+/* USER CODE BEGIN 1 */
+
+/* USER CODE END 1 */
diff --git a/embedded/CANFDMigrate/Core/Startup/startup_stm32g474ceux.s b/embedded/CANFDMigrate/Core/Startup/startup_stm32g474ceux.s
new file mode 100644
index 0000000..334d965
--- /dev/null
+++ b/embedded/CANFDMigrate/Core/Startup/startup_stm32g474ceux.s
@@ -0,0 +1,590 @@
+/**
+ ******************************************************************************
+ * @file startup_stm32g474xx.s
+ * @author MCD Application Team
+ * @brief STM32G474xx devices vector table GCC toolchain.
+ * This module performs:
+ * - Set the initial SP
+ * - Set the initial PC == Reset_Handler,
+ * - Set the vector table entries with the exceptions ISR address,
+ * - Configure the clock system
+ * - Branches to main in the C library (which eventually
+ * calls main()).
+ * After Reset the Cortex-M4 processor is in Thread mode,
+ * priority is Privileged, and the Stack is set to Main.
+ ******************************************************************************
+ * @attention
+ *
+ * Copyright (c) 2019 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software is licensed under terms that can be found in the LICENSE file
+ * in the root directory of this software component.
+ * If no LICENSE file comes with this software, it is provided AS-IS.
+ *
+ ******************************************************************************
+ */
+
+ .syntax unified
+ .cpu cortex-m4
+ .fpu softvfp
+ .thumb
+
+.global g_pfnVectors
+.global Default_Handler
+
+/* start address for the initialization values of the .data section.
+defined in linker script */
+.word _sidata
+/* start address for the .data section. defined in linker script */
+.word _sdata
+/* end address for the .data section. defined in linker script */
+.word _edata
+/* start address for the .bss section. defined in linker script */
+.word _sbss
+/* end address for the .bss section. defined in linker script */
+.word _ebss
+
+.equ BootRAM, 0xF1E0F85F
+/**
+ * @brief This is the code that gets called when the processor first
+ * starts execution following a reset event. Only the absolutely
+ * necessary set is performed, after which the application
+ * supplied main() routine is called.
+ * @param None
+ * @retval : None
+*/
+
+ .section .text.Reset_Handler
+ .weak Reset_Handler
+ .type Reset_Handler, %function
+Reset_Handler:
+ ldr r0, =_estack
+ mov sp, r0 /* set stack pointer */
+
+/* Copy the data segment initializers from flash to SRAM */
+ ldr r0, =_sdata
+ ldr r1, =_edata
+ ldr r2, =_sidata
+ movs r3, #0
+ b LoopCopyDataInit
+
+CopyDataInit:
+ ldr r4, [r2, r3]
+ str r4, [r0, r3]
+ adds r3, r3, #4
+
+LoopCopyDataInit:
+ adds r4, r0, r3
+ cmp r4, r1
+ bcc CopyDataInit
+
+/* Zero fill the bss segment. */
+ ldr r2, =_sbss
+ ldr r4, =_ebss
+ movs r3, #0
+ b LoopFillZerobss
+
+FillZerobss:
+ str r3, [r2]
+ adds r2, r2, #4
+
+LoopFillZerobss:
+ cmp r2, r4
+ bcc FillZerobss
+
+/* Call the clock system intitialization function.*/
+ bl SystemInit
+/* Call static constructors */
+ bl __libc_init_array
+/* Call the application's entry point.*/
+ bl main
+
+LoopForever:
+ b LoopForever
+
+.size Reset_Handler, .-Reset_Handler
+
+/**
+ * @brief This is the code that gets called when the processor receives an
+ * unexpected interrupt. This simply enters an infinite loop, preserving
+ * the system state for examination by a debugger.
+ *
+ * @param None
+ * @retval : None
+*/
+ .section .text.Default_Handler,"ax",%progbits
+Default_Handler:
+Infinite_Loop:
+ b Infinite_Loop
+ .size Default_Handler, .-Default_Handler
+/******************************************************************************
+*
+* The minimal vector table for a Cortex-M4. Note that the proper constructs
+* must be placed on this to ensure that it ends up at physical address
+* 0x0000.0000.
+*
+******************************************************************************/
+ .section .isr_vector,"a",%progbits
+ .type g_pfnVectors, %object
+ .size g_pfnVectors, .-g_pfnVectors
+
+
+g_pfnVectors:
+ .word _estack
+ .word Reset_Handler
+ .word NMI_Handler
+ .word HardFault_Handler
+ .word MemManage_Handler
+ .word BusFault_Handler
+ .word UsageFault_Handler
+ .word 0
+ .word 0
+ .word 0
+ .word 0
+ .word SVC_Handler
+ .word DebugMon_Handler
+ .word 0
+ .word PendSV_Handler
+ .word SysTick_Handler
+ .word WWDG_IRQHandler
+ .word PVD_PVM_IRQHandler
+ .word RTC_TAMP_LSECSS_IRQHandler
+ .word RTC_WKUP_IRQHandler
+ .word FLASH_IRQHandler
+ .word RCC_IRQHandler
+ .word EXTI0_IRQHandler
+ .word EXTI1_IRQHandler
+ .word EXTI2_IRQHandler
+ .word EXTI3_IRQHandler
+ .word EXTI4_IRQHandler
+ .word DMA1_Channel1_IRQHandler
+ .word DMA1_Channel2_IRQHandler
+ .word DMA1_Channel3_IRQHandler
+ .word DMA1_Channel4_IRQHandler
+ .word DMA1_Channel5_IRQHandler
+ .word DMA1_Channel6_IRQHandler
+ .word DMA1_Channel7_IRQHandler
+ .word ADC1_2_IRQHandler
+ .word USB_HP_IRQHandler
+ .word USB_LP_IRQHandler
+ .word FDCAN1_IT0_IRQHandler
+ .word FDCAN1_IT1_IRQHandler
+ .word EXTI9_5_IRQHandler
+ .word TIM1_BRK_TIM15_IRQHandler
+ .word TIM1_UP_TIM16_IRQHandler
+ .word TIM1_TRG_COM_TIM17_IRQHandler
+ .word TIM1_CC_IRQHandler
+ .word TIM2_IRQHandler
+ .word TIM3_IRQHandler
+ .word TIM4_IRQHandler
+ .word I2C1_EV_IRQHandler
+ .word I2C1_ER_IRQHandler
+ .word I2C2_EV_IRQHandler
+ .word I2C2_ER_IRQHandler
+ .word SPI1_IRQHandler
+ .word SPI2_IRQHandler
+ .word USART1_IRQHandler
+ .word USART2_IRQHandler
+ .word USART3_IRQHandler
+ .word EXTI15_10_IRQHandler
+ .word RTC_Alarm_IRQHandler
+ .word USBWakeUp_IRQHandler
+ .word TIM8_BRK_IRQHandler
+ .word TIM8_UP_IRQHandler
+ .word TIM8_TRG_COM_IRQHandler
+ .word TIM8_CC_IRQHandler
+ .word ADC3_IRQHandler
+ .word FMC_IRQHandler
+ .word LPTIM1_IRQHandler
+ .word TIM5_IRQHandler
+ .word SPI3_IRQHandler
+ .word UART4_IRQHandler
+ .word UART5_IRQHandler
+ .word TIM6_DAC_IRQHandler
+ .word TIM7_DAC_IRQHandler
+ .word DMA2_Channel1_IRQHandler
+ .word DMA2_Channel2_IRQHandler
+ .word DMA2_Channel3_IRQHandler
+ .word DMA2_Channel4_IRQHandler
+ .word DMA2_Channel5_IRQHandler
+ .word ADC4_IRQHandler
+ .word ADC5_IRQHandler
+ .word UCPD1_IRQHandler
+ .word COMP1_2_3_IRQHandler
+ .word COMP4_5_6_IRQHandler
+ .word COMP7_IRQHandler
+ .word HRTIM1_Master_IRQHandler
+ .word HRTIM1_TIMA_IRQHandler
+ .word HRTIM1_TIMB_IRQHandler
+ .word HRTIM1_TIMC_IRQHandler
+ .word HRTIM1_TIMD_IRQHandler
+ .word HRTIM1_TIME_IRQHandler
+ .word HRTIM1_FLT_IRQHandler
+ .word HRTIM1_TIMF_IRQHandler
+ .word CRS_IRQHandler
+ .word SAI1_IRQHandler
+ .word TIM20_BRK_IRQHandler
+ .word TIM20_UP_IRQHandler
+ .word TIM20_TRG_COM_IRQHandler
+ .word TIM20_CC_IRQHandler
+ .word FPU_IRQHandler
+ .word I2C4_EV_IRQHandler
+ .word I2C4_ER_IRQHandler
+ .word SPI4_IRQHandler
+ .word 0
+ .word FDCAN2_IT0_IRQHandler
+ .word FDCAN2_IT1_IRQHandler
+ .word FDCAN3_IT0_IRQHandler
+ .word FDCAN3_IT1_IRQHandler
+ .word RNG_IRQHandler
+ .word LPUART1_IRQHandler
+ .word I2C3_EV_IRQHandler
+ .word I2C3_ER_IRQHandler
+ .word DMAMUX_OVR_IRQHandler
+ .word QUADSPI_IRQHandler
+ .word DMA1_Channel8_IRQHandler
+ .word DMA2_Channel6_IRQHandler
+ .word DMA2_Channel7_IRQHandler
+ .word DMA2_Channel8_IRQHandler
+ .word CORDIC_IRQHandler
+ .word FMAC_IRQHandler
+
+/*******************************************************************************
+*
+* Provide weak aliases for each Exception handler to the Default_Handler.
+* As they are weak aliases, any function with the same name will override
+* this definition.
+*
+*******************************************************************************/
+
+ .weak NMI_Handler
+ .thumb_set NMI_Handler,Default_Handler
+
+ .weak HardFault_Handler
+ .thumb_set HardFault_Handler,Default_Handler
+
+ .weak MemManage_Handler
+ .thumb_set MemManage_Handler,Default_Handler
+
+ .weak BusFault_Handler
+ .thumb_set BusFault_Handler,Default_Handler
+
+ .weak UsageFault_Handler
+ .thumb_set UsageFault_Handler,Default_Handler
+
+ .weak SVC_Handler
+ .thumb_set SVC_Handler,Default_Handler
+
+ .weak DebugMon_Handler
+ .thumb_set DebugMon_Handler,Default_Handler
+
+ .weak PendSV_Handler
+ .thumb_set PendSV_Handler,Default_Handler
+
+ .weak SysTick_Handler
+ .thumb_set SysTick_Handler,Default_Handler
+
+ .weak WWDG_IRQHandler
+ .thumb_set WWDG_IRQHandler,Default_Handler
+
+ .weak PVD_PVM_IRQHandler
+ .thumb_set PVD_PVM_IRQHandler,Default_Handler
+
+ .weak RTC_TAMP_LSECSS_IRQHandler
+ .thumb_set RTC_TAMP_LSECSS_IRQHandler,Default_Handler
+
+ .weak RTC_WKUP_IRQHandler
+ .thumb_set RTC_WKUP_IRQHandler,Default_Handler
+
+ .weak FLASH_IRQHandler
+ .thumb_set FLASH_IRQHandler,Default_Handler
+
+ .weak RCC_IRQHandler
+ .thumb_set RCC_IRQHandler,Default_Handler
+
+ .weak EXTI0_IRQHandler
+ .thumb_set EXTI0_IRQHandler,Default_Handler
+
+ .weak EXTI1_IRQHandler
+ .thumb_set EXTI1_IRQHandler,Default_Handler
+
+ .weak EXTI2_IRQHandler
+ .thumb_set EXTI2_IRQHandler,Default_Handler
+
+ .weak EXTI3_IRQHandler
+ .thumb_set EXTI3_IRQHandler,Default_Handler
+
+ .weak EXTI4_IRQHandler
+ .thumb_set EXTI4_IRQHandler,Default_Handler
+
+ .weak DMA1_Channel1_IRQHandler
+ .thumb_set DMA1_Channel1_IRQHandler,Default_Handler
+
+ .weak DMA1_Channel2_IRQHandler
+ .thumb_set DMA1_Channel2_IRQHandler,Default_Handler
+
+ .weak DMA1_Channel3_IRQHandler
+ .thumb_set DMA1_Channel3_IRQHandler,Default_Handler
+
+ .weak DMA1_Channel4_IRQHandler
+ .thumb_set DMA1_Channel4_IRQHandler,Default_Handler
+
+ .weak DMA1_Channel5_IRQHandler
+ .thumb_set DMA1_Channel5_IRQHandler,Default_Handler
+
+ .weak DMA1_Channel6_IRQHandler
+ .thumb_set DMA1_Channel6_IRQHandler,Default_Handler
+
+ .weak DMA1_Channel7_IRQHandler
+ .thumb_set DMA1_Channel7_IRQHandler,Default_Handler
+
+ .weak ADC1_2_IRQHandler
+ .thumb_set ADC1_2_IRQHandler,Default_Handler
+
+ .weak USB_HP_IRQHandler
+ .thumb_set USB_HP_IRQHandler,Default_Handler
+
+ .weak USB_LP_IRQHandler
+ .thumb_set USB_LP_IRQHandler,Default_Handler
+
+ .weak FDCAN1_IT0_IRQHandler
+ .thumb_set FDCAN1_IT0_IRQHandler,Default_Handler
+
+ .weak FDCAN1_IT1_IRQHandler
+ .thumb_set FDCAN1_IT1_IRQHandler,Default_Handler
+
+ .weak EXTI9_5_IRQHandler
+ .thumb_set EXTI9_5_IRQHandler,Default_Handler
+
+ .weak TIM1_BRK_TIM15_IRQHandler
+ .thumb_set TIM1_BRK_TIM15_IRQHandler,Default_Handler
+
+ .weak TIM1_UP_TIM16_IRQHandler
+ .thumb_set TIM1_UP_TIM16_IRQHandler,Default_Handler
+
+ .weak TIM1_TRG_COM_TIM17_IRQHandler
+ .thumb_set TIM1_TRG_COM_TIM17_IRQHandler,Default_Handler
+
+ .weak TIM1_CC_IRQHandler
+ .thumb_set TIM1_CC_IRQHandler,Default_Handler
+
+ .weak TIM2_IRQHandler
+ .thumb_set TIM2_IRQHandler,Default_Handler
+
+ .weak TIM3_IRQHandler
+ .thumb_set TIM3_IRQHandler,Default_Handler
+
+ .weak TIM4_IRQHandler
+ .thumb_set TIM4_IRQHandler,Default_Handler
+
+ .weak I2C1_EV_IRQHandler
+ .thumb_set I2C1_EV_IRQHandler,Default_Handler
+
+ .weak I2C1_ER_IRQHandler
+ .thumb_set I2C1_ER_IRQHandler,Default_Handler
+
+ .weak I2C2_EV_IRQHandler
+ .thumb_set I2C2_EV_IRQHandler,Default_Handler
+
+ .weak I2C2_ER_IRQHandler
+ .thumb_set I2C2_ER_IRQHandler,Default_Handler
+
+ .weak SPI1_IRQHandler
+ .thumb_set SPI1_IRQHandler,Default_Handler
+
+ .weak SPI2_IRQHandler
+ .thumb_set SPI2_IRQHandler,Default_Handler
+
+ .weak USART1_IRQHandler
+ .thumb_set USART1_IRQHandler,Default_Handler
+
+ .weak USART2_IRQHandler
+ .thumb_set USART2_IRQHandler,Default_Handler
+
+ .weak USART3_IRQHandler
+ .thumb_set USART3_IRQHandler,Default_Handler
+
+ .weak EXTI15_10_IRQHandler
+ .thumb_set EXTI15_10_IRQHandler,Default_Handler
+
+ .weak RTC_Alarm_IRQHandler
+ .thumb_set RTC_Alarm_IRQHandler,Default_Handler
+
+ .weak USBWakeUp_IRQHandler
+ .thumb_set USBWakeUp_IRQHandler,Default_Handler
+
+ .weak TIM8_BRK_IRQHandler
+ .thumb_set TIM8_BRK_IRQHandler,Default_Handler
+
+ .weak TIM8_UP_IRQHandler
+ .thumb_set TIM8_UP_IRQHandler,Default_Handler
+
+ .weak TIM8_TRG_COM_IRQHandler
+ .thumb_set TIM8_TRG_COM_IRQHandler,Default_Handler
+
+ .weak TIM8_CC_IRQHandler
+ .thumb_set TIM8_CC_IRQHandler,Default_Handler
+
+ .weak ADC3_IRQHandler
+ .thumb_set ADC3_IRQHandler,Default_Handler
+
+ .weak FMC_IRQHandler
+ .thumb_set FMC_IRQHandler,Default_Handler
+
+ .weak LPTIM1_IRQHandler
+ .thumb_set LPTIM1_IRQHandler,Default_Handler
+
+ .weak TIM5_IRQHandler
+ .thumb_set TIM5_IRQHandler,Default_Handler
+
+ .weak SPI3_IRQHandler
+ .thumb_set SPI3_IRQHandler,Default_Handler
+
+ .weak UART4_IRQHandler
+ .thumb_set UART4_IRQHandler,Default_Handler
+
+ .weak UART5_IRQHandler
+ .thumb_set UART5_IRQHandler,Default_Handler
+
+ .weak TIM6_DAC_IRQHandler
+ .thumb_set TIM6_DAC_IRQHandler,Default_Handler
+
+ .weak TIM7_DAC_IRQHandler
+ .thumb_set TIM7_DAC_IRQHandler,Default_Handler
+
+ .weak DMA2_Channel1_IRQHandler
+ .thumb_set DMA2_Channel1_IRQHandler,Default_Handler
+
+ .weak DMA2_Channel2_IRQHandler
+ .thumb_set DMA2_Channel2_IRQHandler,Default_Handler
+
+ .weak DMA2_Channel3_IRQHandler
+ .thumb_set DMA2_Channel3_IRQHandler,Default_Handler
+
+ .weak DMA2_Channel4_IRQHandler
+ .thumb_set DMA2_Channel4_IRQHandler,Default_Handler
+
+ .weak DMA2_Channel5_IRQHandler
+ .thumb_set DMA2_Channel5_IRQHandler,Default_Handler
+
+ .weak ADC4_IRQHandler
+ .thumb_set ADC4_IRQHandler,Default_Handler
+
+ .weak ADC5_IRQHandler
+ .thumb_set ADC5_IRQHandler,Default_Handler
+
+ .weak UCPD1_IRQHandler
+ .thumb_set UCPD1_IRQHandler,Default_Handler
+
+ .weak COMP1_2_3_IRQHandler
+ .thumb_set COMP1_2_3_IRQHandler,Default_Handler
+
+ .weak COMP4_5_6_IRQHandler
+ .thumb_set COMP4_5_6_IRQHandler,Default_Handler
+
+ .weak COMP7_IRQHandler
+ .thumb_set COMP7_IRQHandler,Default_Handler
+
+ .weak HRTIM1_Master_IRQHandler
+ .thumb_set HRTIM1_Master_IRQHandler,Default_Handler
+
+ .weak HRTIM1_TIMA_IRQHandler
+ .thumb_set HRTIM1_TIMA_IRQHandler,Default_Handler
+
+ .weak HRTIM1_TIMB_IRQHandler
+ .thumb_set HRTIM1_TIMB_IRQHandler,Default_Handler
+
+ .weak HRTIM1_TIMC_IRQHandler
+ .thumb_set HRTIM1_TIMC_IRQHandler,Default_Handler
+
+ .weak HRTIM1_TIMD_IRQHandler
+ .thumb_set HRTIM1_TIMD_IRQHandler,Default_Handler
+
+ .weak HRTIM1_TIME_IRQHandler
+ .thumb_set HRTIM1_TIME_IRQHandler,Default_Handler
+
+ .weak HRTIM1_FLT_IRQHandler
+ .thumb_set HRTIM1_FLT_IRQHandler,Default_Handler
+
+ .weak HRTIM1_TIMF_IRQHandler
+ .thumb_set HRTIM1_TIMF_IRQHandler,Default_Handler
+
+ .weak CRS_IRQHandler
+ .thumb_set CRS_IRQHandler,Default_Handler
+
+ .weak SAI1_IRQHandler
+ .thumb_set SAI1_IRQHandler,Default_Handler
+
+ .weak TIM20_BRK_IRQHandler
+ .thumb_set TIM20_BRK_IRQHandler,Default_Handler
+
+ .weak TIM20_UP_IRQHandler
+ .thumb_set TIM20_UP_IRQHandler,Default_Handler
+
+ .weak TIM20_TRG_COM_IRQHandler
+ .thumb_set TIM20_TRG_COM_IRQHandler,Default_Handler
+
+ .weak TIM20_CC_IRQHandler
+ .thumb_set TIM20_CC_IRQHandler,Default_Handler
+
+ .weak FPU_IRQHandler
+ .thumb_set FPU_IRQHandler,Default_Handler
+
+ .weak I2C4_EV_IRQHandler
+ .thumb_set I2C4_EV_IRQHandler,Default_Handler
+
+ .weak I2C4_ER_IRQHandler
+ .thumb_set I2C4_ER_IRQHandler,Default_Handler
+
+ .weak SPI4_IRQHandler
+ .thumb_set SPI4_IRQHandler,Default_Handler
+
+ .weak FDCAN2_IT0_IRQHandler
+ .thumb_set FDCAN2_IT0_IRQHandler,Default_Handler
+
+ .weak FDCAN2_IT1_IRQHandler
+ .thumb_set FDCAN2_IT1_IRQHandler,Default_Handler
+
+ .weak FDCAN3_IT0_IRQHandler
+ .thumb_set FDCAN3_IT0_IRQHandler,Default_Handler
+
+ .weak FDCAN3_IT1_IRQHandler
+ .thumb_set FDCAN3_IT1_IRQHandler,Default_Handler
+
+ .weak RNG_IRQHandler
+ .thumb_set RNG_IRQHandler,Default_Handler
+
+ .weak LPUART1_IRQHandler
+ .thumb_set LPUART1_IRQHandler,Default_Handler
+
+ .weak I2C3_EV_IRQHandler
+ .thumb_set I2C3_EV_IRQHandler,Default_Handler
+
+ .weak I2C3_ER_IRQHandler
+ .thumb_set I2C3_ER_IRQHandler,Default_Handler
+
+ .weak DMAMUX_OVR_IRQHandler
+ .thumb_set DMAMUX_OVR_IRQHandler,Default_Handler
+
+ .weak QUADSPI_IRQHandler
+ .thumb_set QUADSPI_IRQHandler,Default_Handler
+
+ .weak DMA1_Channel8_IRQHandler
+ .thumb_set DMA1_Channel8_IRQHandler,Default_Handler
+
+ .weak DMA2_Channel6_IRQHandler
+ .thumb_set DMA2_Channel6_IRQHandler,Default_Handler
+
+ .weak DMA2_Channel7_IRQHandler
+ .thumb_set DMA2_Channel7_IRQHandler,Default_Handler
+
+ .weak DMA2_Channel8_IRQHandler
+ .thumb_set DMA2_Channel8_IRQHandler,Default_Handler
+
+ .weak CORDIC_IRQHandler
+ .thumb_set CORDIC_IRQHandler,Default_Handler
+
+ .weak FMAC_IRQHandler
+ .thumb_set FMAC_IRQHandler,Default_Handler
+
diff --git a/embedded/CANFDMigrate/Debug/01-Blink2.elf b/embedded/CANFDMigrate/Debug/01-Blink2.elf
new file mode 100755
index 0000000..97d7dba
Binary files /dev/null and b/embedded/CANFDMigrate/Debug/01-Blink2.elf differ
diff --git a/embedded/CANFDMigrate/Debug/01-Blink2.list b/embedded/CANFDMigrate/Debug/01-Blink2.list
new file mode 100644
index 0000000..780a1f0
--- /dev/null
+++ b/embedded/CANFDMigrate/Debug/01-Blink2.list
@@ -0,0 +1,27661 @@
+
+01-Blink2.elf: file format elf32-littlearm
+
+Sections:
+Idx Name Size VMA LMA File off Algn
+ 0 .isr_vector 000001d8 08000000 08000000 00001000 2**0
+ CONTENTS, ALLOC, LOAD, READONLY, DATA
+ 1 .text 0000b424 080001e0 080001e0 000011e0 2**4
+ CONTENTS, ALLOC, LOAD, READONLY, CODE
+ 2 .rodata 00000140 0800b604 0800b604 0000c604 2**2
+ CONTENTS, ALLOC, LOAD, READONLY, DATA
+ 3 .ARM.extab 00000000 0800b744 0800b744 0000d1e0 2**0
+ CONTENTS, READONLY
+ 4 .ARM 00000008 0800b744 0800b744 0000c744 2**2
+ CONTENTS, ALLOC, LOAD, READONLY, DATA
+ 5 .preinit_array 00000000 0800b74c 0800b74c 0000d1e0 2**0
+ CONTENTS, ALLOC, LOAD, DATA
+ 6 .init_array 00000004 0800b74c 0800b74c 0000c74c 2**2
+ CONTENTS, ALLOC, LOAD, READONLY, DATA
+ 7 .fini_array 00000004 0800b750 0800b750 0000c750 2**2
+ CONTENTS, ALLOC, LOAD, READONLY, DATA
+ 8 .data 000001e0 20000000 0800b754 0000d000 2**2
+ CONTENTS, ALLOC, LOAD, DATA
+ 9 .bss 00001d8c 200001e0 0800b934 0000d1e0 2**2
+ ALLOC
+ 10 ._user_heap_stack 00000604 20001f6c 0800b934 0000df6c 2**0
+ ALLOC
+ 11 .ARM.attributes 00000030 00000000 00000000 0000d1e0 2**0
+ CONTENTS, READONLY
+ 12 .debug_info 0001aeef 00000000 00000000 0000d210 2**0
+ CONTENTS, READONLY, DEBUGGING, OCTETS
+ 13 .debug_abbrev 00004425 00000000 00000000 000280ff 2**0
+ CONTENTS, READONLY, DEBUGGING, OCTETS
+ 14 .debug_aranges 000014b0 00000000 00000000 0002c528 2**3
+ CONTENTS, READONLY, DEBUGGING, OCTETS
+ 15 .debug_rnglists 00000f8a 00000000 00000000 0002d9d8 2**0
+ CONTENTS, READONLY, DEBUGGING, OCTETS
+ 16 .debug_macro 0002aa63 00000000 00000000 0002e962 2**0
+ CONTENTS, READONLY, DEBUGGING, OCTETS
+ 17 .debug_line 00019e32 00000000 00000000 000593c5 2**0
+ CONTENTS, READONLY, DEBUGGING, OCTETS
+ 18 .debug_str 000fbce4 00000000 00000000 000731f7 2**0
+ CONTENTS, READONLY, DEBUGGING, OCTETS
+ 19 .comment 00000043 00000000 00000000 0016eedb 2**0
+ CONTENTS, READONLY
+ 20 .debug_frame 00005adc 00000000 00000000 0016ef20 2**2
+ CONTENTS, READONLY, DEBUGGING, OCTETS
+ 21 .debug_line_str 00000061 00000000 00000000 001749fc 2**0
+ CONTENTS, READONLY, DEBUGGING, OCTETS
+
+Disassembly of section .text:
+
+080001e0 <__do_global_dtors_aux>:
+ 80001e0: b510 push {r4, lr}
+ 80001e2: 4c05 ldr r4, [pc, #20] @ (80001f8 <__do_global_dtors_aux+0x18>)
+ 80001e4: 7823 ldrb r3, [r4, #0]
+ 80001e6: b933 cbnz r3, 80001f6 <__do_global_dtors_aux+0x16>
+ 80001e8: 4b04 ldr r3, [pc, #16] @ (80001fc <__do_global_dtors_aux+0x1c>)
+ 80001ea: b113 cbz r3, 80001f2 <__do_global_dtors_aux+0x12>
+ 80001ec: 4804 ldr r0, [pc, #16] @ (8000200 <__do_global_dtors_aux+0x20>)
+ 80001ee: f3af 8000 nop.w
+ 80001f2: 2301 movs r3, #1
+ 80001f4: 7023 strb r3, [r4, #0]
+ 80001f6: bd10 pop {r4, pc}
+ 80001f8: 200001e0 .word 0x200001e0
+ 80001fc: 00000000 .word 0x00000000
+ 8000200: 0800b5ec .word 0x0800b5ec
+
+08000204 :
+ 8000204: b508 push {r3, lr}
+ 8000206: 4b03 ldr r3, [pc, #12] @ (8000214 )
+ 8000208: b11b cbz r3, 8000212
+ 800020a: 4903 ldr r1, [pc, #12] @ (8000218 )
+ 800020c: 4803 ldr r0, [pc, #12] @ (800021c )
+ 800020e: f3af 8000 nop.w
+ 8000212: bd08 pop {r3, pc}
+ 8000214: 00000000 .word 0x00000000
+ 8000218: 200001e4 .word 0x200001e4
+ 800021c: 0800b5ec .word 0x0800b5ec
+
+08000220 :
+ 8000220: f001 01ff and.w r1, r1, #255 @ 0xff
+ 8000224: 2a10 cmp r2, #16
+ 8000226: db2b blt.n 8000280
+ 8000228: f010 0f07 tst.w r0, #7
+ 800022c: d008 beq.n 8000240
+ 800022e: f810 3b01 ldrb.w r3, [r0], #1
+ 8000232: 3a01 subs r2, #1
+ 8000234: 428b cmp r3, r1
+ 8000236: d02d beq.n 8000294
+ 8000238: f010 0f07 tst.w r0, #7
+ 800023c: b342 cbz r2, 8000290
+ 800023e: d1f6 bne.n 800022e
+ 8000240: b4f0 push {r4, r5, r6, r7}
+ 8000242: ea41 2101 orr.w r1, r1, r1, lsl #8
+ 8000246: ea41 4101 orr.w r1, r1, r1, lsl #16
+ 800024a: f022 0407 bic.w r4, r2, #7
+ 800024e: f07f 0700 mvns.w r7, #0
+ 8000252: 2300 movs r3, #0
+ 8000254: e8f0 5602 ldrd r5, r6, [r0], #8
+ 8000258: 3c08 subs r4, #8
+ 800025a: ea85 0501 eor.w r5, r5, r1
+ 800025e: ea86 0601 eor.w r6, r6, r1
+ 8000262: fa85 f547 uadd8 r5, r5, r7
+ 8000266: faa3 f587 sel r5, r3, r7
+ 800026a: fa86 f647 uadd8 r6, r6, r7
+ 800026e: faa5 f687 sel r6, r5, r7
+ 8000272: b98e cbnz r6, 8000298
+ 8000274: d1ee bne.n 8000254
+ 8000276: bcf0 pop {r4, r5, r6, r7}
+ 8000278: f001 01ff and.w r1, r1, #255 @ 0xff
+ 800027c: f002 0207 and.w r2, r2, #7
+ 8000280: b132 cbz r2, 8000290
+ 8000282: f810 3b01 ldrb.w r3, [r0], #1
+ 8000286: 3a01 subs r2, #1
+ 8000288: ea83 0301 eor.w r3, r3, r1
+ 800028c: b113 cbz r3, 8000294
+ 800028e: d1f8 bne.n 8000282
+ 8000290: 2000 movs r0, #0
+ 8000292: 4770 bx lr
+ 8000294: 3801 subs r0, #1
+ 8000296: 4770 bx lr
+ 8000298: 2d00 cmp r5, #0
+ 800029a: bf06 itte eq
+ 800029c: 4635 moveq r5, r6
+ 800029e: 3803 subeq r0, #3
+ 80002a0: 3807 subne r0, #7
+ 80002a2: f015 0f01 tst.w r5, #1
+ 80002a6: d107 bne.n 80002b8
+ 80002a8: 3001 adds r0, #1
+ 80002aa: f415 7f80 tst.w r5, #256 @ 0x100
+ 80002ae: bf02 ittt eq
+ 80002b0: 3001 addeq r0, #1
+ 80002b2: f415 3fc0 tsteq.w r5, #98304 @ 0x18000
+ 80002b6: 3001 addeq r0, #1
+ 80002b8: bcf0 pop {r4, r5, r6, r7}
+ 80002ba: 3801 subs r0, #1
+ 80002bc: 4770 bx lr
+ 80002be: bf00 nop
+
+080002c0 <__aeabi_uldivmod>:
+ 80002c0: b953 cbnz r3, 80002d8 <__aeabi_uldivmod+0x18>
+ 80002c2: b94a cbnz r2, 80002d8 <__aeabi_uldivmod+0x18>
+ 80002c4: 2900 cmp r1, #0
+ 80002c6: bf08 it eq
+ 80002c8: 2800 cmpeq r0, #0
+ 80002ca: bf1c itt ne
+ 80002cc: f04f 31ff movne.w r1, #4294967295 @ 0xffffffff
+ 80002d0: f04f 30ff movne.w r0, #4294967295 @ 0xffffffff
+ 80002d4: f000 b988 b.w 80005e8 <__aeabi_idiv0>
+ 80002d8: f1ad 0c08 sub.w ip, sp, #8
+ 80002dc: e96d ce04 strd ip, lr, [sp, #-16]!
+ 80002e0: f000 f806 bl 80002f0 <__udivmoddi4>
+ 80002e4: f8dd e004 ldr.w lr, [sp, #4]
+ 80002e8: e9dd 2302 ldrd r2, r3, [sp, #8]
+ 80002ec: b004 add sp, #16
+ 80002ee: 4770 bx lr
+
+080002f0 <__udivmoddi4>:
+ 80002f0: e92d 47f0 stmdb sp!, {r4, r5, r6, r7, r8, r9, sl, lr}
+ 80002f4: 9d08 ldr r5, [sp, #32]
+ 80002f6: 468e mov lr, r1
+ 80002f8: 4604 mov r4, r0
+ 80002fa: 4688 mov r8, r1
+ 80002fc: 2b00 cmp r3, #0
+ 80002fe: d14a bne.n 8000396 <__udivmoddi4+0xa6>
+ 8000300: 428a cmp r2, r1
+ 8000302: 4617 mov r7, r2
+ 8000304: d962 bls.n 80003cc <__udivmoddi4+0xdc>
+ 8000306: fab2 f682 clz r6, r2
+ 800030a: b14e cbz r6, 8000320 <__udivmoddi4+0x30>
+ 800030c: f1c6 0320 rsb r3, r6, #32
+ 8000310: fa01 f806 lsl.w r8, r1, r6
+ 8000314: fa20 f303 lsr.w r3, r0, r3
+ 8000318: 40b7 lsls r7, r6
+ 800031a: ea43 0808 orr.w r8, r3, r8
+ 800031e: 40b4 lsls r4, r6
+ 8000320: ea4f 4e17 mov.w lr, r7, lsr #16
+ 8000324: fa1f fc87 uxth.w ip, r7
+ 8000328: fbb8 f1fe udiv r1, r8, lr
+ 800032c: 0c23 lsrs r3, r4, #16
+ 800032e: fb0e 8811 mls r8, lr, r1, r8
+ 8000332: ea43 4308 orr.w r3, r3, r8, lsl #16
+ 8000336: fb01 f20c mul.w r2, r1, ip
+ 800033a: 429a cmp r2, r3
+ 800033c: d909 bls.n 8000352 <__udivmoddi4+0x62>
+ 800033e: 18fb adds r3, r7, r3
+ 8000340: f101 30ff add.w r0, r1, #4294967295 @ 0xffffffff
+ 8000344: f080 80ea bcs.w 800051c <__udivmoddi4+0x22c>
+ 8000348: 429a cmp r2, r3
+ 800034a: f240 80e7 bls.w 800051c <__udivmoddi4+0x22c>
+ 800034e: 3902 subs r1, #2
+ 8000350: 443b add r3, r7
+ 8000352: 1a9a subs r2, r3, r2
+ 8000354: b2a3 uxth r3, r4
+ 8000356: fbb2 f0fe udiv r0, r2, lr
+ 800035a: fb0e 2210 mls r2, lr, r0, r2
+ 800035e: ea43 4302 orr.w r3, r3, r2, lsl #16
+ 8000362: fb00 fc0c mul.w ip, r0, ip
+ 8000366: 459c cmp ip, r3
+ 8000368: d909 bls.n 800037e <__udivmoddi4+0x8e>
+ 800036a: 18fb adds r3, r7, r3
+ 800036c: f100 32ff add.w r2, r0, #4294967295 @ 0xffffffff
+ 8000370: f080 80d6 bcs.w 8000520 <__udivmoddi4+0x230>
+ 8000374: 459c cmp ip, r3
+ 8000376: f240 80d3 bls.w 8000520 <__udivmoddi4+0x230>
+ 800037a: 443b add r3, r7
+ 800037c: 3802 subs r0, #2
+ 800037e: ea40 4001 orr.w r0, r0, r1, lsl #16
+ 8000382: eba3 030c sub.w r3, r3, ip
+ 8000386: 2100 movs r1, #0
+ 8000388: b11d cbz r5, 8000392 <__udivmoddi4+0xa2>
+ 800038a: 40f3 lsrs r3, r6
+ 800038c: 2200 movs r2, #0
+ 800038e: e9c5 3200 strd r3, r2, [r5]
+ 8000392: e8bd 87f0 ldmia.w sp!, {r4, r5, r6, r7, r8, r9, sl, pc}
+ 8000396: 428b cmp r3, r1
+ 8000398: d905 bls.n 80003a6 <__udivmoddi4+0xb6>
+ 800039a: b10d cbz r5, 80003a0 <__udivmoddi4+0xb0>
+ 800039c: e9c5 0100 strd r0, r1, [r5]
+ 80003a0: 2100 movs r1, #0
+ 80003a2: 4608 mov r0, r1
+ 80003a4: e7f5 b.n 8000392 <__udivmoddi4+0xa2>
+ 80003a6: fab3 f183 clz r1, r3
+ 80003aa: 2900 cmp r1, #0
+ 80003ac: d146 bne.n 800043c <__udivmoddi4+0x14c>
+ 80003ae: 4573 cmp r3, lr
+ 80003b0: d302 bcc.n 80003b8 <__udivmoddi4+0xc8>
+ 80003b2: 4282 cmp r2, r0
+ 80003b4: f200 8105 bhi.w 80005c2 <__udivmoddi4+0x2d2>
+ 80003b8: 1a84 subs r4, r0, r2
+ 80003ba: eb6e 0203 sbc.w r2, lr, r3
+ 80003be: 2001 movs r0, #1
+ 80003c0: 4690 mov r8, r2
+ 80003c2: 2d00 cmp r5, #0
+ 80003c4: d0e5 beq.n 8000392 <__udivmoddi4+0xa2>
+ 80003c6: e9c5 4800 strd r4, r8, [r5]
+ 80003ca: e7e2 b.n 8000392 <__udivmoddi4+0xa2>
+ 80003cc: 2a00 cmp r2, #0
+ 80003ce: f000 8090 beq.w 80004f2 <__udivmoddi4+0x202>
+ 80003d2: fab2 f682 clz r6, r2
+ 80003d6: 2e00 cmp r6, #0
+ 80003d8: f040 80a4 bne.w 8000524 <__udivmoddi4+0x234>
+ 80003dc: 1a8a subs r2, r1, r2
+ 80003de: 0c03 lsrs r3, r0, #16
+ 80003e0: ea4f 4e17 mov.w lr, r7, lsr #16
+ 80003e4: b280 uxth r0, r0
+ 80003e6: b2bc uxth r4, r7
+ 80003e8: 2101 movs r1, #1
+ 80003ea: fbb2 fcfe udiv ip, r2, lr
+ 80003ee: fb0e 221c mls r2, lr, ip, r2
+ 80003f2: ea43 4302 orr.w r3, r3, r2, lsl #16
+ 80003f6: fb04 f20c mul.w r2, r4, ip
+ 80003fa: 429a cmp r2, r3
+ 80003fc: d907 bls.n 800040e <__udivmoddi4+0x11e>
+ 80003fe: 18fb adds r3, r7, r3
+ 8000400: f10c 38ff add.w r8, ip, #4294967295 @ 0xffffffff
+ 8000404: d202 bcs.n 800040c <__udivmoddi4+0x11c>
+ 8000406: 429a cmp r2, r3
+ 8000408: f200 80e0 bhi.w 80005cc <__udivmoddi4+0x2dc>
+ 800040c: 46c4 mov ip, r8
+ 800040e: 1a9b subs r3, r3, r2
+ 8000410: fbb3 f2fe udiv r2, r3, lr
+ 8000414: fb0e 3312 mls r3, lr, r2, r3
+ 8000418: ea40 4303 orr.w r3, r0, r3, lsl #16
+ 800041c: fb02 f404 mul.w r4, r2, r4
+ 8000420: 429c cmp r4, r3
+ 8000422: d907 bls.n 8000434 <__udivmoddi4+0x144>
+ 8000424: 18fb adds r3, r7, r3
+ 8000426: f102 30ff add.w r0, r2, #4294967295 @ 0xffffffff
+ 800042a: d202 bcs.n 8000432 <__udivmoddi4+0x142>
+ 800042c: 429c cmp r4, r3
+ 800042e: f200 80ca bhi.w 80005c6 <__udivmoddi4+0x2d6>
+ 8000432: 4602 mov r2, r0
+ 8000434: 1b1b subs r3, r3, r4
+ 8000436: ea42 400c orr.w r0, r2, ip, lsl #16
+ 800043a: e7a5 b.n 8000388 <__udivmoddi4+0x98>
+ 800043c: f1c1 0620 rsb r6, r1, #32
+ 8000440: 408b lsls r3, r1
+ 8000442: fa22 f706 lsr.w r7, r2, r6
+ 8000446: 431f orrs r7, r3
+ 8000448: fa0e f401 lsl.w r4, lr, r1
+ 800044c: fa20 f306 lsr.w r3, r0, r6
+ 8000450: fa2e fe06 lsr.w lr, lr, r6
+ 8000454: ea4f 4917 mov.w r9, r7, lsr #16
+ 8000458: 4323 orrs r3, r4
+ 800045a: fa00 f801 lsl.w r8, r0, r1
+ 800045e: fa1f fc87 uxth.w ip, r7
+ 8000462: fbbe f0f9 udiv r0, lr, r9
+ 8000466: 0c1c lsrs r4, r3, #16
+ 8000468: fb09 ee10 mls lr, r9, r0, lr
+ 800046c: ea44 440e orr.w r4, r4, lr, lsl #16
+ 8000470: fb00 fe0c mul.w lr, r0, ip
+ 8000474: 45a6 cmp lr, r4
+ 8000476: fa02 f201 lsl.w r2, r2, r1
+ 800047a: d909 bls.n 8000490 <__udivmoddi4+0x1a0>
+ 800047c: 193c adds r4, r7, r4
+ 800047e: f100 3aff add.w sl, r0, #4294967295 @ 0xffffffff
+ 8000482: f080 809c bcs.w 80005be <__udivmoddi4+0x2ce>
+ 8000486: 45a6 cmp lr, r4
+ 8000488: f240 8099 bls.w 80005be <__udivmoddi4+0x2ce>
+ 800048c: 3802 subs r0, #2
+ 800048e: 443c add r4, r7
+ 8000490: eba4 040e sub.w r4, r4, lr
+ 8000494: fa1f fe83 uxth.w lr, r3
+ 8000498: fbb4 f3f9 udiv r3, r4, r9
+ 800049c: fb09 4413 mls r4, r9, r3, r4
+ 80004a0: ea4e 4404 orr.w r4, lr, r4, lsl #16
+ 80004a4: fb03 fc0c mul.w ip, r3, ip
+ 80004a8: 45a4 cmp ip, r4
+ 80004aa: d908 bls.n 80004be <__udivmoddi4+0x1ce>
+ 80004ac: 193c adds r4, r7, r4
+ 80004ae: f103 3eff add.w lr, r3, #4294967295 @ 0xffffffff
+ 80004b2: f080 8082 bcs.w 80005ba <__udivmoddi4+0x2ca>
+ 80004b6: 45a4 cmp ip, r4
+ 80004b8: d97f bls.n 80005ba <__udivmoddi4+0x2ca>
+ 80004ba: 3b02 subs r3, #2
+ 80004bc: 443c add r4, r7
+ 80004be: ea43 4000 orr.w r0, r3, r0, lsl #16
+ 80004c2: eba4 040c sub.w r4, r4, ip
+ 80004c6: fba0 ec02 umull lr, ip, r0, r2
+ 80004ca: 4564 cmp r4, ip
+ 80004cc: 4673 mov r3, lr
+ 80004ce: 46e1 mov r9, ip
+ 80004d0: d362 bcc.n 8000598 <__udivmoddi4+0x2a8>
+ 80004d2: d05f beq.n 8000594 <__udivmoddi4+0x2a4>
+ 80004d4: b15d cbz r5, 80004ee <__udivmoddi4+0x1fe>
+ 80004d6: ebb8 0203 subs.w r2, r8, r3
+ 80004da: eb64 0409 sbc.w r4, r4, r9
+ 80004de: fa04 f606 lsl.w r6, r4, r6
+ 80004e2: fa22 f301 lsr.w r3, r2, r1
+ 80004e6: 431e orrs r6, r3
+ 80004e8: 40cc lsrs r4, r1
+ 80004ea: e9c5 6400 strd r6, r4, [r5]
+ 80004ee: 2100 movs r1, #0
+ 80004f0: e74f b.n 8000392 <__udivmoddi4+0xa2>
+ 80004f2: fbb1 fcf2 udiv ip, r1, r2
+ 80004f6: 0c01 lsrs r1, r0, #16
+ 80004f8: ea41 410e orr.w r1, r1, lr, lsl #16
+ 80004fc: b280 uxth r0, r0
+ 80004fe: ea40 4201 orr.w r2, r0, r1, lsl #16
+ 8000502: 463b mov r3, r7
+ 8000504: 4638 mov r0, r7
+ 8000506: 463c mov r4, r7
+ 8000508: 46b8 mov r8, r7
+ 800050a: 46be mov lr, r7
+ 800050c: 2620 movs r6, #32
+ 800050e: fbb1 f1f7 udiv r1, r1, r7
+ 8000512: eba2 0208 sub.w r2, r2, r8
+ 8000516: ea41 410c orr.w r1, r1, ip, lsl #16
+ 800051a: e766 b.n 80003ea <__udivmoddi4+0xfa>
+ 800051c: 4601 mov r1, r0
+ 800051e: e718 b.n 8000352 <__udivmoddi4+0x62>
+ 8000520: 4610 mov r0, r2
+ 8000522: e72c b.n 800037e <__udivmoddi4+0x8e>
+ 8000524: f1c6 0220 rsb r2, r6, #32
+ 8000528: fa2e f302 lsr.w r3, lr, r2
+ 800052c: 40b7 lsls r7, r6
+ 800052e: 40b1 lsls r1, r6
+ 8000530: fa20 f202 lsr.w r2, r0, r2
+ 8000534: ea4f 4e17 mov.w lr, r7, lsr #16
+ 8000538: 430a orrs r2, r1
+ 800053a: fbb3 f8fe udiv r8, r3, lr
+ 800053e: b2bc uxth r4, r7
+ 8000540: fb0e 3318 mls r3, lr, r8, r3
+ 8000544: 0c11 lsrs r1, r2, #16
+ 8000546: ea41 4103 orr.w r1, r1, r3, lsl #16
+ 800054a: fb08 f904 mul.w r9, r8, r4
+ 800054e: 40b0 lsls r0, r6
+ 8000550: 4589 cmp r9, r1
+ 8000552: ea4f 4310 mov.w r3, r0, lsr #16
+ 8000556: b280 uxth r0, r0
+ 8000558: d93e bls.n 80005d8 <__udivmoddi4+0x2e8>
+ 800055a: 1879 adds r1, r7, r1
+ 800055c: f108 3cff add.w ip, r8, #4294967295 @ 0xffffffff
+ 8000560: d201 bcs.n 8000566 <__udivmoddi4+0x276>
+ 8000562: 4589 cmp r9, r1
+ 8000564: d81f bhi.n 80005a6 <__udivmoddi4+0x2b6>
+ 8000566: eba1 0109 sub.w r1, r1, r9
+ 800056a: fbb1 f9fe udiv r9, r1, lr
+ 800056e: fb09 f804 mul.w r8, r9, r4
+ 8000572: fb0e 1119 mls r1, lr, r9, r1
+ 8000576: b292 uxth r2, r2
+ 8000578: ea42 4201 orr.w r2, r2, r1, lsl #16
+ 800057c: 4542 cmp r2, r8
+ 800057e: d229 bcs.n 80005d4 <__udivmoddi4+0x2e4>
+ 8000580: 18ba adds r2, r7, r2
+ 8000582: f109 31ff add.w r1, r9, #4294967295 @ 0xffffffff
+ 8000586: d2c4 bcs.n 8000512 <__udivmoddi4+0x222>
+ 8000588: 4542 cmp r2, r8
+ 800058a: d2c2 bcs.n 8000512 <__udivmoddi4+0x222>
+ 800058c: f1a9 0102 sub.w r1, r9, #2
+ 8000590: 443a add r2, r7
+ 8000592: e7be b.n 8000512 <__udivmoddi4+0x222>
+ 8000594: 45f0 cmp r8, lr
+ 8000596: d29d bcs.n 80004d4 <__udivmoddi4+0x1e4>
+ 8000598: ebbe 0302 subs.w r3, lr, r2
+ 800059c: eb6c 0c07 sbc.w ip, ip, r7
+ 80005a0: 3801 subs r0, #1
+ 80005a2: 46e1 mov r9, ip
+ 80005a4: e796 b.n 80004d4 <__udivmoddi4+0x1e4>
+ 80005a6: eba7 0909 sub.w r9, r7, r9
+ 80005aa: 4449 add r1, r9
+ 80005ac: f1a8 0c02 sub.w ip, r8, #2
+ 80005b0: fbb1 f9fe udiv r9, r1, lr
+ 80005b4: fb09 f804 mul.w r8, r9, r4
+ 80005b8: e7db b.n 8000572 <__udivmoddi4+0x282>
+ 80005ba: 4673 mov r3, lr
+ 80005bc: e77f b.n 80004be <__udivmoddi4+0x1ce>
+ 80005be: 4650 mov r0, sl
+ 80005c0: e766 b.n 8000490 <__udivmoddi4+0x1a0>
+ 80005c2: 4608 mov r0, r1
+ 80005c4: e6fd b.n 80003c2 <__udivmoddi4+0xd2>
+ 80005c6: 443b add r3, r7
+ 80005c8: 3a02 subs r2, #2
+ 80005ca: e733 b.n 8000434 <__udivmoddi4+0x144>
+ 80005cc: f1ac 0c02 sub.w ip, ip, #2
+ 80005d0: 443b add r3, r7
+ 80005d2: e71c b.n 800040e <__udivmoddi4+0x11e>
+ 80005d4: 4649 mov r1, r9
+ 80005d6: e79c b.n 8000512 <__udivmoddi4+0x222>
+ 80005d8: eba1 0109 sub.w r1, r1, r9
+ 80005dc: 46c4 mov ip, r8
+ 80005de: fbb1 f9fe udiv r9, r1, lr
+ 80005e2: fb09 f804 mul.w r8, r9, r4
+ 80005e6: e7c4 b.n 8000572 <__udivmoddi4+0x282>
+
+080005e8 <__aeabi_idiv0>:
+ 80005e8: 4770 bx lr
+ 80005ea: bf00 nop
+
+080005ec :
+FDCAN_HandleTypeDef hfdcan2;
+FDCAN_HandleTypeDef hfdcan3;
+
+/* FDCAN2 init function */
+void MX_FDCAN2_Init(void)
+{
+ 80005ec: b580 push {r7, lr}
+ 80005ee: af00 add r7, sp, #0
+ /* USER CODE END FDCAN2_Init 0 */
+
+ /* USER CODE BEGIN FDCAN2_Init 1 */
+
+ /* USER CODE END FDCAN2_Init 1 */
+ hfdcan2.Instance = FDCAN2;
+ 80005f0: 4b1f ldr r3, [pc, #124] @ (8000670 )
+ 80005f2: 4a20 ldr r2, [pc, #128] @ (8000674 )
+ 80005f4: 601a str r2, [r3, #0]
+ hfdcan2.Init.ClockDivider = FDCAN_CLOCK_DIV1;
+ 80005f6: 4b1e ldr r3, [pc, #120] @ (8000670 )
+ 80005f8: 2200 movs r2, #0
+ 80005fa: 605a str r2, [r3, #4]
+ hfdcan2.Init.FrameFormat = FDCAN_FRAME_CLASSIC;
+ 80005fc: 4b1c ldr r3, [pc, #112] @ (8000670 )
+ 80005fe: 2200 movs r2, #0
+ 8000600: 609a str r2, [r3, #8]
+ hfdcan2.Init.Mode = FDCAN_MODE_NORMAL;
+ 8000602: 4b1b ldr r3, [pc, #108] @ (8000670 )
+ 8000604: 2200 movs r2, #0
+ 8000606: 60da str r2, [r3, #12]
+ hfdcan2.Init.AutoRetransmission = ENABLE;
+ 8000608: 4b19 ldr r3, [pc, #100] @ (8000670 )
+ 800060a: 2201 movs r2, #1
+ 800060c: 741a strb r2, [r3, #16]
+ hfdcan2.Init.TransmitPause = DISABLE;
+ 800060e: 4b18 ldr r3, [pc, #96] @ (8000670 )
+ 8000610: 2200 movs r2, #0
+ 8000612: 745a strb r2, [r3, #17]
+ hfdcan2.Init.ProtocolException = ENABLE;
+ 8000614: 4b16 ldr r3, [pc, #88] @ (8000670 )
+ 8000616: 2201 movs r2, #1
+ 8000618: 749a strb r2, [r3, #18]
+ hfdcan2.Init.NominalPrescaler = 1;
+ 800061a: 4b15 ldr r3, [pc, #84] @ (8000670 )
+ 800061c: 2201 movs r2, #1
+ 800061e: 615a str r2, [r3, #20]
+ hfdcan2.Init.NominalSyncJumpWidth = 7;
+ 8000620: 4b13 ldr r3, [pc, #76] @ (8000670 )
+ 8000622: 2207 movs r2, #7
+ 8000624: 619a str r2, [r3, #24]
+ hfdcan2.Init.NominalTimeSeg1 = 40;
+ 8000626: 4b12 ldr r3, [pc, #72] @ (8000670 )
+ 8000628: 2228 movs r2, #40 @ 0x28
+ 800062a: 61da str r2, [r3, #28]
+ hfdcan2.Init.NominalTimeSeg2 = 7;
+ 800062c: 4b10 ldr r3, [pc, #64] @ (8000670 )
+ 800062e: 2207 movs r2, #7
+ 8000630: 621a str r2, [r3, #32]
+ hfdcan2.Init.DataPrescaler = 2;
+ 8000632: 4b0f ldr r3, [pc, #60] @ (8000670 )
+ 8000634: 2202 movs r2, #2
+ 8000636: 625a str r2, [r3, #36] @ 0x24
+ hfdcan2.Init.DataSyncJumpWidth = 5;
+ 8000638: 4b0d ldr r3, [pc, #52] @ (8000670 )
+ 800063a: 2205 movs r2, #5
+ 800063c: 629a str r2, [r3, #40] @ 0x28
+ hfdcan2.Init.DataTimeSeg1 = 18;
+ 800063e: 4b0c ldr r3, [pc, #48] @ (8000670 )
+ 8000640: 2212 movs r2, #18
+ 8000642: 62da str r2, [r3, #44] @ 0x2c
+ hfdcan2.Init.DataTimeSeg2 = 5;
+ 8000644: 4b0a ldr r3, [pc, #40] @ (8000670 )
+ 8000646: 2205 movs r2, #5
+ 8000648: 631a str r2, [r3, #48] @ 0x30
+ hfdcan2.Init.StdFiltersNbr = 0;
+ 800064a: 4b09 ldr r3, [pc, #36] @ (8000670 )
+ 800064c: 2200 movs r2, #0
+ 800064e: 635a str r2, [r3, #52] @ 0x34
+ hfdcan2.Init.ExtFiltersNbr = 0;
+ 8000650: 4b07 ldr r3, [pc, #28] @ (8000670 )
+ 8000652: 2200 movs r2, #0
+ 8000654: 639a str r2, [r3, #56] @ 0x38
+ hfdcan2.Init.TxFifoQueueMode = FDCAN_TX_FIFO_OPERATION;
+ 8000656: 4b06 ldr r3, [pc, #24] @ (8000670 )
+ 8000658: 2200 movs r2, #0
+ 800065a: 63da str r2, [r3, #60] @ 0x3c
+ if (HAL_FDCAN_Init(&hfdcan2) != HAL_OK)
+ 800065c: 4804 ldr r0, [pc, #16] @ (8000670 )
+ 800065e: f000 ff13 bl 8001488