CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutSign UpSign In
Ardupilot

Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.

GitHub Repository: Ardupilot/ardupilot
Path: blob/master/Tools/Linux_HAL_Essentials/pru/pwmpru/pwmpru1.c
Views: 1800
1
/*
2
* testpru
3
*
4
*/
5
6
#define PRU1
7
#include <stdio.h>
8
#include <stdlib.h>
9
#include <stdarg.h>
10
#include <stdio.h>
11
#include <strings.h>
12
13
#include "linux_types.h"
14
#include "pru_defs.h"
15
#include "prucomm.h"
16
17
18
struct pwm_cmd_l cfg;
19
20
static void pwm_setup(void)
21
{
22
u8 i;
23
24
cfg.enmask = 0;
25
for (i = 0; i < MAX_PWMS; i++)
26
cfg.hilo[i][0] = cfg.hilo[i][1] = PRU_us(200);
27
}
28
29
30
static inline u32 read_PIEP_COUNT(void)
31
{
32
return PIEP_COUNT;
33
34
}
35
36
int main(int argc, char *argv[])
37
{
38
u8 i;
39
u32 cnt, next;
40
u32 msk, setmsk, clrmsk;
41
u32 delta, deltamin, tnext, hi, lo;
42
u32 *nextp;
43
const u32 *hilop;
44
u32 period;
45
u32 enmask; /* enable mask */
46
u32 stmask; /* state mask */
47
static u32 next_hi_lo[MAX_PWMS][3];
48
static struct cxt cxt;
49
/* enable OCP master port */
50
PRUCFG_SYSCFG &= ~SYSCFG_STANDBY_INIT;
51
PRUCFG_SYSCFG = (PRUCFG_SYSCFG &
52
~(SYSCFG_IDLE_MODE_M | SYSCFG_STANDBY_MODE_M)) |
53
SYSCFG_IDLE_MODE_NO | SYSCFG_STANDBY_MODE_NO;
54
55
/* our PRU wins arbitration */
56
PRUCFG_SPP |= SPP_PRU1_PAD_HP_EN;
57
pwm_setup();
58
59
/* configure timer */
60
PIEP_GLOBAL_CFG = GLOBAL_CFG_DEFAULT_INC(1) |
61
GLOBAL_CFG_CMP_INC(1);
62
PIEP_CMP_STATUS = CMD_STATUS_CMP_HIT(1); /* clear the interrupt */
63
PIEP_CMP_CMP1 = 0x0;
64
PIEP_CMP_CFG |= CMP_CFG_CMP_EN(1);
65
PIEP_GLOBAL_CFG |= GLOBAL_CFG_CNT_ENABLE;
66
67
/* initialize */
68
cnt = read_PIEP_COUNT();
69
70
enmask = cfg.enmask;
71
stmask = 0; /* starting all low */
72
73
clrmsk = 0;
74
for (i = 0, msk = 1, nextp = &next_hi_lo[0][0], hilop = &cfg.hilo[0][0];
75
i < MAX_PWMS;
76
i++, msk <<= 1, nextp += 3, hilop += 2) {
77
if ((enmask & msk) == 0) {
78
nextp[1] = PRU_us(100); /* default */
79
nextp[2] = PRU_us(100);
80
continue;
81
}
82
nextp[0] = cnt; /* next */
83
nextp[1] = 200000; /* hi */
84
nextp[2] = 208000; /* lo */
85
PWM_CMD->periodhi[i][0] = 408000;
86
PWM_CMD->periodhi[i][1] = 180000;
87
}
88
PWM_CMD->enmask = 0;
89
clrmsk = enmask;
90
setmsk = 0;
91
/* guaranteed to be immediate */
92
deltamin = 0;
93
next = cnt + deltamin;
94
PWM_CMD->magic = PWM_REPLY_MAGIC;
95
96
while(1) {
97
98
99
//if(PWM_CMD->magic == PWM_CMD_MAGIC)
100
{
101
msk = PWM_CMD->enmask;
102
for(i=0, nextp = &next_hi_lo[0][0]; i<MAX_PWMS;
103
i++, nextp += 3){
104
//Enable
105
if ((PWM_EN_MASK & (msk&(1U<<i))) && (enmask & (msk&(1U<<i))) == 0) {
106
enmask |= (msk&(1U<<i));
107
108
__R30 |= (msk&(1U<<i));
109
nextp[0] = cnt; //since we start high, wait this amount
110
111
// first enable
112
if (enmask == (msk&(1U<<i)))
113
cnt = read_PIEP_COUNT();
114
deltamin = 0;
115
next = cnt;
116
}
117
//Disable
118
if ((PWM_EN_MASK & (msk&(1U<<i))) && ((msk & ~(1U<<i)) == 0)) {
119
enmask &= ~(1U<<i);
120
__R30 &= ~(1U<<i);
121
}
122
123
//get and set pwm_vals
124
if (PWM_EN_MASK & (msk&(1U<<i))) {
125
126
//nextp = &next_hi_lo[i * 3];
127
nextp[1] = PWM_CMD->periodhi[i][1];
128
period = PWM_CMD->periodhi[i][0];
129
nextp[2] =period - nextp[1];
130
131
}
132
PWM_CMD->hilo_read[i][0] = nextp[0];
133
PWM_CMD->hilo_read[i][1] = nextp[1];
134
135
136
}
137
138
// guaranteed to be immediate
139
deltamin = 0;
140
141
PWM_CMD->magic = PWM_REPLY_MAGIC;
142
}
143
PWM_CMD->enmask_read = enmask;
144
/* if nothing is enabled just skip it all */
145
if (enmask == 0)
146
continue;
147
148
setmsk = 0;
149
clrmsk = (u32)-1;
150
deltamin = PRU_ms(100); /* (1U << 31) - 1; */
151
next = cnt + deltamin;
152
153
#define SINGLE_PWM(_i) \
154
do { \
155
if (enmask & (1U << (_i))) { \
156
nextp = &next_hi_lo[(_i)][0]; \
157
tnext = nextp[0]; \
158
hi = nextp[1]; \
159
lo = nextp[2]; \
160
/* avoid signed arithmetic */ \
161
while (((delta = (tnext - cnt)) & (1U << 31)) != 0) { \
162
/* toggle the state */ \
163
if (stmask & (1U << (_i))) { \
164
stmask &= ~(1U << (_i)); \
165
clrmsk &= ~(1U << (_i)); \
166
tnext += lo; \
167
} else { \
168
stmask |= (1U << (_i)); \
169
setmsk |= (1U << (_i)); \
170
tnext += hi; \
171
} \
172
} \
173
if (delta <= deltamin) { \
174
deltamin = delta; \
175
next = tnext; \
176
} \
177
nextp[0] = tnext; \
178
} \
179
} while (0)
180
181
182
183
#if MAX_PWMS > 0 && (PWM_EN_MASK & BIT(0))
184
SINGLE_PWM(0);
185
#endif
186
#if MAX_PWMS > 1 && (PWM_EN_MASK & BIT(1))
187
SINGLE_PWM(1);
188
#endif
189
#if MAX_PWMS > 2 && (PWM_EN_MASK & BIT(2))
190
SINGLE_PWM(2);
191
#endif
192
#if MAX_PWMS > 3 && (PWM_EN_MASK & BIT(3))
193
SINGLE_PWM(3);
194
#endif
195
#if MAX_PWMS > 4 && (PWM_EN_MASK & BIT(4))
196
SINGLE_PWM(4);
197
#endif
198
#if MAX_PWMS > 5 && (PWM_EN_MASK & BIT(5))
199
SINGLE_PWM(5);
200
#endif
201
#if MAX_PWMS > 6 && (PWM_EN_MASK & BIT(6))
202
SINGLE_PWM(6);
203
#endif
204
#if MAX_PWMS > 7 && (PWM_EN_MASK & BIT(7))
205
SINGLE_PWM(7);
206
#endif
207
#if MAX_PWMS > 8 && (PWM_EN_MASK & BIT(8))
208
SINGLE_PWM(8);
209
#endif
210
#if MAX_PWMS > 9 && (PWM_EN_MASK & BIT(9))
211
SINGLE_PWM(9);
212
#endif
213
#if MAX_PWMS > 10 && (PWM_EN_MASK & BIT(10))
214
SINGLE_PWM(10);
215
#endif
216
#if MAX_PWMS > 11 && (PWM_EN_MASK & BIT(11))
217
SINGLE_PWM(11);
218
#endif
219
#if MAX_PWMS > 12 && (PWM_EN_MASK & BIT(12))
220
SINGLE_PWM(12);
221
#endif
222
223
/* results in set bits where there are changes */
224
225
__R30 = (__R30 & (clrmsk & 0xfff)) | (setmsk & 0xfff);
226
227
/* loop while nothing changes */
228
do {
229
cnt = read_PIEP_COUNT();
230
if(PWM_CMD->magic == PWM_CMD_MAGIC){
231
break;
232
}
233
} while (((next - cnt) & (1U << 31)) == 0);
234
}
235
}
236
237