]> defiant.homedns.org Git - ros_wild_thumper.git/commitdiff
wt_node: Warn every 10s if voltage is lo10s if voltage is loww
authorErik Andresen <erik@vontaene.de>
Tue, 8 Aug 2017 20:08:14 +0000 (22:08 +0200)
committerErik Andresen <erik@vontaene.de>
Tue, 8 Aug 2017 20:08:14 +0000 (22:08 +0200)
scripts/wt_node.py

index 1cf9d8d49fc42608ca1db0b1a0ed69873a95e4ef..bb6fbb02f0ef832f4c30da7dac25e0d767e60cd7 100755 (executable)
@@ -69,6 +69,7 @@ class MoveBase:
                self.cur_vel = (0, 0)
                self.bMotorManual = False
                self.set_speed(0, 0)
                self.cur_vel = (0, 0)
                self.bMotorManual = False
                self.set_speed(0, 0)
+               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.loginfo("Init done")
                i2c_write_reg(0x50, 0x90, struct.pack("BB", 1, 1)) # switch direction
                self.pStripe = LPD8806(1, 0, 12)
@@ -210,6 +211,10 @@ class MoveBase:
                msg.status.append(stat)
                self.pub_diag.publish(msg)
 
                msg.status.append(stat)
                self.pub_diag.publish(msg)
 
+               if volt < 7 and (rospy.Time.now() - self.volt_last_warn).to_sec() > 10:
+                       rospy.logerr("Voltage critical: %.2fV" % (volt))
+                       self.volt_last_warn = rospy.Time.now()
+
 
        def get_odom(self):
                speed_trans, speed_rot, posx, posy, angle = struct.unpack(">fffff", i2c_read_reg(0x50, 0x38, 20))
 
        def get_odom(self):
                speed_trans, speed_rot, posx, posy, angle = struct.unpack(">fffff", i2c_read_reg(0x50, 0x38, 20))