]> defiant.homedns.org Git - ros_wild_thumper.git/blobdiff - scripts/wt_node.py
dwm1000: Always send transform even if there are no valid sensors values
[ros_wild_thumper.git] / scripts / wt_node.py
index 4a6af7b9f954989b8fa14c38422ce620addd9395..f7b02f5b009626e9a6dc90544705ed9c1287fd08 100755 (executable)
@@ -74,7 +74,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)
+               self.pStripe = LPD8806(1, 0, 16)
                rospy.Subscriber("cmd_vel_out", Twist, self.cmdVelReceived)
                rospy.Subscriber("led_stripe", LedStripe, self.led_stripe_received)
                rospy.Subscriber("imu", Imu, self.imuReceived)
@@ -94,7 +94,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 +138,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,21 +206,20 @@ 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)
 
-               current = struct.unpack(">h", i2c_read_reg(0x52, 0x0D, 2))[0]/1000.0
-
                if self.pub_battery.get_num_connections() > 0:
                        batmsg = BatteryState()
                        batmsg.header.stamp = rospy.Time.now()
@@ -239,7 +238,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):