]> defiant.homedns.org Git - ros_wild_thumper.git/blobdiff - scripts/wt_node.py
enabled range sensor layer
[ros_wild_thumper.git] / scripts / wt_node.py
index 96d07689809932aee4722db7e37e4627e25615d8..a2a09ba1854a79694a98e4d1afbba89478bfde56 100755 (executable)
@@ -151,7 +151,7 @@ class MoveBase:
                odom.pose.covariance[14] = 1e6 # z
                odom.pose.covariance[21] = 1e6 # rotation about X axis
                odom.pose.covariance[28] = 1e6 # rotation about Y axis
-               odom.pose.covariance[35] = 0.1 # rotation about Z axis
+               odom.pose.covariance[35] = 0.03 # rotation about Z axis
 
                # set the velocity
                odom.child_frame_id = "base_footprint"
@@ -163,7 +163,7 @@ class MoveBase:
                odom.twist.covariance[14] = 1e6 # z
                odom.twist.covariance[21] = 1e6 # rotation about X axis
                odom.twist.covariance[28] = 1e6 # rotation about Y axis
-               odom.twist.covariance[35] = 0.1 # rotation about Z axis
+               odom.twist.covariance[35] = 0.03 # rotation about Z axis
 
                # publish the message
                self.pub_odom.publish(odom)
@@ -231,12 +231,12 @@ class MoveBase:
        def get_dist_forward(self):
                if self.pub_range_fwd.get_num_connections() > 0:
                        dist = self.get_dist_srf(0x5)
-                       self.send_range(self.pub_range_fwd, "sonar_forward", Range.ULTRASOUND, dist, 0.04, 6, 60)
+                       self.send_range(self.pub_range_fwd, "sonar_forward", Range.ULTRASOUND, dist, 0.04, 6, 30)
 
        def get_dist_backward(self):
                if self.pub_range_bwd.get_num_connections() > 0:
                        dist = self.get_dist_srf(0x7)
-                       self.send_range(self.pub_range_bwd, "sonar_backward", Range.ULTRASOUND, dist, 0.04, 6, 60)
+                       self.send_range(self.pub_range_bwd, "sonar_backward", Range.ULTRASOUND, dist, 0.04, 6, 30)
                
 
 if __name__ == "__main__":