From a7bf130f7e0ea44d8ba7d02d1fa1310b658a9d87 Mon Sep 17 00:00:00 2001 From: Erik Andresen Date: Sun, 22 Oct 2017 08:26:28 +0200 Subject: [PATCH] wt_node: Implement docking check --- config/robot_localization.yaml | 2 ++ config/wt_node.cfg | 1 + scripts/wt_node.py | 36 ++++++++++++++++++++++++++++++++-- 3 files changed, 37 insertions(+), 2 deletions(-) diff --git a/config/robot_localization.yaml b/config/robot_localization.yaml index 193db56..82d5fff 100644 --- a/config/robot_localization.yaml +++ b/config/robot_localization.yaml @@ -64,6 +64,7 @@ imu0_queue_size: 10 # message types lack certain variables. For example, a TwistWithCovarianceStamped message has no pose information, so # the first six values would be meaningless in that case. Each vector defaults to all false if unspecified, effectively # making this parameter required for each sensor. +# odom # x/y not included because of redundancy with velocities # vyaw not included in odom because too inaccurate odom0_config: [false, false, false, @@ -71,6 +72,7 @@ odom0_config: [false, false, false, true, true, true, false, false, true, false, false, false] +# gps odom1_config: [true, true, false, false, false, false, false, false, false, diff --git a/config/wt_node.cfg b/config/wt_node.cfg index fe8798c..08d089f 100755 --- a/config/wt_node.cfg +++ b/config/wt_node.cfg @@ -12,5 +12,6 @@ gen.add("odom_covar_angle", double_t, 0, "Odometry covariance: rotation", 1.00, gen.add("rollover_protect", bool_t, 0, "Enable motor rollover protection on pitch", True) gen.add("rollover_protect_limit",double_t, 0, "Pitch rollover protection limit (degree)", 45, 0, 90) gen.add("rollover_protect_pwm", double_t, 0, "Pitch rollover protection speed (pwm)", 255, 0, 255) +gen.add("stay_docked", bool_t, 0, "Try to stay dock again after an undocking event", True) exit(gen.generate("wild_thumper", "wild_thumper", "WildThumper")) diff --git a/scripts/wt_node.py b/scripts/wt_node.py index 663a4f1..8589156 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") @@ -77,6 +78,8 @@ class MoveBase: 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): @@ -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,6 +133,7 @@ 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 @@ -231,6 +237,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)) @@ -365,7 +373,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() -- 2.39.5