Skip to content

Commit f86d5c4

Browse files
committed
sensor precision fix - refactored API
1 parent fef9782 commit f86d5c4

14 files changed

+81
-62
lines changed

src/common/base_classes/Sensor.cpp

Lines changed: 10 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -3,8 +3,9 @@
33
#include "../time_utils.h"
44

55

6-
float Sensor::getAngle() {
7-
float val = getShaftAngle();
6+
7+
float Sensor::updateSensor() {
8+
float val = getSensorAngle();
89
angle_prev_ts = _micros();
910
float d_angle = val - angle_prev;
1011
// if overflow happened track it as full rotation
@@ -14,7 +15,6 @@ float Sensor::getAngle() {
1415
}
1516

1617

17-
1818
/** get current angular velocity (rad/s)*/
1919
float Sensor::getVelocity() {
2020
// calculate sample time
@@ -30,14 +30,19 @@ float Sensor::getVelocity() {
3030
}
3131

3232

33+
float Sensor::getShaftAngle() {
34+
return angle_prev;
35+
}
36+
37+
3338

34-
float Sensor::getPosition(){
39+
float Sensor::getAngle(){
3540
return (float)full_rotations * _2PI + angle_prev;
3641
}
3742

3843

3944

40-
double Sensor::getPrecisePosition() {
45+
double Sensor::getPreciseAngle() {
4146
return (double)full_rotations * (double)_2PI + (double)angle_prev;
4247
}
4348

src/common/base_classes/Sensor.h

Lines changed: 40 additions & 20 deletions
Original file line numberDiff line numberDiff line change
@@ -32,7 +32,7 @@ enum Pullup{
3232
* method. getAngle() returns a float value, in radians, representing the current shaft angle in the
3333
* range 0 to 2*PI (one full turn).
3434
*
35-
* To function correctly, the sensor class getAngle() method has to be called sufficiently quickly. Normally,
35+
* To function correctly, the sensor class updateSensor() method has to be called sufficiently quickly. Normally,
3636
* the BLDCMotor's loopFOC() function calls it once per iteration, so you must ensure to call loopFOC() quickly
3737
* enough, both for correct motor and sensor operation.
3838
*
@@ -43,17 +43,26 @@ enum Pullup{
4343
*/
4444
class Sensor{
4545
public:
46-
/**
47-
* Get current shaft angle, as a float in radians, in the range 0 to 2PI.
46+
/**
47+
* Get shaft angle in the range 0 to 2PI. This value will be as precise as possible with
48+
* the hardware.
49+
*/
50+
virtual float getShaftAngle();
51+
52+
/**
53+
* Get current position (in rad) including full rotations and shaft angle
54+
* Note that this value has limited precision as the number of rotations increases,
55+
* because the limited precision of float can't capture the large angle of the full
56+
* rotations and the small angle of the shaft angle at the same time.
4857
*/
4958
virtual float getAngle();
59+
5060
/**
51-
* Get current shaft angle, as a float in radians, in the range 0 to 2PI.
52-
* This method is pure virtual and must be implemented in subclasses.
53-
* Calling this method directly does not update the base-class internal fields.
54-
* Use getAngle() when calling from other code.
61+
* On architectures supporting it, this will return a double precision position value,
62+
* which should have improved precision for large position values.
5563
*/
56-
virtual float getShaftAngle()=0;
64+
virtual double getPreciseAngle();
65+
5766
/**
5867
* Get current angular velocity (rad/s)
5968
* Can be overridden in subclasses. Base implementation uses the values
@@ -62,22 +71,23 @@ class Sensor{
6271
virtual float getVelocity();
6372

6473
/**
65-
* Get current position (in rad) including full rotations and shaft angle
66-
* Note that this value has limited precision as the number of rotations increases,
67-
* as the limited precision of float can't capture the large angle of the full rotations
68-
* and the small angle of the shaft angle at the same time.
69-
*/
70-
virtual float getPosition();
71-
72-
/**
73-
* On architectures supporting it, this will return a double precision position value
74+
* Get the number of full rotations
7475
*/
75-
virtual double getPrecisePosition();
76+
virtual int32_t getFullRotations();
7677

7778
/**
78-
* Get the number of full rotations
79+
* Updates the sensor values by reading the hardware sensor.
80+
* Some implementations may work with interrupts, and not need this.
81+
* The base implementation calls getSensorAngle(), and updates internal
82+
* fields for angle, timestamp and full rotations.
83+
* This method must be called frequently enough to guarantee that full
84+
* rotations are not "missed" due to infrequent polling.
85+
* Override in subclasses if alternative behaviours are required for your
86+
* sensor hardware.
87+
*
88+
* Returns the current value of getShaftAngle()
7989
*/
80-
virtual int32_t getFullRotations();
90+
virtual float updateSensor();
8191

8292
/**
8393
* returns 0 if it does need search for absolute zero
@@ -86,6 +96,16 @@ class Sensor{
8696
*/
8797
virtual int needsSearch();
8898
protected:
99+
/**
100+
* Get current shaft angle from the sensor hardware, and
101+
* return it as a float in radians, in the range 0 to 2PI.
102+
*
103+
* This method is pure virtual and must be implemented in subclasses.
104+
* Calling this method directly does not update the base-class internal fields.
105+
* Use updateSensor() when calling from outside code.
106+
*/
107+
virtual float getSensorAngle()=0;
108+
89109
// velocity calculation variables
90110
float angle_prev=0; // result of last call to getAngle, used for full rotations and velocity
91111
long angle_prev_ts=0; // timestamp of last call to getAngle, used for velocity

src/sensors/Encoder.cpp

Lines changed: 6 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -101,23 +101,22 @@ void Encoder::handleIndex() {
101101
/*
102102
Shaft angle calculation
103103
*/
104-
float Encoder::getAngle(){
104+
float Encoder::getSensorAngle(){
105+
return getShaftAngle();
106+
}
107+
float Encoder::getShaftAngle(){
105108
return _2PI * (pulse_counter % (int)cpr);
106109
}
107110

108-
float Encoder::getPosition(){
111+
float Encoder::getAngle(){
109112
return _2PI * (pulse_counter) / ((float)cpr);
110113
}
111-
double Encoder::getPrecisePosition(){
114+
double Encoder::getPreciseAngle(){
112115
return _2PI * (pulse_counter) / ((double)cpr);
113116
}
114117
int32_t Encoder::getFullRotations(){
115118
return pulse_counter / (int)cpr;
116119
}
117-
float Encoder::getShaftAngle(){
118-
return getAngle();
119-
}
120-
121120

122121

123122

src/sensors/Encoder.h

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -60,12 +60,12 @@ class Encoder: public Sensor{
6060

6161
// Abstract functions of the Sensor class implementation
6262
/** get current angle (rad) */
63+
float getSensorAngle() override;
6364
float getShaftAngle() override;
64-
float getAngle() override;
6565
/** get current angular velocity (rad/s) */
6666
float getVelocity() override;
67-
float getPosition() override;
68-
double getPrecisePosition() override;
67+
float getAngle() override;
68+
double getPreciseAngle() override;
6969
int32_t getFullRotations() override;
7070

7171
/**

src/sensors/HallSensor.cpp

Lines changed: 12 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -92,11 +92,19 @@ void HallSensor::attachSectorCallback(void (*_onSectorChange)(int sector)) {
9292
onSectorChange = _onSectorChange;
9393
}
9494

95+
96+
97+
float HallSensor::getSensorAngle() {
98+
return getShaftAngle();
99+
}
100+
101+
102+
95103
/*
96104
Shaft angle calculation
97105
*/
98-
float HallSensor::getAngle() {
99-
return getShaftAngle();
106+
float HallSensor::getShaftAngle() {
107+
return (float)((electric_rotations * 6 + electric_sector) % cpr) * _2PI ;
100108
}
101109

102110
/*
@@ -114,17 +122,12 @@ float HallSensor::getVelocity(){
114122

115123

116124

117-
float HallSensor::getShaftAngle() {
118-
return (float)((electric_rotations * 6 + electric_sector) % cpr) * _2PI ;
119-
}
120-
121-
122-
float HallSensor::getPosition() {
125+
float HallSensor::getAngle() {
123126
return ((float)(electric_rotations * 6 + electric_sector) / (float)cpr) * _2PI ;
124127
}
125128

126129

127-
double HallSensor::getPrecisePosition() {
130+
double HallSensor::getPreciseAngle() {
128131
return ((double)(electric_rotations * 6 + electric_sector) / (double)cpr) * (double)_2PI ;
129132
}
130133

src/sensors/HallSensor.h

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -54,12 +54,12 @@ class HallSensor: public Sensor{
5454

5555
// Abstract functions of the Sensor class implementation
5656
/** get current angle (rad) */
57+
float getSensorAngle() override;
5758
float getShaftAngle() override;
5859
float getAngle() override;
5960
/** get current angular velocity (rad/s) */
6061
float getVelocity() override;
61-
float getPosition() override;
62-
double getPrecisePosition() override;
62+
double getPreciseAngle() override;
6363
int32_t getFullRotations() override;
6464

6565
// whether last step was CW (+1) or CCW (-1).

src/sensors/MagneticSensorAnalog.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -28,7 +28,7 @@ void MagneticSensorAnalog::init(){
2828

2929
// Shaft angle calculation
3030
// angle is in radians [rad]
31-
float MagneticSensorAnalog::getShaftAngle(){
31+
float MagneticSensorAnalog::getSensorAngle(){
3232
// raw data from the sensor
3333
raw_count = getRawCount();
3434
return ( (float) (raw_count) / (float)cpr) * _2PI;

src/sensors/MagneticSensorAnalog.h

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -29,7 +29,7 @@ class MagneticSensorAnalog: public Sensor{
2929

3030
// implementation of abstract functions of the Sensor class
3131
/** get current angle (rad) */
32-
float getShaftAngle() override;
32+
float getSensorAngle() override;
3333
/** raw count (typically in range of 0-1023), useful for debugging resolution issues */
3434
int raw_count;
3535

src/sensors/MagneticSensorI2C.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -68,7 +68,7 @@ void MagneticSensorI2C::init(TwoWire* _wire){
6868

6969
// Shaft angle calculation
7070
// angle is in radians [rad]
71-
float MagneticSensorI2C::getShaftAngle(){
71+
float MagneticSensorI2C::getSensorAngle(){
7272
// (number of full rotations)*2PI + current sensor angle
7373
return ( getRawCount() / (float)cpr) * _2PI ;
7474
}

src/sensors/MagneticSensorI2C.h

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -46,7 +46,7 @@ class MagneticSensorI2C: public Sensor{
4646

4747
// implementation of abstract functions of the Sensor class
4848
/** get current angle (rad) */
49-
float getShaftAngle() override;
49+
float getSensorAngle() override;
5050

5151
/** experimental function to check and fix SDA locked LOW issues */
5252
int checkBus(byte sda_pin = SDA, byte scl_pin = SCL);

0 commit comments

Comments
 (0)