]> defiant.homedns.org Git - ros_wild_thumper.git/blobdiff - scripts/wt_node.py
Move forward sonars 2cm more apart
[ros_wild_thumper.git] / scripts / wt_node.py
index fcb20be43f2a8fd1795b19a66590a7c79ea70873..5215d49ca5d3e7dd68fb751181f0fac9d8f197cd 100755 (executable)
@@ -325,7 +325,7 @@ class MoveBase:
                if self.pub_range_fwd_right.get_num_connections() > 0:
                        dist = self.read_dist_srf(0x19)
                        self.send_range(self.pub_range_fwd_right, "sonar_forward_right", Range.ULTRASOUND, dist, 0.04, self.range_sensor_max, 30)
                if self.pub_range_fwd_right.get_num_connections() > 0:
                        dist = self.read_dist_srf(0x19)
                        self.send_range(self.pub_range_fwd_right, "sonar_forward_right", Range.ULTRASOUND, dist, 0.04, self.range_sensor_max, 30)
-                       self.start_dist_srf(0x9) # get next value
+                       self.start_dist_srf(0xb) # get next value
        
        def led_stripe_received(self, msg):
                for led in msg.leds:
        
        def led_stripe_received(self, msg):
                for led in msg.leds: