X-Git-Url: https://defiant.homedns.org/gitweb/?p=ros_wild_thumper.git;a=blobdiff_plain;f=scripts%2Fwt_node.py;h=5fc2e2d53155630563bf342d12769c9d3861de27;hp=1cf9d8d49fc42608ca1db0b1a0ed69873a95e4ef;hb=8818294be6d3833647713c6db2412e742c4d34fe;hpb=b301eb19e6487497a8bb946c538a25aa4ee28c1d diff --git a/scripts/wt_node.py b/scripts/wt_node.py index 1cf9d8d..5fc2e2d 100755 --- a/scripts/wt_node.py +++ b/scripts/wt_node.py @@ -13,7 +13,7 @@ from geometry_msgs.msg import Twist 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 +from sensor_msgs.msg import Imu, Range, BatteryState from wild_thumper.msg import LedStripe from wild_thumper.cfg import WildThumperConfig @@ -65,10 +65,12 @@ class MoveBase: self.pub_range_bwd = rospy.Publisher("range_backward", Range, queue_size=16) self.pub_range_left = rospy.Publisher("range_left", Range, queue_size=16) self.pub_range_right = rospy.Publisher("range_right", Range, queue_size=16) + self.pub_battery = rospy.Publisher("battery", BatteryState, queue_size=16) self.cmd_vel = None 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 +212,24 @@ class MoveBase: msg.status.append(stat) self.pub_diag.publish(msg) + if self.pub_battery.get_num_connections() > 0: + batmsg = BatteryState() + batmsg.header.stamp = rospy.Time.now() + batmsg.voltage = volt + batmsg.current = float('nan') + batmsg.charge = float('nan') + batmsg.capacity = float('nan') + batmsg.design_capacity = 5.0 + batmsg.percentage = float('nan') + batmsg.power_supply_status = BatteryState.POWER_SUPPLY_STATUS_DISCHARGING + batmsg.power_supply_health = BatteryState.POWER_SUPPLY_HEALTH_UNKNOWN + batmsg.power_supply_technology = BatteryState.POWER_SUPPLY_TECHNOLOGY_NIMH + self.pub_battery.publish(batmsg) + + 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))