]> defiant.homedns.org Git - ros_wild_thumper.git/blobdiff - scripts/wt_node.py
added gps_follow_waypoints script
[ros_wild_thumper.git] / scripts / wt_node.py
index 50cde9f5af3b10b75281767562a0924bd14747c5..1cf9d8d49fc42608ca1db0b1a0ed69873a95e4ef 100755 (executable)
@@ -12,9 +12,9 @@ from math import *
 from geometry_msgs.msg import Twist
 from nav_msgs.msg import Odometry
 from diagnostic_msgs.msg import DiagnosticArray, DiagnosticStatus, KeyValue
+from dynamic_reconfigure.server import Server
 from sensor_msgs.msg import Imu, Range
 from wild_thumper.msg import LedStripe
-from dynamic_reconfigure.server import Server
 from wild_thumper.cfg import WildThumperConfig
 
 WHEEL_DIST = 0.248
@@ -31,7 +31,7 @@ class LPD8806:
                self.update()
        
        def set(self, i, red=0, green=0, blue=0):
-               if red > 127 or green > 127 or blue >> 127 or red < 0 or green < 0 or blue < 0:
+               if red > 127 or green > 127 or blue > 127 or red < 0 or green < 0 or blue < 0:
                        raise Exception("Bad RGB Value")
                self.l[i] = (red, green, blue)
 
@@ -96,16 +96,19 @@ class MoveBase:
                                ir_count+=1
                        else:
                                self.get_dist_right()
-                               ir_count+=1
+                               ir_count=0
 
                        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()
+                               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
@@ -255,7 +258,7 @@ class MoveBase:
 
        def cmdVelReceived(self, msg):
                if not self.bMotorManual:
-                       rospy.logdebug("Set new cmd_vel:", msg.linear.x, msg.angular.z)
+                       rospy.logdebug("Set new cmd_vel: %.2f %.2f", msg.linear.x, msg.angular.z)
                        self.cmd_vel = (msg.linear.x, msg.angular.z) # commit speed on next update cycle
                        rospy.logdebug("Set new cmd_vel done")
 
@@ -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)
-                       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)
-                       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, "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: