]> defiant.homedns.org Git - ros_wild_thumper.git/blobdiff - scripts/wt_node.py
Revert pid changes and update steps per m
[ros_wild_thumper.git] / scripts / wt_node.py
index fcb20be43f2a8fd1795b19a66590a7c79ea70873..1cf9d8d49fc42608ca1db0b1a0ed69873a95e4ef 100755 (executable)
@@ -100,12 +100,15 @@ class MoveBase:
 
                        if sonar_count == 0:
                                self.get_dist_forward_left()
+                               self.update_dist_backward()
                                sonar_count+=1
                        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()
+                               self.update_dist_forward_left()
                                sonar_count=0
 
                        if self.cmd_vel != None:
@@ -234,9 +237,9 @@ class MoveBase:
                odom.pose.pose.orientation.w = odom_quat[3]
                odom.pose.covariance[0] = self.odom_covar_xy # x
                odom.pose.covariance[7] = self.odom_covar_xy # y
-               odom.pose.covariance[14] = 99999 # z
-               odom.pose.covariance[21] = 99999 # rotation about X axis
-               odom.pose.covariance[28] = 99999 # rotation about Y axis
+               odom.pose.covariance[14] = self.odom_covar_xy # z
+               odom.pose.covariance[21] = self.odom_covar_angle # rotation about X axis
+               odom.pose.covariance[28] = self.odom_covar_angle # rotation about Y axis
                odom.pose.covariance[35] = self.odom_covar_angle # rotation about Z axis
 
                # set the velocity
@@ -313,19 +316,28 @@ class MoveBase:
                if self.pub_range_fwd_left.get_num_connections() > 0:
                        dist = self.read_dist_srf(0x15)
                        self.send_range(self.pub_range_fwd_left, "sonar_forward_left", Range.ULTRASOUND, dist, 0.04, self.range_sensor_max, 30)
-                       self.start_dist_srf(0x5) # get next value
+
+       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)
-                       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)
                        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
+
+       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: