]> defiant.homedns.org Git - ros_wild_thumper.git/blobdiff - scripts/wt_node.py
Update srf sensors closer to readout
[ros_wild_thumper.git] / scripts / wt_node.py
index bbda8488780341b9167365e8b77c5cad3477cc18..1549ea6f7aad56b906c7ad18321dd5857fadd882 100755 (executable)
@@ -96,16 +96,19 @@ class MoveBase:
                                ir_count+=1
                        else:
                                self.get_dist_right()
                                ir_count+=1
                        else:
                                self.get_dist_right()
-                               ir_count+=1
+                               ir_count=0
 
                        if sonar_count == 0:
                                self.get_dist_forward_left()
 
                        if sonar_count == 0:
                                self.get_dist_forward_left()
-                               sonar_count=0
+                               self.update_dist_backward()
+                               sonar_count+=1
                        elif sonar_count == 1:
                                self.get_dist_backward()
                        elif sonar_count == 1:
                                self.get_dist_backward()
+                               self.update_dist_forward_right()
                                sonar_count+=1
                        elif sonar_count == 2:
                                self.get_dist_forward_right()
                                sonar_count+=1
                        elif sonar_count == 2:
                                self.get_dist_forward_right()
+                               self.update_dist_forward_left()
                                sonar_count=0
 
                        if self.cmd_vel != None:
                                sonar_count=0
 
                        if self.cmd_vel != None:
@@ -312,20 +315,29 @@ class MoveBase:
        def get_dist_forward_left(self):
                if self.pub_range_fwd_left.get_num_connections() > 0:
                        dist = self.read_dist_srf(0x15)
        def get_dist_forward_left(self):
                if self.pub_range_fwd_left.get_num_connections() > 0:
                        dist = self.read_dist_srf(0x15)
-                       self.send_range(self.pub_range_fwd, "sonar_forward_left", Range.ULTRASOUND, dist, 0.04, self.range_sensor_max, 30)
-                       self.start_dist_srf(0x5) # get next value
+                       self.send_range(self.pub_range_fwd_left, "sonar_forward_left", Range.ULTRASOUND, dist, 0.04, self.range_sensor_max, 30)
+
+       def update_dist_forward_left(self):
+               if self.pub_range_fwd_left.get_num_connections() > 0:
+                       self.start_dist_srf(0x5)
 
        def get_dist_backward(self):
                if self.pub_range_bwd.get_num_connections() > 0:
                        dist = self.read_dist_srf(0x17)
                        self.send_range(self.pub_range_bwd, "sonar_backward", Range.ULTRASOUND, dist, 0.04, self.range_sensor_max, 30)
 
        def get_dist_backward(self):
                if self.pub_range_bwd.get_num_connections() > 0:
                        dist = self.read_dist_srf(0x17)
                        self.send_range(self.pub_range_bwd, "sonar_backward", Range.ULTRASOUND, dist, 0.04, self.range_sensor_max, 30)
-                       self.start_dist_srf(0x7) # get next value
+
+       def update_dist_backward(self):
+               if self.pub_range_bwd.get_num_connections() > 0:
+                       self.start_dist_srf(0x7)
 
        def get_dist_forward_right(self):
                if self.pub_range_fwd_right.get_num_connections() > 0:
                        dist = self.read_dist_srf(0x19)
 
        def get_dist_forward_right(self):
                if self.pub_range_fwd_right.get_num_connections() > 0:
                        dist = self.read_dist_srf(0x19)
-                       self.send_range(self.pub_range_fwd, "sonar_forward_right", Range.ULTRASOUND, dist, 0.04, self.range_sensor_max, 30)
-                       self.start_dist_srf(0x9) # get next value
+                       self.send_range(self.pub_range_fwd_right, "sonar_forward_right", Range.ULTRASOUND, dist, 0.04, self.range_sensor_max, 30)
+
+       def update_dist_forward_right(self):
+               if self.pub_range_fwd_right.get_num_connections() > 0:
+                       self.start_dist_srf(0xb)
        
        def led_stripe_received(self, msg):
                for led in msg.leds:
        
        def led_stripe_received(self, msg):
                for led in msg.leds: