mirror of
https://github.com/YikeStone/ros_arduino_bridge.git
synced 2025-08-05 20:14:07 +05:30
Changed return value for GP2D12 IR sensor from max_range to NaN when raw values are out of range
This commit is contained in:
parent
828984dd96
commit
3f98ea4df8
@ -210,20 +210,21 @@ class GP2D12(IRSensor):
|
|||||||
def read_value(self):
|
def read_value(self):
|
||||||
value = self.controller.analog_read(self.pin)
|
value = self.controller.analog_read(self.pin)
|
||||||
|
|
||||||
|
# The GP2D12 cannot provide a meaning result closer than 3 cm.
|
||||||
if value <= 3.0:
|
if value <= 3.0:
|
||||||
return self.msg.max_range
|
return float('NaN')
|
||||||
|
|
||||||
try:
|
try:
|
||||||
distance = (6787.0 / (float(value) - 3.0)) - 4.0
|
distance = (6787.0 / (float(value) - 3.0)) - 4.0
|
||||||
except:
|
except:
|
||||||
return self.msg.max_range
|
return float('NaN')
|
||||||
|
|
||||||
# Convert to meters
|
# Convert to meters
|
||||||
distance /= 100.0
|
distance /= 100.0
|
||||||
|
|
||||||
# If we get a spurious reading, set it to the max_range
|
# If we get a spurious reading, set it to the max_range
|
||||||
if distance > self.msg.max_range: distance = self.msg.max_range
|
if distance > self.msg.max_range: distance = float('NaN')
|
||||||
if distance < self.msg.min_range: distance = self.msg.max_range
|
if distance < self.msg.min_range: distance = float('NaN')
|
||||||
|
|
||||||
return distance
|
return distance
|
||||||
|
|
||||||
|
Loading…
x
Reference in New Issue
Block a user