2 # -*- coding: iso-8859-15 -*-
10 from i2c import i2c, i2c_write_reg, i2c_read_reg
12 from geometry_msgs.msg import Twist
13 from nav_msgs.msg import Odometry
14 from diagnostic_msgs.msg import DiagnosticArray, DiagnosticStatus, KeyValue
15 from dynamic_reconfigure.server import Server
16 from sensor_msgs.msg import Imu, Range
17 from wild_thumper.msg import LedStripe
18 from wild_thumper.cfg import WildThumperConfig
23 def __init__(self, bus, device, num_leds):
24 self.spi = spidev.SpiDev()
25 self.spi.open(bus, device)
27 self.spi.max_speed_hz=int(2e6)
28 self.num_leds = num_leds
30 self.l = [(0, 0, 0)] * num_leds
33 def set(self, i, red=0, green=0, blue=0):
34 if red > 127 or green > 127 or blue > 127 or red < 0 or green < 0 or blue < 0:
35 raise Exception("Bad RGB Value")
36 self.l[i] = (red, green, blue)
39 self.spi.writebytes([0x0 for i in range((self.num_leds+31)/32)])
43 for i in range(self.num_leds):
44 red, green, blue = self.l[i]
45 l.append(0x80 | green)
48 self.spi.writebytes(l)
53 rospy.init_node('wild_thumper')
54 prctl.set_name("wild_thumper")
55 enable_odom_tf = rospy.get_param("~enable_odom_tf", True)
57 self.tf_broadcaster = tf.broadcaster.TransformBroadcaster()
59 self.tf_broadcaster = None
60 self.dyn_conf = Server(WildThumperConfig, self.execute_dyn_reconf)
61 self.pub_odom = rospy.Publisher("odom", Odometry, queue_size=16)
62 self.pub_diag = rospy.Publisher("diagnostics", DiagnosticArray, queue_size=16)
63 self.pub_range_fwd_left = rospy.Publisher("range_forward_left", Range, queue_size=16)
64 self.pub_range_fwd_right = rospy.Publisher("range_forward_right", Range, queue_size=16)
65 self.pub_range_bwd = rospy.Publisher("range_backward", Range, queue_size=16)
66 self.pub_range_left = rospy.Publisher("range_left", Range, queue_size=16)
67 self.pub_range_right = rospy.Publisher("range_right", Range, queue_size=16)
70 self.bMotorManual = False
72 self.volt_last_warn = rospy.Time.now()
73 rospy.loginfo("Init done")
74 i2c_write_reg(0x50, 0x90, struct.pack("BB", 1, 1)) # switch direction
75 self.pStripe = LPD8806(1, 0, 12)
76 rospy.Subscriber("cmd_vel_out", Twist, self.cmdVelReceived)
77 rospy.Subscriber("led_stripe", LedStripe, self.led_stripe_received)
78 rospy.Subscriber("imu", Imu, self.imuReceived)
82 rate = rospy.Rate(20.0)
83 sleep(3) # wait 3s for ros to register and establish all subscriber connections before sending reset diag
84 reset_val = self.get_reset()
85 rospy.loginfo("Reset Status: 0x%x" % reset_val)
88 while not rospy.is_shutdown():
89 rospy.logdebug("Loop alive")
90 #print struct.unpack(">B", i2c_read_reg(0x50, 0xA2, 1))[0] # count test
103 self.get_dist_forward_left()
104 self.update_dist_backward()
106 elif sonar_count == 1:
107 self.get_dist_backward()
108 self.update_dist_forward_right()
110 elif sonar_count == 2:
111 self.get_dist_forward_right()
112 self.update_dist_forward_left()
115 if self.cmd_vel != None:
116 self.set_speed(self.cmd_vel[0], self.cmd_vel[1])
117 self.cur_vel = self.cmd_vel
121 def execute_dyn_reconf(self, config, level):
122 self.bClipRangeSensor = config["range_sensor_clip"]
123 self.range_sensor_max = config["range_sensor_max"]
124 self.odom_covar_xy = config["odom_covar_xy"]
125 self.odom_covar_angle = config["odom_covar_angle"]
126 self.rollover_protect = config["rollover_protect"]
127 self.rollover_protect_limit = config["rollover_protect_limit"]
128 self.rollover_protect_pwm = config["rollover_protect_pwm"]
132 def imuReceived(self, msg):
133 if self.rollover_protect and any(self.cur_vel):
134 (roll, pitch, yaw) = tf.transformations.euler_from_quaternion(msg.orientation.__getstate__())
135 if pitch > self.rollover_protect_limit*pi/180:
136 self.bMotorManual = True
137 i2c_write_reg(0x50, 0x1, struct.pack(">hhhh", 0, self.rollover_protect_pwm, 0, self.rollover_protect_pwm))
138 rospy.logwarn("Running forward rollver protection")
139 elif pitch < -self.rollover_protect_limit*pi/180:
140 self.bMotorManual = True
141 i2c_write_reg(0x50, 0x1, struct.pack(">hhhh", -self.rollover_protect_pwm, 0, -self.rollover_protect_pwm, 0))
142 rospy.logwarn("Running backward rollver protection")
143 elif self.bMotorManual:
144 i2c_write_reg(0x50, 0x1, struct.pack(">hhhh", 0, 0, 0, 0))
145 self.bMotorManual = False
146 self.cmd_vel = (0, 0)
147 rospy.logwarn("Rollver protection done")
150 reset = struct.unpack(">B", i2c_read_reg(0x50, 0xA0, 1))[0]
152 msg = DiagnosticArray()
153 msg.header.stamp = rospy.Time.now()
154 stat = DiagnosticStatus()
155 stat.name = "Reset reason"
156 stat.level = DiagnosticStatus.ERROR if reset & 0x0c else DiagnosticStatus.OK
157 stat.message = "0x%02x" % reset
159 wdrf = bool(reset & (1 << 3))
160 if wdrf: rospy.loginfo("Watchdog Reset")
161 borf = bool(reset & (1 << 2))
162 if borf: rospy.loginfo("Brown-out Reset Flag")
163 extrf = bool(reset & (1 << 1))
164 if extrf: rospy.loginfo("External Reset Flag")
165 porf = bool(reset & (1 << 0))
166 if porf: rospy.loginfo("Power-on Reset Flag")
167 stat.values.append(KeyValue("Watchdog Reset Flag", str(wdrf)))
168 stat.values.append(KeyValue("Brown-out Reset Flag", str(borf)))
169 stat.values.append(KeyValue("External Reset Flag", str(extrf)))
170 stat.values.append(KeyValue("Power-on Reset Flag", str(porf)))
172 msg.status.append(stat)
173 self.pub_diag.publish(msg)
177 def get_motor_err(self):
178 err = struct.unpack(">B", i2c_read_reg(0x50, 0xA1, 1))[0]
180 msg = DiagnosticArray()
181 msg.header.stamp = rospy.Time.now()
182 stat = DiagnosticStatus()
183 stat.name = "Motor: Error Status"
184 stat.level = DiagnosticStatus.ERROR if err else DiagnosticStatus.OK
185 stat.message = "0x%02x" % err
188 stat.values.append(KeyValue("aft left diag", str(bool(err & (1 << 0)))))
189 stat.values.append(KeyValue("front left diag", str(bool(err & (1 << 1)))))
190 stat.values.append(KeyValue("aft right diag", str(bool(err & (1 << 2)))))
191 stat.values.append(KeyValue("front right diag", str(bool(err & (1 << 3)))))
193 stat.values.append(KeyValue("aft left stall", str(bool(err & (1 << 4)))))
194 stat.values.append(KeyValue("front left stall", str(bool(err & (1 << 5)))))
195 stat.values.append(KeyValue("aft right stall", str(bool(err & (1 << 6)))))
196 stat.values.append(KeyValue("front right stall", str(bool(err & (1 << 7)))))
198 msg.status.append(stat)
199 self.pub_diag.publish(msg)
201 def get_voltage(self):
202 volt = struct.unpack(">h", i2c_read_reg(0x52, 0x09, 2))[0]/100.0
204 msg = DiagnosticArray()
205 msg.header.stamp = rospy.Time.now()
206 stat = DiagnosticStatus()
207 stat.name = "Voltage"
208 stat.level = DiagnosticStatus.ERROR if volt < 7 else DiagnosticStatus.OK
209 stat.message = "%.2fV" % volt
211 msg.status.append(stat)
212 self.pub_diag.publish(msg)
214 if volt < 7 and (rospy.Time.now() - self.volt_last_warn).to_sec() > 10:
215 rospy.logerr("Voltage critical: %.2fV" % (volt))
216 self.volt_last_warn = rospy.Time.now()
220 speed_trans, speed_rot, posx, posy, angle = struct.unpack(">fffff", i2c_read_reg(0x50, 0x38, 20))
221 current_time = rospy.Time.now()
223 # since all odometry is 6DOF we'll need a quaternion created from yaw
224 odom_quat = tf.transformations.quaternion_from_euler(0, 0, angle)
226 # first, we'll publish the transform over tf
227 if self.tf_broadcaster is not None:
228 self.tf_broadcaster.sendTransform((posx, posy, 0.0), odom_quat, current_time, "base_footprint", "odom")
230 # next, we'll publish the odometry message over ROS
232 odom.header.stamp = current_time
233 odom.header.frame_id = "odom"
236 odom.pose.pose.position.x = posx
237 odom.pose.pose.position.y = posy
238 odom.pose.pose.position.z = 0.0
239 odom.pose.pose.orientation.x = odom_quat[0]
240 odom.pose.pose.orientation.y = odom_quat[1]
241 odom.pose.pose.orientation.z = odom_quat[2]
242 odom.pose.pose.orientation.w = odom_quat[3]
243 odom.pose.covariance[0] = self.odom_covar_xy # x
244 odom.pose.covariance[7] = self.odom_covar_xy # y
245 odom.pose.covariance[14] = self.odom_covar_xy # z
246 odom.pose.covariance[21] = self.odom_covar_angle # rotation about X axis
247 odom.pose.covariance[28] = self.odom_covar_angle # rotation about Y axis
248 odom.pose.covariance[35] = self.odom_covar_angle # rotation about Z axis
251 odom.child_frame_id = "base_footprint"
252 odom.twist.twist.linear.x = speed_trans
253 odom.twist.twist.linear.y = 0.0
254 odom.twist.twist.angular.z = speed_rot
255 odom.twist.covariance = odom.pose.covariance
257 # publish the message
258 self.pub_odom.publish(odom)
261 def set_speed(self, trans, rot):
262 i2c_write_reg(0x50, 0x50, struct.pack(">ff", trans, rot))
264 def cmdVelReceived(self, msg):
265 if not self.bMotorManual:
266 rospy.logdebug("Set new cmd_vel: %.2f %.2f", msg.linear.x, msg.angular.z)
267 self.cmd_vel = (msg.linear.x, msg.angular.z) # commit speed on next update cycle
268 rospy.logdebug("Set new cmd_vel done")
270 # http://rn-wissen.de/wiki/index.php/Sensorarten#Sharp_GP2D12
271 def get_dist_ir(self, num):
273 s = struct.pack("B", num)
283 val = struct.unpack(">H", s)[0]
286 def start_dist_srf(self, num):
288 s = struct.pack("B", num)
292 def read_dist_srf(self, num):
293 return struct.unpack(">H", i2c_read_reg(0x52, num, 2))[0]/1000.0
295 def send_range(self, pub, frame_id, typ, dist, min_range, max_range, fov_deg):
296 if self.bClipRangeSensor and dist > max_range:
299 msg.header.stamp = rospy.Time.now()
300 msg.header.frame_id = frame_id
301 msg.radiation_type = typ
302 msg.field_of_view = fov_deg*pi/180
303 msg.min_range = min_range
304 msg.max_range = max_range
308 def get_dist_left(self):
309 if self.pub_range_left.get_num_connections() > 0:
310 dist = self.get_dist_ir(0x1)
312 self.send_range(self.pub_range_left, "ir_left", Range.INFRARED, 30.553/(dist - -67.534), 0.04, 0.3, 1)
314 def get_dist_right(self):
315 if self.pub_range_right.get_num_connections() > 0:
316 dist = self.get_dist_ir(0x3)
318 self.send_range(self.pub_range_right, "ir_right", Range.INFRARED, 17.4/(dist - 69), 0.04, 0.3, 1)
320 def get_dist_forward_left(self):
321 if self.pub_range_fwd_left.get_num_connections() > 0:
322 dist = self.read_dist_srf(0x15)
323 self.send_range(self.pub_range_fwd_left, "sonar_forward_left", Range.ULTRASOUND, dist, 0.04, self.range_sensor_max, 30)
325 def update_dist_forward_left(self):
326 if self.pub_range_fwd_left.get_num_connections() > 0:
327 self.start_dist_srf(0x5)
329 def get_dist_backward(self):
330 if self.pub_range_bwd.get_num_connections() > 0:
331 dist = self.read_dist_srf(0x17)
332 self.send_range(self.pub_range_bwd, "sonar_backward", Range.ULTRASOUND, dist, 0.04, self.range_sensor_max, 30)
334 def update_dist_backward(self):
335 if self.pub_range_bwd.get_num_connections() > 0:
336 self.start_dist_srf(0x7)
338 def get_dist_forward_right(self):
339 if self.pub_range_fwd_right.get_num_connections() > 0:
340 dist = self.read_dist_srf(0x19)
341 self.send_range(self.pub_range_fwd_right, "sonar_forward_right", Range.ULTRASOUND, dist, 0.04, self.range_sensor_max, 30)
343 def update_dist_forward_right(self):
344 if self.pub_range_fwd_right.get_num_connections() > 0:
345 self.start_dist_srf(0xb)
347 def led_stripe_received(self, msg):
349 self.pStripe.set(led.num, red=led.red, green=led.green, blue=led.blue)
350 self.pStripe.update()
353 if __name__ == "__main__":