7 changed files with 398 additions and 0 deletions
Binary file not shown.
@ -0,0 +1,84 @@
@@ -0,0 +1,84 @@
|
||||
/****************************************************************************/ |
||||
/* AM335x_PRU.cmd */ |
||||
/* Copyright (c) 2014 Texas Instruments Incorporated */ |
||||
/* */ |
||||
/* Description: This file is a linker command file that can be used for */ |
||||
/* linking PRU programs built with the C compiler and */ |
||||
/* the resulting .out file on an AM335x device. */ |
||||
/****************************************************************************/ |
||||
|
||||
-cr /* Link using C conventions */ |
||||
|
||||
/* Specify the System Memory Map */ |
||||
MEMORY |
||||
{ |
||||
PAGE 0: |
||||
PRU_IMEM : org = 0x00000000 len = 0x00002000 /* 8kB PRU0 Instruction RAM */ |
||||
|
||||
PAGE 1: |
||||
|
||||
/* RAM */ |
||||
|
||||
PRU_DMEM_0_1 : org = 0x00000000 len = 0x00002000 CREGISTER=24 /* 8kB PRU Data RAM 0_1 */ |
||||
PRU_DMEM_1_0 : org = 0x00002000 len = 0x00002000 CREGISTER=25 /* 8kB PRU Data RAM 1_0 */ |
||||
PRU_SHAREDMEM : org = 0x00010000 len = 0x00003000 CREGISTER=28 /* 12kB Shared RAM */ |
||||
|
||||
DDR : org = 0x80000000 len = 0x00000100 CREGISTER=31 |
||||
L3OCMC : org = 0x40000000 len = 0x00010000 CREGISTER=30 |
||||
|
||||
|
||||
/* Peripherals */ |
||||
|
||||
PRU_CFG : org = 0x00026000 len = 0x00000100 CREGISTER=4 |
||||
PRU_ECAP : org = 0x00030000 len = 0x00000100 CREGISTER=3 |
||||
PRU_IEP : org = 0x0002E000 len = 0x0000031C CREGISTER=26 |
||||
PRU_INTC : org = 0x00020000 len = 0x00001504 CREGISTER=0 |
||||
PRU_UART : org = 0x00028000 len = 0x00000100 CREGISTER=7 |
||||
|
||||
DCAN0 : org = 0x481CC000 len = 0x00000100 CREGISTER=14 |
||||
DCAN1 : org = 0x481D0000 len = 0x00000100 CREGISTER=15 |
||||
DMTIMER2 : org = 0x48040000 len = 0x00000100 CREGISTER=1 |
||||
EHRPWM1 : org = 0x48300000 len = 0x00000100 CREGISTER=18 |
||||
EHRPWM2 : org = 0x48302000 len = 0x00000100 CREGISTER=19 |
||||
EHRPWM3 : org = 0x48304000 len = 0x00000100 CREGISTER=20 |
||||
GEMAC : org = 0x4A100000 len = 0x00000100 CREGISTER=9 |
||||
I2C1 : org = 0x4802A000 len = 0x00000100 CREGISTER=2 |
||||
I2C2 : org = 0x4819C000 len = 0x00000100 CREGISTER=17 |
||||
MBX0 : org = 0x480C8000 len = 0x00000100 CREGISTER=22 |
||||
MCASP0_DMA : org = 0x46000000 len = 0x00000100 CREGISTER=8 |
||||
MCSPI0 : org = 0x48030000 len = 0x00000100 CREGISTER=6 |
||||
MCSPI1 : org = 0x481A0000 len = 0x00000100 CREGISTER=16 |
||||
MDIO : org = 0x00032400 len = 0x00000100 CREGISTER=21 |
||||
MMCHS0 : org = 0x48060000 len = 0x00000100 CREGISTER=5 |
||||
SPINLOCK : org = 0x480CA000 len = 0x00000100 CREGISTER=23 |
||||
TPCC : org = 0x49000000 len = 0x000010A0 CREGISTER=29 |
||||
UART1 : org = 0x48022000 len = 0x00000100 CREGISTER=11 |
||||
UART2 : org = 0x48024000 len = 0x00000100 CREGISTER=12 |
||||
|
||||
RSVD10 : org = 0x48318000 len = 0x00000100 CREGISTER=10 |
||||
RSVD13 : org = 0x48310000 len = 0x00000100 CREGISTER=13 |
||||
RSVD27 : org = 0x00032000 len = 0x00000100 CREGISTER=27 |
||||
|
||||
} |
||||
|
||||
/* Specify the sections allocation into memory */ |
||||
SECTIONS { |
||||
/* Forces _c_int00 to the start of PRU IRAM. Not necessary when loading |
||||
an ELF file, but useful when loading a binary */ |
||||
.text:_c_int00* > 0x0, PAGE 0 |
||||
|
||||
.text > PRU_IMEM, PAGE 0 |
||||
.stack > PRU_DMEM_0_1, PAGE 1 |
||||
.bss > PRU_DMEM_0_1, PAGE 1 |
||||
.cio > PRU_DMEM_0_1, PAGE 1 |
||||
.data > PRU_DMEM_0_1, PAGE 1 |
||||
.switch > PRU_DMEM_0_1, PAGE 1 |
||||
.sysmem > PRU_DMEM_0_1, PAGE 1 |
||||
.cinit > PRU_DMEM_0_1, PAGE 1 |
||||
.rodata > PRU_DMEM_0_1, PAGE 1 |
||||
.rofardata > PRU_DMEM_0_1, PAGE 1 |
||||
.farbss > PRU_DMEM_0_1, PAGE 1 |
||||
.fardata > PRU_DMEM_0_1, PAGE 1 |
||||
|
||||
.resource_table > PRU_DMEM_0_1, PAGE 1 |
||||
} |
@ -0,0 +1,9 @@
@@ -0,0 +1,9 @@
|
||||
-b |
||||
--image |
||||
|
||||
ROMS { |
||||
PAGE 0: |
||||
.text: o = 0x0, l = 0x2000, files={rangefinderprutext.bin} |
||||
PAGE 1: |
||||
.data: o = 0x0, l = 0x2000, files={rangefinderprudata.bin} |
||||
} |
@ -0,0 +1,42 @@
@@ -0,0 +1,42 @@
|
||||
all: rangefinder.stripped rangefinder.lst |
||||
|
||||
CC=clpru
|
||||
LD=lnkpru
|
||||
AR=arpru
|
||||
OBJDUMP=dispru
|
||||
STRIP=strippru
|
||||
HEX=hexpru
|
||||
|
||||
CFLAGS= --endian=little -v3 -s -al --c99 --gcc -O3 --printf_support=minimal --symdebug:none
|
||||
|
||||
LDFLAGS=-cr --diag_warning=225 -lAM335x_PRU.cmd -x
|
||||
|
||||
STRIPFLAGS=-p
|
||||
|
||||
OBJS1:=rangefinder.obj
|
||||
|
||||
%.obj: %.c |
||||
$(CC) $(CFLAGS) -c $< -ea=.s
|
||||
|
||||
%.obj: %.asm |
||||
$(CC) $(CFLAGS) -c $<
|
||||
|
||||
rangefinder: $(OBJS1) |
||||
$(CC) $(CFLAGS) $^ -q -z $(LDFLAGS) -o $@
|
||||
|
||||
rangefinder.stripped: rangefinder |
||||
$(STRIP) $(STRIPFLAGS) $< -o $@
|
||||
size rangefinder.stripped
|
||||
$(HEX) rangefinder.stripped HexUtil_PRU.cmd
|
||||
|
||||
rangefinder.lst: rangefinder |
||||
$(OBJDUMP) -1 $< > $@
|
||||
|
||||
install: |
||||
cp rangefinderprutext.bin /lib/firmware
|
||||
cp rangefinderprudata.bin /lib/firmware
|
||||
|
||||
clean: |
||||
rm -f \
|
||||
rangefinder rangefinder.asm rangefinder.s \
|
||||
*.bin *.obj *.lst *.out *.stripped \
|
@ -0,0 +1,120 @@
@@ -0,0 +1,120 @@
|
||||
|
||||
|
||||
/* PRU_CTRL register set */ |
||||
typedef struct{ |
||||
|
||||
/* PRU_CTRL_CONTROL register bit field */ |
||||
union { |
||||
volatile uint32_t CTRL; |
||||
|
||||
volatile struct{ |
||||
unsigned SOFT_RST_N : 1; |
||||
unsigned EN : 1; |
||||
unsigned SLEEPING : 1; |
||||
unsigned CTR_EN : 1; |
||||
unsigned rsvd4 : 4; |
||||
unsigned SINGLE_STEP : 1; |
||||
unsigned rsvd9 : 6; |
||||
unsigned RUNSTATE : 1; |
||||
unsigned PCTR_RST_VAL : 16; |
||||
} CONTROL_bit; |
||||
} ; // 0x0
|
||||
|
||||
|
||||
/* PRU_CTRL_STATUS register bit field */ |
||||
union { |
||||
volatile uint32_t STS; |
||||
|
||||
volatile struct{ |
||||
unsigned PCTR : 16; |
||||
unsigned rsvd16 : 16; |
||||
} STATUS_bit; |
||||
} ; // 0x4
|
||||
|
||||
|
||||
/* PRU_CTRL_WAKEUP_EN register bit field */ |
||||
union { |
||||
volatile uint32_t WAKEUP_EN; |
||||
|
||||
volatile struct{ |
||||
unsigned BITWISE_ENS : 32; |
||||
} WAKEUP_EN_bit; |
||||
} ; // 0x8
|
||||
|
||||
|
||||
/* PRU_CTRL_CYCLE register bit field */ |
||||
union { |
||||
volatile uint32_t CYCLE; |
||||
|
||||
volatile struct{ |
||||
unsigned CYCLECOUNT : 32; |
||||
} CYCLE_bit; |
||||
} ; // 0xC
|
||||
|
||||
|
||||
/* PRU_CTRL_STALL register bit field */ |
||||
union { |
||||
volatile uint32_t STALL; |
||||
|
||||
volatile struct{ |
||||
unsigned STALLCOUNT : 32; |
||||
} STALL_bit; |
||||
} ; // 0x10
|
||||
|
||||
|
||||
uint32_t rsvd14[3]; // 0x14 - 0x1C
|
||||
|
||||
|
||||
/* PRU_CTRL_CTBIR0 register bit field */ |
||||
union { |
||||
volatile uint32_t CTBIR0; |
||||
|
||||
volatile struct{ |
||||
unsigned C24_BLK_IDX : 8; |
||||
unsigned rsvd8 : 8; |
||||
unsigned C25_BLK_IDX : 8; |
||||
unsigned rsvd24 : 8; |
||||
} CTBIR0_bit; |
||||
} ; // 0x20
|
||||
|
||||
|
||||
/* PRU_CTRL_CTBIR1 register bit field */ |
||||
union { |
||||
volatile uint32_t CTBIR1; |
||||
|
||||
volatile struct{ |
||||
unsigned C26_BLK_IDX : 8; |
||||
unsigned rsvd8 : 8; |
||||
unsigned C27_BLK_IDX : 8; |
||||
unsigned rsvd24 : 8; |
||||
} CTBIR1_bit; |
||||
} ; // 0x24
|
||||
|
||||
|
||||
/* PRU_CTRL_CTPPR0 register bit field */ |
||||
union { |
||||
volatile uint32_t CTPPR0; |
||||
|
||||
volatile struct{ |
||||
unsigned C28_BLK_POINTER : 16; |
||||
unsigned C29_BLK_POINTER : 16; |
||||
} CTPPR0_bit; |
||||
} ; // 0x28
|
||||
|
||||
|
||||
/* PRU_CTRL_CTPPR1 register bit field */ |
||||
union { |
||||
volatile uint32_t CTPPR1; |
||||
|
||||
volatile struct{ |
||||
unsigned C30_BLK_POINTER : 16; |
||||
unsigned C31_BLK_POINTER : 16; |
||||
} CTPPR1_bit; |
||||
} ; // 0x2C
|
||||
|
||||
} pruCtrl; |
||||
|
||||
/* Definition of control register structures. */ |
||||
#define PRU0_CTRL (*((volatile pruCtrl*)0x22000)) |
||||
#define PRU1_CTRL (*((volatile pruCtrl*)0x24000)) |
||||
|
@ -0,0 +1,137 @@
@@ -0,0 +1,137 @@
|
||||
/*
|
||||
This program is free software: you can redistribute it and/or modify |
||||
it under the terms of the GNU General Public License as published by |
||||
the Free Software Foundation, either version 3 of the License, or |
||||
(at your option) any later version. |
||||
|
||||
This program is distributed in the hope that it will be useful, |
||||
but WITHOUT ANY WARRANTY; without even the implied warranty of |
||||
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the |
||||
GNU General Public License for more details. |
||||
|
||||
You should have received a copy of the GNU General Public License |
||||
along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||
|
||||
HC-SR04 Ultrasonic Distance Sensor by Mirko Denecke <mirkix@gmail.com> |
||||
|
||||
*/ |
||||
|
||||
#include <stdint.h> |
||||
|
||||
#include "pru_ctrl.h" |
||||
|
||||
volatile register uint32_t __R30; |
||||
volatile register uint32_t __R31; |
||||
|
||||
// Trigger pin
|
||||
#define TRIGGER 1<<14 |
||||
|
||||
// Echo pin
|
||||
#define ECHO 1<<14 |
||||
|
||||
#define TICKS_PER_US 200 |
||||
#define TICKS_PER_MS (1000 * TICKS_PER_US) |
||||
|
||||
#define TICKS_PER_CM 11600 |
||||
|
||||
#define COUNTER_MIN_DISTANCE (2 * TICKS_PER_CM) |
||||
#define COUNTER_MAX_DISTANCE (400 * TICKS_PER_CM) |
||||
|
||||
enum RangeFinder_Status { |
||||
RangeFinder_NotConnected = 0, |
||||
RangeFinder_NoData, |
||||
RangeFinder_OutOfRangeLow, |
||||
RangeFinder_OutOfRangeHigh, |
||||
RangeFinder_Good |
||||
}; |
||||
|
||||
struct range { |
||||
uint32_t distance; |
||||
uint32_t status; |
||||
}; |
||||
|
||||
#pragma LOCATION(ranger, 0x0) |
||||
volatile struct range ranger; |
||||
|
||||
main() |
||||
{ |
||||
// Init data
|
||||
ranger.distance = 0; |
||||
ranger.status = RangeFinder_NoData; |
||||
|
||||
// Reset trigger
|
||||
__R30 &= ~(TRIGGER); |
||||
|
||||
// Wait 100ms
|
||||
__delay_cycles(250 * TICKS_PER_MS); |
||||
|
||||
// Disable counter
|
||||
PRU0_CTRL.CONTROL_bit.CTR_EN = 0; |
||||
|
||||
// Clear counter
|
||||
PRU0_CTRL.CYCLE_bit.CYCLECOUNT = 0xFFFFFFFF; |
||||
|
||||
while(1) |
||||
{ |
||||
// Enable trigger
|
||||
__R30 |= TRIGGER; |
||||
|
||||
// Wait 15us
|
||||
__delay_cycles(3000); |
||||
|
||||
// Reset trigger
|
||||
__R30 &= ~(TRIGGER); |
||||
|
||||
// Wait for echo
|
||||
while((__R31 & ECHO) == 0) |
||||
{ |
||||
if(PRU0_CTRL.CYCLE_bit.CYCLECOUNT > (600 * TICKS_PER_CM)) |
||||
{ |
||||
ranger.status = RangeFinder_NoData; |
||||
} |
||||
} |
||||
|
||||
// Start counter
|
||||
PRU0_CTRL.CONTROL_bit.CTR_EN = 1; |
||||
|
||||
// Count echo length
|
||||
while(__R31 & ECHO) |
||||
{ |
||||
; |
||||
} |
||||
|
||||
// Stop counter
|
||||
PRU0_CTRL.CONTROL_bit.CTR_EN = 0; |
||||
|
||||
// Check status
|
||||
if(PRU0_CTRL.CYCLE_bit.CYCLECOUNT < COUNTER_MIN_DISTANCE) |
||||
{ |
||||
ranger.distance = 0; |
||||
|
||||
// Set status out of range low
|
||||
ranger.status = RangeFinder_OutOfRangeLow; |
||||
} |
||||
else if(PRU0_CTRL.CYCLE_bit.CYCLECOUNT > COUNTER_MAX_DISTANCE) |
||||
{ |
||||
ranger.distance = 0; |
||||
|
||||
// Set stauts
|
||||
ranger.status = RangeFinder_OutOfRangeHigh; |
||||
} |
||||
else |
||||
{ |
||||
// Calculate distance in cm
|
||||
ranger.distance = PRU0_CTRL.CYCLE_bit.CYCLECOUNT / TICKS_PER_CM; |
||||
|
||||
// Set status out of range high
|
||||
ranger.status = RangeFinder_Good; |
||||
} |
||||
|
||||
// Clear counter
|
||||
PRU0_CTRL.CYCLE_bit.CYCLECOUNT = 0xFFFFFFFF; |
||||
|
||||
// Wait 20ms
|
||||
__delay_cycles(20 * TICKS_PER_MS); |
||||
} |
||||
} |
||||
|
Loading…
Reference in new issue