]> defiant.homedns.org Git - ros_wild_thumper.git/blobdiff - scripts/wt_node.py
CMakeLists: Require OpenCV
[ros_wild_thumper.git] / scripts / wt_node.py
index 8589156bcf517d75aabea58ac16f5e33f62d3ec4..dfa69b0c6e2a2d097c57d78cc23b2a7343527764 100755 (executable)
@@ -15,40 +15,10 @@ 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, BatteryState
-from wild_thumper.msg import LedStripe
 from wild_thumper.cfg import WildThumperConfig
 
 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 WTBase:
        def __init__(self):
                rospy.init_node('wild_thumper')
@@ -74,9 +44,7 @@ class WTBase:
                self.volt_last_warn = rospy.Time.now()
                rospy.loginfo("Init done")
                i2c_write_reg(0x50, 0x90, struct.pack("BB", 1, 1)) # switch direction
-               self.pStripe = LPD8806(1, 0, 12)
                rospy.Subscriber("cmd_vel_out", Twist, self.cmdVelReceived)
-               rospy.Subscriber("led_stripe", LedStripe, self.led_stripe_received)
                rospy.Subscriber("imu", Imu, self.imuReceived)
                self.bDocked = False
                self.bDocked_last = False
@@ -94,7 +62,7 @@ class WTBase:
                        #print struct.unpack(">B", i2c_read_reg(0x50, 0xA2, 1))[0] # count test
                        self.get_motor_err()
                        self.get_odom()
-                       self.get_voltage()
+                       self.get_power()
 
                        if ir_count == 0:
                                self.get_dist_left()
@@ -138,7 +106,7 @@ class WTBase:
                return config
 
        def imuReceived(self, msg):
-               if self.rollover_protect and any(self.cur_vel):
+               if self.rollover_protect and (any(self.cur_vel) or self.bMotorManual):
                        (roll, pitch, yaw) = tf.transformations.euler_from_quaternion(msg.orientation.__getstate__())
                        if pitch > self.rollover_protect_limit*pi/180:
                                self.bMotorManual = True
@@ -206,15 +174,16 @@ class WTBase:
                msg.status.append(stat)
                self.pub_diag.publish(msg)
        
-       def get_voltage(self):
+       def get_power(self):
                volt = struct.unpack(">h", i2c_read_reg(0x52, 0x09, 2))[0]/100.0
+               current = struct.unpack(">h", i2c_read_reg(0x52, 0x0D, 2))[0]/1000.0
 
                msg = DiagnosticArray()
                msg.header.stamp = rospy.Time.now()
                stat = DiagnosticStatus()
-               stat.name = "Voltage"
-               stat.level = DiagnosticStatus.ERROR if volt < 7 else DiagnosticStatus.OK
-               stat.message = "%.2fV" % volt
+               stat.name = "Power"
+               stat.level = DiagnosticStatus.ERROR if volt < 7 or current > 5 else DiagnosticStatus.OK
+               stat.message = "%.2fV, %.2fA" % (volt, current)
 
                msg.status.append(stat)
                self.pub_diag.publish(msg)
@@ -223,7 +192,7 @@ class WTBase:
                        batmsg = BatteryState()
                        batmsg.header.stamp = rospy.Time.now()
                        batmsg.voltage = volt
-                       batmsg.current = float('nan')
+                       batmsg.current = current
                        batmsg.charge = float('nan')
                        batmsg.capacity = float('nan')
                        batmsg.design_capacity = 5.0
@@ -237,7 +206,7 @@ class WTBase:
                        rospy.logerr("Voltage critical: %.2fV" % (volt))
                        self.volt_last_warn = rospy.Time.now()
 
-               self.bDocked = volt > 10
+               self.bDocked = volt > 10.1
 
 
        def get_odom(self):
@@ -369,11 +338,6 @@ class WTBase:
                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:
-                       self.pStripe.set(led.num, red=led.red, green=led.green, blue=led.blue)
-                       self.pStripe.update()
-
        def check_docked(self):
                if self.bDocked and not self.bDocked_last:
                        rospy.loginfo("Docking event")