# 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,
true, true, true,
false, false, true,
false, false, false]
+# gps
odom1_config: [true, true, false,
false, false, false,
false, false, false,
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"))
import rospy
import tf
import struct
+import thread
import prctl
import spidev
from time import sleep
self.spi.writebytes(l)
self.latch()
-class MoveBase:
+class WTBase:
def __init__(self):
rospy.init_node('wild_thumper')
prctl.set_name("wild_thumper")
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):
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):
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
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))
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()