]> defiant.homedns.org Git - ros_wild_thumper.git/blobdiff - scripts/wt_node.py
motor_ctrl: pid tuning data and added helper script
[ros_wild_thumper.git] / scripts / wt_node.py
index 5056107206766930273850efc4dc6a8ce579a222..a5978b032850342b1a0e3ad04e03f72a408ba584 100755 (executable)
@@ -5,21 +5,51 @@ import rospy
 import tf
 import struct
 import prctl
-from i2c import *
+import spidev
+from time import sleep
+from i2c import i2c, i2c_write_reg, i2c_read_reg
 from math import *
 from geometry_msgs.msg import Twist
 from nav_msgs.msg import Odometry
 from diagnostic_msgs.msg import DiagnosticArray, DiagnosticStatus, KeyValue
 from sensor_msgs.msg import Imu, Range
+from wild_thumper.msg import LedStripe
 
 WHEEL_DIST = 0.248
 
+class LPD8806:
+       def __init__(self, bus, device, num_leds):
+               self.spi = spidev.SpiDev()
+               self.spi.open(bus, device)
+               self.spi.mode=0b00
+               self.spi.max_speed_hz=int(2e6)
+               self.num_leds = num_leds
+               self.latch()
+               self.l = [(0, 0, 0)] * num_leds
+               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:
+                       raise Exception("Bad RGB Value")
+               self.l[i] = (red, green, blue)
+
+       def latch(self):
+               self.spi.writebytes([0x0 for i in range((self.num_leds+31)/32)])
+       
+       def update(self):
+               l = []
+               for i in range(self.num_leds):
+                       red, green, blue = self.l[i]
+                       l.append(0x80 | green)
+                       l.append(0x80 | red)
+                       l.append(0x80 | blue)
+               self.spi.writebytes(l)
+               self.latch()
+
 class MoveBase:
        def __init__(self):
                rospy.init_node('wild_thumper')
                prctl.set_name("wild_thumper")
-               rospy.Subscriber("cmd_vel_out", Twist, self.cmdVelReceived)
-               rospy.Subscriber("imu", Imu, self.imuReceived)
                enable_odom_tf = rospy.get_param("~enable_odom_tf", True)
                if enable_odom_tf:
                        self.tf_broadcaster = tf.broadcaster.TransformBroadcaster()
@@ -31,14 +61,20 @@ class MoveBase:
                self.pub_range_bwd = rospy.Publisher("range_backward", Range, queue_size=16)
                self.pub_range_left = rospy.Publisher("range_left", Range, queue_size=16)
                self.pub_range_right = rospy.Publisher("range_right", Range, queue_size=16)
+               self.cmd_vel = None
                self.set_speed(0, 0)
                rospy.loginfo("Init done")
                i2c_write_reg(0x50, 0x90, struct.pack("BB", 1, 1)) # switch direction
                self.handicap_last = (-1, -1)
+               self.pStripe = LPD8806(1, 0, 12)
+               rospy.Subscriber("cmd_vel_out", Twist, self.cmdVelReceived)
+               rospy.Subscriber("imu", Imu, self.imuReceived)
+               rospy.Subscriber("led_stripe", LedStripe, self.led_stripe_received)
                self.run()
        
        def run(self):
                rate = rospy.Rate(20.0)
+               sleep(3) # wait 3s for ros to register and establish all subscriber connections before sending reset diag
                reset_val = self.get_reset()
                rospy.loginfo("Reset Status: 0x%x" % reset_val)
                i = 0
@@ -54,9 +90,14 @@ class MoveBase:
                                self.get_dist_backward()
                                self.get_dist_right()
                        i+=1
+                       if self.cmd_vel != None:
+                               self.set_speed(self.cmd_vel[0], self.cmd_vel[1])
+                               self.cmd_vel = None
                        rate.sleep()
 
        def set_motor_handicap(self, front, aft): # percent
+               if front > 100: front = 100
+               if aft > 100: aft = 100
                if self.handicap_last != (front, aft):
                        i2c_write_reg(0x50, 0x94, struct.pack(">bb", front, aft))
                        self.handicap_last = (front, aft)
@@ -64,10 +105,10 @@ class MoveBase:
        def imuReceived(self, msg):
                (roll, pitch, yaw) = tf.transformations.euler_from_quaternion(msg.orientation.__getstate__())
                if pitch > 30*pi/180:
-                       val = (100.0/65)*abs(pitch)*180/pi
+                       val = (100.0/60)*abs(pitch)*180/pi
                        self.set_motor_handicap(int(val), 0)
                elif pitch < -30*pi/180:
-                       val = (100.0/65)*abs(pitch)*180/pi
+                       val = (100.0/60)*abs(pitch)*180/pi
                        self.set_motor_handicap(0, int(val))
                else:
                        self.set_motor_handicap(0, 0)
@@ -82,10 +123,18 @@ class MoveBase:
                stat.level = DiagnosticStatus.ERROR if reset & 0x0c else DiagnosticStatus.OK
                stat.message = "0x%02x" % reset
 
-               stat.values.append(KeyValue("Watchdog Reset Flag", str(bool(reset & (1 << 3)))))
-               stat.values.append(KeyValue("Brown-out Reset Flag", str(bool(reset & (1 << 2)))))
-               stat.values.append(KeyValue("External Reset Flag", str(bool(reset & (1 << 1)))))
-               stat.values.append(KeyValue("Power-on Reset Flag", str(bool(reset & (1 << 0)))))
+               wdrf = bool(reset & (1 << 3))
+               if wdrf: rospy.loginfo("Watchdog Reset")
+               borf = bool(reset & (1 << 2))
+               if borf: rospy.loginfo("Brown-out Reset Flag")
+               extrf = bool(reset & (1 << 1))
+               if extrf: rospy.loginfo("External Reset Flag")
+               porf = bool(reset & (1 << 0))
+               if porf: rospy.loginfo("Power-on Reset Flag")
+               stat.values.append(KeyValue("Watchdog Reset Flag", str(wdrf)))
+               stat.values.append(KeyValue("Brown-out Reset Flag", str(borf)))
+               stat.values.append(KeyValue("External Reset Flag", str(extrf)))
+               stat.values.append(KeyValue("Power-on Reset Flag", str(porf)))
 
                msg.status.append(stat)
                self.pub_diag.publish(msg)
@@ -125,8 +174,7 @@ class MoveBase:
 
 
        def get_odom(self):
-               posx, posy, angle = struct.unpack(">fff", i2c_read_reg(0x50, 0x40, 12))
-               speed_trans, speed_rot = struct.unpack(">ff", i2c_read_reg(0x50, 0x38, 8))
+               speed_trans, speed_rot, posx, posy, angle = struct.unpack(">fffff", i2c_read_reg(0x50, 0x38, 20))
                current_time = rospy.Time.now()
 
                # since all odometry is 6DOF we'll need a quaternion created from yaw
@@ -176,9 +224,7 @@ class MoveBase:
                i2c_write_reg(0x50, 0x50, struct.pack(">ff", trans, rot))
 
        def cmdVelReceived(self, msg):
-               trans = msg.linear.x
-               rot = msg.angular.z # rad/s
-               self.set_speed(trans, rot)
+               self.cmd_vel = (msg.linear.x, msg.angular.z) # commit speed on next update cycle
 
        # http://rn-wissen.de/wiki/index.php/Sensorarten#Sharp_GP2D12
        def get_dist_ir(self, num):
@@ -203,16 +249,7 @@ class MoveBase:
                dev.close()
 
        def read_dist_srf(self, num):
-               dev = i2c(0x52)
-               s = struct.pack("B", num)
-               dev.write(s)
-               dev.close()
-
-               dev = i2c(0x52)
-               s = dev.read(2)
-               dev.close()
-
-               return struct.unpack(">H", s)[0]/1000.0
+               return struct.unpack(">H", i2c_read_reg(0x52, num, 2))[0]/1000.0
 
        def send_range(self, pub, frame_id, typ, dist, min_range, max_range, fov_deg):
                msg = Range()
@@ -227,25 +264,32 @@ class MoveBase:
 
        def get_dist_left(self):
                if self.pub_range_left.get_num_connections() > 0:
-                       dist = 30.553/(self.get_dist_ir(0x1) - -67.534)
-                       self.send_range(self.pub_range_left, "ir_left", Range.INFRARED, dist, 0.04, 0.3, 1)
+                       dist = self.get_dist_ir(0x1)
+                       if dist > -67:
+                               self.send_range(self.pub_range_left, "ir_left", Range.INFRARED, 30.553/(dist - -67.534), 0.04, 0.3, 1)
 
        def get_dist_right(self):
                if self.pub_range_right.get_num_connections() > 0:
-                       dist = 17.4/(self.get_dist_ir(0x3) - 69)
-                       self.send_range(self.pub_range_right, "ir_right", Range.INFRARED, dist, 0.04, 0.3, 1)
+                       dist = self.get_dist_ir(0x3)
+                       if dist > 69:
+                               self.send_range(self.pub_range_right, "ir_right", Range.INFRARED, 17.4/(dist - 69), 0.04, 0.3, 1)
 
        def get_dist_forward(self):
                if self.pub_range_fwd.get_num_connections() > 0:
                        dist = self.read_dist_srf(0x15)
-                       self.send_range(self.pub_range_fwd, "sonar_forward", Range.ULTRASOUND, dist, 0.04, 6, 30)
+                       self.send_range(self.pub_range_fwd, "sonar_forward", Range.ULTRASOUND, dist, 0.04, 6, 40)
                        self.start_dist_srf(0x5) # get next value
 
        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, 6, 30)
+                       self.send_range(self.pub_range_bwd, "sonar_backward", Range.ULTRASOUND, dist, 0.04, 6, 40)
                        self.start_dist_srf(0x7) # get next value
+       
+       def led_stripe_received(self, msg):
+               for led in msg.leds:
+                       self.pStripe.set(led.num, red=led.red, green=led.green, blue=led.blue)
+                       self.pStripe.update()
                
 
 if __name__ == "__main__":