X-Git-Url: https://defiant.homedns.org/gitweb/?p=ros_wild_thumper.git;a=blobdiff_plain;f=scripts%2Fwt_node.py;h=bb6fbb02f0ef832f4c30da7dac25e0d767e60cd7;hp=1549ea6f7aad56b906c7ad18321dd5857fadd882;hb=d14cfe50a46c4225db4ff6b05de6954bf30de259;hpb=54a59e74352041bdda72f2eea2cab24683f0e16a diff --git a/scripts/wt_node.py b/scripts/wt_node.py index 1549ea6..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)) @@ -237,9 +242,9 @@ class MoveBase: odom.pose.pose.orientation.w = odom_quat[3] odom.pose.covariance[0] = self.odom_covar_xy # x odom.pose.covariance[7] = self.odom_covar_xy # y - odom.pose.covariance[14] = 99999 # z - odom.pose.covariance[21] = 99999 # rotation about X axis - odom.pose.covariance[28] = 99999 # rotation about Y axis + odom.pose.covariance[14] = self.odom_covar_xy # z + odom.pose.covariance[21] = self.odom_covar_angle # rotation about X axis + odom.pose.covariance[28] = self.odom_covar_angle # rotation about Y axis odom.pose.covariance[35] = self.odom_covar_angle # rotation about Z axis # set the velocity