Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/Tools/Linux_HAL_Essentials/pru/rangefinderpru/rangefinder.c
Views: 1800
/*1This program is free software: you can redistribute it and/or modify2it under the terms of the GNU General Public License as published by3the Free Software Foundation, either version 3 of the License, or4(at your option) any later version.56This program is distributed in the hope that it will be useful,7but WITHOUT ANY WARRANTY; without even the implied warranty of8MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the9GNU General Public License for more details.1011You should have received a copy of the GNU General Public License12along with this program. If not, see <http://www.gnu.org/licenses/>.1314HC-SR04 Ultrasonic Distance Sensor by Mirko Denecke <[email protected]>1516*/1718#include <stdint.h>1920#include "pru_ctrl.h"2122volatile register uint32_t __R30;23volatile register uint32_t __R31;2425// Trigger pin26#define TRIGGER 1<<142728// Echo pin29#define ECHO 1<<143031#define TICKS_PER_US 20032#define TICKS_PER_MS (1000 * TICKS_PER_US)3334#define TICKS_PER_CM 116003536#define COUNTER_MIN_DISTANCE (2 * TICKS_PER_CM)37#define COUNTER_MAX_DISTANCE (400 * TICKS_PER_CM)3839enum RangeFinder_Status {40RangeFinder_NotConnected = 0,41RangeFinder_NoData,42RangeFinder_OutOfRangeLow,43RangeFinder_OutOfRangeHigh,44RangeFinder_Good45};4647struct range {48uint32_t distance;49uint32_t status;50};5152#pragma LOCATION(ranger, 0x0)53volatile struct range ranger;5455main()56{57// Init data58ranger.distance = 0;59ranger.status = RangeFinder_NoData;6061// Reset trigger62__R30 &= ~(TRIGGER);6364// Wait 100ms65__delay_cycles(250 * TICKS_PER_MS);6667// Disable counter68PRU0_CTRL.CONTROL_bit.CTR_EN = 0;6970// Clear counter71PRU0_CTRL.CYCLE_bit.CYCLECOUNT = 0xFFFFFFFF;7273while(1)74{75// Enable trigger76__R30 |= TRIGGER;7778// Wait 15us79__delay_cycles(3000);8081// Reset trigger82__R30 &= ~(TRIGGER);8384// Wait for echo85while((__R31 & ECHO) == 0)86{87if(PRU0_CTRL.CYCLE_bit.CYCLECOUNT > (600 * TICKS_PER_CM))88{89ranger.status = RangeFinder_NoData;90}91}9293// Start counter94PRU0_CTRL.CONTROL_bit.CTR_EN = 1;9596// Count echo length97while(__R31 & ECHO)98{99;100}101102// Stop counter103PRU0_CTRL.CONTROL_bit.CTR_EN = 0;104105// Check status106if(PRU0_CTRL.CYCLE_bit.CYCLECOUNT < COUNTER_MIN_DISTANCE)107{108ranger.distance = 0;109110// Set status out of range low111ranger.status = RangeFinder_OutOfRangeLow;112}113else if(PRU0_CTRL.CYCLE_bit.CYCLECOUNT > COUNTER_MAX_DISTANCE)114{115ranger.distance = 0;116117// Set stauts118ranger.status = RangeFinder_OutOfRangeHigh;119}120else121{122// Calculate distance in cm123ranger.distance = PRU0_CTRL.CYCLE_bit.CYCLECOUNT / TICKS_PER_CM;124125// Set status out of range high126ranger.status = RangeFinder_Good;127}128129// Clear counter130PRU0_CTRL.CYCLE_bit.CYCLECOUNT = 0xFFFFFFFF;131132// Wait 20ms133__delay_cycles(20 * TICKS_PER_MS);134}135}136137138139