]> defiant.homedns.org Git - ros_wild_thumper.git/blobdiff - scripts/wt_node.py
remove ir sensors
[ros_wild_thumper.git] / scripts / wt_node.py
index 03d61be0b722cc5b7399e8068f29fb45a6c0087a..2969d613c7f11a06e81ac6efe17d740f059cf80f 100755 (executable)
@@ -37,8 +37,6 @@ class WTBase:
                self.pub_range_fwd_left = rospy.Publisher("range_forward_left", Range, queue_size=16)
                self.pub_range_fwd_right = rospy.Publisher("range_forward_right", Range, queue_size=16)
                self.pub_range_bwd = rospy.Publisher("range_backward", Range, queue_size=16)
-               self.pub_range_left = rospy.Publisher("range_left", Range, queue_size=16)
-               self.pub_range_right = rospy.Publisher("range_right", Range, queue_size=16)
                self.pub_battery = rospy.Publisher("battery", BatteryState, queue_size=16)
                self.cmd_vel = None
                self.cur_vel = (0, 0)
@@ -313,18 +311,6 @@ class WTBase:
                msg.range = dist
                pub.publish(msg)
 
-       def get_dist_left(self):
-               if self.pub_range_left.get_num_connections() > 0:
-                       dist = self.get_dist_ir(0x1)
-                       if dist > -67:
-                               self.send_range(self.pub_range_left, "ir_left", Range.INFRARED, 30.553/(dist - -67.534), 0.04, 0.3, 1)
-
-       def get_dist_right(self):
-               if self.pub_range_right.get_num_connections() > 0:
-                       dist = self.get_dist_ir(0x3)
-                       if dist > 69:
-                               self.send_range(self.pub_range_right, "ir_right", Range.INFRARED, 17.4/(dist - 69), 0.04, 0.3, 1)
-
        def get_dist_forward_left(self):
                if self.pub_range_fwd_left.get_num_connections() > 0:
                        dist = self.read_dist_srf(0x15)