Skip to content

Commit e30233d

Browse files
committed
auto detect hall sensor configuration, and flip lines accordingly
1 parent ced1129 commit e30233d

File tree

2 files changed

+101
-15
lines changed

2 files changed

+101
-15
lines changed

src/sensors/HallSensor.cpp

Lines changed: 76 additions & 11 deletions
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,5 @@
11
#include "HallSensor.h"
2+
#include "./communication/SimpleFOCDebug.h"
23

34
// seq 1 > 5 > 4 > 6 > 2 > 3 > 1 000 001 010 011 100 101 110 111
45
const int8_t ELECTRIC_SECTORS_120[8] = { -1, 0, 4, 5, 2, 1, 3 , -1 };
@@ -11,13 +12,19 @@ const int8_t ELECTRIC_SECTORS_60[8] = { 0, 5, 1, 2, 5, 4, 2 , 3 };
1112
- hallA, hallB, hallC - HallSensor A, B and C pins
1213
- pp - pole pairs
1314
*/
14-
HallSensor::HallSensor(int _hallA, int _hallB, int _hallC, int _pp, bool _hall_60deg){
15+
HallSensor::HallSensor(int _hallA, int _hallB, int _hallC, int _pp, HallType _hall_type){
1516

1617
// hardware pins
1718
pinA = _hallA;
1819
pinB = _hallB;
1920
pinC = _hallC;
20-
hall_60deg = _hall_60deg;
21+
hall_type = _hall_type;
22+
last_print_type = hall_type;
23+
for (size_t i = 0; i < sizeof(previous_states); i++)
24+
{
25+
previous_states[i] = -1;
26+
}
27+
2128

2229
// hall has 6 segments per electrical revolution
2330
cpr = _pp * 6;
@@ -49,22 +56,50 @@ void HallSensor::handleC() {
4956
*/
5057
void HallSensor::updateState() {
5158
int8_t new_hall_state = C_active + (B_active << 1) + (A_active << 2);
52-
5359
// glitch avoidance #1 - sometimes we get an interrupt but pins haven't changed
54-
if (new_hall_state == hall_state) return;
60+
if (new_hall_state == hall_state_raw) return;
61+
hall_state_raw = new_hall_state;
5562

56-
long new_pulse_timestamp = _micros();
57-
hall_state = new_hall_state;
63+
static const int num_previous_states = sizeof(previous_states);
5864

59-
int8_t new_electric_sector;
60-
if (hall_60deg)
65+
//flip a line maybe
66+
if (hall_type != HallType::UNKNOWN)
6167
{
62-
new_electric_sector = ELECTRIC_SECTORS_60[hall_state];
68+
new_hall_state ^= static_cast<int8_t>(hall_type);
6369
}
64-
else
70+
71+
long new_pulse_timestamp = _micros();
72+
if (hall_type == HallType::UNKNOWN) //Store previous steps for hall config detection
6573
{
66-
new_electric_sector = ELECTRIC_SECTORS_120[hall_state];
74+
for (int i = num_previous_states - 2; i >= 0; i--)
75+
{
76+
previous_states[i+1] = previous_states[i];
77+
}
78+
previous_states[0] = new_hall_state;
79+
//7 and 0 are illegal in 120deg mode, so we're gonna try to see which line hel up during that time and flip it so it doesn't happen
80+
if ((previous_states[1] == 0b111 || previous_states[1] == 0b000) && previous_states[2] != -1)
81+
{
82+
if (previous_states[2] == previous_states[0])
83+
{
84+
//went back, can't do anything
85+
}
86+
else
87+
{
88+
hall_type = static_cast<HallType>((0b111 - previous_states[0] ^ previous_states[2])%8);
89+
previous_states[0] ^= static_cast<int8_t>(hall_type);
90+
}
91+
}
92+
if (abs(electric_rotations) > 2)
93+
{
94+
hall_type = HallType::HALL_120;
95+
}
6796
}
97+
98+
99+
100+
101+
int8_t new_electric_sector;
102+
new_electric_sector = ELECTRIC_SECTORS_120[new_hall_state];
68103
int8_t electric_sector_dif = new_electric_sector - electric_sector;
69104
if (electric_sector_dif > 3) {
70105
//underflow
@@ -124,6 +159,31 @@ void HallSensor::update() {
124159
if (use_interrupt) interrupts();
125160
angle_prev = ((float)((last_electric_rotations * 6 + last_electric_sector) % cpr) / (float)cpr) * _2PI ;
126161
full_rotations = (int32_t)((last_electric_rotations * 6 + last_electric_sector) / cpr);
162+
if (last_print_type != hall_type)
163+
{
164+
last_print_type = hall_type;
165+
switch (hall_type)
166+
{
167+
case HallType::HALL_120 :
168+
SIMPLEFOC_DEBUG("HALL: Found type: HALL_120");
169+
break;
170+
case HallType::HALL_60A :
171+
SIMPLEFOC_DEBUG("HALL: Found type: HALL_60A");
172+
break;
173+
case HallType::HALL_60B :
174+
SIMPLEFOC_DEBUG("HALL: Found type: HALL_60B");
175+
break;
176+
case HallType::HALL_60C :
177+
SIMPLEFOC_DEBUG("HALL: Found type: HALL_60C");
178+
break;
179+
180+
default:
181+
SIMPLEFOC_DEBUG("HALL: Type unknown! Wtf!");
182+
break;
183+
}
184+
185+
}
186+
127187
}
128188

129189

@@ -153,6 +213,11 @@ float HallSensor::getVelocity(){
153213

154214
}
155215

216+
int HallSensor::needsSearch()
217+
{
218+
return hall_type == HallType::UNKNOWN;
219+
}
220+
156221
// HallSensor initialisation of the hardware pins
157222
// and calculation variables
158223
void HallSensor::init(){

src/sensors/HallSensor.h

Lines changed: 25 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -9,6 +9,17 @@
99

1010
class HallSensor: public Sensor{
1111
public:
12+
13+
14+
enum class HallType : uint8_t
15+
{
16+
HALL_120 = 0,
17+
HALL_60C = 0b001,
18+
HALL_60B = 0b010,
19+
HALL_60A = 0b100,
20+
UNKNOWN = 0b111
21+
};
22+
1223
/**
1324
HallSensor class constructor
1425
@param encA HallSensor A pin
@@ -17,7 +28,7 @@ class HallSensor: public Sensor{
1728
@param pp pole pairs (e.g hoverboard motor has 15pp and small gimbals often have 7pp)
1829
@param hall_60deg Indicate if the hall sensors are 60 degrees apart electrically (means that they can all be one or off at the same time). In 60deg mode, B needs to lead, so you may need to swap the connections until you find one that works
1930
*/
20-
HallSensor(int encA, int encB, int encC, int pp, bool hall_60deg = false);
31+
HallSensor(int encA, int encB, int encC, int pp, HallType hall_type = HallType::UNKNOWN);
2132

2233
/** HallSensor initialise pins */
2334
void init();
@@ -46,7 +57,7 @@ class HallSensor: public Sensor{
4657
int pinB; //!< HallSensor hardware pin B
4758
int pinC; //!< HallSensor hardware pin C
4859
bool use_interrupt; //!< True if interrupts have been attached
49-
bool hall_60deg; //!< Hall sensors are 60 degrees apart electrically (means that they can all be one or off at the same time)
60+
HallType hall_type, last_print_type; //!< Connectivity of hall sensor. The type indicates the pin to be swapped. Hall120 has no swapped pin
5061

5162
// HallSensor configuration
5263
Pullup pullup; //!< Configuration parameter internal or external pullups
@@ -60,14 +71,24 @@ class HallSensor: public Sensor{
6071
/** get current angular velocity (rad/s) */
6172
float getVelocity() override;
6273

74+
/**
75+
* returns 0 if it does need search for absolute zero
76+
* 0 - magnetic sensor (& encoder with index which is found)
77+
* 1 - ecoder with index (with index not found yet)
78+
*/
79+
int needsSearch() override;
80+
81+
6382
// whether last step was CW (+1) or CCW (-1).
6483
Direction direction;
6584
Direction old_direction;
6685

6786
void attachSectorCallback(void (*onSectorChange)(int a) = nullptr);
6887

69-
// the current 3bit state of the hall sensors
70-
volatile int8_t hall_state;
88+
//last unique previous states, 0 = recent, used to detect the hall type
89+
volatile uint8_t previous_states[3];
90+
// the current 3bit state of the hall sensors, without any line flipped
91+
volatile int8_t hall_state_raw;
7192
// the current sector of the sensor. Each sector is 60deg electrical
7293
volatile int8_t electric_sector;
7394
// the number of electric rotations

0 commit comments

Comments
 (0)