mirror of https://github.com/arendst/Tasmota.git
Merge pull request #4488 from winstona/hc-sr04-newping
HC-SR04: switch to using NewPing libraries directly
This commit is contained in:
commit
f4348f19dc
|
@ -0,0 +1,3 @@
|
|||
# NewPing Arduino Library for Arduino
|
||||
|
||||
## See the [NewPing Wiki](https://bitbucket.org/teckel12/arduino-new-ping/wiki/Home) for documentation
|
|
@ -0,0 +1,78 @@
|
|||
// ---------------------------------------------------------------------------
|
||||
// Before attempting to use this sketch, please read the "Help with 15 Sensors Example Sketch":
|
||||
// https://bitbucket.org/teckel12/arduino-new-ping/wiki/Help%20with%2015%20Sensors%20Example%20Sketch
|
||||
//
|
||||
// This example code was used to successfully communicate with 15 ultrasonic sensors. You can adjust
|
||||
// the number of sensors in your project by changing SONAR_NUM and the number of NewPing objects in the
|
||||
// "sonar" array. You also need to change the pins for each sensor for the NewPing objects. Each sensor
|
||||
// is pinged at 33ms intervals. So, one cycle of all sensors takes 495ms (33 * 15 = 495ms). The results
|
||||
// are sent to the "oneSensorCycle" function which currently just displays the distance data. Your project
|
||||
// would normally process the sensor results in this function (for example, decide if a robot needs to
|
||||
// turn and call the turn function). Keep in mind this example is event-driven. Your complete sketch needs
|
||||
// to be written so there's no "delay" commands and the loop() cycles at faster than a 33ms rate. If other
|
||||
// processes take longer than 33ms, you'll need to increase PING_INTERVAL so it doesn't get behind.
|
||||
// ---------------------------------------------------------------------------
|
||||
#include <NewPing.h>
|
||||
|
||||
#define SONAR_NUM 15 // Number of sensors.
|
||||
#define MAX_DISTANCE 200 // Maximum distance (in cm) to ping.
|
||||
#define PING_INTERVAL 33 // Milliseconds between sensor pings (29ms is about the min to avoid cross-sensor echo).
|
||||
|
||||
unsigned long pingTimer[SONAR_NUM]; // Holds the times when the next ping should happen for each sensor.
|
||||
unsigned int cm[SONAR_NUM]; // Where the ping distances are stored.
|
||||
uint8_t currentSensor = 0; // Keeps track of which sensor is active.
|
||||
|
||||
NewPing sonar[SONAR_NUM] = { // Sensor object array.
|
||||
NewPing(41, 42, MAX_DISTANCE), // Each sensor's trigger pin, echo pin, and max distance to ping.
|
||||
NewPing(43, 44, MAX_DISTANCE),
|
||||
NewPing(45, 20, MAX_DISTANCE),
|
||||
NewPing(21, 22, MAX_DISTANCE),
|
||||
NewPing(23, 24, MAX_DISTANCE),
|
||||
NewPing(25, 26, MAX_DISTANCE),
|
||||
NewPing(27, 28, MAX_DISTANCE),
|
||||
NewPing(29, 30, MAX_DISTANCE),
|
||||
NewPing(31, 32, MAX_DISTANCE),
|
||||
NewPing(34, 33, MAX_DISTANCE),
|
||||
NewPing(35, 36, MAX_DISTANCE),
|
||||
NewPing(37, 38, MAX_DISTANCE),
|
||||
NewPing(39, 40, MAX_DISTANCE),
|
||||
NewPing(50, 51, MAX_DISTANCE),
|
||||
NewPing(52, 53, MAX_DISTANCE)
|
||||
};
|
||||
|
||||
void setup() {
|
||||
Serial.begin(115200);
|
||||
pingTimer[0] = millis() + 75; // First ping starts at 75ms, gives time for the Arduino to chill before starting.
|
||||
for (uint8_t i = 1; i < SONAR_NUM; i++) // Set the starting time for each sensor.
|
||||
pingTimer[i] = pingTimer[i - 1] + PING_INTERVAL;
|
||||
}
|
||||
|
||||
void loop() {
|
||||
for (uint8_t i = 0; i < SONAR_NUM; i++) { // Loop through all the sensors.
|
||||
if (millis() >= pingTimer[i]) { // Is it this sensor's time to ping?
|
||||
pingTimer[i] += PING_INTERVAL * SONAR_NUM; // Set next time this sensor will be pinged.
|
||||
if (i == 0 && currentSensor == SONAR_NUM - 1) oneSensorCycle(); // Sensor ping cycle complete, do something with the results.
|
||||
sonar[currentSensor].timer_stop(); // Make sure previous timer is canceled before starting a new ping (insurance).
|
||||
currentSensor = i; // Sensor being accessed.
|
||||
cm[currentSensor] = 0; // Make distance zero in case there's no ping echo for this sensor.
|
||||
sonar[currentSensor].ping_timer(echoCheck); // Do the ping (processing continues, interrupt will call echoCheck to look for echo).
|
||||
}
|
||||
}
|
||||
// Other code that *DOESN'T* analyze ping results can go here.
|
||||
}
|
||||
|
||||
void echoCheck() { // If ping received, set the sensor distance to array.
|
||||
if (sonar[currentSensor].check_timer())
|
||||
cm[currentSensor] = sonar[currentSensor].ping_result / US_ROUNDTRIP_CM;
|
||||
}
|
||||
|
||||
void oneSensorCycle() { // Sensor ping cycle complete, do something with the results.
|
||||
// The following code would be replaced with your code that does something with the ping results.
|
||||
for (uint8_t i = 0; i < SONAR_NUM; i++) {
|
||||
Serial.print(i);
|
||||
Serial.print("=");
|
||||
Serial.print(cm[i]);
|
||||
Serial.print("cm ");
|
||||
}
|
||||
Serial.println();
|
||||
}
|
|
@ -0,0 +1,29 @@
|
|||
// ---------------------------------------------------------------------------
|
||||
// Example NewPing library sketch that pings 3 sensors 20 times a second.
|
||||
// ---------------------------------------------------------------------------
|
||||
|
||||
#include <NewPing.h>
|
||||
|
||||
#define SONAR_NUM 3 // Number of sensors.
|
||||
#define MAX_DISTANCE 200 // Maximum distance (in cm) to ping.
|
||||
|
||||
NewPing sonar[SONAR_NUM] = { // Sensor object array.
|
||||
NewPing(4, 5, MAX_DISTANCE), // Each sensor's trigger pin, echo pin, and max distance to ping.
|
||||
NewPing(6, 7, MAX_DISTANCE),
|
||||
NewPing(8, 9, MAX_DISTANCE)
|
||||
};
|
||||
|
||||
void setup() {
|
||||
Serial.begin(115200); // Open serial monitor at 115200 baud to see ping results.
|
||||
}
|
||||
|
||||
void loop() {
|
||||
for (uint8_t i = 0; i < SONAR_NUM; i++) { // Loop through each sensor and display results.
|
||||
delay(50); // Wait 50ms between pings (about 20 pings/sec). 29ms should be the shortest delay between pings.
|
||||
Serial.print(i);
|
||||
Serial.print("=");
|
||||
Serial.print(sonar[i].ping_cm());
|
||||
Serial.print("cm ");
|
||||
}
|
||||
Serial.println();
|
||||
}
|
|
@ -0,0 +1,46 @@
|
|||
// ---------------------------------------------------------------------------
|
||||
// This example shows how to use NewPing's ping_timer method which uses the Timer2 interrupt to get the
|
||||
// ping time. The advantage of using this method over the standard ping method is that it permits a more
|
||||
// event-driven sketch which allows you to appear to do two things at once. An example would be to ping
|
||||
// an ultrasonic sensor for a possible collision while at the same time navigating. This allows a
|
||||
// properly developed sketch to multitask. Be aware that because the ping_timer method uses Timer2,
|
||||
// other features or libraries that also use Timer2 would be effected. For example, the PWM function on
|
||||
// pins 3 & 11 on Arduino Uno (pins 9 and 11 on Arduino Mega) and the Tone library. Note, only the PWM
|
||||
// functionality of the pins is lost (as they use Timer2 to do PWM), the pins are still available to use.
|
||||
// NOTE: For Teensy/Leonardo (ATmega32U4) the library uses Timer4 instead of Timer2.
|
||||
// ---------------------------------------------------------------------------
|
||||
#include <NewPing.h>
|
||||
|
||||
#define TRIGGER_PIN 12 // Arduino pin tied to trigger pin on ping sensor.
|
||||
#define ECHO_PIN 11 // Arduino pin tied to echo pin on ping sensor.
|
||||
#define MAX_DISTANCE 200 // Maximum distance we want to ping for (in centimeters). Maximum sensor distance is rated at 400-500cm.
|
||||
|
||||
NewPing sonar(TRIGGER_PIN, ECHO_PIN, MAX_DISTANCE); // NewPing setup of pins and maximum distance.
|
||||
|
||||
unsigned int pingSpeed = 50; // How frequently are we going to send out a ping (in milliseconds). 50ms would be 20 times a second.
|
||||
unsigned long pingTimer; // Holds the next ping time.
|
||||
|
||||
void setup() {
|
||||
Serial.begin(115200); // Open serial monitor at 115200 baud to see ping results.
|
||||
pingTimer = millis(); // Start now.
|
||||
}
|
||||
|
||||
void loop() {
|
||||
// Notice how there's no delays in this sketch to allow you to do other processing in-line while doing distance pings.
|
||||
if (millis() >= pingTimer) { // pingSpeed milliseconds since last ping, do another ping.
|
||||
pingTimer += pingSpeed; // Set the next ping time.
|
||||
sonar.ping_timer(echoCheck); // Send out the ping, calls "echoCheck" function every 24uS where you can check the ping status.
|
||||
}
|
||||
// Do other stuff here, really. Think of it as multi-tasking.
|
||||
}
|
||||
|
||||
void echoCheck() { // Timer2 interrupt calls this function every 24uS where you can check the ping status.
|
||||
// Don't do anything here!
|
||||
if (sonar.check_timer()) { // This is how you check to see if the ping was received.
|
||||
// Here's where you can add code.
|
||||
Serial.print("Ping: ");
|
||||
Serial.print(sonar.ping_result / US_ROUNDTRIP_CM); // Ping returned, uS result in ping_result, convert to cm with US_ROUNDTRIP_CM.
|
||||
Serial.println("cm");
|
||||
}
|
||||
// Don't do anything here!
|
||||
}
|
|
@ -0,0 +1,22 @@
|
|||
// ---------------------------------------------------------------------------
|
||||
// Example NewPing library sketch that does a ping about 20 times per second.
|
||||
// ---------------------------------------------------------------------------
|
||||
|
||||
#include <NewPing.h>
|
||||
|
||||
#define TRIGGER_PIN 12 // Arduino pin tied to trigger pin on the ultrasonic sensor.
|
||||
#define ECHO_PIN 11 // Arduino pin tied to echo pin on the ultrasonic sensor.
|
||||
#define MAX_DISTANCE 200 // Maximum distance we want to ping for (in centimeters). Maximum sensor distance is rated at 400-500cm.
|
||||
|
||||
NewPing sonar(TRIGGER_PIN, ECHO_PIN, MAX_DISTANCE); // NewPing setup of pins and maximum distance.
|
||||
|
||||
void setup() {
|
||||
Serial.begin(115200); // Open serial monitor at 115200 baud to see ping results.
|
||||
}
|
||||
|
||||
void loop() {
|
||||
delay(50); // Wait 50ms between pings (about 20 pings/sec). 29ms should be the shortest delay between pings.
|
||||
Serial.print("Ping: ");
|
||||
Serial.print(sonar.ping_cm()); // Send ping, get distance in cm and print result (0 = outside set distance range)
|
||||
Serial.println("cm");
|
||||
}
|
|
@ -0,0 +1,60 @@
|
|||
// ---------------------------------------------------------------------------
|
||||
// Calculate a ping median using the ping_timer() method.
|
||||
// ---------------------------------------------------------------------------
|
||||
|
||||
#include <NewPing.h>
|
||||
|
||||
#define ITERATIONS 5 // Number of iterations.
|
||||
#define TRIGGER_PIN 12 // Arduino pin tied to trigger pin on ping sensor.
|
||||
#define ECHO_PIN 11 // Arduino pin tied to echo pin on ping sensor.
|
||||
#define MAX_DISTANCE 200 // Maximum distance (in cm) to ping.
|
||||
#define PING_INTERVAL 33 // Milliseconds between sensor pings (29ms is about the min to avoid cross-sensor echo).
|
||||
|
||||
unsigned long pingTimer[ITERATIONS]; // Holds the times when the next ping should happen for each iteration.
|
||||
unsigned int cm[ITERATIONS]; // Where the ping distances are stored.
|
||||
uint8_t currentIteration = 0; // Keeps track of iteration step.
|
||||
|
||||
NewPing sonar(TRIGGER_PIN, ECHO_PIN, MAX_DISTANCE); // NewPing setup of pins and maximum distance.
|
||||
|
||||
void setup() {
|
||||
Serial.begin(115200);
|
||||
pingTimer[0] = millis() + 75; // First ping starts at 75ms, gives time for the Arduino to chill before starting.
|
||||
for (uint8_t i = 1; i < ITERATIONS; i++) // Set the starting time for each iteration.
|
||||
pingTimer[i] = pingTimer[i - 1] + PING_INTERVAL;
|
||||
}
|
||||
|
||||
void loop() {
|
||||
for (uint8_t i = 0; i < ITERATIONS; i++) { // Loop through all the iterations.
|
||||
if (millis() >= pingTimer[i]) { // Is it this iteration's time to ping?
|
||||
pingTimer[i] += PING_INTERVAL * ITERATIONS; // Set next time this sensor will be pinged.
|
||||
if (i == 0 && currentIteration == ITERATIONS - 1) oneSensorCycle(); // Sensor ping cycle complete, do something with the results.
|
||||
sonar.timer_stop(); // Make sure previous timer is canceled before starting a new ping (insurance).
|
||||
currentIteration = i; // Sensor being accessed.
|
||||
cm[currentIteration] = 0; // Make distance zero in case there's no ping echo for this iteration.
|
||||
sonar.ping_timer(echoCheck); // Do the ping (processing continues, interrupt will call echoCheck to look for echo).
|
||||
}
|
||||
}
|
||||
// Other code that *DOESN'T* analyze ping results can go here.
|
||||
}
|
||||
|
||||
void echoCheck() { // If ping received, set the sensor distance to array.
|
||||
if (sonar.check_timer())
|
||||
cm[currentIteration] = sonar.ping_result / US_ROUNDTRIP_CM;
|
||||
}
|
||||
|
||||
void oneSensorCycle() { // All iterations complete, calculate the median.
|
||||
unsigned int uS[ITERATIONS];
|
||||
uint8_t j, it = ITERATIONS;
|
||||
uS[0] = NO_ECHO;
|
||||
for (uint8_t i = 0; i < it; i++) { // Loop through iteration results.
|
||||
if (cm[i] != NO_ECHO) { // Ping in range, include as part of median.
|
||||
if (i > 0) { // Don't start sort till second ping.
|
||||
for (j = i; j > 0 && uS[j - 1] < cm[i]; j--) // Insertion sort loop.
|
||||
uS[j] = uS[j - 1]; // Shift ping array to correct position for sort insertion.
|
||||
} else j = 0; // First ping is sort starting point.
|
||||
uS[j] = cm[i]; // Add last ping to array in sorted position.
|
||||
} else it--; // Ping out of range, skip and don't include as part of median.
|
||||
}
|
||||
Serial.print(uS[it >> 1]);
|
||||
Serial.println("cm");
|
||||
}
|
|
@ -0,0 +1,25 @@
|
|||
// ---------------------------------------------------------------------------
|
||||
// While the NewPing library's primary goal is to interface with ultrasonic sensors, interfacing with
|
||||
// the Timer2 interrupt was a result of creating an interrupt-based ping method. Since these Timer2
|
||||
// interrupt methods were built, the library may as well provide the functionality to use these methods
|
||||
// in your sketches. This shows how simple it is (no ultrasonic sensor required). Keep in mind that
|
||||
// these methods use Timer2, as does NewPing's ping_timer method for using ultrasonic sensors. You
|
||||
// can't use ping_timer at the same time you're using timer_ms or timer_us as all use the same timer.
|
||||
// ---------------------------------------------------------------------------
|
||||
|
||||
#include <NewPing.h>
|
||||
|
||||
#define LED_PIN 13 // Pin with LED attached.
|
||||
|
||||
void setup() {
|
||||
pinMode(LED_PIN, OUTPUT);
|
||||
NewPing::timer_ms(500, toggleLED); // Create a Timer2 interrupt that calls toggleLED in your sketch once every 500 milliseconds.
|
||||
}
|
||||
|
||||
void loop() {
|
||||
// Do anything here, the Timer2 interrupt will take care of the flashing LED without your intervention.
|
||||
}
|
||||
|
||||
void toggleLED() {
|
||||
digitalWrite(LED_PIN, !digitalRead(LED_PIN)); // Toggle the LED.
|
||||
}
|
|
@ -0,0 +1,31 @@
|
|||
###################################
|
||||
# Syntax Coloring Map For NewPing
|
||||
###################################
|
||||
|
||||
###################################
|
||||
# Datatypes (KEYWORD1)
|
||||
###################################
|
||||
|
||||
NewPing KEYWORD1
|
||||
|
||||
###################################
|
||||
# Methods and Functions (KEYWORD2)
|
||||
###################################
|
||||
|
||||
ping KEYWORD2
|
||||
ping_in KEYWORD2
|
||||
ping_cm KEYWORD2
|
||||
ping_median KEYWORD2
|
||||
ping_timer KEYWORD2
|
||||
check_timer KEYWORD2
|
||||
ping_result KEYWORD2
|
||||
timer_us KEYWORD2
|
||||
timer_ms KEYWORD2
|
||||
timer_stop KEYWORD2
|
||||
convert_in KEYWORD2
|
||||
convert_cm KEYWORD2
|
||||
|
||||
###################################
|
||||
# Constants (LITERAL1)
|
||||
###################################
|
||||
|
|
@ -0,0 +1,10 @@
|
|||
name=NewPing
|
||||
version=1.9.1
|
||||
author=Tim Eckel <tim@leethost.com>
|
||||
maintainer=Tim Eckel <tim@leethost.com>
|
||||
sentence=A library that makes working with ultrasonic sensors easy.
|
||||
paragraph=When I first received an ultrasonic sensor I was not happy with how poorly it performed. I soon realized the problem was not the sensor, it was the available ping and ultrasonic libraries causing the problem. The NewPing library totally fixes these problems, adds many new features, and breathes new life into these very affordable distance sensors.
|
||||
category=Sensors
|
||||
url=https://bitbucket.org/teckel12/arduino-new-ping/wiki/Home
|
||||
architectures=avr,arm
|
||||
includes=NewPing.h
|
|
@ -0,0 +1,365 @@
|
|||
// ---------------------------------------------------------------------------
|
||||
// Created by Tim Eckel - teckel@leethost.com
|
||||
//
|
||||
// See NewPing.h for license, purpose, syntax, version history, links, etc.
|
||||
// ---------------------------------------------------------------------------
|
||||
|
||||
#include "NewPing.h"
|
||||
|
||||
|
||||
// ---------------------------------------------------------------------------
|
||||
// NewPing constructor
|
||||
// ---------------------------------------------------------------------------
|
||||
|
||||
NewPing::NewPing(uint8_t trigger_pin, uint8_t echo_pin, unsigned int max_cm_distance) {
|
||||
#if DO_BITWISE == true
|
||||
_triggerBit = digitalPinToBitMask(trigger_pin); // Get the port register bitmask for the trigger pin.
|
||||
_echoBit = digitalPinToBitMask(echo_pin); // Get the port register bitmask for the echo pin.
|
||||
|
||||
_triggerOutput = portOutputRegister(digitalPinToPort(trigger_pin)); // Get the output port register for the trigger pin.
|
||||
_echoInput = portInputRegister(digitalPinToPort(echo_pin)); // Get the input port register for the echo pin.
|
||||
|
||||
_triggerMode = (uint8_t *) portModeRegister(digitalPinToPort(trigger_pin)); // Get the port mode register for the trigger pin.
|
||||
#else
|
||||
_triggerPin = trigger_pin;
|
||||
_echoPin = echo_pin;
|
||||
#endif
|
||||
|
||||
set_max_distance(max_cm_distance); // Call function to set the max sensor distance.
|
||||
|
||||
#if (defined (__arm__) && (defined (TEENSYDUINO) || defined(PARTICLE))) || DO_BITWISE != true
|
||||
pinMode(echo_pin, INPUT); // Set echo pin to input (on Teensy 3.x (ARM), pins default to disabled, at least one pinMode() is needed for GPIO mode).
|
||||
pinMode(trigger_pin, OUTPUT); // Set trigger pin to output (on Teensy 3.x (ARM), pins default to disabled, at least one pinMode() is needed for GPIO mode).
|
||||
#endif
|
||||
|
||||
#if defined (ARDUINO_AVR_YUN)
|
||||
pinMode(echo_pin, INPUT); // Set echo pin to input for the Arduino Yun, not sure why it doesn't default this way.
|
||||
#endif
|
||||
|
||||
#if ONE_PIN_ENABLED != true && DO_BITWISE == true
|
||||
*_triggerMode |= _triggerBit; // Set trigger pin to output.
|
||||
#endif
|
||||
}
|
||||
|
||||
|
||||
// ---------------------------------------------------------------------------
|
||||
// Standard ping methods
|
||||
// ---------------------------------------------------------------------------
|
||||
|
||||
unsigned int NewPing::ping(unsigned int max_cm_distance) {
|
||||
if (max_cm_distance > 0) set_max_distance(max_cm_distance); // Call function to set a new max sensor distance.
|
||||
|
||||
if (!ping_trigger()) return NO_ECHO; // Trigger a ping, if it returns false, return NO_ECHO to the calling function.
|
||||
|
||||
#if URM37_ENABLED == true
|
||||
#if DO_BITWISE == true
|
||||
while (!(*_echoInput & _echoBit)) // Wait for the ping echo.
|
||||
#else
|
||||
while (!digitalRead(_echoPin)) // Wait for the ping echo.
|
||||
#endif
|
||||
if (micros() > _max_time) return NO_ECHO; // Stop the loop and return NO_ECHO (false) if we're beyond the set maximum distance.
|
||||
#else
|
||||
#if DO_BITWISE == true
|
||||
while (*_echoInput & _echoBit) // Wait for the ping echo.
|
||||
#else
|
||||
while (digitalRead(_echoPin)) // Wait for the ping echo.
|
||||
#endif
|
||||
if (micros() > _max_time) return NO_ECHO; // Stop the loop and return NO_ECHO (false) if we're beyond the set maximum distance.
|
||||
#endif
|
||||
|
||||
return (micros() - (_max_time - _maxEchoTime) - PING_OVERHEAD); // Calculate ping time, include overhead.
|
||||
}
|
||||
|
||||
|
||||
unsigned long NewPing::ping_cm(unsigned int max_cm_distance) {
|
||||
unsigned long echoTime = NewPing::ping(max_cm_distance); // Calls the ping method and returns with the ping echo distance in uS.
|
||||
#if ROUNDING_ENABLED == false
|
||||
return (echoTime / US_ROUNDTRIP_CM); // Call the ping method and returns the distance in centimeters (no rounding).
|
||||
#else
|
||||
return NewPingConvert(echoTime, US_ROUNDTRIP_CM); // Convert uS to centimeters.
|
||||
#endif
|
||||
}
|
||||
|
||||
|
||||
unsigned long NewPing::ping_in(unsigned int max_cm_distance) {
|
||||
unsigned long echoTime = NewPing::ping(max_cm_distance); // Calls the ping method and returns with the ping echo distance in uS.
|
||||
#if ROUNDING_ENABLED == false
|
||||
return (echoTime / US_ROUNDTRIP_IN); // Call the ping method and returns the distance in inches (no rounding).
|
||||
#else
|
||||
return NewPingConvert(echoTime, US_ROUNDTRIP_IN); // Convert uS to inches.
|
||||
#endif
|
||||
}
|
||||
|
||||
|
||||
unsigned long NewPing::ping_median(uint8_t it, unsigned int max_cm_distance) {
|
||||
unsigned int uS[it], last;
|
||||
uint8_t j, i = 0;
|
||||
unsigned long t;
|
||||
uS[0] = NO_ECHO;
|
||||
|
||||
while (i < it) {
|
||||
t = micros(); // Start ping timestamp.
|
||||
last = ping(max_cm_distance); // Send ping.
|
||||
|
||||
if (last != NO_ECHO) { // Ping in range, include as part of median.
|
||||
if (i > 0) { // Don't start sort till second ping.
|
||||
for (j = i; j > 0 && uS[j - 1] < last; j--) // Insertion sort loop.
|
||||
uS[j] = uS[j - 1]; // Shift ping array to correct position for sort insertion.
|
||||
} else j = 0; // First ping is sort starting point.
|
||||
uS[j] = last; // Add last ping to array in sorted position.
|
||||
i++; // Move to next ping.
|
||||
} else it--; // Ping out of range, skip and don't include as part of median.
|
||||
|
||||
if (i < it && micros() - t < PING_MEDIAN_DELAY)
|
||||
delay((PING_MEDIAN_DELAY + t - micros()) / 1000); // Millisecond delay between pings.
|
||||
|
||||
}
|
||||
return (uS[it >> 1]); // Return the ping distance median.
|
||||
}
|
||||
|
||||
|
||||
// ---------------------------------------------------------------------------
|
||||
// Standard and timer interrupt ping method support functions (not called directly)
|
||||
// ---------------------------------------------------------------------------
|
||||
|
||||
boolean NewPing::ping_trigger() {
|
||||
#if DO_BITWISE == true
|
||||
#if ONE_PIN_ENABLED == true
|
||||
*_triggerMode |= _triggerBit; // Set trigger pin to output.
|
||||
#endif
|
||||
|
||||
*_triggerOutput &= ~_triggerBit; // Set the trigger pin low, should already be low, but this will make sure it is.
|
||||
delayMicroseconds(4); // Wait for pin to go low.
|
||||
*_triggerOutput |= _triggerBit; // Set trigger pin high, this tells the sensor to send out a ping.
|
||||
delayMicroseconds(10); // Wait long enough for the sensor to realize the trigger pin is high. Sensor specs say to wait 10uS.
|
||||
*_triggerOutput &= ~_triggerBit; // Set trigger pin back to low.
|
||||
|
||||
#if ONE_PIN_ENABLED == true
|
||||
*_triggerMode &= ~_triggerBit; // Set trigger pin to input (when using one Arduino pin, this is technically setting the echo pin to input as both are tied to the same Arduino pin).
|
||||
#endif
|
||||
|
||||
#if URM37_ENABLED == true
|
||||
if (!(*_echoInput & _echoBit)) return false; // Previous ping hasn't finished, abort.
|
||||
_max_time = micros() + _maxEchoTime + MAX_SENSOR_DELAY; // Maximum time we'll wait for ping to start (most sensors are <450uS, the SRF06 can take up to 34,300uS!)
|
||||
while (*_echoInput & _echoBit) // Wait for ping to start.
|
||||
if (micros() > _max_time) return false; // Took too long to start, abort.
|
||||
#else
|
||||
if (*_echoInput & _echoBit) return false; // Previous ping hasn't finished, abort.
|
||||
_max_time = micros() + _maxEchoTime + MAX_SENSOR_DELAY; // Maximum time we'll wait for ping to start (most sensors are <450uS, the SRF06 can take up to 34,300uS!)
|
||||
while (!(*_echoInput & _echoBit)) // Wait for ping to start.
|
||||
if (micros() > _max_time) return false; // Took too long to start, abort.
|
||||
#endif
|
||||
#else
|
||||
#if ONE_PIN_ENABLED == true
|
||||
pinMode(_triggerPin, OUTPUT); // Set trigger pin to output.
|
||||
#endif
|
||||
|
||||
digitalWrite(_triggerPin, LOW); // Set the trigger pin low, should already be low, but this will make sure it is.
|
||||
delayMicroseconds(4); // Wait for pin to go low.
|
||||
digitalWrite(_triggerPin, HIGH); // Set trigger pin high, this tells the sensor to send out a ping.
|
||||
delayMicroseconds(10); // Wait long enough for the sensor to realize the trigger pin is high. Sensor specs say to wait 10uS.
|
||||
digitalWrite(_triggerPin, LOW); // Set trigger pin back to low.
|
||||
|
||||
#if ONE_PIN_ENABLED == true
|
||||
pinMode(_triggerPin, INPUT); // Set trigger pin to input (when using one Arduino pin, this is technically setting the echo pin to input as both are tied to the same Arduino pin).
|
||||
#endif
|
||||
|
||||
#if URM37_ENABLED == true
|
||||
if (!digitalRead(_echoPin)) return false; // Previous ping hasn't finished, abort.
|
||||
_max_time = micros() + _maxEchoTime + MAX_SENSOR_DELAY; // Maximum time we'll wait for ping to start (most sensors are <450uS, the SRF06 can take up to 34,300uS!)
|
||||
while (digitalRead(_echoPin)) // Wait for ping to start.
|
||||
if (micros() > _max_time) return false; // Took too long to start, abort.
|
||||
#else
|
||||
if (digitalRead(_echoPin)) return false; // Previous ping hasn't finished, abort.
|
||||
_max_time = micros() + _maxEchoTime + MAX_SENSOR_DELAY; // Maximum time we'll wait for ping to start (most sensors are <450uS, the SRF06 can take up to 34,300uS!)
|
||||
while (!digitalRead(_echoPin)) // Wait for ping to start.
|
||||
if (micros() > _max_time) return false; // Took too long to start, abort.
|
||||
#endif
|
||||
#endif
|
||||
|
||||
_max_time = micros() + _maxEchoTime; // Ping started, set the time-out.
|
||||
return true; // Ping started successfully.
|
||||
}
|
||||
|
||||
|
||||
void NewPing::set_max_distance(unsigned int max_cm_distance) {
|
||||
#if ROUNDING_ENABLED == false
|
||||
_maxEchoTime = min(max_cm_distance + 1, (unsigned int) MAX_SENSOR_DISTANCE + 1) * US_ROUNDTRIP_CM; // Calculate the maximum distance in uS (no rounding).
|
||||
#else
|
||||
_maxEchoTime = min(max_cm_distance, (unsigned int) MAX_SENSOR_DISTANCE) * US_ROUNDTRIP_CM + (US_ROUNDTRIP_CM / 2); // Calculate the maximum distance in uS.
|
||||
#endif
|
||||
}
|
||||
|
||||
|
||||
#if TIMER_ENABLED == true && DO_BITWISE == true
|
||||
|
||||
// ---------------------------------------------------------------------------
|
||||
// Timer interrupt ping methods (won't work with ATmega128, ATtiny and most non-AVR microcontrollers)
|
||||
// ---------------------------------------------------------------------------
|
||||
|
||||
void NewPing::ping_timer(void (*userFunc)(void), unsigned int max_cm_distance) {
|
||||
if (max_cm_distance > 0) set_max_distance(max_cm_distance); // Call function to set a new max sensor distance.
|
||||
|
||||
if (!ping_trigger()) return; // Trigger a ping, if it returns false, return without starting the echo timer.
|
||||
timer_us(ECHO_TIMER_FREQ, userFunc); // Set ping echo timer check every ECHO_TIMER_FREQ uS.
|
||||
}
|
||||
|
||||
|
||||
boolean NewPing::check_timer() {
|
||||
if (micros() > _max_time) { // Outside the time-out limit.
|
||||
timer_stop(); // Disable timer interrupt
|
||||
return false; // Cancel ping timer.
|
||||
}
|
||||
|
||||
#if URM37_ENABLED == false
|
||||
if (!(*_echoInput & _echoBit)) { // Ping echo received.
|
||||
#else
|
||||
if (*_echoInput & _echoBit) { // Ping echo received.
|
||||
#endif
|
||||
timer_stop(); // Disable timer interrupt
|
||||
ping_result = (micros() - (_max_time - _maxEchoTime) - PING_TIMER_OVERHEAD); // Calculate ping time including overhead.
|
||||
return true; // Return ping echo true.
|
||||
}
|
||||
|
||||
return false; // Return false because there's no ping echo yet.
|
||||
}
|
||||
|
||||
|
||||
// ---------------------------------------------------------------------------
|
||||
// Timer2/Timer4 interrupt methods (can be used for non-ultrasonic needs)
|
||||
// ---------------------------------------------------------------------------
|
||||
|
||||
// Variables used for timer functions
|
||||
void (*intFunc)();
|
||||
void (*intFunc2)();
|
||||
unsigned long _ms_cnt_reset;
|
||||
volatile unsigned long _ms_cnt;
|
||||
#if defined(__arm__) && (defined (TEENSYDUINO) || defined(PARTICLE))
|
||||
IntervalTimer itimer;
|
||||
#endif
|
||||
|
||||
|
||||
void NewPing::timer_us(unsigned int frequency, void (*userFunc)(void)) {
|
||||
intFunc = userFunc; // User's function to call when there's a timer event.
|
||||
timer_setup(); // Configure the timer interrupt.
|
||||
|
||||
#if defined (__AVR_ATmega32U4__) // Use Timer4 for ATmega32U4 (Teensy/Leonardo).
|
||||
OCR4C = min((frequency>>2) - 1, 255); // Every count is 4uS, so divide by 4 (bitwise shift right 2) subtract one, then make sure we don't go over 255 limit.
|
||||
TIMSK4 = (1<<TOIE4); // Enable Timer4 interrupt.
|
||||
#elif defined (__arm__) && defined (TEENSYDUINO) // Timer for Teensy 3.x
|
||||
itimer.begin(userFunc, frequency); // Really simple on the Teensy 3.x, calls userFunc every 'frequency' uS.
|
||||
#elif defined (__arm__) && defined (PARTICLE) // Timer for Particle devices
|
||||
itimer.begin(userFunc, frequency, uSec); // Really simple on the Particle, calls userFunc every 'frequency' uS.
|
||||
#else
|
||||
OCR2A = min((frequency>>2) - 1, 255); // Every count is 4uS, so divide by 4 (bitwise shift right 2) subtract one, then make sure we don't go over 255 limit.
|
||||
TIMSK2 |= (1<<OCIE2A); // Enable Timer2 interrupt.
|
||||
#endif
|
||||
}
|
||||
|
||||
|
||||
void NewPing::timer_ms(unsigned long frequency, void (*userFunc)(void)) {
|
||||
intFunc = NewPing::timer_ms_cntdwn; // Timer events are sent here once every ms till user's frequency is reached.
|
||||
intFunc2 = userFunc; // User's function to call when user's frequency is reached.
|
||||
_ms_cnt = _ms_cnt_reset = frequency; // Current ms counter and reset value.
|
||||
timer_setup(); // Configure the timer interrupt.
|
||||
|
||||
#if defined (__AVR_ATmega32U4__) // Use Timer4 for ATmega32U4 (Teensy/Leonardo).
|
||||
OCR4C = 249; // Every count is 4uS, so 1ms = 250 counts - 1.
|
||||
TIMSK4 = (1<<TOIE4); // Enable Timer4 interrupt.
|
||||
#elif defined (__arm__) && defined (TEENSYDUINO) // Timer for Teensy 3.x
|
||||
itimer.begin(NewPing::timer_ms_cntdwn, 1000); // Set timer to 1ms (1000 uS).
|
||||
#elif defined (__arm__) && defined (PARTICLE) // Timer for Particle
|
||||
itimer.begin(NewPing::timer_ms_cntdwn, 1000, uSec); // Set timer to 1ms (1000 uS).
|
||||
#else
|
||||
OCR2A = 249; // Every count is 4uS, so 1ms = 250 counts - 1.
|
||||
TIMSK2 |= (1<<OCIE2A); // Enable Timer2 interrupt.
|
||||
#endif
|
||||
}
|
||||
|
||||
|
||||
void NewPing::timer_stop() { // Disable timer interrupt.
|
||||
#if defined (__AVR_ATmega32U4__) // Use Timer4 for ATmega32U4 (Teensy/Leonardo).
|
||||
TIMSK4 = 0;
|
||||
#elif defined (__arm__) && (defined (TEENSYDUINO) || defined (PARTICLE)) // Timer for Teensy 3.x & Particle
|
||||
itimer.end();
|
||||
#else
|
||||
TIMSK2 &= ~(1<<OCIE2A);
|
||||
#endif
|
||||
}
|
||||
|
||||
|
||||
// ---------------------------------------------------------------------------
|
||||
// Timer2/Timer4 interrupt method support functions (not called directly)
|
||||
// ---------------------------------------------------------------------------
|
||||
|
||||
void NewPing::timer_setup() {
|
||||
#if defined (__AVR_ATmega32U4__) // Use Timer4 for ATmega32U4 (Teensy/Leonardo).
|
||||
timer_stop(); // Disable Timer4 interrupt.
|
||||
TCCR4A = TCCR4C = TCCR4D = TCCR4E = 0;
|
||||
TCCR4B = (1<<CS42) | (1<<CS41) | (1<<CS40) | (1<<PSR4); // Set Timer4 prescaler to 64 (4uS/count, 4uS-1020uS range).
|
||||
TIFR4 = (1<<TOV4);
|
||||
TCNT4 = 0; // Reset Timer4 counter.
|
||||
#elif defined (__AVR_ATmega8__) || defined (__AVR_ATmega16__) || defined (__AVR_ATmega32__) || defined (__AVR_ATmega8535__) // Alternate timer commands for certain microcontrollers.
|
||||
timer_stop(); // Disable Timer2 interrupt.
|
||||
ASSR &= ~(1<<AS2); // Set clock, not pin.
|
||||
TCCR2 = (1<<WGM21 | 1<<CS22); // Set Timer2 to CTC mode, prescaler to 64 (4uS/count, 4uS-1020uS range).
|
||||
TCNT2 = 0; // Reset Timer2 counter.
|
||||
#elif defined (__arm__) && (defined (TEENSYDUINO) || defined (PARTICLE))
|
||||
timer_stop(); // Stop the timer.
|
||||
#else
|
||||
timer_stop(); // Disable Timer2 interrupt.
|
||||
ASSR &= ~(1<<AS2); // Set clock, not pin.
|
||||
TCCR2A = (1<<WGM21); // Set Timer2 to CTC mode.
|
||||
TCCR2B = (1<<CS22); // Set Timer2 prescaler to 64 (4uS/count, 4uS-1020uS range).
|
||||
TCNT2 = 0; // Reset Timer2 counter.
|
||||
#endif
|
||||
}
|
||||
|
||||
|
||||
void NewPing::timer_ms_cntdwn() {
|
||||
if (!_ms_cnt--) { // Count down till we reach zero.
|
||||
intFunc2(); // Scheduled time reached, run the main timer event function.
|
||||
_ms_cnt = _ms_cnt_reset; // Reset the ms timer.
|
||||
}
|
||||
}
|
||||
|
||||
#if defined (__AVR_ATmega32U4__) // Use Timer4 for ATmega32U4 (Teensy/Leonardo).
|
||||
ISR(TIMER4_OVF_vect) {
|
||||
intFunc(); // Call wrapped function.
|
||||
}
|
||||
#elif defined (__AVR_ATmega8__) || defined (__AVR_ATmega16__) || defined (__AVR_ATmega32__) || defined (__AVR_ATmega8535__) // Alternate timer commands for certain microcontrollers.
|
||||
ISR(TIMER2_COMP_vect) {
|
||||
intFunc(); // Call wrapped function.
|
||||
}
|
||||
#elif defined (__arm__)
|
||||
// Do nothing...
|
||||
#else
|
||||
ISR(TIMER2_COMPA_vect) {
|
||||
intFunc(); // Call wrapped function.
|
||||
}
|
||||
#endif
|
||||
|
||||
|
||||
#endif
|
||||
|
||||
|
||||
// ---------------------------------------------------------------------------
|
||||
// Conversion methods (rounds result to nearest cm or inch).
|
||||
// ---------------------------------------------------------------------------
|
||||
|
||||
unsigned int NewPing::convert_cm(unsigned int echoTime) {
|
||||
#if ROUNDING_ENABLED == false
|
||||
return (echoTime / US_ROUNDTRIP_CM); // Convert uS to centimeters (no rounding).
|
||||
#else
|
||||
return NewPingConvert(echoTime, US_ROUNDTRIP_CM); // Convert uS to centimeters.
|
||||
#endif
|
||||
}
|
||||
|
||||
|
||||
unsigned int NewPing::convert_in(unsigned int echoTime) {
|
||||
#if ROUNDING_ENABLED == false
|
||||
return (echoTime / US_ROUNDTRIP_IN); // Convert uS to inches (no rounding).
|
||||
#else
|
||||
return NewPingConvert(echoTime, US_ROUNDTRIP_IN); // Convert uS to inches.
|
||||
#endif
|
||||
}
|
|
@ -0,0 +1,275 @@
|
|||
// ---------------------------------------------------------------------------
|
||||
// NewPing Library - v1.9.1 - 07/15/2018
|
||||
//
|
||||
// AUTHOR/LICENSE:
|
||||
// Created by Tim Eckel - teckel@leethost.com
|
||||
// Copyright 2018 License: Forks and derivitive works are NOT permitted without
|
||||
// permission. Permission is only granted to use as-is for private and
|
||||
// commercial use. If you wish to contribute, make changes, or enhancements,
|
||||
// please create a pull request. I get a TON of support issues from this
|
||||
// library, most of which comes from old versions, buggy forks or sites without
|
||||
// proper documentation, just trying to wrangle this project together.
|
||||
//
|
||||
// LINKS:
|
||||
// Project home: https://bitbucket.org/teckel12/arduino-new-ping/wiki/Home
|
||||
// Blog: http://arduino.cc/forum/index.php/topic,106043.0.html
|
||||
//
|
||||
// DISCLAIMER:
|
||||
// This software is furnished "as is", without technical support, and with no
|
||||
// warranty, express or implied, as to its usefulness for any purpose.
|
||||
//
|
||||
// BACKGROUND:
|
||||
// When I first received an ultrasonic sensor I was not happy with how poorly
|
||||
// it worked. Quickly I realized the problem wasn't the sensor, it was the
|
||||
// available ping and ultrasonic libraries causing the problem. The NewPing
|
||||
// library totally fixes these problems, adds many new features, and breaths
|
||||
// new life into these very affordable distance sensors.
|
||||
//
|
||||
// FEATURES:
|
||||
// * Works with many different ultrasonic sensors: SR04, SRF05, SRF06, DYP-ME007, URM37 & Parallax PING)))™.
|
||||
// * Compatible with the entire Arduino line-up (and clones), Teensy family (including $19.80 96Mhz 32 bit Teensy 3.2) and non-AVR microcontrollers.
|
||||
// * Interface with all but the SRF06 sensor using only one Arduino pin.
|
||||
// * Doesn't lag for a full second if no ping/echo is received.
|
||||
// * Ping sensors consistently and reliably at up to 30 times per second.
|
||||
// * Timer interrupt method for event-driven sketches.
|
||||
// * Built-in digital filter method ping_median() for easy error correction.
|
||||
// * Uses port registers for a faster pin interface and smaller code size.
|
||||
// * Allows you to set a maximum distance where pings beyond that distance are read as no ping "clear".
|
||||
// * Ease of using multiple sensors (example sketch with 15 sensors).
|
||||
// * More accurate distance calculation (cm, inches & uS).
|
||||
// * Doesn't use pulseIn, which is slow and gives incorrect results with some ultrasonic sensor models.
|
||||
// * Actively developed with features being added and bugs/issues addressed.
|
||||
//
|
||||
// CONSTRUCTOR:
|
||||
// NewPing sonar(trigger_pin, echo_pin [, max_cm_distance])
|
||||
// trigger_pin & echo_pin - Arduino pins connected to sensor trigger and echo.
|
||||
// NOTE: To use the same Arduino pin for trigger and echo, specify the same pin for both values.
|
||||
// max_cm_distance - [Optional] Maximum distance you wish to sense. Default=500cm.
|
||||
//
|
||||
// METHODS:
|
||||
// sonar.ping([max_cm_distance]) - Send a ping and get the echo time (in microseconds) as a result. [max_cm_distance] allows you to optionally set a new max distance.
|
||||
// sonar.ping_in([max_cm_distance]) - Send a ping and get the distance in whole inches. [max_cm_distance] allows you to optionally set a new max distance.
|
||||
// sonar.ping_cm([max_cm_distance]) - Send a ping and get the distance in whole centimeters. [max_cm_distance] allows you to optionally set a new max distance.
|
||||
// sonar.ping_median(iterations [, max_cm_distance]) - Do multiple pings (default=5), discard out of range pings and return median in microseconds. [max_cm_distance] allows you to optionally set a new max distance.
|
||||
// NewPing::convert_in(echoTime) - Convert echoTime from microseconds to inches (rounds to nearest inch).
|
||||
// NewPing::convert_cm(echoTime) - Convert echoTime from microseconds to centimeters (rounds to nearest cm).
|
||||
// sonar.ping_timer(function [, max_cm_distance]) - Send a ping and call function to test if ping is complete. [max_cm_distance] allows you to optionally set a new max distance.
|
||||
// sonar.check_timer() - Check if ping has returned within the set distance limit.
|
||||
// NewPing::timer_us(frequency, function) - Call function every frequency microseconds.
|
||||
// NewPing::timer_ms(frequency, function) - Call function every frequency milliseconds.
|
||||
// NewPing::timer_stop() - Stop the timer.
|
||||
//
|
||||
// HISTORY:
|
||||
// 07/15/2018 v1.9.1 - Added support for ATtiny441 and ATtiny841
|
||||
// microcontrollers.
|
||||
// 12/09/2017 v1.9.0 - Added support for the ARM-based Particle devices. If
|
||||
// other ARM-based microcontrollers adopt a similar timer method that the
|
||||
// Particle and Teensy 3.x share, support for other ARM-based microcontrollers
|
||||
// could be possible. Attempt to add to Arduino library manager. License
|
||||
// changed.
|
||||
// 07/30/2016 v1.8 - Added support for non-AVR microcontrollers. For non-AVR
|
||||
// microcontrollers, advanced ping_timer() timer methods are disabled due to
|
||||
// inconsistencies or no support at all between platforms. However, standard
|
||||
// ping methods are all supported. Added new optional variable to ping(),
|
||||
// ping_in(), ping_cm(), ping_median(), and ping_timer() methods which allows
|
||||
// you to set a new maximum distance for each ping. Added support for the
|
||||
// ATmega16, ATmega32 and ATmega8535 microcontrollers. Changed convert_cm()
|
||||
// and convert_in() methods to static members. You can now call them without
|
||||
// an object. For example: cm = NewPing::convert_cm(distance);
|
||||
//
|
||||
// 09/29/2015 v1.7 - Removed support for the Arduino Due and Zero because
|
||||
// they're both 3.3 volt boards and are not 5 volt tolerant while the HC-SR04
|
||||
// is a 5 volt sensor. Also, the Due and Zero don't support pin manipulation
|
||||
// compatibility via port registers which can be done (see the Teensy 3.2).
|
||||
//
|
||||
// 06/17/2014 v1.6 - Corrected delay between pings when using ping_median()
|
||||
// method. Added support for the URM37 sensor (must change URM37_ENABLED from
|
||||
// false to true). Added support for Arduino microcontrollers like the $20
|
||||
// 32 bit ARM Cortex-M4 based Teensy 3.2. Added automatic support for the
|
||||
// Atmel ATtiny family of microcontrollers. Added timer support for the
|
||||
// ATmega8 microcontroller. Rounding disabled by default, reduces compiled
|
||||
// code size (can be turned on with ROUNDING_ENABLED switch). Added
|
||||
// TIMER_ENABLED switch to get around compile-time "__vector_7" errors when
|
||||
// using the Tone library, or you can use the toneAC, NewTone or
|
||||
// TimerFreeTone libraries: https://bitbucket.org/teckel12/arduino-toneac/
|
||||
// Other speed and compiled size optimizations.
|
||||
//
|
||||
// 08/15/2012 v1.5 - Added ping_median() method which does a user specified
|
||||
// number of pings (default=5) and returns the median ping in microseconds
|
||||
// (out of range pings ignored). This is a very effective digital filter.
|
||||
// Optimized for smaller compiled size (even smaller than sketches that
|
||||
// don't use a library).
|
||||
//
|
||||
// 07/14/2012 v1.4 - Added support for the Parallax PING)))<29> sensor. Interface
|
||||
// with all but the SRF06 sensor using only one Arduino pin. You can also
|
||||
// interface with the SRF06 using one pin if you install a 0.1uf capacitor
|
||||
// on the trigger and echo pins of the sensor then tie the trigger pin to
|
||||
// the Arduino pin (doesn't work with Teensy). To use the same Arduino pin
|
||||
// for trigger and echo, specify the same pin for both values. Various bug
|
||||
// fixes.
|
||||
//
|
||||
// 06/08/2012 v1.3 - Big feature addition, event-driven ping! Uses Timer2
|
||||
// interrupt, so be mindful of PWM or timing conflicts messing with Timer2
|
||||
// may cause (namely PWM on pins 3 & 11 on Arduino, PWM on pins 9 and 10 on
|
||||
// Mega, and Tone library). Simple to use timer interrupt functions you can
|
||||
// use in your sketches totally unrelated to ultrasonic sensors (don't use if
|
||||
// you're also using NewPing's ping_timer because both use Timer2 interrupts).
|
||||
// Loop counting ping method deleted in favor of timing ping method after
|
||||
// inconsistent results kept surfacing with the loop timing ping method.
|
||||
// Conversion to cm and inches now rounds to the nearest cm or inch. Code
|
||||
// optimized to save program space and fixed a couple minor bugs here and
|
||||
// there. Many new comments added as well as line spacing to group code
|
||||
// sections for better source readability.
|
||||
//
|
||||
// 05/25/2012 v1.2 - Lots of code clean-up thanks to Arduino Forum members.
|
||||
// Rebuilt the ping timing code from scratch, ditched the pulseIn code as it
|
||||
// doesn't give correct results (at least with ping sensors). The NewPing
|
||||
// library is now VERY accurate and the code was simplified as a bonus.
|
||||
// Smaller and faster code as well. Fixed some issues with very close ping
|
||||
// results when converting to inches. All functions now return 0 only when
|
||||
// there's no ping echo (out of range) and a positive value for a successful
|
||||
// ping. This can effectively be used to detect if something is out of range
|
||||
// or in-range and at what distance. Now compatible with Arduino 0023.
|
||||
//
|
||||
// 05/16/2012 v1.1 - Changed all I/O functions to use low-level port registers
|
||||
// for ultra-fast and lean code (saves from 174 to 394 bytes). Tested on both
|
||||
// the Arduino Uno and Teensy 2.0 but should work on all Arduino-based
|
||||
// platforms because it calls standard functions to retrieve port registers
|
||||
// and bit masks. Also made a couple minor fixes to defines.
|
||||
//
|
||||
// 05/15/2012 v1.0 - Initial release.
|
||||
// ---------------------------------------------------------------------------
|
||||
|
||||
#ifndef NewPing_h
|
||||
|
||||
#define NewPing_h
|
||||
|
||||
#if defined (ARDUINO) && ARDUINO >= 100
|
||||
#include <Arduino.h>
|
||||
#else
|
||||
#include <WProgram.h>
|
||||
#if defined (PARTICLE)
|
||||
#include <SparkIntervalTimer.h>
|
||||
#else
|
||||
#include <pins_arduino.h>
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#if defined (__AVR__)
|
||||
#include <avr/io.h>
|
||||
#include <avr/interrupt.h>
|
||||
#endif
|
||||
|
||||
// Shouldn't need to change these values unless you have a specific need to do so.
|
||||
#define MAX_SENSOR_DISTANCE 500 // Maximum sensor distance can be as high as 500cm, no reason to wait for ping longer than sound takes to travel this distance and back. Default=500
|
||||
#define US_ROUNDTRIP_CM 57 // Microseconds (uS) it takes sound to travel round-trip 1cm (2cm total), uses integer to save compiled code space. Default=57
|
||||
#define US_ROUNDTRIP_IN 146 // Microseconds (uS) it takes sound to travel round-trip 1 inch (2 inches total), uses integer to save compiled code space. Defalult=146
|
||||
#define ONE_PIN_ENABLED true // Set to "false" to disable one pin mode which saves around 14-26 bytes of binary size. Default=true
|
||||
#define ROUNDING_ENABLED false // Set to "true" to enable distance rounding which also adds 64 bytes to binary size. Default=false
|
||||
#define URM37_ENABLED false // Set to "true" to enable support for the URM37 sensor in PWM mode. Default=false
|
||||
#define TIMER_ENABLED true // Set to "false" to disable the timer ISR (if getting "__vector_7" compile errors set this to false). Default=true
|
||||
|
||||
// Probably shouldn't change these values unless you really know what you're doing.
|
||||
#define NO_ECHO 0 // Value returned if there's no ping echo within the specified MAX_SENSOR_DISTANCE or max_cm_distance. Default=0
|
||||
#define MAX_SENSOR_DELAY 5800 // Maximum uS it takes for sensor to start the ping. Default=5800
|
||||
#define ECHO_TIMER_FREQ 24 // Frequency to check for a ping echo (every 24uS is about 0.4cm accuracy). Default=24
|
||||
#define PING_MEDIAN_DELAY 29000 // Microsecond delay between pings in the ping_median method. Default=29000
|
||||
#define PING_OVERHEAD 5 // Ping overhead in microseconds (uS). Default=5
|
||||
#define PING_TIMER_OVERHEAD 13 // Ping timer overhead in microseconds (uS). Default=13
|
||||
#if URM37_ENABLED == true
|
||||
#undef US_ROUNDTRIP_CM
|
||||
#undef US_ROUNDTRIP_IN
|
||||
#define US_ROUNDTRIP_CM 50 // Every 50uS PWM signal is low indicates 1cm distance. Default=50
|
||||
#define US_ROUNDTRIP_IN 127 // If 50uS is 1cm, 1 inch would be 127uS (50 x 2.54 = 127). Default=127
|
||||
#endif
|
||||
|
||||
// Conversion from uS to distance (round result to nearest cm or inch).
|
||||
#define NewPingConvert(echoTime, conversionFactor) (max(((unsigned int)echoTime + conversionFactor / 2) / conversionFactor, (echoTime ? 1 : 0)))
|
||||
|
||||
// Detect non-AVR microcontrollers (Teensy 3.x, Arduino DUE, etc.) and don't use port registers or timer interrupts as required.
|
||||
#if (defined (__arm__) && (defined (TEENSYDUINO) || defined (PARTICLE)))
|
||||
#undef PING_OVERHEAD
|
||||
#define PING_OVERHEAD 1
|
||||
#undef PING_TIMER_OVERHEAD
|
||||
#define PING_TIMER_OVERHEAD 1
|
||||
#define DO_BITWISE true
|
||||
#elif !defined (__AVR__)
|
||||
#undef PING_OVERHEAD
|
||||
#define PING_OVERHEAD 1
|
||||
#undef PING_TIMER_OVERHEAD
|
||||
#define PING_TIMER_OVERHEAD 1
|
||||
#undef TIMER_ENABLED
|
||||
#define TIMER_ENABLED false
|
||||
#define DO_BITWISE false
|
||||
#else
|
||||
#define DO_BITWISE true
|
||||
#endif
|
||||
|
||||
// Disable the timer interrupts when using ATmega128 and all ATtiny microcontrollers.
|
||||
#if defined (__AVR_ATmega128__) || defined (__AVR_ATtiny24__) || defined (__AVR_ATtiny44__) || defined (__AVR_ATtiny441__) || defined (__AVR_ATtiny84__) || defined (__AVR_ATtiny841__) || defined (__AVR_ATtiny25__) || defined (__AVR_ATtiny45__) || defined (__AVR_ATtiny85__) || defined (__AVR_ATtiny261__) || defined (__AVR_ATtiny461__) || defined (__AVR_ATtiny861__) || defined (__AVR_ATtiny43U__)
|
||||
#undef TIMER_ENABLED
|
||||
#define TIMER_ENABLED false
|
||||
#endif
|
||||
|
||||
// Define timers when using ATmega8, ATmega16, ATmega32 and ATmega8535 microcontrollers.
|
||||
#if defined (__AVR_ATmega8__) || defined (__AVR_ATmega16__) || defined (__AVR_ATmega32__) || defined (__AVR_ATmega8535__)
|
||||
#define OCR2A OCR2
|
||||
#define TIMSK2 TIMSK
|
||||
#define OCIE2A OCIE2
|
||||
#endif
|
||||
|
||||
class NewPing {
|
||||
public:
|
||||
NewPing(uint8_t trigger_pin, uint8_t echo_pin, unsigned int max_cm_distance = MAX_SENSOR_DISTANCE);
|
||||
unsigned int ping(unsigned int max_cm_distance = 0);
|
||||
unsigned long ping_cm(unsigned int max_cm_distance = 0);
|
||||
unsigned long ping_in(unsigned int max_cm_distance = 0);
|
||||
unsigned long ping_median(uint8_t it = 5, unsigned int max_cm_distance = 0);
|
||||
static unsigned int convert_cm(unsigned int echoTime);
|
||||
static unsigned int convert_in(unsigned int echoTime);
|
||||
#if TIMER_ENABLED == true
|
||||
void ping_timer(void (*userFunc)(void), unsigned int max_cm_distance = 0);
|
||||
boolean check_timer();
|
||||
unsigned long ping_result;
|
||||
static void timer_us(unsigned int frequency, void (*userFunc)(void));
|
||||
static void timer_ms(unsigned long frequency, void (*userFunc)(void));
|
||||
static void timer_stop();
|
||||
#endif
|
||||
private:
|
||||
boolean ping_trigger();
|
||||
void set_max_distance(unsigned int max_cm_distance);
|
||||
#if TIMER_ENABLED == true
|
||||
boolean ping_trigger_timer(unsigned int trigger_delay);
|
||||
boolean ping_wait_timer();
|
||||
static void timer_setup();
|
||||
static void timer_ms_cntdwn();
|
||||
#endif
|
||||
#if DO_BITWISE == true
|
||||
uint8_t _triggerBit;
|
||||
uint8_t _echoBit;
|
||||
#if defined(PARTICLE)
|
||||
#if !defined(portModeRegister)
|
||||
#if defined (STM32F10X_MD)
|
||||
#define portModeRegister(port) ( &(port->CRL) )
|
||||
#elif defined (STM32F2XX)
|
||||
#define portModeRegister(port) ( &(port->MODER) )
|
||||
#endif
|
||||
#endif
|
||||
volatile uint32_t *_triggerOutput;
|
||||
volatile uint32_t *_echoInput;
|
||||
volatile uint32_t *_triggerMode;
|
||||
#else
|
||||
volatile uint8_t *_triggerOutput;
|
||||
volatile uint8_t *_echoInput;
|
||||
volatile uint8_t *_triggerMode;
|
||||
#endif
|
||||
#else
|
||||
uint8_t _triggerPin;
|
||||
uint8_t _echoPin;
|
||||
#endif
|
||||
unsigned int _maxEchoTime;
|
||||
unsigned long _max_time;
|
||||
};
|
||||
|
||||
|
||||
#endif
|
|
@ -18,6 +18,8 @@
|
|||
*/
|
||||
|
||||
#ifdef USE_SR04
|
||||
|
||||
#include <NewPing.h>
|
||||
/*********************************************************************************************\
|
||||
* HC-SR04, HC-SR04+, JSN-SR04T - Ultrasonic distance sensor
|
||||
*
|
||||
|
@ -26,124 +28,43 @@
|
|||
* - https://www.dfrobot.com/wiki/index.php/Weather-proof_Ultrasonic_Sensor_SKU_:_SEN0207
|
||||
\*********************************************************************************************/
|
||||
|
||||
#define XSNS_22 22
|
||||
|
||||
uint8_t sr04_echo_pin = 0;
|
||||
uint8_t sr04_trig_pin = 0;
|
||||
real64_t distance;
|
||||
|
||||
/*********************************************************************************************\
|
||||
* Embedded stripped and tuned NewPing library from Tim Eckel - teckel@leethost.com
|
||||
* https://bitbucket.org/teckel12/arduino-new-ping
|
||||
\*********************************************************************************************/
|
||||
#define US_ROUNDTRIP_CM 58 // Microseconds (uS) it takes sound to travel round-trip 1cm (2cm total), uses integer to save compiled code space. Default: 58
|
||||
#define US_ROUNDTRIP_IN 148 // Microseconds (uS) it takes sound to travel round-trip 1 inch (2 inches total), uses integer to save compiled code space. Default: 148
|
||||
#define PING_MEDIAN_DELAY 29000
|
||||
#define MAX_SENSOR_DISTANCE 500
|
||||
#define PING_OVERHEAD 5
|
||||
|
||||
// Conversion from uS to distance (round result to nearest cm or inch).
|
||||
#define EchoConvert(echoTime, conversionFactor) (tmax(((unsigned int)echoTime + conversionFactor / 2) / conversionFactor, (echoTime ? 1 : 0)))
|
||||
|
||||
/********************************************************************************************/
|
||||
NewPing* sonar = NULL;
|
||||
|
||||
void Sr04Init(void)
|
||||
{
|
||||
sr04_echo_pin = pin[GPIO_SR04_ECHO];
|
||||
sr04_trig_pin = pin[GPIO_SR04_TRIG];
|
||||
pinMode(sr04_trig_pin, OUTPUT);
|
||||
pinMode(sr04_echo_pin, INPUT_PULLUP);
|
||||
}
|
||||
|
||||
boolean Sr04Read(uint16_t *distance)
|
||||
{
|
||||
uint16_t duration = 0;
|
||||
|
||||
*distance = 0;
|
||||
|
||||
/* Send ping and get delay */
|
||||
duration = Sr04GetSamples(9, 250);
|
||||
|
||||
/* Calculate the distance (in cm) based on the speed of sound. */
|
||||
*distance = EchoConvert(duration, US_ROUNDTRIP_CM);
|
||||
|
||||
return 1;
|
||||
}
|
||||
|
||||
uint16_t Sr04Ping(uint16_t max_cm_distance)
|
||||
{
|
||||
uint16_t duration = 0;
|
||||
uint16_t maxEchoTime;
|
||||
|
||||
maxEchoTime = tmin(max_cm_distance + 1, (uint16_t) MAX_SENSOR_DISTANCE + 1) * US_ROUNDTRIP_CM;
|
||||
|
||||
/* The following trigPin/echoPin cycle is used to determine the
|
||||
distance of the nearest object by bouncing soundwaves off of it. */
|
||||
digitalWrite(sr04_trig_pin, LOW);
|
||||
delayMicroseconds(2);
|
||||
digitalWrite(sr04_trig_pin, HIGH);
|
||||
delayMicroseconds(10);
|
||||
digitalWrite(sr04_trig_pin, LOW);
|
||||
|
||||
/* Wait for the echo */
|
||||
duration = pulseIn(sr04_echo_pin, HIGH, 26000) - PING_OVERHEAD;
|
||||
|
||||
return (duration > maxEchoTime) ? 0 : duration;
|
||||
}
|
||||
|
||||
uint16_t Sr04GetSamples(uint8_t it, uint16_t max_cm_distance)
|
||||
{
|
||||
uint16_t uS[it];
|
||||
uint16_t last;
|
||||
uint8_t j;
|
||||
uint8_t i = 0;
|
||||
uint16_t t;
|
||||
uS[0] = 0;
|
||||
|
||||
while (i < it) {
|
||||
t = micros();
|
||||
last = Sr04Ping(max_cm_distance);
|
||||
|
||||
if (last != 0) {
|
||||
if (i > 0) {
|
||||
for (j = i; j > 0 && uS[j - 1] < last; j--) {
|
||||
uS[j] = uS[j - 1];
|
||||
}
|
||||
} else {
|
||||
j = 0;
|
||||
}
|
||||
uS[j] = last;
|
||||
i++;
|
||||
} else {
|
||||
it--;
|
||||
}
|
||||
if (i < it && micros() - t < PING_MEDIAN_DELAY) {
|
||||
delay((PING_MEDIAN_DELAY + t - micros()) / 1000);
|
||||
}
|
||||
}
|
||||
|
||||
return (uS[1]); // Return the ping distance from the 2nd highest reading
|
||||
sonar = new NewPing(sr04_trig_pin, sr04_echo_pin, 300);
|
||||
}
|
||||
|
||||
#ifdef USE_WEBSERVER
|
||||
const char HTTP_SNS_DISTANCE[] PROGMEM =
|
||||
"%s{s}SR04 " D_DISTANCE "{m}%d" D_UNIT_CENTIMETER "{e}"; // {s} = <tr><th>, {m} = </th><td>, {e} = </td></tr>
|
||||
"%s{s}SR04 " D_DISTANCE "{m}%s" D_UNIT_CENTIMETER "{e}"; // {s} = <tr><th>, {m} = </th><td>, {e} = </td></tr>
|
||||
#endif // USE_WEBSERVER
|
||||
|
||||
void Sr04Show(boolean json)
|
||||
{
|
||||
uint16_t distance;
|
||||
distance = (real64_t)(sonar->ping_median(5))/ US_ROUNDTRIP_CM;
|
||||
|
||||
if (distance != 0) { // Check if read failed
|
||||
char distance_chr[10];
|
||||
|
||||
dtostrfd(distance, 3, distance_chr);
|
||||
|
||||
if (Sr04Read(&distance)) { // Check if read failed
|
||||
if(json) {
|
||||
snprintf_P(mqtt_data, sizeof(mqtt_data), PSTR("%s,\"SR04\":{\"" D_JSON_DISTANCE "\":%d}"), mqtt_data, distance);
|
||||
snprintf_P(mqtt_data, sizeof(mqtt_data), PSTR("%s,\"SR04\":{\"" D_JSON_DISTANCE "\":%s}"), mqtt_data, distance_chr);
|
||||
#ifdef USE_DOMOTICZ
|
||||
if (0 == tele_period) {
|
||||
DomoticzSensor(DZ_COUNT, distance); // Send distance as Domoticz Counter value
|
||||
DomoticzSensor(DZ_COUNT, distance_chr); // Send distance as Domoticz Counter value
|
||||
}
|
||||
#endif // USE_DOMOTICZ
|
||||
#ifdef USE_WEBSERVER
|
||||
} else {
|
||||
snprintf_P(mqtt_data, sizeof(mqtt_data), HTTP_SNS_DISTANCE, mqtt_data, distance);
|
||||
snprintf_P(mqtt_data, sizeof(mqtt_data), HTTP_SNS_DISTANCE, mqtt_data, distance_chr);
|
||||
#endif // USE_WEBSERVER
|
||||
}
|
||||
}
|
||||
|
@ -153,6 +74,8 @@ void Sr04Show(boolean json)
|
|||
* Interface
|
||||
\*********************************************************************************************/
|
||||
|
||||
#define XSNS_22
|
||||
|
||||
boolean Xsns22(byte function)
|
||||
{
|
||||
boolean result = false;
|
||||
|
|
Loading…
Reference in New Issue