add DFU button. update defines for v3
This commit is contained in:
@@ -58,14 +58,11 @@ MagneticSensorMT6835 sensor = MagneticSensorMT6835(ENC_CS, myMT6835SPISettings);
|
|||||||
STM32HWEncoder enc = STM32HWEncoder(ENC_PPR, ENC_A, ENC_B, ENC_Z);
|
STM32HWEncoder enc = STM32HWEncoder(ENC_PPR, ENC_A, ENC_B, ENC_Z);
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* The current sense amps have a gain of 90mA/V -> over 1.5A this is 135mA so we need gain of 24 to get full-scale.
|
* TODO: Change the current sense code to reflect the new inline current sense amplifier choice with sense resistor.
|
||||||
* Actually we are limited to powers of 2 for gain. So it should be 16. This gives sensitivity of 1440mV/A.
|
*/
|
||||||
* */
|
// InlineCurrentSenseSync currentsense = InlineCurrentSenseSync(90, ISENSE_U, ISENSE_V, ISENSE_W);
|
||||||
InlineCurrentSenseSync currentsense = InlineCurrentSenseSync(90, ISENSE_U, ISENSE_V, ISENSE_W);
|
|
||||||
|
|
||||||
StepperDriver4PWM driver = StepperDriver4PWM(MOT_A1, MOT_A2, MOT_B1, MOT_B2);
|
StepperDriver4PWM driver = StepperDriver4PWM(MOT_A1, MOT_A2, MOT_B1, MOT_B2);
|
||||||
// StepperDriver4PWM driver = StepperDriver4PWM(PA0, PA9, PA1, PA10, PB12);
|
|
||||||
// StepperDriver4PWM driver = StepperDriver4PWM(MOT_A1, MOT_A2, MOT_B1, MOT_B2);
|
|
||||||
// StepperMotor motor = StepperMotor(POLEPAIRS, RPHASE, MOTORKV, 0.0045);
|
// StepperMotor motor = StepperMotor(POLEPAIRS, RPHASE, MOTORKV, 0.0045);
|
||||||
StepperMotor motor = StepperMotor(POLEPAIRS);
|
StepperMotor motor = StepperMotor(POLEPAIRS);
|
||||||
Commander commander = Commander(SERIALPORT);
|
Commander commander = Commander(SERIALPORT);
|
||||||
@@ -74,17 +71,26 @@ uint16_t counter = 0;
|
|||||||
extern volatile uint16_t adc1Result[3];
|
extern volatile uint16_t adc1Result[3];
|
||||||
extern volatile uint16_t adc2Result[2];
|
extern volatile uint16_t adc2Result[2];
|
||||||
|
|
||||||
|
DQCurrent_s foc_currents;
|
||||||
|
float electrical_angle;
|
||||||
|
PhaseCurrent_s phase_currents;
|
||||||
|
|
||||||
// Prototypes
|
// Prototypes
|
||||||
uint8_t configureFOC(void);
|
uint8_t configureFOC(void);
|
||||||
uint8_t configureCAN(void);
|
uint8_t configureCAN(void);
|
||||||
uint8_t calibrateEncoder(void);
|
uint8_t calibrateEncoder(void);
|
||||||
|
|
||||||
|
void userButton(void);
|
||||||
|
|
||||||
void setup()
|
void setup()
|
||||||
{
|
{
|
||||||
pinMode(LED_GOOD, OUTPUT);
|
pinMode(LED_GOOD, OUTPUT);
|
||||||
pinMode(LED_FAULT, OUTPUT);
|
pinMode(LED_FAULT, OUTPUT);
|
||||||
pinMode(CAL_EN, OUTPUT);
|
pinMode(CAL_EN, OUTPUT);
|
||||||
pinMode(MOT_EN, OUTPUT);
|
pinMode(MOT_EN, OUTPUT);
|
||||||
|
pinMode(USER_BUTTON, INPUT);
|
||||||
|
|
||||||
|
attachInterrupt(USER_BUTTON, userButton, RISING);
|
||||||
|
|
||||||
SERIALPORT.begin(115200);
|
SERIALPORT.begin(115200);
|
||||||
|
|
||||||
@@ -148,10 +154,6 @@ void setup()
|
|||||||
// }
|
// }
|
||||||
}
|
}
|
||||||
|
|
||||||
DQCurrent_s foc_currents;
|
|
||||||
float electrical_angle;
|
|
||||||
PhaseCurrent_s phase_currents;
|
|
||||||
|
|
||||||
void loop()
|
void loop()
|
||||||
{
|
{
|
||||||
motor.loopFOC();
|
motor.loopFOC();
|
||||||
@@ -159,8 +161,8 @@ void loop()
|
|||||||
commander.run();
|
commander.run();
|
||||||
|
|
||||||
electrical_angle = motor.electricalAngle();
|
electrical_angle = motor.electricalAngle();
|
||||||
phase_currents = currentsense.getPhaseCurrents();
|
// phase_currents = currentsense.getPhaseCurrents();
|
||||||
foc_currents = currentsense.getFOCCurrents(electrical_angle);
|
// foc_currents = currentsense.getFOCCurrents(electrical_angle);
|
||||||
|
|
||||||
if(counter == 0xFFF){
|
if(counter == 0xFFF){
|
||||||
digitalToggle(LED_GOOD);
|
digitalToggle(LED_GOOD);
|
||||||
@@ -254,10 +256,10 @@ uint8_t configureFOC(void)
|
|||||||
motor.linkSensor(&sensor);
|
motor.linkSensor(&sensor);
|
||||||
motor.linkDriver(&driver);
|
motor.linkDriver(&driver);
|
||||||
|
|
||||||
currentsense.linkDriver(&driver);
|
// currentsense.linkDriver(&driver);
|
||||||
int ret = currentsense.init();
|
// int ret = currentsense.init();
|
||||||
SERIALPORT.printf("Current Sense init result: %i\n", ret);
|
// SERIALPORT.printf("Current Sense init result: %i\n", ret);
|
||||||
motor.linkCurrentSense(¤tsense);
|
// motor.linkCurrentSense(¤tsense);
|
||||||
|
|
||||||
motor.target = 10;
|
motor.target = 10;
|
||||||
|
|
||||||
@@ -320,3 +322,9 @@ uint8_t calibrateEncoder(void)
|
|||||||
|
|
||||||
return sensor.getCalibrationStatus();
|
return sensor.getCalibrationStatus();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void userButton(void)
|
||||||
|
{
|
||||||
|
if(USB->DADDR != 0)
|
||||||
|
jump_to_bootloader();
|
||||||
|
}
|
||||||
@@ -38,6 +38,7 @@ build_flags =
|
|||||||
-D SN65HVD23x
|
-D SN65HVD23x
|
||||||
-D ARDUINO_GENERIC_G431CBUX
|
-D ARDUINO_GENERIC_G431CBUX
|
||||||
-D SIMPLEFOC_STM32_CUSTOMCURRENTSENSE
|
-D SIMPLEFOC_STM32_CUSTOMCURRENTSENSE
|
||||||
|
-D LEMONPEPPER
|
||||||
; -D PCB_REV1 ; or PCB_REV2
|
; -D PCB_REV1 ; or PCB_REV2
|
||||||
; -D HAS_MONITOR
|
; -D HAS_MONITOR
|
||||||
|
|
||||||
|
|||||||
Reference in New Issue
Block a user