Skip to content

Commit cfed655

Browse files
committed
added example sketch to find linear hall ADC center offsets, plus tweak to BLDCMotor for continuous sensor updating
1 parent daaa0fb commit cfed655

File tree

2 files changed

+64
-0
lines changed

2 files changed

+64
-0
lines changed
Lines changed: 62 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,62 @@
1+
/**
2+
* An example to find the center offsets for both ADC channels used in the LinearHall sensor constructor
3+
* Spin your motor through at least one full revolution to average out all of the variations in magnet strength.
4+
*/
5+
6+
//Change these defines to match the analog input pins that your hall sensors are connected to
7+
#define LINEAR_HALL_CHANNEL_A 39
8+
#define LINEAR_HALL_CHANNEL_B 33
9+
10+
11+
//program variables
12+
int minA, maxA, minB, maxB, centerA, centerB;
13+
unsigned long timestamp;
14+
15+
void setup() {
16+
// monitoring port
17+
Serial.begin(115200);
18+
19+
// initialise magnetic sensor hardware
20+
pinMode(LINEAR_HALL_CHANNEL_A, INPUT);
21+
pinMode(LINEAR_HALL_CHANNEL_B, INPUT);
22+
23+
minA = analogRead(LINEAR_HALL_CHANNEL_A);
24+
maxA = minA;
25+
centerA = (minA + maxA) / 2;
26+
minB = analogRead(LINEAR_HALL_CHANNEL_B);
27+
maxB = minB;
28+
centerB = (minB + maxB) / 2;
29+
30+
Serial.println("Sensor ready");
31+
delay(1000);
32+
timestamp = millis();
33+
}
34+
35+
void loop() {
36+
//read sensors and update variables
37+
int tempA = analogRead(LINEAR_HALL_CHANNEL_A);
38+
if (tempA < minA) minA = tempA;
39+
if (tempA > maxA) maxA = tempA;
40+
centerA = (minA + maxA) / 2;
41+
int tempB = analogRead(LINEAR_HALL_CHANNEL_B);
42+
if (tempB < minB) minB = tempB;
43+
if (tempB > maxB) maxB = tempB;
44+
centerB = (minB + maxB) / 2;
45+
46+
if (millis() > timestamp + 100) {
47+
timestamp = millis();
48+
// display the center counts, and max and min count
49+
Serial.print("A:");
50+
Serial.print(centerA);
51+
Serial.print("\t, B:");
52+
Serial.print(centerB);
53+
Serial.print("\t, min A:");
54+
Serial.print(minA);
55+
Serial.print("\t, max A:");
56+
Serial.print(maxA);
57+
Serial.print("\t, min B:");
58+
Serial.print(minB);
59+
Serial.print("\t, max B:");
60+
Serial.println(maxB);
61+
}
62+
}

src/BLDCMotor.cpp

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -174,6 +174,7 @@ int BLDCMotor::alignSensor() {
174174
for (int i = 0; i <=500; i++ ) {
175175
float angle = _3PI_2 + _2PI * i / 500.0f;
176176
setPhaseVoltage(voltage_sensor_align, 0, angle);
177+
sensor->update();
177178
_delay(2);
178179
}
179180
// take and angle in the middle
@@ -183,6 +184,7 @@ int BLDCMotor::alignSensor() {
183184
for (int i = 500; i >=0; i-- ) {
184185
float angle = _3PI_2 + _2PI * i / 500.0f ;
185186
setPhaseVoltage(voltage_sensor_align, 0, angle);
187+
sensor->update();
186188
_delay(2);
187189
}
188190
sensor->update();

0 commit comments

Comments
 (0)