]> defiant.homedns.org Git - ros_wild_thumper.git/blobdiff - scripts/wt_node.py
dwm1000 kalman: Check covariance < 0
[ros_wild_thumper.git] / scripts / wt_node.py
index e234058dc66af5fcd6065110f86ebeabe3fe38ff..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)
@@ -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
@@ -238,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):