X-Git-Url: https://defiant.homedns.org/gitweb/?p=ros_wild_thumper.git;a=blobdiff_plain;f=scripts%2Fwt_node.py;h=6006f9562bef641e510005c84676553ac6c52801;hp=8589156bcf517d75aabea58ac16f5e33f62d3ec4;hb=4b090b45eb6d10571944874b8b23921f96a9db54;hpb=a7bf130f7e0ea44d8ba7d02d1fa1310b658a9d87 diff --git a/scripts/wt_node.py b/scripts/wt_node.py index 8589156..6006f95 100755 --- a/scripts/wt_node.py +++ b/scripts/wt_node.py @@ -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,15 +206,16 @@ 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) @@ -223,7 +224,7 @@ class WTBase: batmsg = BatteryState() batmsg.header.stamp = rospy.Time.now() batmsg.voltage = volt - batmsg.current = float('nan') + batmsg.current = current batmsg.charge = float('nan') batmsg.capacity = float('nan') batmsg.design_capacity = 5.0