From 7bb28d5ff12d8d40d2f5f8c2a40ba99d585ebffd Mon Sep 17 00:00:00 2001 From: Stormiix Date: Tue, 25 Feb 2020 22:54:09 +0100 Subject: [PATCH 1/2] Remove previous scans from scan message --- src/ping360_sonar/node.py | 15 ++++++--------- 1 file changed, 6 insertions(+), 9 deletions(-) diff --git a/src/ping360_sonar/node.py b/src/ping360_sonar/node.py index 4b0bae9..22c20bb 100644 --- a/src/ping360_sonar/node.py +++ b/src/ping360_sonar/node.py @@ -149,8 +149,8 @@ def main(): # Initial the LaserScan Intensities & Ranges angle_increment = 2 * pi * step / 400 - ranges = [0] * (FOV // step) - intensities = [0] * (FOV // step) + ranges = [0] + intensities = [0] # Center point coordinates center = (float(imgSize / 2), float(imgSize / 2)) @@ -164,8 +164,6 @@ def main(): transmitDuration, samplePeriod, numberOfSamples) angle_increment = 2 * pi * step / 400 - ranges = [0] * (FOV // step) - intensities = [0] * (FOV // step) # Get sonar response data = getSonarData(sensor, angle) @@ -177,7 +175,6 @@ def main(): # Prepare scan msg if enableScanTopic: - index = int(((angle - minAngle) * 2 * pi / 400) / angle_increment) # Get the first high intensity value for detectedIntensity in data: if detectedIntensity >= threshold: @@ -186,12 +183,12 @@ def main(): distance = calculateRange( (1 + detectedIndex), samplePeriod, speedOfSound) if distance >= 0.75 and distance <= sonarRange: - ranges[index] = distance - intensities[index] = detectedIntensity + ranges[0] = distance + intensities[0] = detectedIntensity if debug: print("Object at {} grad : {}m - {}%".format(angle, - ranges[index], - float(intensities[index] * 100 / 255))) + ranges[0], + float(intensities[0] * 100 / 255))) break # Contruct and publish Sonar scan msg scanDataMsg = generateScanMsg(ranges, intensities, sonarRange, step, maxAngle, minAngle) From 72efcdef59a4ff681935c1dd6e706bbcb30cfd11 Mon Sep 17 00:00:00 2001 From: Stormiix Date: Fri, 27 Mar 2020 21:44:08 +0100 Subject: [PATCH 2/2] chore: readme update and code cleanup --- README.md | 21 +++++++++++++-------- src/ping360_sonar/node.py | 8 ++------ 2 files changed, 15 insertions(+), 14 deletions(-) diff --git a/README.md b/README.md index 3f8fc34..749c528 100644 --- a/README.md +++ b/README.md @@ -68,19 +68,24 @@ Run the main node with: ![alt img](https://github.com/CentraleNantesRobotics/ping360_sonar/blob/master/img/print.png) + +Three extra parameters can be set to toggle specific topics, they are set to true by default. - Three extra parameters can be set to toggle specific topics, they are set to true by default. - - - - + + + - By default, the sensor does a full 360° rotation, but that can be changed by modifying the min and max scan angle values. +By default, the sensor does a full 360° rotation, but that can be changed by modifying the min and max scan angle values. - - Please note that these angle value are in GRAD and not DEG. + +Please note that these angle value are in GRAD and not DEG. + +You can also enable or disable the sensor oscillation by setting the **oscillate** parameter. + + + ## Nodes diff --git a/src/ping360_sonar/node.py b/src/ping360_sonar/node.py index 9a63fb4..91c3844 100644 --- a/src/ping360_sonar/node.py +++ b/src/ping360_sonar/node.py @@ -151,7 +151,6 @@ def main(): image = np.zeros((imgSize, imgSize, 1), np.uint8) # Initial the LaserScan Intensities & Ranges - angle_increment = 2 * pi * step / 400 ranges = [0] intensities = [0] @@ -165,9 +164,6 @@ def main(): if updated: updateSonarConfig(sensor, gain, transmitFrequency, transmitDuration, samplePeriod, numberOfSamples) - - angle_increment = 2 * pi * step / 400 - # Get sonar response data = getSonarData(sensor, angle) @@ -220,14 +216,14 @@ def main(): publishImage(image, imagePub, bridge) angle += sign * step - if angle > maxAngle: + if angle >= maxAngle: if not oscillate: angle = minAngle else: angle = maxAngle sign = -1 - if angle < minAngle and oscillate: + if angle <= minAngle and oscillate: sign = 1 angle = minAngle