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/rangefinderpru/rangefinder.c
Views: 1800
1
/*
2
This program is free software: you can redistribute it and/or modify
3
it under the terms of the GNU General Public License as published by
4
the Free Software Foundation, either version 3 of the License, or
5
(at your option) any later version.
6
7
This program is distributed in the hope that it will be useful,
8
but WITHOUT ANY WARRANTY; without even the implied warranty of
9
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10
GNU General Public License for more details.
11
12
You should have received a copy of the GNU General Public License
13
along with this program. If not, see <http://www.gnu.org/licenses/>.
14
15
HC-SR04 Ultrasonic Distance Sensor by Mirko Denecke <[email protected]>
16
17
*/
18
19
#include <stdint.h>
20
21
#include "pru_ctrl.h"
22
23
volatile register uint32_t __R30;
24
volatile register uint32_t __R31;
25
26
// Trigger pin
27
#define TRIGGER 1<<14
28
29
// Echo pin
30
#define ECHO 1<<14
31
32
#define TICKS_PER_US 200
33
#define TICKS_PER_MS (1000 * TICKS_PER_US)
34
35
#define TICKS_PER_CM 11600
36
37
#define COUNTER_MIN_DISTANCE (2 * TICKS_PER_CM)
38
#define COUNTER_MAX_DISTANCE (400 * TICKS_PER_CM)
39
40
enum RangeFinder_Status {
41
RangeFinder_NotConnected = 0,
42
RangeFinder_NoData,
43
RangeFinder_OutOfRangeLow,
44
RangeFinder_OutOfRangeHigh,
45
RangeFinder_Good
46
};
47
48
struct range {
49
uint32_t distance;
50
uint32_t status;
51
};
52
53
#pragma LOCATION(ranger, 0x0)
54
volatile struct range ranger;
55
56
main()
57
{
58
// Init data
59
ranger.distance = 0;
60
ranger.status = RangeFinder_NoData;
61
62
// Reset trigger
63
__R30 &= ~(TRIGGER);
64
65
// Wait 100ms
66
__delay_cycles(250 * TICKS_PER_MS);
67
68
// Disable counter
69
PRU0_CTRL.CONTROL_bit.CTR_EN = 0;
70
71
// Clear counter
72
PRU0_CTRL.CYCLE_bit.CYCLECOUNT = 0xFFFFFFFF;
73
74
while(1)
75
{
76
// Enable trigger
77
__R30 |= TRIGGER;
78
79
// Wait 15us
80
__delay_cycles(3000);
81
82
// Reset trigger
83
__R30 &= ~(TRIGGER);
84
85
// Wait for echo
86
while((__R31 & ECHO) == 0)
87
{
88
if(PRU0_CTRL.CYCLE_bit.CYCLECOUNT > (600 * TICKS_PER_CM))
89
{
90
ranger.status = RangeFinder_NoData;
91
}
92
}
93
94
// Start counter
95
PRU0_CTRL.CONTROL_bit.CTR_EN = 1;
96
97
// Count echo length
98
while(__R31 & ECHO)
99
{
100
;
101
}
102
103
// Stop counter
104
PRU0_CTRL.CONTROL_bit.CTR_EN = 0;
105
106
// Check status
107
if(PRU0_CTRL.CYCLE_bit.CYCLECOUNT < COUNTER_MIN_DISTANCE)
108
{
109
ranger.distance = 0;
110
111
// Set status out of range low
112
ranger.status = RangeFinder_OutOfRangeLow;
113
}
114
else if(PRU0_CTRL.CYCLE_bit.CYCLECOUNT > COUNTER_MAX_DISTANCE)
115
{
116
ranger.distance = 0;
117
118
// Set stauts
119
ranger.status = RangeFinder_OutOfRangeHigh;
120
}
121
else
122
{
123
// Calculate distance in cm
124
ranger.distance = PRU0_CTRL.CYCLE_bit.CYCLECOUNT / TICKS_PER_CM;
125
126
// Set status out of range high
127
ranger.status = RangeFinder_Good;
128
}
129
130
// Clear counter
131
PRU0_CTRL.CYCLE_bit.CYCLECOUNT = 0xFFFFFFFF;
132
133
// Wait 20ms
134
__delay_cycles(20 * TICKS_PER_MS);
135
}
136
}
137
138
139