/
Timers.cpp
73 lines (57 loc) · 1.36 KB
/
Timers.cpp
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
/*
* Timers.c
*
* Created on: 24.09.2017
* Author: anonymous
*/
#include "globals.h"
#include "defines.h"
#include <stdio.h>
#include "freertos/FreeRTOS.h"
#include "freertos/task.h"
#include "freertos/queue.h"
#include "esp_types.h"
#include "soc/timer_group_struct.h"
#include "driver/periph_ctrl.h"
#include "driver/timer.h"
#include "esp32-hal-timer.h"
extern "C" {
portMUX_TYPE muxer1 = portMUX_INITIALIZER_UNLOCKED;
portMUX_TYPE muxer2 = portMUX_INITIALIZER_UNLOCKED;
void IRAM_ATTR timer1ISR() {
portENTER_CRITICAL_ISR(&muxer1);
if (dir_M1 != 0) {
// We generate 1us STEP pulse
digitalWrite(PIN_MOTOR1_STEP, HIGH);
if (dir_M1 > 0)
steps1--;
else
steps1++;
digitalWrite(PIN_MOTOR1_STEP, LOW);
}
portEXIT_CRITICAL_ISR(&muxer1);
}
void IRAM_ATTR timer2ISR() {
portENTER_CRITICAL_ISR(&muxer2);
if (dir_M2 != 0) {
// We generate 1us STEP pulse
digitalWrite(PIN_MOTOR2_STEP, HIGH);
if (dir_M2 > 0)
steps2--;
else
steps2++;
digitalWrite(PIN_MOTOR2_STEP, LOW);
}
portEXIT_CRITICAL_ISR(&muxer2);
}
}
void initTimers() {
timer1 = timerBegin(0, 40, true);
timerAttachInterrupt(timer1, &timer1ISR, true);
timerAlarmWrite(timer1, ZERO_SPEED, true);
timer2 = timerBegin(1, 40, true);
timerAttachInterrupt(timer2, &timer2ISR, true);
timerAlarmWrite(timer2, ZERO_SPEED, true);
timerAlarmEnable(timer1);
timerAlarmEnable(timer2);
}