X-Git-Url: https://defiant.homedns.org/gitweb/?p=ros_wild_thumper.git;a=blobdiff_plain;f=scripts%2Fwt_node.py;h=6006f9562bef641e510005c84676553ac6c52801;hp=ab58496fca7b6f0220fe05216632f3d8c0811a4e;hb=4b090b45eb6d10571944874b8b23921f96a9db54;hpb=0338dec7b42d0454df844491f9404df5207e1382 diff --git a/scripts/wt_node.py b/scripts/wt_node.py index ab58496..6006f95 100755 --- a/scripts/wt_node.py +++ b/scripts/wt_node.py @@ -4,6 +4,7 @@ import rospy import tf import struct +import thread import prctl import spidev from time import sleep @@ -48,7 +49,7 @@ class LPD8806: self.spi.writebytes(l) self.latch() -class MoveBase: +class WTBase: def __init__(self): rospy.init_node('wild_thumper') prctl.set_name("wild_thumper") @@ -73,10 +74,12 @@ class MoveBase: 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) + self.bDocked = False + self.bDocked_last = False self.run() def run(self): @@ -91,7 +94,7 @@ class MoveBase: #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() @@ -117,6 +120,8 @@ class MoveBase: self.set_speed(self.cmd_vel[0], self.cmd_vel[1]) self.cur_vel = self.cmd_vel self.cmd_vel = None + + self.check_docked() rate.sleep() def execute_dyn_reconf(self, config, level): @@ -128,11 +133,12 @@ class MoveBase: self.rollover_protect = config["rollover_protect"] self.rollover_protect_limit = config["rollover_protect_limit"] self.rollover_protect_pwm = config["rollover_protect_pwm"] + self.bStayDocked = config["stay_docked"] 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 @@ -200,15 +206,16 @@ class MoveBase: 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) @@ -217,7 +224,7 @@ class MoveBase: 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 @@ -231,6 +238,8 @@ class MoveBase: rospy.logerr("Voltage critical: %.2fV" % (volt)) self.volt_last_warn = rospy.Time.now() + self.bDocked = volt > 10 + def get_odom(self): speed_trans, speed_rot, posx, posy, angle = struct.unpack(">fffff", i2c_read_reg(0x50, 0x38, 20)) @@ -267,6 +276,7 @@ class MoveBase: odom.child_frame_id = "base_footprint" odom.twist.twist.linear.x = speed_trans odom.twist.twist.linear.y = 0.0 + odom.twist.twist.linear.z = 0.0 odom.twist.twist.angular.z = speed_rot odom.twist.covariance = odom.pose.covariance @@ -364,7 +374,31 @@ class MoveBase: for led in msg.leds: self.pStripe.set(led.num, red=led.red, green=led.green, blue=led.blue) self.pStripe.update() + + def check_docked(self): + if self.bDocked and not self.bDocked_last: + rospy.loginfo("Docking event") + elif not self.bDocked and self.bDocked_last: + if not self.bStayDocked or self.cur_vel != (0, 0): + rospy.loginfo("Undocking event") + else: + rospy.loginfo("Undocking event..redocking") + thread.start_new_thread(self.redock, ()) + + self.bDocked_last = self.bDocked + + def redock(self): + self.cmd_vel = (-0.1, 0) + for i in range(100): + if self.bDocked: + break + sleep(0.01) + self.cmd_vel = (0, 0) + if self.bDocked: + rospy.loginfo("Redocking done") + else: + rospy.logerr("Redocking failed") if __name__ == "__main__": - MoveBase() + WTBase()