Skip to content

Commit dffb330

Browse files
committed
Merge branch 'dev' of github.com:askuric/Arduino-FOC into dev
2 parents b065098 + ab8d239 commit dffb330

File tree

3 files changed

+18
-11
lines changed

3 files changed

+18
-11
lines changed

examples/motion_control/velocity_motion_control/magnetic_sensor/velocity_control/velocity_control.ino

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -77,7 +77,7 @@ void setup() {
7777
motor.initFOC();
7878

7979
// add target command T
80-
command.add('T', doTarget, "target voltage");
80+
command.add('T', doTarget, "target velocity");
8181

8282
Serial.println(F("Motor ready."));
8383
Serial.println(F("Set the target velocity using serial terminal:"));
@@ -103,4 +103,4 @@ void loop() {
103103

104104
// user communication
105105
command.run();
106-
}
106+
}

src/common/base_classes/Sensor.cpp

Lines changed: 7 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -2,7 +2,7 @@
22
#include "../foc_utils.h"
33
#include "../time_utils.h"
44

5-
// TODO add an init method to make the startup smoother by initializing internal variables to current values rather than 0
5+
66

77
void Sensor::update() {
88
float val = getSensorAngle();
@@ -18,17 +18,17 @@ void Sensor::update() {
1818
float Sensor::getVelocity() {
1919
// calculate sample time
2020
float Ts = (angle_prev_ts - vel_angle_prev_ts)*1e-6;
21-
// quick fix for strange cases (micros overflow)
22-
if(Ts <= 0) Ts = 1e-3f;
23-
// velocity calculation
24-
float vel = ( (float)(full_rotations - vel_full_rotations)*_2PI + (angle_prev - vel_angle_prev) ) / Ts;
25-
// save variables for future pass
21+
if (Ts<minDeltaT) return velocity; // don't update velocity if deltaT is too small
22+
23+
velocity = ( (float)(full_rotations - vel_full_rotations)*_2PI + (angle_prev - vel_angle_prev) ) / Ts;
2624
vel_angle_prev = angle_prev;
2725
vel_full_rotations = full_rotations;
2826
vel_angle_prev_ts = angle_prev_ts;
29-
return vel;
27+
return velocity;
3028
}
3129

30+
31+
3232
void Sensor::init() {
3333
// initialize all the internal variables of Sensor to ensure a "smooth" startup (without a 'jump' from zero)
3434
getSensorAngle(); // call once

src/common/base_classes/Sensor.h

Lines changed: 9 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -101,6 +101,12 @@ class Sensor{
101101
* 1 - ecoder with index (with index not found yet)
102102
*/
103103
virtual int needsSearch();
104+
105+
/**
106+
* Minimum time between updates to velocity. If time elapsed is lower than this, the velocity is not updated.
107+
*/
108+
float minDeltaT = 0.000100; // default is 100 microseconds, or 10kHz
109+
104110
protected:
105111
/**
106112
* Get current shaft angle from the sensor hardware, and
@@ -120,9 +126,10 @@ class Sensor{
120126
virtual void init();
121127

122128
// velocity calculation variables
123-
float angle_prev=0; // result of last call to getSensorAngle(), used for full rotations and velocity
129+
float velocity=0.0f;
130+
float angle_prev=0.0f; // result of last call to getSensorAngle(), used for full rotations and velocity
124131
long angle_prev_ts=0; // timestamp of last call to getAngle, used for velocity
125-
float vel_angle_prev=0; // angle at last call to getVelocity, used for velocity
132+
float vel_angle_prev=0.0f; // angle at last call to getVelocity, used for velocity
126133
long vel_angle_prev_ts=0; // last velocity calculation timestamp
127134
int32_t full_rotations=0; // full rotation tracking
128135
int32_t vel_full_rotations=0; // previous full rotation value for velocity calculation

0 commit comments

Comments
 (0)