mirror of
https://github.com/YikeStone/ros_arduino_bridge.git
synced 2025-08-04 03:34:08 +05:30
Updated formula for computing distance for the Sharp GP2D12 IR range sensor
This commit is contained in:
parent
3f98ea4df8
commit
1289091111
@ -22,6 +22,7 @@
|
|||||||
import rospy
|
import rospy
|
||||||
from sensor_msgs.msg import Range
|
from sensor_msgs.msg import Range
|
||||||
from ros_arduino_msgs.msg import *
|
from ros_arduino_msgs.msg import *
|
||||||
|
from math import pow
|
||||||
|
|
||||||
LOW = 0
|
LOW = 0
|
||||||
HIGH = 1
|
HIGH = 1
|
||||||
@ -210,12 +211,14 @@ 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.
|
# The GP2D12 cannot provide a meaning result closer than 3 cm.
|
||||||
if value <= 3.0:
|
if value <= 3.0:
|
||||||
return float('NaN')
|
return float('NaN')
|
||||||
|
|
||||||
try:
|
try:
|
||||||
distance = (6787.0 / (float(value) - 3.0)) - 4.0
|
distance = pow(4187.8 / value, 1.106)
|
||||||
|
#distance = (6787.0 / (float(value) - 3.0)) - 4.0
|
||||||
except:
|
except:
|
||||||
return float('NaN')
|
return float('NaN')
|
||||||
|
|
||||||
|
Loading…
x
Reference in New Issue
Block a user