import rospy
import tf
import struct
+import thread
import prctl
import spidev
from time import sleep
from geometry_msgs.msg import Twist
from nav_msgs.msg import Odometry
from diagnostic_msgs.msg import DiagnosticArray, DiagnosticStatus, KeyValue
-from sensor_msgs.msg import Imu, Range
+from dynamic_reconfigure.server import Server
+from sensor_msgs.msg import Imu, Range, BatteryState
from wild_thumper.msg import LedStripe
+from wild_thumper.cfg import WildThumperConfig
WHEEL_DIST = 0.248
self.update()
def set(self, i, red=0, green=0, blue=0):
- if red > 127 or green > 127 or blue >> 127 or red < 0 or green < 0 or blue < 0:
+ if red > 127 or green > 127 or blue > 127 or red < 0 or green < 0 or blue < 0:
raise Exception("Bad RGB Value")
self.l[i] = (red, green, blue)
self.spi.writebytes(l)
self.latch()
-class MoveBase:
+class WTBase:
def __init__(self):
rospy.init_node('wild_thumper')
prctl.set_name("wild_thumper")
self.tf_broadcaster = tf.broadcaster.TransformBroadcaster()
else:
self.tf_broadcaster = None
+ self.dyn_conf = Server(WildThumperConfig, self.execute_dyn_reconf)
self.pub_odom = rospy.Publisher("odom", Odometry, queue_size=16)
self.pub_diag = rospy.Publisher("diagnostics", DiagnosticArray, queue_size=16)
- self.pub_range_fwd = rospy.Publisher("range_forward", Range, queue_size=16)
+ self.pub_range_fwd_left = rospy.Publisher("range_forward_left", Range, queue_size=16)
+ self.pub_range_fwd_right = rospy.Publisher("range_forward_right", Range, queue_size=16)
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.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.handicap_last = (-1, -1)
self.pStripe = LPD8806(1, 0, 12)
rospy.Subscriber("cmd_vel_out", Twist, self.cmdVelReceived)
- rospy.Subscriber("imu", Imu, self.imuReceived)
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):
sleep(3) # wait 3s for ros to register and establish all subscriber connections before sending reset diag
reset_val = self.get_reset()
rospy.loginfo("Reset Status: 0x%x" % reset_val)
- i = 0
+ ir_count = 0
+ sonar_count = 0
while not rospy.is_shutdown():
+ rospy.logdebug("Loop alive")
#print struct.unpack(">B", i2c_read_reg(0x50, 0xA2, 1))[0] # count test
- self.get_tle_err()
+ self.get_motor_err()
self.get_odom()
- self.get_voltage()
- if i % 2:
- self.get_dist_forward()
+ self.get_power()
+
+ if ir_count == 0:
self.get_dist_left()
+ ir_count+=1
else:
- self.get_dist_backward()
self.get_dist_right()
- i+=1
+ ir_count=0
+
+ if sonar_count == 0:
+ self.get_dist_forward_left()
+ self.update_dist_backward()
+ sonar_count+=1
+ elif sonar_count == 1:
+ self.get_dist_backward()
+ self.update_dist_forward_right()
+ sonar_count+=1
+ elif sonar_count == 2:
+ self.get_dist_forward_right()
+ self.update_dist_forward_left()
+ sonar_count=0
+
if self.cmd_vel != None:
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 set_motor_handicap(self, front, aft): # percent
- if front > 100: front = 100
- if aft > 100: aft = 100
- if self.handicap_last != (front, aft):
- i2c_write_reg(0x50, 0x94, struct.pack(">bb", front, aft))
- self.handicap_last = (front, aft)
+ 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):
- (roll, pitch, yaw) = tf.transformations.euler_from_quaternion(msg.orientation.__getstate__())
- if pitch > 30*pi/180:
- val = (100.0/60)*abs(pitch)*180/pi
- self.set_motor_handicap(int(val), 0)
- elif pitch < -30*pi/180:
- val = (100.0/60)*abs(pitch)*180/pi
- self.set_motor_handicap(0, int(val))
- else:
- self.set_motor_handicap(0, 0)
+ if self.rollover_protect and any(self.cur_vel):
+ (roll, pitch, yaw) = tf.transformations.euler_from_quaternion(msg.orientation.__getstate__())
+ if pitch > self.rollover_protect_limit*pi/180:
+ self.bMotorManual = True
+ i2c_write_reg(0x50, 0x1, struct.pack(">hhhh", 0, self.rollover_protect_pwm, 0, self.rollover_protect_pwm))
+ rospy.logwarn("Running forward rollver protection")
+ elif pitch < -self.rollover_protect_limit*pi/180:
+ self.bMotorManual = True
+ i2c_write_reg(0x50, 0x1, struct.pack(">hhhh", -self.rollover_protect_pwm, 0, -self.rollover_protect_pwm, 0))
+ rospy.logwarn("Running backward rollver protection")
+ elif self.bMotorManual:
+ i2c_write_reg(0x50, 0x1, struct.pack(">hhhh", 0, 0, 0, 0))
+ self.bMotorManual = False
+ self.cmd_vel = (0, 0)
+ rospy.logwarn("Rollver protection done")
def get_reset(self):
reset = struct.unpack(">B", i2c_read_reg(0x50, 0xA0, 1))[0]
return reset
- def get_tle_err(self):
+ def get_motor_err(self):
err = struct.unpack(">B", i2c_read_reg(0x50, 0xA1, 1))[0]
msg = DiagnosticArray()
stat.level = DiagnosticStatus.ERROR if err else DiagnosticStatus.OK
stat.message = "0x%02x" % err
- stat.values.append(KeyValue("aft left", str(bool(err & (1 << 0)))))
- stat.values.append(KeyValue("front left", str(bool(err & (1 << 1)))))
- stat.values.append(KeyValue("front right", str(bool(err & (1 << 2)))))
- stat.values.append(KeyValue("aft right", str(bool(err & (1 << 3)))))
+ # Diag
+ stat.values.append(KeyValue("aft left diag", str(bool(err & (1 << 0)))))
+ stat.values.append(KeyValue("front left diag", str(bool(err & (1 << 1)))))
+ stat.values.append(KeyValue("aft right diag", str(bool(err & (1 << 2)))))
+ stat.values.append(KeyValue("front right diag", str(bool(err & (1 << 3)))))
+ # Stall
+ stat.values.append(KeyValue("aft left stall", str(bool(err & (1 << 4)))))
+ stat.values.append(KeyValue("front left stall", str(bool(err & (1 << 5)))))
+ stat.values.append(KeyValue("aft right stall", str(bool(err & (1 << 6)))))
+ stat.values.append(KeyValue("front right stall", str(bool(err & (1 << 7)))))
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
+
def get_odom(self):
speed_trans, speed_rot, posx, posy, angle = struct.unpack(">fffff", i2c_read_reg(0x50, 0x38, 20))
odom.pose.pose.orientation.y = odom_quat[1]
odom.pose.pose.orientation.z = odom_quat[2]
odom.pose.pose.orientation.w = odom_quat[3]
- odom.pose.covariance[0] = 1e-3 # x
- odom.pose.covariance[7] = 1e-3 # y
- odom.pose.covariance[14] = 1e6 # z
- odom.pose.covariance[21] = 1e6 # rotation about X axis
- odom.pose.covariance[28] = 1e6 # rotation about Y axis
- odom.pose.covariance[35] = 0.03 # rotation about Z axis
+ odom.pose.covariance[0] = self.odom_covar_xy # x
+ odom.pose.covariance[7] = self.odom_covar_xy # y
+ 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
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[0] = 1e-3 # x
- odom.twist.covariance[7] = 1e-3 # y
- odom.twist.covariance[14] = 1e6 # z
- odom.twist.covariance[21] = 1e6 # rotation about X axis
- odom.twist.covariance[28] = 1e6 # rotation about Y axis
- odom.twist.covariance[35] = 0.03 # rotation about Z axis
+ odom.twist.covariance = odom.pose.covariance
# publish the message
self.pub_odom.publish(odom)
i2c_write_reg(0x50, 0x50, struct.pack(">ff", trans, rot))
def cmdVelReceived(self, msg):
- self.cmd_vel = (msg.linear.x, msg.angular.z) # commit speed on next update cycle
+ if not self.bMotorManual:
+ rospy.logdebug("Set new cmd_vel: %.2f %.2f", msg.linear.x, msg.angular.z)
+ self.cmd_vel = (msg.linear.x, msg.angular.z) # commit speed on next update cycle
+ rospy.logdebug("Set new cmd_vel done")
# http://rn-wissen.de/wiki/index.php/Sensorarten#Sharp_GP2D12
def get_dist_ir(self, num):
return struct.unpack(">H", i2c_read_reg(0x52, num, 2))[0]/1000.0
def send_range(self, pub, frame_id, typ, dist, min_range, max_range, fov_deg):
+ if self.bClipRangeSensor and dist > max_range:
+ dist = max_range
msg = Range()
msg.header.stamp = rospy.Time.now()
msg.header.frame_id = frame_id
if dist > 69:
self.send_range(self.pub_range_right, "ir_right", Range.INFRARED, 17.4/(dist - 69), 0.04, 0.3, 1)
- def get_dist_forward(self):
- if self.pub_range_fwd.get_num_connections() > 0:
+ 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, "sonar_forward", Range.ULTRASOUND, dist, 0.04, 6, 40)
- self.start_dist_srf(0x5) # get next value
+ 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:
+ self.start_dist_srf(0x5)
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, 6, 40)
- self.start_dist_srf(0x7) # get next value
+ 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:
+ self.start_dist_srf(0x7)
+
+ 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, self.range_sensor_fov)
+
+ def update_dist_forward_right(self):
+ if self.pub_range_fwd_right.get_num_connections() > 0:
+ self.start_dist_srf(0xb)
def led_stripe_received(self, msg):
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()