2 # -*- coding: iso-8859-15 -*-
10 from time import sleep
11 from i2c import i2c, i2c_write_reg, i2c_read_reg
13 from geometry_msgs.msg import Twist
14 from nav_msgs.msg import Odometry
15 from diagnostic_msgs.msg import DiagnosticArray, DiagnosticStatus, KeyValue
16 from dynamic_reconfigure.server import Server
17 from sensor_msgs.msg import Imu, Range, BatteryState
18 from wild_thumper.msg import LedStripe
19 from wild_thumper.cfg import WildThumperConfig
24 def __init__(self, bus, device, num_leds):
25 self.spi = spidev.SpiDev()
26 self.spi.open(bus, device)
28 self.spi.max_speed_hz=int(2e6)
29 self.num_leds = num_leds
31 self.l = [(0, 0, 0)] * num_leds
34 def set(self, i, red=0, green=0, blue=0):
35 if red > 127 or green > 127 or blue > 127 or red < 0 or green < 0 or blue < 0:
36 raise Exception("Bad RGB Value")
37 self.l[i] = (red, green, blue)
40 self.spi.writebytes([0x0 for i in range((self.num_leds+31)/32)])
44 for i in range(self.num_leds):
45 red, green, blue = self.l[i]
46 l.append(0x80 | green)
49 self.spi.writebytes(l)
54 rospy.init_node('wild_thumper')
55 prctl.set_name("wild_thumper")
56 enable_odom_tf = rospy.get_param("~enable_odom_tf", True)
58 self.tf_broadcaster = tf.broadcaster.TransformBroadcaster()
60 self.tf_broadcaster = None
61 self.dyn_conf = Server(WildThumperConfig, self.execute_dyn_reconf)
62 self.pub_odom = rospy.Publisher("odom", Odometry, queue_size=16)
63 self.pub_diag = rospy.Publisher("diagnostics", DiagnosticArray, queue_size=16)
64 self.pub_range_fwd_left = rospy.Publisher("range_forward_left", Range, queue_size=16)
65 self.pub_range_fwd_right = rospy.Publisher("range_forward_right", Range, queue_size=16)
66 self.pub_range_bwd = rospy.Publisher("range_backward", Range, queue_size=16)
67 self.pub_range_left = rospy.Publisher("range_left", Range, queue_size=16)
68 self.pub_range_right = rospy.Publisher("range_right", Range, queue_size=16)
69 self.pub_battery = rospy.Publisher("battery", BatteryState, queue_size=16)
72 self.bMotorManual = False
74 self.volt_last_warn = rospy.Time.now()
75 rospy.loginfo("Init done")
76 i2c_write_reg(0x50, 0x90, struct.pack("BB", 1, 1)) # switch direction
77 self.pStripe = LPD8806(1, 0, 16)
78 rospy.Subscriber("cmd_vel_out", Twist, self.cmdVelReceived)
79 rospy.Subscriber("led_stripe", LedStripe, self.led_stripe_received)
80 rospy.Subscriber("imu", Imu, self.imuReceived)
82 self.bDocked_last = False
86 rate = rospy.Rate(20.0)
87 sleep(3) # wait 3s for ros to register and establish all subscriber connections before sending reset diag
88 reset_val = self.get_reset()
89 rospy.loginfo("Reset Status: 0x%x" % reset_val)
92 while not rospy.is_shutdown():
93 rospy.logdebug("Loop alive")
94 #print struct.unpack(">B", i2c_read_reg(0x50, 0xA2, 1))[0] # count test
103 self.get_dist_right()
107 self.get_dist_forward_left()
108 self.update_dist_backward()
110 elif sonar_count == 1:
111 self.get_dist_backward()
112 self.update_dist_forward_right()
114 elif sonar_count == 2:
115 self.get_dist_forward_right()
116 self.update_dist_forward_left()
119 if self.cmd_vel != None:
120 self.set_speed(self.cmd_vel[0], self.cmd_vel[1])
121 self.cur_vel = self.cmd_vel
127 def execute_dyn_reconf(self, config, level):
128 self.bClipRangeSensor = config["range_sensor_clip"]
129 self.range_sensor_max = config["range_sensor_max"]
130 self.range_sensor_fov = config["range_sensor_fov"]
131 self.odom_covar_xy = config["odom_covar_xy"]
132 self.odom_covar_angle = config["odom_covar_angle"]
133 self.rollover_protect = config["rollover_protect"]
134 self.rollover_protect_limit = config["rollover_protect_limit"]
135 self.rollover_protect_pwm = config["rollover_protect_pwm"]
136 self.bStayDocked = config["stay_docked"]
140 def imuReceived(self, msg):
141 if self.rollover_protect and (any(self.cur_vel) or self.bMotorManual):
142 (roll, pitch, yaw) = tf.transformations.euler_from_quaternion(msg.orientation.__getstate__())
143 if pitch > self.rollover_protect_limit*pi/180:
144 self.bMotorManual = True
145 i2c_write_reg(0x50, 0x1, struct.pack(">hhhh", 0, self.rollover_protect_pwm, 0, self.rollover_protect_pwm))
146 rospy.logwarn("Running forward rollver protection")
147 elif pitch < -self.rollover_protect_limit*pi/180:
148 self.bMotorManual = True
149 i2c_write_reg(0x50, 0x1, struct.pack(">hhhh", -self.rollover_protect_pwm, 0, -self.rollover_protect_pwm, 0))
150 rospy.logwarn("Running backward rollver protection")
151 elif self.bMotorManual:
152 i2c_write_reg(0x50, 0x1, struct.pack(">hhhh", 0, 0, 0, 0))
153 self.bMotorManual = False
154 self.cmd_vel = (0, 0)
155 rospy.logwarn("Rollver protection done")
158 reset = struct.unpack(">B", i2c_read_reg(0x50, 0xA0, 1))[0]
160 msg = DiagnosticArray()
161 msg.header.stamp = rospy.Time.now()
162 stat = DiagnosticStatus()
163 stat.name = "Reset reason"
164 stat.level = DiagnosticStatus.ERROR if reset & 0x0c else DiagnosticStatus.OK
165 stat.message = "0x%02x" % reset
167 wdrf = bool(reset & (1 << 3))
168 if wdrf: rospy.loginfo("Watchdog Reset")
169 borf = bool(reset & (1 << 2))
170 if borf: rospy.loginfo("Brown-out Reset Flag")
171 extrf = bool(reset & (1 << 1))
172 if extrf: rospy.loginfo("External Reset Flag")
173 porf = bool(reset & (1 << 0))
174 if porf: rospy.loginfo("Power-on Reset Flag")
175 stat.values.append(KeyValue("Watchdog Reset Flag", str(wdrf)))
176 stat.values.append(KeyValue("Brown-out Reset Flag", str(borf)))
177 stat.values.append(KeyValue("External Reset Flag", str(extrf)))
178 stat.values.append(KeyValue("Power-on Reset Flag", str(porf)))
180 msg.status.append(stat)
181 self.pub_diag.publish(msg)
185 def get_motor_err(self):
186 err = struct.unpack(">B", i2c_read_reg(0x50, 0xA1, 1))[0]
188 msg = DiagnosticArray()
189 msg.header.stamp = rospy.Time.now()
190 stat = DiagnosticStatus()
191 stat.name = "Motor: Error Status"
192 stat.level = DiagnosticStatus.ERROR if err else DiagnosticStatus.OK
193 stat.message = "0x%02x" % err
196 stat.values.append(KeyValue("aft left diag", str(bool(err & (1 << 0)))))
197 stat.values.append(KeyValue("front left diag", str(bool(err & (1 << 1)))))
198 stat.values.append(KeyValue("aft right diag", str(bool(err & (1 << 2)))))
199 stat.values.append(KeyValue("front right diag", str(bool(err & (1 << 3)))))
201 stat.values.append(KeyValue("aft left stall", str(bool(err & (1 << 4)))))
202 stat.values.append(KeyValue("front left stall", str(bool(err & (1 << 5)))))
203 stat.values.append(KeyValue("aft right stall", str(bool(err & (1 << 6)))))
204 stat.values.append(KeyValue("front right stall", str(bool(err & (1 << 7)))))
206 msg.status.append(stat)
207 self.pub_diag.publish(msg)
210 volt = struct.unpack(">h", i2c_read_reg(0x52, 0x09, 2))[0]/100.0
211 current = struct.unpack(">h", i2c_read_reg(0x52, 0x0D, 2))[0]/1000.0
213 msg = DiagnosticArray()
214 msg.header.stamp = rospy.Time.now()
215 stat = DiagnosticStatus()
217 stat.level = DiagnosticStatus.ERROR if volt < 7 or current > 5 else DiagnosticStatus.OK
218 stat.message = "%.2fV, %.2fA" % (volt, current)
220 msg.status.append(stat)
221 self.pub_diag.publish(msg)
223 if self.pub_battery.get_num_connections() > 0:
224 batmsg = BatteryState()
225 batmsg.header.stamp = rospy.Time.now()
226 batmsg.voltage = volt
227 batmsg.current = current
228 batmsg.charge = float('nan')
229 batmsg.capacity = float('nan')
230 batmsg.design_capacity = 5.0
231 batmsg.percentage = float('nan')
232 batmsg.power_supply_status = BatteryState.POWER_SUPPLY_STATUS_DISCHARGING
233 batmsg.power_supply_health = BatteryState.POWER_SUPPLY_HEALTH_UNKNOWN
234 batmsg.power_supply_technology = BatteryState.POWER_SUPPLY_TECHNOLOGY_NIMH
235 self.pub_battery.publish(batmsg)
237 if volt < 7 and (rospy.Time.now() - self.volt_last_warn).to_sec() > 10:
238 rospy.logerr("Voltage critical: %.2fV" % (volt))
239 self.volt_last_warn = rospy.Time.now()
241 self.bDocked = volt > 10
245 speed_trans, speed_rot, posx, posy, angle = struct.unpack(">fffff", i2c_read_reg(0x50, 0x38, 20))
246 current_time = rospy.Time.now()
248 # since all odometry is 6DOF we'll need a quaternion created from yaw
249 odom_quat = tf.transformations.quaternion_from_euler(0, 0, angle)
251 # first, we'll publish the transform over tf
252 if self.tf_broadcaster is not None:
253 self.tf_broadcaster.sendTransform((posx, posy, 0.0), odom_quat, current_time, "base_footprint", "odom")
255 # next, we'll publish the odometry message over ROS
257 odom.header.stamp = current_time
258 odom.header.frame_id = "odom"
261 odom.pose.pose.position.x = posx
262 odom.pose.pose.position.y = posy
263 odom.pose.pose.position.z = 0.0
264 odom.pose.pose.orientation.x = odom_quat[0]
265 odom.pose.pose.orientation.y = odom_quat[1]
266 odom.pose.pose.orientation.z = odom_quat[2]
267 odom.pose.pose.orientation.w = odom_quat[3]
268 odom.pose.covariance[0] = self.odom_covar_xy # x
269 odom.pose.covariance[7] = self.odom_covar_xy # y
270 odom.pose.covariance[14] = self.odom_covar_xy # z
271 odom.pose.covariance[21] = self.odom_covar_angle # rotation about X axis
272 odom.pose.covariance[28] = self.odom_covar_angle # rotation about Y axis
273 odom.pose.covariance[35] = self.odom_covar_angle # rotation about Z axis
276 odom.child_frame_id = "base_footprint"
277 odom.twist.twist.linear.x = speed_trans
278 odom.twist.twist.linear.y = 0.0
279 odom.twist.twist.linear.z = 0.0
280 odom.twist.twist.angular.z = speed_rot
281 odom.twist.covariance = odom.pose.covariance
283 # publish the message
284 self.pub_odom.publish(odom)
287 def set_speed(self, trans, rot):
288 i2c_write_reg(0x50, 0x50, struct.pack(">ff", trans, rot))
290 def cmdVelReceived(self, msg):
291 if not self.bMotorManual:
292 rospy.logdebug("Set new cmd_vel: %.2f %.2f", msg.linear.x, msg.angular.z)
293 self.cmd_vel = (msg.linear.x, msg.angular.z) # commit speed on next update cycle
294 rospy.logdebug("Set new cmd_vel done")
296 # http://rn-wissen.de/wiki/index.php/Sensorarten#Sharp_GP2D12
297 def get_dist_ir(self, num):
299 s = struct.pack("B", num)
309 val = struct.unpack(">H", s)[0]
312 def start_dist_srf(self, num):
314 s = struct.pack("B", num)
318 def read_dist_srf(self, num):
319 return struct.unpack(">H", i2c_read_reg(0x52, num, 2))[0]/1000.0
321 def send_range(self, pub, frame_id, typ, dist, min_range, max_range, fov_deg):
322 if self.bClipRangeSensor and dist > max_range:
325 msg.header.stamp = rospy.Time.now()
326 msg.header.frame_id = frame_id
327 msg.radiation_type = typ
328 msg.field_of_view = fov_deg*pi/180
329 msg.min_range = min_range
330 msg.max_range = max_range
334 def get_dist_left(self):
335 if self.pub_range_left.get_num_connections() > 0:
336 dist = self.get_dist_ir(0x1)
338 self.send_range(self.pub_range_left, "ir_left", Range.INFRARED, 30.553/(dist - -67.534), 0.04, 0.3, 1)
340 def get_dist_right(self):
341 if self.pub_range_right.get_num_connections() > 0:
342 dist = self.get_dist_ir(0x3)
344 self.send_range(self.pub_range_right, "ir_right", Range.INFRARED, 17.4/(dist - 69), 0.04, 0.3, 1)
346 def get_dist_forward_left(self):
347 if self.pub_range_fwd_left.get_num_connections() > 0:
348 dist = self.read_dist_srf(0x15)
349 self.send_range(self.pub_range_fwd_left, "sonar_forward_left", Range.ULTRASOUND, dist, 0.04, self.range_sensor_max, self.range_sensor_fov)
351 def update_dist_forward_left(self):
352 if self.pub_range_fwd_left.get_num_connections() > 0:
353 self.start_dist_srf(0x5)
355 def get_dist_backward(self):
356 if self.pub_range_bwd.get_num_connections() > 0:
357 dist = self.read_dist_srf(0x17)
358 self.send_range(self.pub_range_bwd, "sonar_backward", Range.ULTRASOUND, dist, 0.04, self.range_sensor_max, self.range_sensor_fov)
360 def update_dist_backward(self):
361 if self.pub_range_bwd.get_num_connections() > 0:
362 self.start_dist_srf(0x7)
364 def get_dist_forward_right(self):
365 if self.pub_range_fwd_right.get_num_connections() > 0:
366 dist = self.read_dist_srf(0x19)
367 self.send_range(self.pub_range_fwd_right, "sonar_forward_right", Range.ULTRASOUND, dist, 0.04, self.range_sensor_max, self.range_sensor_fov)
369 def update_dist_forward_right(self):
370 if self.pub_range_fwd_right.get_num_connections() > 0:
371 self.start_dist_srf(0xb)
373 def led_stripe_received(self, msg):
375 self.pStripe.set(led.num, red=led.red, green=led.green, blue=led.blue)
376 self.pStripe.update()
378 def check_docked(self):
379 if self.bDocked and not self.bDocked_last:
380 rospy.loginfo("Docking event")
381 elif not self.bDocked and self.bDocked_last:
382 if not self.bStayDocked or self.cur_vel != (0, 0):
383 rospy.loginfo("Undocking event")
385 rospy.loginfo("Undocking event..redocking")
386 thread.start_new_thread(self.redock, ())
388 self.bDocked_last = self.bDocked
391 self.cmd_vel = (-0.1, 0)
396 self.cmd_vel = (0, 0)
398 rospy.loginfo("Redocking done")
400 rospy.logerr("Redocking failed")
403 if __name__ == "__main__":