Skip to content

Commit 43e2649

Browse files
committed
Added step/dir interface
1 parent a231a1e commit 43e2649

File tree

11 files changed

+257
-3
lines changed

11 files changed

+257
-3
lines changed
Lines changed: 36 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,36 @@
1+
/**
2+
* A simple example of reading step/dir communication
3+
* - this example uses hadware interrupts
4+
*/
5+
6+
#include <SimpleFOC.h>
7+
8+
// angle
9+
float received_angle = 0;
10+
11+
// StepDirListener( step_pin, dir_pin, counts_per_revolution)
12+
StepDirListener step_dir = StepDirListener(2, 3, 200);
13+
void onStep() { step_dir.handle(); }
14+
15+
void setup() {
16+
17+
Serial.begin(115200);
18+
19+
// init step and dir pins
20+
step_dir.init();
21+
// enable interrupts
22+
step_dir.enableInterrupt(onStep);
23+
// attach the variable to be updated on each step (optional)
24+
// the same can be done asynchronously by caling step_dir.getValue();
25+
step_dir.attach(&received_angle);
26+
27+
Serial.println(F("Step/Dir listenning."));
28+
_delay(1000);
29+
}
30+
31+
void loop() {
32+
Serial.print(received_angle);
33+
Serial.print("\t");
34+
Serial.println(step_dir.getValue());
35+
_delay(500);
36+
}
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,44 @@
1+
/**
2+
* A simple example of reading step/dir communication
3+
* - this example uses software interrupts - this code is intended primarily
4+
* for Arduino UNO/Mega and similar boards with very limited number of interrupt pins
5+
*/
6+
7+
#include <SimpleFOC.h>
8+
// software interrupt library
9+
#include <PciManager.h>
10+
#include <PciListenerImp.h>
11+
12+
13+
// angle
14+
float received_angle = 0;
15+
16+
// StepDirListener( step_pin, dir_pin, counts_per_revolution)
17+
StepDirListener step_dir = StepDirListener(4, 5, 200);
18+
void onStep() { step_dir.handle(); }
19+
20+
// If no available hadware interrupt pins use the software interrupt
21+
PciListenerImp listenStep(step_dir.pin_step, onStep);
22+
23+
void setup() {
24+
25+
Serial.begin(115200);
26+
27+
// init step and dir pins
28+
step_dir.init();
29+
// enable software interrupts
30+
PciManager.registerListener(&listenStep);
31+
// attach the variable to be updated on each step (optional)
32+
// the same can be done asynchronously by caling step_dir.getValue();
33+
step_dir.attach(&received_angle);
34+
35+
Serial.println(F("Step/Dir listenning."));
36+
_delay(1000);
37+
}
38+
39+
void loop() {
40+
Serial.print(received_angle);
41+
Serial.print("\t");
42+
Serial.println(step_dir.getValue());
43+
_delay(500);
44+
}
Lines changed: 98 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,98 @@
1+
/**
2+
* A position control example using step/dir interface to update the motor position
3+
*/
4+
5+
#include <SimpleFOC.h>
6+
7+
// BLDC motor & driver instance
8+
BLDCMotor motor = BLDCMotor(11);
9+
BLDCDriver3PWM driver = BLDCDriver3PWM(10, 5, 6, 8);
10+
11+
// Stepper motor & driver instance
12+
//StepperMotor motor = StepperMotor(50);
13+
//StepperDriver4PWM driver = StepperDriver4PWM(9, 5, 10, 6, 8);
14+
15+
// encoder instance
16+
Encoder encoder = Encoder(2, 3, 500);
17+
// channel A and B callbacks
18+
void doA() { encoder.handleA(); }
19+
void doB() { encoder.handleB(); }
20+
21+
// StepDirListener( step_pin, dir_pin, counts_per_revolution)
22+
StepDirListener step_dir = StepDirListener(A4, A5, 200);
23+
void onStep() { step_dir.handle(); }
24+
25+
void setup() {
26+
27+
// initialize encoder sensor hardware
28+
encoder.init();
29+
encoder.enableInterrupts(doA, doB);
30+
// link the motor to the sensor
31+
motor.linkSensor(&encoder);
32+
33+
// driver config
34+
// power supply voltage [V]
35+
driver.voltage_power_supply = 12;
36+
driver.init();
37+
// link the motor and the driver
38+
motor.linkDriver(&driver);
39+
40+
// aligning voltage [V]
41+
motor.voltage_sensor_align = 3;
42+
// index search velocity [rad/s]
43+
motor.velocity_index_search = 3;
44+
45+
// set motion control loop to be used
46+
motor.controller = MotionControlType::angle;
47+
48+
// contoller configuration
49+
// default parameters in defaults.h
50+
// velocity PI controller parameters
51+
motor.PID_velocity.P = 0.2;
52+
motor.PID_velocity.I = 20;
53+
motor.PID_velocity.D = 0;
54+
// default voltage_power_supply
55+
motor.voltage_limit = 12;
56+
// jerk control using voltage voltage ramp
57+
// default value is 300 volts per sec ~ 0.3V per millisecond
58+
motor.PID_velocity.output_ramp = 1000;
59+
60+
// velocity low pass filtering time constant
61+
motor.LPF_velocity.Tf = 0.01;
62+
63+
// angle P controller
64+
motor.P_angle.P = 10;
65+
// maximal velocity of the position control
66+
motor.velocity_limit = 100;
67+
68+
// use monitoring with serial
69+
Serial.begin(115200);
70+
// comment out if not needed
71+
motor.useMonitoring(Serial);
72+
73+
// initialize motor
74+
motor.init();
75+
// align encoder and start FOC
76+
motor.initFOC();
77+
78+
// init step and dir pins
79+
step_dir.init();
80+
// enable interrupts
81+
step_dir.enableInterrupt(onStep);
82+
// attach the variable to be updated on each step (optional)
83+
// the same can be done asynchronously by caling motor.move(step_dir.getValue());
84+
step_dir.attach(&motor.target);
85+
86+
Serial.println(F("Motor ready."));
87+
Serial.println(F("Listening to step/dir commands!"));
88+
_delay(1000);
89+
}
90+
91+
void loop() {
92+
93+
// main FOC algorithm function
94+
motor.loopFOC();
95+
96+
// Motion control function
97+
motor.move();
98+
}

keywords.txt

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -19,6 +19,7 @@ LowPassFilter KEYWORD1
1919
InlineCurrentSense KEYWORD1
2020
CurrentSense KEYWORD1
2121
Commander KEYWORD1
22+
StepDirListener KEYWORD1
2223

2324

2425
initFOC KEYWORD2
@@ -83,6 +84,11 @@ driverAlign KEYWORD2
8384
driverSync KEYWORD2
8485
add KEYWORD2
8586
run KEYWORD2
87+
attach KEYWORD2
88+
enableInterrupt KEYWORD2
89+
getValue KEYWORD2
90+
handle KEYWORD2
91+
8692

8793

8894
current KEYWORD2

src/SimpleFOC.h

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -109,5 +109,6 @@ void loop() {
109109
#include "drivers/StepperDriver2PWM.h"
110110
#include "current_sense/InlineCurrentSense.h"
111111
#include "communication/Commander.h"
112+
#include "communication/StepDirListener.h"
112113

113114
#endif

src/communication/StepDirListener.cpp

Lines changed: 40 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,40 @@
1+
#include "StepDirListener.h"
2+
3+
StepDirListener::StepDirListener(int _pinStep, int _pinDir, float _step_per_rotation){
4+
5+
pin_step = _pinStep;
6+
pin_dir = _pinDir;
7+
8+
step_per_rotation = _step_per_rotation;
9+
10+
}
11+
12+
void StepDirListener::init(){
13+
pinMode(pin_dir, INPUT);
14+
pinMode(pin_step, INPUT_PULLUP);
15+
count = 0;
16+
}
17+
18+
void StepDirListener::enableInterrupt(void (*doA)()){
19+
attachInterrupt(digitalPinToInterrupt(pin_step), doA, CHANGE);
20+
}
21+
22+
void StepDirListener::attach(float* variable){
23+
attached_variable = variable;
24+
}
25+
26+
void StepDirListener::handle(){
27+
bool step = digitalRead(pin_step);
28+
if(step && step != step_active){
29+
if(digitalRead(pin_dir))
30+
count++;
31+
else
32+
count--;
33+
}
34+
step_active = step;
35+
if(attached_variable) *attached_variable = getValue();
36+
}
37+
38+
float StepDirListener::getValue(){
39+
return (float) count / step_per_rotation * _2PI;
40+
}

src/communication/StepDirListener.h

Lines changed: 29 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,29 @@
1+
#ifndef STEPDIR_H
2+
#define STEPDIR_H
3+
4+
#include "Arduino.h"
5+
#include "../common/foc_utils.h"
6+
7+
class StepDirListener
8+
{
9+
public:
10+
StepDirListener(int pinStep, int pinDir, float step_per_rotation);
11+
void enableInterrupt(void (*doA)());
12+
void init();
13+
void handle();
14+
15+
float getValue();
16+
17+
void attach(float* variable);
18+
19+
int pin_step;
20+
int pin_dir;
21+
long count;
22+
23+
private:
24+
float* attached_variable = nullptr;
25+
long step_per_rotation;
26+
bool step_active = 0;
27+
};
28+
29+
#endif

0 commit comments

Comments
 (0)