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/aiopru/RcAioPRUTest.c
Views: 1800
1
// This program is free software: you can redistribute it and/or modify
2
// it under the terms of the GNU General Public License as published by
3
// the Free Software Foundation, either version 3 of the License, or
4
// (at your option) any later version.
5
// This program is distributed in the hope that it will be useful,
6
// but WITHOUT ANY WARRANTY; without even the implied warranty of
7
// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
8
// GNU General Public License for more details.
9
// You should have received a copy of the GNU General Public License
10
// along with this program. If not, see <http://www.gnu.org/licenses/>.
11
12
#include <stdio.h>
13
#include <stdint.h>
14
#include <stdlib.h>
15
#include <string.h>
16
#include <unistd.h>
17
#include <fcntl.h>
18
#include <sys/mman.h>
19
20
//Comment/uncomment the #includes statements depending on your BeagleBone version:
21
//#include "RcAioPRU_POCKET_bin.h"
22
//#include "RcAioPRU_BBBMINI_bin.h"
23
#include "RcAioPRU_BBBLUE_bin.h"
24
25
#define NUM_RING_ENTRIES 300
26
#define RCOUT_PRUSS_RAM_BASE 0x4a302000
27
#define RCOUT_PRUSS_CTRL_BASE 0x4a324000
28
#define RCOUT_PRUSS_IRAM_BASE 0x4a338000
29
#define RCIN_PRUSS_RAM_BASE 0x4a303000
30
31
#define ARRAY_SIZE(_arr) (sizeof(_arr) / sizeof(_arr[0]))
32
33
#define PWM_FREQ 50
34
35
struct ring_buffer {
36
volatile uint16_t ring_head;
37
volatile uint16_t ring_tail;
38
struct {
39
volatile uint32_t s1;
40
volatile uint32_t s0;
41
} buffer[NUM_RING_ENTRIES];
42
};
43
44
struct pwm {
45
volatile uint32_t enable;
46
volatile uint32_t ch1_hi_time;
47
volatile uint32_t ch1_t_time;
48
volatile uint32_t ch2_hi_time;
49
volatile uint32_t ch2_t_time;
50
volatile uint32_t ch3_hi_time;
51
volatile uint32_t ch3_t_time;
52
volatile uint32_t ch4_hi_time;
53
volatile uint32_t ch4_t_time;
54
volatile uint32_t ch5_hi_time;
55
volatile uint32_t ch5_t_time;
56
volatile uint32_t ch6_hi_time;
57
volatile uint32_t ch6_t_time;
58
volatile uint32_t ch7_hi_time;
59
volatile uint32_t ch7_t_time;
60
volatile uint32_t ch8_hi_time;
61
volatile uint32_t ch8_t_time;
62
volatile uint32_t ch9_hi_time;
63
volatile uint32_t ch9_t_time;
64
volatile uint32_t ch10_hi_time;
65
volatile uint32_t ch10_t_time;
66
volatile uint32_t ch11_hi_time;
67
volatile uint32_t ch11_t_time;
68
volatile uint32_t ch12_hi_time;
69
volatile uint32_t ch12_t_time;
70
volatile uint32_t time;
71
volatile uint32_t max_cycle_time;
72
};
73
74
volatile struct ring_buffer *ring_buffer;
75
volatile struct pwm *pwm;
76
77
static const uint32_t TICK_PER_US = 200;
78
static const uint32_t TICK_PER_S = 200000000;
79
static const uint32_t TICK_DURATION_NS = 5;
80
81
int main (void)
82
{
83
unsigned int ret, s0, s1, min_s0 = 0xffffffff, min_s1 = 0xffffffff, max_s0 = 0, max_s1 = 0;
84
uint32_t mem_fd = open("/dev/mem", O_RDWR|O_SYNC|O_CLOEXEC);
85
ring_buffer = (struct ring_buffer*) mmap(0, 0x1000, PROT_READ|PROT_WRITE, MAP_SHARED, mem_fd, RCIN_PRUSS_RAM_BASE);
86
pwm = (struct pwm*) mmap(0, 0x1000, PROT_READ|PROT_WRITE, MAP_SHARED, mem_fd, RCOUT_PRUSS_RAM_BASE);
87
uint32_t *iram = (uint32_t*)mmap(0, 0x2000, PROT_READ|PROT_WRITE, MAP_SHARED, mem_fd, RCOUT_PRUSS_IRAM_BASE);
88
uint32_t *ctrl = (uint32_t*)mmap(0, 0x1000, PROT_READ|PROT_WRITE, MAP_SHARED, mem_fd, RCOUT_PRUSS_CTRL_BASE);
89
uint64_t time_ns;
90
close(mem_fd);
91
92
// This loop checks that the IEP counter is really started. If not, the PRU is reset, the program is reload and PRU restarted
93
// To report pwm->time and pwm->max_cycle_time, the PRU program must be compiled with -DDEBUG option, for example:
94
// pasm -V3 -c RcAioPRU.p RcAioPRU_BBBLUE -DBBBLUE -DDEBUG
95
// This is made for you by 'make debug' followed by 'make test'
96
do {
97
printf("The PRU will be reset\n");
98
// Reset PRU 1
99
*ctrl = 0;
100
//You might uncomment this to identify more easily where the program ends in the IRAM
101
//memset(iram, '\0', sizeof(PRUcode) + 128);
102
// Load firmware
103
memcpy(iram, PRUcode, sizeof(PRUcode));
104
// Start PRU 1
105
*ctrl |= 2;
106
pwm->ch1_t_time = TICK_PER_S / PWM_FREQ;
107
pwm->ch2_t_time = TICK_PER_S / PWM_FREQ;
108
pwm->ch3_t_time = TICK_PER_S / PWM_FREQ;
109
pwm->ch4_t_time = TICK_PER_S / PWM_FREQ;
110
pwm->ch5_t_time = TICK_PER_S / PWM_FREQ;
111
pwm->ch6_t_time = TICK_PER_S / PWM_FREQ;
112
pwm->ch7_t_time = TICK_PER_S / PWM_FREQ;
113
pwm->ch8_t_time = TICK_PER_S / PWM_FREQ;
114
pwm->ch9_t_time = TICK_PER_S / PWM_FREQ;
115
pwm->ch10_t_time = TICK_PER_S / PWM_FREQ;
116
pwm->ch11_t_time = TICK_PER_S / PWM_FREQ;
117
pwm->ch12_t_time = TICK_PER_S / PWM_FREQ;
118
pwm->enable=0xffffffff;
119
printf("IEP counter: 0x%08x\n", pwm->time);
120
} while (pwm->time == 0xffffffff);
121
122
while(1) {
123
for(unsigned int a = 0; a < NUM_RING_ENTRIES; a++) {
124
s0 = ring_buffer->buffer[a].s0;
125
s1 = ring_buffer->buffer[a].s1;
126
if(s0 > max_s0) {max_s0 = s0;}
127
if(s1 > max_s1) {max_s1 = s1;}
128
if(s0 < min_s0) {min_s0 = s0;}
129
if(s1 < min_s1) {min_s1 = s1;}
130
}
131
s0 = ring_buffer->buffer[ring_buffer->ring_tail].s0;
132
s1 = ring_buffer->buffer[ring_buffer->ring_tail].s1;
133
time_ns = ((double)pwm->time) * ((double)TICK_DURATION_NS);
134
printf("max ct: %3u cycles time: %11lluns head: %u tail: %3u s0: %7u s1: %7u s01: %7u jitter_s0: %uns jitter_s1: %uns\n", pwm->max_cycle_time, time_ns, ring_buffer->ring_head, ring_buffer->ring_tail, s0 * TICK_DURATION_NS, s1 * TICK_DURATION_NS, (s0+s1) * TICK_DURATION_NS, ((max_s0-min_s0) * TICK_DURATION_NS), ((max_s1-min_s1) * TICK_DURATION_NS));
135
// uint32_t value = (uint32_t)((rand() % 1001 + 900) * TICK_PER_US);
136
// pwm->ch1_hi_time = value;
137
// pwm->ch2_hi_time = value;
138
//pwm->ch1_hi_time = 1500 * TICK_PER_US;
139
pwm->ch1_hi_time = (uint32_t)((rand() % 1001 + 900) * TICK_PER_US);
140
pwm->ch2_hi_time = 1500 * TICK_PER_US;
141
pwm->ch3_hi_time = (uint32_t)((rand() % 1001 + 900) * TICK_PER_US);
142
pwm->ch4_hi_time = (uint32_t)((rand() % 1001 + 900) * TICK_PER_US);
143
pwm->ch5_hi_time = (uint32_t)((rand() % 1001 + 900) * TICK_PER_US);
144
pwm->ch6_hi_time = (uint32_t)((rand() % 1001 + 900) * TICK_PER_US);
145
pwm->ch7_hi_time = (uint32_t)((rand() % 1001 + 900) * TICK_PER_US);
146
pwm->ch8_hi_time = (uint32_t)((rand() % 1001 + 900) * TICK_PER_US);
147
pwm->ch9_hi_time = (uint32_t)((rand() % 1001 + 900) * TICK_PER_US);
148
pwm->ch10_hi_time = (uint32_t)((rand() % 1001 + 900) * TICK_PER_US);
149
pwm->ch11_hi_time = (uint32_t)((rand() % 1001 + 900) * TICK_PER_US);
150
pwm->ch12_hi_time = (uint32_t)((rand() % 1001 + 900) * TICK_PER_US);
151
usleep(1000000);
152
min_s0 = 0xffffffff;
153
min_s1 = 0xffffffff;
154
max_s0 = 0;
155
max_s1 = 0;
156
}
157
return 0;
158
}
159
160