X-Git-Url: https://defiant.homedns.org/gitweb/?p=ros_wild_thumper.git;a=blobdiff_plain;f=scripts%2Fwt_node.py;fp=scripts%2Fwt_node.py;h=bb6fbb02f0ef832f4c30da7dac25e0d767e60cd7;hp=1cf9d8d49fc42608ca1db0b1a0ed69873a95e4ef;hb=065571396c4327c12198fa8b368f7e17eb633861;hpb=59f39a51a977ca93173e1074db0e7381a3d24e0d diff --git a/scripts/wt_node.py b/scripts/wt_node.py index 1cf9d8d..bb6fbb0 100755 --- a/scripts/wt_node.py +++ b/scripts/wt_node.py @@ -69,6 +69,7 @@ class MoveBase: 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) @@ -210,6 +211,10 @@ class MoveBase: 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))