import rospy
import tf
import struct
+import thread
import prctl
import spidev
from time import sleep
from nav_msgs.msg import Odometry
from diagnostic_msgs.msg import DiagnosticArray, DiagnosticStatus, KeyValue
from dynamic_reconfigure.server import Server
-from sensor_msgs.msg import Imu, Range
+from sensor_msgs.msg import Imu, Range, BatteryState
from wild_thumper.msg import LedStripe
from wild_thumper.cfg import WildThumperConfig
self.spi.writebytes(l)
self.latch()
-class MoveBase:
+class WTBase:
def __init__(self):
rospy.init_node('wild_thumper')
prctl.set_name("wild_thumper")
self.pub_range_bwd = rospy.Publisher("range_backward", Range, queue_size=16)
self.pub_range_left = rospy.Publisher("range_left", Range, queue_size=16)
self.pub_range_right = rospy.Publisher("range_right", Range, queue_size=16)
+ self.pub_battery = rospy.Publisher("battery", BatteryState, queue_size=16)
self.cmd_vel = None
self.cur_vel = (0, 0)
self.bMotorManual = False
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):
#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()
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.bClipRangeSensor = config["range_sensor_clip"]
self.range_sensor_max = config["range_sensor_max"]
+ self.range_sensor_fov = config["range_sensor_fov"]
self.odom_covar_xy = config["odom_covar_xy"]
self.odom_covar_angle = config["odom_covar_angle"]
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
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)
+ if self.pub_battery.get_num_connections() > 0:
+ batmsg = BatteryState()
+ batmsg.header.stamp = rospy.Time.now()
+ batmsg.voltage = volt
+ batmsg.current = current
+ batmsg.charge = float('nan')
+ batmsg.capacity = float('nan')
+ batmsg.design_capacity = 5.0
+ batmsg.percentage = float('nan')
+ batmsg.power_supply_status = BatteryState.POWER_SUPPLY_STATUS_DISCHARGING
+ batmsg.power_supply_health = BatteryState.POWER_SUPPLY_HEALTH_UNKNOWN
+ batmsg.power_supply_technology = BatteryState.POWER_SUPPLY_TECHNOLOGY_NIMH
+ self.pub_battery.publish(batmsg)
+
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()
+ self.bDocked = volt > 10.1
+
def get_odom(self):
speed_trans, speed_rot, posx, posy, angle = struct.unpack(">fffff", i2c_read_reg(0x50, 0x38, 20))
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
def get_dist_forward_left(self):
if self.pub_range_fwd_left.get_num_connections() > 0:
dist = self.read_dist_srf(0x15)
- self.send_range(self.pub_range_fwd_left, "sonar_forward_left", Range.ULTRASOUND, dist, 0.04, self.range_sensor_max, 30)
+ self.send_range(self.pub_range_fwd_left, "sonar_forward_left", Range.ULTRASOUND, dist, 0.04, self.range_sensor_max, self.range_sensor_fov)
def update_dist_forward_left(self):
if self.pub_range_fwd_left.get_num_connections() > 0:
def get_dist_backward(self):
if self.pub_range_bwd.get_num_connections() > 0:
dist = self.read_dist_srf(0x17)
- self.send_range(self.pub_range_bwd, "sonar_backward", Range.ULTRASOUND, dist, 0.04, self.range_sensor_max, 30)
+ self.send_range(self.pub_range_bwd, "sonar_backward", Range.ULTRASOUND, dist, 0.04, self.range_sensor_max, self.range_sensor_fov)
def update_dist_backward(self):
if self.pub_range_bwd.get_num_connections() > 0:
def get_dist_forward_right(self):
if self.pub_range_fwd_right.get_num_connections() > 0:
dist = self.read_dist_srf(0x19)
- self.send_range(self.pub_range_fwd_right, "sonar_forward_right", Range.ULTRASOUND, dist, 0.04, self.range_sensor_max, 30)
+ self.send_range(self.pub_range_fwd_right, "sonar_forward_right", Range.ULTRASOUND, dist, 0.04, self.range_sensor_max, self.range_sensor_fov)
def update_dist_forward_right(self):
if self.pub_range_fwd_right.get_num_connections() > 0:
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()