Skip to content

Commit 9f38d0e

Browse files
committedFeb 23, 2024
Cleaned up code, added tons of comments
1 parent 87d2352 commit 9f38d0e

File tree

2 files changed

+140
-156
lines changed

2 files changed

+140
-156
lines changed
 

‎board/main.brd

+5-5
Original file line numberDiff line numberDiff line change
@@ -1029,8 +1029,8 @@ Note, that not all DRC settings must be set by the manufacturer. Several can be
10291029
</element>
10301030
<element name="D2" library="Seeed-Diode" package="SOD-123" value="" x="24" y="6" smashed="yes" rot="R180">
10311031
<attribute name="MPN" value="MMSD4148" x="24" y="6" size="1.778" layer="27" rot="R180" display="off"/>
1032-
<attribute name="NAME" x="24.905" y="4.857" size="0.889" layer="25" ratio="11" rot="R180"/>
10331032
<attribute name="NAME" x="24.889" y="6.635" size="0.381" layer="33" ratio="10" rot="R180"/>
1033+
<attribute name="NAME" x="24.905" y="4.857" size="0.889" layer="25" ratio="11" rot="R180"/>
10341034
<attribute name="VALUE" x="25.905" y="8.032" size="0.889" layer="27" font="vector" ratio="11" rot="R180"/>
10351035
</element>
10361036
<element name="C2" library="SparkFun-Capacitors" package="1206" value="1uF" x="16" y="3" smashed="yes">
@@ -1044,8 +1044,8 @@ Note, that not all DRC settings must be set by the manufacturer. Several can be
10441044
</element>
10451045
<element name="D3" library="Seeed-Diode" package="SOD-123" value="" x="16" y="6" smashed="yes" rot="R180">
10461046
<attribute name="MPN" value="MMSD4148" x="16" y="9" size="1.778" layer="27" rot="R180" display="off"/>
1047-
<attribute name="NAME" x="16.889" y="6.635" size="0.381" layer="33" ratio="10" rot="R180"/>
10481047
<attribute name="NAME" x="16.905" y="4.857" size="0.889" layer="25" ratio="11" rot="R180"/>
1048+
<attribute name="NAME" x="16.889" y="6.635" size="0.381" layer="33" ratio="10" rot="R180"/>
10491049
<attribute name="VALUE" x="17.905" y="8.032" size="0.889" layer="27" font="vector" ratio="11" rot="R180"/>
10501050
</element>
10511051
<element name="C3" library="SparkFun-Capacitors" package="1206" value="1uF" x="9.5" y="3" smashed="yes">
@@ -1059,8 +1059,8 @@ Note, that not all DRC settings must be set by the manufacturer. Several can be
10591059
</element>
10601060
<element name="D4" library="Seeed-Diode" package="SOD-123" value="" x="9" y="6" smashed="yes" rot="R180">
10611061
<attribute name="MPN" value="MMSD4148" x="9" y="9" size="1.778" layer="27" rot="R180" display="off"/>
1062-
<attribute name="NAME" x="9.889" y="6.635" size="0.381" layer="33" ratio="10" rot="R180"/>
10631062
<attribute name="NAME" x="9.905" y="4.857" size="0.889" layer="25" ratio="11" rot="R180"/>
1063+
<attribute name="NAME" x="9.889" y="6.635" size="0.381" layer="33" ratio="10" rot="R180"/>
10641064
<attribute name="VALUE" x="10.905" y="8.032" size="0.889" layer="27" font="vector" ratio="11" rot="R180"/>
10651065
</element>
10661066
<element name="S1" library="SparkFun-Switches" package="TACTILE_SWITCH_PTH_6.0MM" value="" x="88.8" y="27.4" smashed="yes" rot="R180">
@@ -1127,9 +1127,9 @@ Note, that not all DRC settings must be set by the manufacturer. Several can be
11271127
<attribute name="VALUE" x="54" y="21.143" size="0.6096" layer="27" font="vector" ratio="20" rot="R180" align="top-center"/>
11281128
</element>
11291129
<element name="R14" library="SparkFun-Resistors" package="1206" value="22" x="6" y="19" smashed="yes" rot="R90">
1130-
<attribute name="NAME" x="7.8" y="18" size="0.6096" layer="25" font="vector" ratio="20" rot="R90" align="bottom-center"/>
1130+
<attribute name="NAME" x="4.8" y="18" size="0.6096" layer="25" font="vector" ratio="20" rot="R90" align="bottom-center"/>
11311131
<attribute name="PROD_ID" value=" " x="6" y="19" size="1.016" layer="27" rot="R90" display="off"/>
1132-
<attribute name="VALUE" x="7.8" y="20" size="0.6096" layer="27" font="vector" ratio="20" rot="R270" align="top-center"/>
1132+
<attribute name="VALUE" x="4.8" y="20" size="0.6096" layer="27" font="vector" ratio="20" rot="R270" align="top-center"/>
11331133
</element>
11341134
<element name="R15" library="SparkFun-Resistors" package="1206" value="22" x="10" y="19" smashed="yes" rot="R90">
11351135
<attribute name="NAME" x="8.857" y="18" size="0.6096" layer="25" font="vector" ratio="20" rot="R90" align="bottom-center"/>

‎code/easycontroller.c

+135-151
Original file line numberDiff line numberDiff line change
@@ -10,33 +10,20 @@
1010

1111
// Begin user config section ---------------------------
1212

13-
const bool IDENTIFY_HALLS_ON_BOOT = true;
14-
const bool IDENTIFY_HALLS_REVERSE = false;
15-
16-
// uint8_t hallToMotor[8] = {255, 255, 255, 255, 255, 255, 255, 255}; // Default
17-
uint8_t hallToMotor[8] = {255, 0, 2, 1, 4, 5, 3, 255}; // Bike motor
18-
// uint8_t hallToMotor[8] = {255, 1, 5, 0, 3, 2, 4, 255}; // Prop motor
19-
// uint8_t hallToMotor[8] = {255, 2, 0, 1, 4, 3, 5, 255}; // state +1
20-
// uint8_t hallToMotor[8] = {255, 0, 4, 5, 2, 1, 3, 255}; // state -1
21-
const int THROTTLE_LOW = 600;
22-
const int THROTTLE_HIGH = 2650;
23-
24-
const bool CURRENT_CONTROL = true;
25-
const int PHASE_MAX_CURRENT_MA = 60000;
26-
const int BATTERY_MAX_CURRENT_MA = 30000;
27-
const int CURRENT_LOOP_DIV = 200;
13+
const bool IDENTIFY_HALLS_ON_BOOT = true; // If true, controller will initialize the hall table by slowly spinning the motor
14+
const bool IDENTIFY_HALLS_REVERSE = false; // If true, will initialize the hall table to spin the motor backwards
2815

29-
// End user config section -----------------------------
16+
uint8_t hallToMotor[8] = {255, 255, 255, 255, 255, 255, 255, 255}; // Default hall table. Overwrite this with the output of the hall auto-identification
17+
18+
const int THROTTLE_LOW = 600; // ADC value corresponding to minimum throttle, 0-4095
19+
const int THROTTLE_HIGH = 2650; // ADC value corresponding to maximum throttle, 0-4095
3020

31-
#define MEMORY_LEN 10000
32-
int memory_current[MEMORY_LEN];
33-
int memory_current_target[MEMORY_LEN];
34-
int memory_throttle[MEMORY_LEN];
35-
int memory_hall[MEMORY_LEN];
36-
int memory_voltage[MEMORY_LEN];
37-
int memory_duty[MEMORY_LEN];
38-
int memory_pos = 0;
39-
bool memory_writing = false;
21+
const bool CURRENT_CONTROL = true; // Use current control or duty cycle control
22+
const int PHASE_MAX_CURRENT_MA = 6000; // If using current control, the maximum phase current allowed
23+
const int BATTERY_MAX_CURRENT_MA = 3000; // If using current control, the maximum battery current allowed
24+
const int CURRENT_CONTROL_LOOP_GAIN = 200; // Adjusts the speed of the current control loop
25+
26+
// End user config section -----------------------------
4027

4128
const uint LED_PIN = 25;
4229
const uint AH_PIN = 16;
@@ -87,99 +74,115 @@ uint8_t read_throttle();
8774

8875

8976
void on_adc_fifo() {
90-
uint32_t flags = save_and_disable_interrupts(); // Disable interrupts for the time-critical reading ADC section
77+
// This interrupt is where the magic happens. This is fired once the ADC conversions have finished (roughly 6us for 3 conversions)
78+
// This reads the hall sensors, determines the motor state to switch to, and reads the current sensors and throttle to
79+
// determine the desired duty cycle. This takes ~7us to complete.
80+
81+
uint32_t flags = save_and_disable_interrupts(); // Disable interrupts for the time-critical reading ADC section. USB interrupts may interfere
9182

92-
adc_run(false);
93-
gpio_put(FLAG_PIN, 1);
83+
adc_run(false); // Stop the ADC from free running
84+
gpio_put(FLAG_PIN, 1); // For debugging, toggle the flag pin
9485

95-
fifo_level = adc_fifo_get_level();
96-
adc_isense = adc_fifo_get();
86+
fifo_level = adc_fifo_get_level();
87+
adc_isense = adc_fifo_get(); // Read the ADC values into the registers
9788
adc_vsense = adc_fifo_get();
9889
adc_throttle = adc_fifo_get();
9990

100-
restore_interrupts(flags);
91+
restore_interrupts(flags); // Re-enable interrupts
10192

10293
if(fifo_level != 3) {
10394
// The RP2040 is a shitty microcontroller. The ADC is unpredictable, and 1% of times
10495
// will return more or less than the 3 samples it should. If we don't get the expected number, abort
10596
return;
10697
}
10798

108-
hall = get_halls(); // Takes ~200 nanoseconds
109-
motorState = hallToMotor[hall];
99+
hall = get_halls(); // Read the hall sensors
100+
motorState = hallToMotor[hall]; // Convert the current hall reading to the desired motor state
110101

111-
int throttle = ((adc_throttle - THROTTLE_LOW) * 256) / (THROTTLE_HIGH - THROTTLE_LOW);
112-
throttle = MAX(0, MIN(255, throttle));
102+
int throttle = ((adc_throttle - THROTTLE_LOW) * 256) / (THROTTLE_HIGH - THROTTLE_LOW); // Scale the throttle value read from the ADC
103+
throttle = MAX(0, MIN(255, throttle)); // Clamp to 0-255
113104

114-
current_ma = (adc_isense - adc_bias) * CURRENT_SCALING;
115-
current_target_ma = throttle * PHASE_MAX_CURRENT_MA / 256;
116-
int current_target_batt_ma = BATTERY_MAX_CURRENT_MA * DUTY_CYCLE_MAX / duty_cycle;
117-
current_target_ma = MIN(current_target_batt_ma, current_target_ma);
118-
voltage_mv = adc_vsense * VOLTAGE_SCALING;
119-
120-
if (throttle == 0)
121-
{
122-
duty_cycle = 0;
123-
ticks_since_init = 0;
124-
}
125-
ticks_since_init++;
105+
current_ma = (adc_isense - adc_bias) * CURRENT_SCALING; // Since the current sensor is bidirectional, subtract the zero-current value and scale
106+
voltage_mv = adc_vsense * VOLTAGE_SCALING; // Calculate the bus voltage
126107

127108
if(CURRENT_CONTROL) {
128-
duty_cycle += (current_target_ma - current_ma) / CURRENT_LOOP_DIV;
129-
duty_cycle = MAX(0, MIN(DUTY_CYCLE_MAX, duty_cycle));
109+
int user_current_target_ma = throttle * PHASE_MAX_CURRENT_MA / 256; // Calculate the user-demanded phase current
110+
int battery_current_limit_ma = BATTERY_MAX_CURRENT_MA * DUTY_CYCLE_MAX / duty_cycle; // Calculate the maximum phase current allowed while respecting the battery current limit
111+
current_target_ma = MIN(user_current_target_ma, battery_current_limit_ma);
112+
113+
if (throttle == 0)
114+
{
115+
duty_cycle = 0; // If zero throttle, ignore the current control loop and turn all transistors off
116+
ticks_since_init = 0; // Reset the timer since the transistors were turned on
117+
}
118+
else
119+
ticks_since_init++;
120+
121+
duty_cycle += (current_target_ma - current_ma) / CURRENT_CONTROL_LOOP_GAIN; // Perform a simple integral controller to adjust the duty cycle
122+
duty_cycle = MAX(0, MIN(DUTY_CYCLE_MAX, duty_cycle)); // Clamp the duty cycle
130123

131124
bool do_synchronous = ticks_since_init > 16000; // Only enable synchronous switching some time after beginning control loop. This allows control loop to stabilize
132125
writePWM(motorState, (uint)(duty_cycle / 256), do_synchronous);
133126
}
134127
else {
135-
duty_cycle = throttle * 256;
136-
writePWM(motorState, (uint)(duty_cycle / 256), true);
137-
}
128+
duty_cycle = throttle * 256; // Set duty cycle based directly on throttle
129+
bool do_synchronous = true; // Note, if doing synchronous duty-cycle control, the motor will regen if the throttle decreases. This may regen VERY HARD
138130

139-
if(memory_writing)
140-
{
141-
memory_current[memory_pos] = current_ma;
142-
memory_current_target[memory_pos] = current_target_ma;
143-
memory_voltage[memory_pos] = voltage_mv;
144-
memory_throttle[memory_pos] = throttle;
145-
memory_hall[memory_pos] = hall;
146-
memory_voltage[memory_pos] = voltage_mv;
147-
memory_duty[memory_pos] = duty_cycle;
148-
memory_pos++;
149-
150-
if(memory_pos >= MEMORY_LEN)
151-
memory_writing = false;
131+
writePWM(motorState, (uint)(duty_cycle / 256), do_synchronous);
152132
}
153133

154134
gpio_put(FLAG_PIN, 0);
155135
}
156136

157137
void on_pwm_wrap() {
158-
gpio_put(FLAG_PIN, 1);
159-
adc_select_input(0);
160-
adc_run(true);
161-
pwm_clear_irq(A_PWM_SLICE);
162-
while(!adc_fifo_is_empty())
138+
// This interrupt is triggered when the A_PWM slice reaches 0 (the middle of the PWM cycle)
139+
// This allows us to start ADC conversions while the high-side FETs are on, which is required
140+
// to read current, based on where the current sensor is placed in the schematic.
141+
// Takes ~1.3 microseconds
142+
143+
gpio_put(FLAG_PIN, 1); // Toggle the flag pin high for debugging
144+
adc_select_input(0); // Force the ADC to start with input 0
145+
adc_run(true); // Start the ADC
146+
pwm_clear_irq(A_PWM_SLICE); // Clear this interrupt flag
147+
while(!adc_fifo_is_empty()) // Clear out the ADC fifo, in case it still has samples in it
163148
adc_fifo_get();
164149

165150
gpio_put(FLAG_PIN, 0);
166151
}
167152

168153
void writePhases(uint ah, uint bh, uint ch, uint al, uint bl, uint cl)
169154
{
155+
// Set the timer registers for each PWM slice. The lowside values are inverted,
156+
// since the PWM slices were already configured to invert the lowside pin.
157+
// ah: desired high-side duty cycle, range of 0-255
158+
// al: desired low-side duty cycle, range of 0-255
159+
170160
pwm_set_both_levels(A_PWM_SLICE, ah, 255 - al);
171161
pwm_set_both_levels(B_PWM_SLICE, bh, 255 - bl);
172162
pwm_set_both_levels(C_PWM_SLICE, ch, 255 - cl);
173163
}
174164

175165
void writePWM(uint motorState, uint duty, bool synchronous)
176166
{
177-
if(duty == 0 || duty > 255) // If zero throttle, turn all off
167+
// Switch the transistors given a desired electrical state and duty cycle
168+
// motorState: desired electrical position, range of 0-5
169+
// duty: desired duty cycle, range of 0-255
170+
// synchronous: perfom synchronous (low-side and high-side alternating) or non-synchronous switching (high-side only)
171+
172+
if(duty == 0 || duty > 255) // If zero throttle, turn both low-sides and high-sides off
178173
motorState = 255;
179174

175+
// At near 100% duty cycles, the gate driver bootstrap capacitor may become discharged as the high-side gate is repeatedly driven
176+
// high and low without time for the phase voltage to fall to zero and charge the bootstrap capacitor. Thus, if duty cycle is near
177+
// 100%, clamp it to 100%.
178+
if(duty > 245)
179+
duty = 255;
180+
180181
uint complement = 0;
181182
if(synchronous)
182-
complement = 250 - duty;
183+
{
184+
complement = MAX(0, 248 - (int)duty); // Provide switching deadtime by having duty + complement < 255
185+
}
183186

184187
if(motorState == 0) // LOW A, HIGH B
185188
writePhases(0, duty, 0, 255, complement, 0);
@@ -193,7 +196,7 @@ void writePWM(uint motorState, uint duty, bool synchronous)
193196
writePhases(duty, 0, 0, complement, 0, 255);
194197
else if(motorState == 5) // LOW C, HIGH B
195198
writePhases(0, duty, 0, 0, complement, 255);
196-
else // All off
199+
else // All transistors off
197200
writePhases(0, 0, 0, 0, 0, 0);
198201
}
199202

@@ -202,167 +205,148 @@ void init_hardware() {
202205

203206
stdio_init_all();
204207

205-
uart_init(uart0, 9600);
206-
gpio_set_function(0, GPIO_FUNC_UART);
207-
gpio_set_function(1, GPIO_FUNC_UART);
208-
209-
gpio_init(LED_PIN);
208+
gpio_init(LED_PIN); // Set LED and FLAG pin as outputs
210209
gpio_set_dir(LED_PIN, GPIO_OUT);
211210
gpio_init(FLAG_PIN);
212211
gpio_set_dir(FLAG_PIN, GPIO_OUT);
213212

214-
gpio_init(HALL_1_PIN);
213+
gpio_init(HALL_1_PIN); // Set up hall sensor pins
215214
gpio_set_dir(HALL_1_PIN, GPIO_IN);
216215
gpio_init(HALL_2_PIN);
217216
gpio_set_dir(HALL_2_PIN, GPIO_IN);
218217
gpio_init(HALL_3_PIN);
219218
gpio_set_dir(HALL_3_PIN, GPIO_IN);
220219

221-
gpio_set_function(AH_PIN, GPIO_FUNC_PWM);
220+
gpio_set_function(AH_PIN, GPIO_FUNC_PWM); // Set gate control pins as output
222221
gpio_set_function(AL_PIN, GPIO_FUNC_PWM);
223222
gpio_set_function(BH_PIN, GPIO_FUNC_PWM);
224223
gpio_set_function(BL_PIN, GPIO_FUNC_PWM);
225224
gpio_set_function(CH_PIN, GPIO_FUNC_PWM);
226225
gpio_set_function(CL_PIN, GPIO_FUNC_PWM);
227226

228227
adc_init();
229-
adc_gpio_init(ISENSE_PIN); // Make sure GPIO is high-impedance, no pullups etc
230-
adc_gpio_init(VSENSE_PIN); // Make sure GPIO is high-impedance, no pullups etc
231-
adc_gpio_init(THROTTLE_PIN); // Make sure GPIO is high-impedance, no pullups etc
228+
adc_gpio_init(ISENSE_PIN); // Set up ADC pins
229+
adc_gpio_init(VSENSE_PIN);
230+
adc_gpio_init(THROTTLE_PIN);
232231

233232
sleep_ms(100);
234-
for(uint i = 0; i < ADC_BIAS_OVERSAMPLE; i++)
233+
for(uint i = 0; i < ADC_BIAS_OVERSAMPLE; i++) // Find the zero-current ADC reading. Reads the ADC multiple times and takes the average
235234
{
236235
adc_select_input(0);
237236
adc_bias += adc_read();
238237
}
239238
adc_bias /= ADC_BIAS_OVERSAMPLE;
240239

241-
adc_set_round_robin(0b111);
242-
adc_fifo_setup(true, false, 3, false, false);
243-
irq_set_exclusive_handler(ADC_IRQ_FIFO, on_adc_fifo);
240+
adc_set_round_robin(0b111); // Set ADC to read our three ADC pins one after the other (round robin)
241+
adc_fifo_setup(true, false, 3, false, false); // ADC writes into a FIFO buffer, and an interrupt is fired once FIFO reaches 3 samples
242+
irq_set_exclusive_handler(ADC_IRQ_FIFO, on_adc_fifo); // Sets ADC interrupt
244243
irq_set_priority(ADC_IRQ_FIFO, 0);
245244
adc_irq_set_enabled(true);
246245
irq_set_enabled(ADC_IRQ_FIFO, true);
247246

248-
pwm_clear_irq(A_PWM_SLICE);
249-
irq_set_exclusive_handler(PWM_IRQ_WRAP, on_pwm_wrap);
247+
pwm_clear_irq(A_PWM_SLICE); // Clear interrupt flag, just in case
248+
irq_set_exclusive_handler(PWM_IRQ_WRAP, on_pwm_wrap); // Set interrupt to fire when PWM counter wraps
250249
irq_set_priority(PWM_IRQ_WRAP, 0);
251250
irq_set_enabled(PWM_IRQ_WRAP, true);
252251

253-
float pwm_divider = (float)(clock_get_hz(clk_sys)) / (F_PWM * 255 * 2);
252+
float pwm_divider = (float)(clock_get_hz(clk_sys)) / (F_PWM * 255 * 2); // Calculate the desired PWM divisor
254253
pwm_config config = pwm_get_default_config();
255254
pwm_config_set_clkdiv(&config, pwm_divider);
256-
pwm_config_set_wrap(&config, 255 - 1);
257-
pwm_config_set_phase_correct(&config, true);
258-
pwm_config_set_output_polarity(&config, false, true);
255+
pwm_config_set_wrap(&config, 255 - 1); // Set the PWM to wrap at 254. This allows a PWM value of 255 to equal 100% duty cycle
256+
pwm_config_set_phase_correct(&config, true); // Set phase correct (counts up then down). This is allows firing the interrupt in the middle of the PWM cycle
257+
pwm_config_set_output_polarity(&config, false, true); // Invert the lowside PWM such that 0 corresponds to lowside transistors on
259258

260-
writePhases(0, 0, 0, 0, 0, 0);
259+
writePhases(0, 0, 0, 0, 0, 0); // Initialize all the PWMs to be off
261260

262261
pwm_init(A_PWM_SLICE, &config, false);
263262
pwm_init(B_PWM_SLICE, &config, false);
264263
pwm_init(C_PWM_SLICE, &config, false);
265264

266-
pwm_set_mask_enabled(0x07);
265+
pwm_set_mask_enabled(0x07); // Enable our three PWM timers
267266
}
268267

269268
uint get_halls() {
269+
// Read the hall sensors with oversampling. Hall sensor readings can be noisy, which produces commutation "glitches".
270+
// This reads the hall sensors multiple times, then takes the majority reading to reduce noise. Takes ~200 nanoseconds
271+
270272
uint hallCounts[] = {0, 0, 0};
271-
for(uint i = 0; i < HALL_OVERSAMPLE; i++) // Read all the hall pins repeatedly, tally results
273+
for(uint i = 0; i < HALL_OVERSAMPLE; i++) // Read all the hall pins repeatedly, count votes
272274
{
273275
hallCounts[0] += gpio_get(HALL_1_PIN);
274276
hallCounts[1] += gpio_get(HALL_2_PIN);
275277
hallCounts[2] += gpio_get(HALL_3_PIN);
276278
}
277279

278280
uint hall_raw = 0;
281+
for(uint i = 0; i < 3; i++)
282+
if (hallCounts[i] > HALL_OVERSAMPLE / 2) // If more than half the readings are positive,
283+
hall_raw |= 1<<i; // set the i-th bit high
279284

280-
if (hallCounts[0] > HALL_OVERSAMPLE / 2) // If votes >= threshold, call that a 1
281-
hall_raw |= (1<<0); // Store a 1 in the 0th bit
282-
if (hallCounts[1] > HALL_OVERSAMPLE / 2)
283-
hall_raw |= (1<<1); // Store a 1 in the 1st bit
284-
if (hallCounts[2] > HALL_OVERSAMPLE / 2)
285-
hall_raw |= (1<<2); // Store a 1 in the 2nd bit
286-
287-
return hall_raw & 0x7; // Just to make sure we didn't do anything stupid, set the maximum output value to 7
285+
return hall_raw; // Range is 0-7. However, 0 and 7 are invalid hall states
288286
}
289287

290288
void identify_halls()
291289
{
290+
// This is the magic function which sets the hallToMotor commutation table. This allows
291+
// you to plug in the motor and hall wires in any order, and the controller figures out the order.
292+
// This works by PWM-ing to all of the "half states", such as 0.5, by switching rapidly between state 0 and 1.
293+
// This commutates to all half-states and reads the corresponding hall value. Then, since electrical position
294+
// should lead rotor position by 90 degrees, for this hall state, save a motor state 1.5 steps ahead.
295+
292296
sleep_ms(2000);
293297
for(uint i = 0; i < 6; i++)
294298
{
295-
uint8_t nextState = (i + 1) % 6; // Calculate what the next state should be. This is for switching into half-states
296-
printf("Going to %d\n", i);
297-
for(uint j = 0; j < 1000; j++) // For a while, repeatedly switch between states
299+
for(uint j = 0; j < 1000; j++) // Commutate to a half-state long enough to allow the rotor to stop moving
298300
{
299301
sleep_us(500);
300302
writePWM(i, HALL_IDENTIFY_DUTY_CYCLE, false);
301303
sleep_us(500);
302-
writePWM(nextState, HALL_IDENTIFY_DUTY_CYCLE, false);
304+
writePWM((i + 1) % 6, HALL_IDENTIFY_DUTY_CYCLE, false); // PWM to the next half-state
303305
}
306+
304307
if(IDENTIFY_HALLS_REVERSE)
305-
hallToMotor[get_halls()] = (i + 5) % 6;
308+
hallToMotor[get_halls()] = (i + 5) % 6; // If the motor should spin backwards, save a motor state of -1.5 steps
306309
else
307-
hallToMotor[get_halls()] = (i + 2) % 6;
308-
309-
// printf("hall %d step %d\n", get_halls(), i);
310+
hallToMotor[get_halls()] = (i + 2) % 6; // If the motor should spin forwards, save a motor state of +1.5 steps
310311
}
311312

312-
writePWM(0, 0, false); // Turn phases off
313+
writePWM(0, 0, false); // Turn phases off
313314

314-
printf("hallToMotor array:\n");
315-
for(uint8_t i = 0; i < 8; i++) // Print out the array
315+
printf("hallToMotor array:\n"); // Print out the array
316+
for(uint8_t i = 0; i < 8; i++)
316317
printf("%d, ", hallToMotor[i]);
317-
printf("\nIf any values are 255 except the first and last, the auto-identify was not successful.\n");
318+
printf("\nIf any values are 255 except the first and last, auto-identify failed. Otherwise, save this table in code.\n");
319+
}
320+
321+
void commutate_open_loop()
322+
{
323+
// A useful function to debug electrical problems with the board.
324+
// This slowly advances the motor commutation without reading hall sensors. The motor should slowly spin
325+
int state = 0;
326+
while(true)
327+
{
328+
writePWM(state % 6, 25, false);
329+
sleep_ms(50);
330+
state++;
331+
}
318332
}
319333

320334
int main() {
321335
init_hardware();
322336

337+
// commutate_open_loop(); // May be helpful for debugging electrical problems
338+
323339
if(IDENTIFY_HALLS_ON_BOOT)
324340
identify_halls();
325341

326-
// int s = 0;
327-
// while(true)
328-
// {
329-
// writePWM(s % 6, 25, false);
330-
// sleep_ms(50);
331-
// s++;
332-
// }
333-
334342
sleep_ms(1000);
335343

336-
pwm_set_irq_enabled(A_PWM_SLICE, true); // Enables interrupts, starting commutation
344+
pwm_set_irq_enabled(A_PWM_SLICE, true); // Enables interrupts, starting motor commutation
337345

338-
uint ticks = 0;
339346
while (true) {
340-
// if(ticks == 300)
341-
// adc_throttle = 1500;
342-
// // if(ticks == 800)
343-
// // adc_throttle = 3000;
344-
// if(ticks == 1000)
345-
// adc_throttle = 500;
346-
// if(memory_pos == 0 && ticks == 290)
347-
// memory_writing = true;
348-
349-
// if(memory_pos == MEMORY_LEN && !memory_writing) {
350-
// adc_throttle = 500;
351-
// for(int i=0; i<MEMORY_LEN; i++) {
352-
// printf("%6d, %6d, %6d, %6d, %6d, %6d\n", memory_current[i], memory_current_target[i], memory_duty[i], memory_voltage[i], memory_hall[i], memory_throttle[i]);
353-
// sleep_ms(1);
354-
// }
355-
// memory_pos += 100;
356-
// }
357-
358-
char bt_str[100];
359-
sprintf(bt_str, "%6d, %6d, %6d\n", current_ma / 1000, duty_cycle / 1000, voltage_mv / 1000);
360-
uart_puts(uart0, bt_str);
361-
362-
printf("%6d, %6d, %6d, %6d, %2d, %2d, %1d\n", current_ma, current_target_ma, duty_cycle, voltage_mv, hall, motorState, fifo_level);
363-
gpio_put(LED_PIN, !gpio_get(LED_PIN));
347+
printf("%6d, %6d, %6d, %6d, %2d, %2d\n", current_ma, current_target_ma, duty_cycle, voltage_mv, hall, motorState);
348+
gpio_put(LED_PIN, !gpio_get(LED_PIN)); // Toggle the LED
364349
sleep_ms(100);
365-
ticks++;
366350
}
367351

368352
return 0;

0 commit comments

Comments
 (0)
Please sign in to comment.