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 sensor_msgs.msg import Imu, Range
16 from wild_thumper.msg import LedStripe
21 def __init__(self, bus, device, num_leds):
22 self.spi = spidev.SpiDev()
23 self.spi.open(bus, device)
25 self.spi.max_speed_hz=int(2e6)
26 self.num_leds = num_leds
28 self.l = [(0, 0, 0)] * num_leds
31 def set(self, i, red=0, green=0, blue=0):
32 if red > 127 or green > 127 or blue >> 127 or red < 0 or green < 0 or blue < 0:
33 raise Exception("Bad RGB Value")
34 self.l[i] = (red, green, blue)
37 self.spi.writebytes([0x0 for i in range((self.num_leds+31)/32)])
41 for i in range(self.num_leds):
42 red, green, blue = self.l[i]
43 l.append(0x80 | green)
46 self.spi.writebytes(l)
51 rospy.init_node('wild_thumper')
52 prctl.set_name("wild_thumper")
53 enable_odom_tf = rospy.get_param("~enable_odom_tf", True)
55 self.tf_broadcaster = tf.broadcaster.TransformBroadcaster()
57 self.tf_broadcaster = None
58 self.pub_odom = rospy.Publisher("odom", Odometry, queue_size=16)
59 self.pub_diag = rospy.Publisher("diagnostics", DiagnosticArray, queue_size=16)
60 self.pub_range_fwd = rospy.Publisher("range_forward", Range, queue_size=16)
61 self.pub_range_bwd = rospy.Publisher("range_backward", Range, queue_size=16)
62 self.pub_range_left = rospy.Publisher("range_left", Range, queue_size=16)
63 self.pub_range_right = rospy.Publisher("range_right", Range, queue_size=16)
66 rospy.loginfo("Init done")
67 i2c_write_reg(0x50, 0x90, struct.pack("BB", 1, 1)) # switch direction
68 self.handicap_last = (-1, -1)
69 self.pStripe = LPD8806(1, 0, 12)
70 rospy.Subscriber("cmd_vel_out", Twist, self.cmdVelReceived)
71 #rospy.Subscriber("imu", Imu, self.imuReceived)
72 rospy.Subscriber("led_stripe", LedStripe, self.led_stripe_received)
76 rate = rospy.Rate(20.0)
77 sleep(3) # wait 3s for ros to register and establish all subscriber connections before sending reset diag
78 reset_val = self.get_reset()
79 rospy.loginfo("Reset Status: 0x%x" % reset_val)
81 while not rospy.is_shutdown():
82 rospy.logdebug("Loop alive")
83 #print struct.unpack(">B", i2c_read_reg(0x50, 0xA2, 1))[0] # count test
88 self.get_dist_forward()
91 self.get_dist_backward()
94 if self.cmd_vel != None:
95 self.set_speed(self.cmd_vel[0], self.cmd_vel[1])
99 def set_motor_handicap(self, front, aft): # percent
100 if front > 100: front = 100
101 if aft > 100: aft = 100
102 if self.handicap_last != (front, aft):
103 i2c_write_reg(0x50, 0x94, struct.pack(">bb", front, aft))
104 self.handicap_last = (front, aft)
106 def imuReceived(self, msg):
107 (roll, pitch, yaw) = tf.transformations.euler_from_quaternion(msg.orientation.__getstate__())
108 if pitch > 30*pi/180:
109 val = (100.0/60)*abs(pitch)*180/pi
110 self.set_motor_handicap(int(val), 0)
111 elif pitch < -30*pi/180:
112 val = (100.0/60)*abs(pitch)*180/pi
113 self.set_motor_handicap(0, int(val))
115 self.set_motor_handicap(0, 0)
118 reset = struct.unpack(">B", i2c_read_reg(0x50, 0xA0, 1))[0]
120 msg = DiagnosticArray()
121 msg.header.stamp = rospy.Time.now()
122 stat = DiagnosticStatus()
123 stat.name = "Reset reason"
124 stat.level = DiagnosticStatus.ERROR if reset & 0x0c else DiagnosticStatus.OK
125 stat.message = "0x%02x" % reset
127 wdrf = bool(reset & (1 << 3))
128 if wdrf: rospy.loginfo("Watchdog Reset")
129 borf = bool(reset & (1 << 2))
130 if borf: rospy.loginfo("Brown-out Reset Flag")
131 extrf = bool(reset & (1 << 1))
132 if extrf: rospy.loginfo("External Reset Flag")
133 porf = bool(reset & (1 << 0))
134 if porf: rospy.loginfo("Power-on Reset Flag")
135 stat.values.append(KeyValue("Watchdog Reset Flag", str(wdrf)))
136 stat.values.append(KeyValue("Brown-out Reset Flag", str(borf)))
137 stat.values.append(KeyValue("External Reset Flag", str(extrf)))
138 stat.values.append(KeyValue("Power-on Reset Flag", str(porf)))
140 msg.status.append(stat)
141 self.pub_diag.publish(msg)
145 def get_motor_err(self):
146 err = struct.unpack(">B", i2c_read_reg(0x50, 0xA1, 1))[0]
148 msg = DiagnosticArray()
149 msg.header.stamp = rospy.Time.now()
150 stat = DiagnosticStatus()
151 stat.name = "Motor: Error Status"
152 stat.level = DiagnosticStatus.ERROR if err else DiagnosticStatus.OK
153 stat.message = "0x%02x" % err
156 stat.values.append(KeyValue("aft left diag", str(bool(err & (1 << 0)))))
157 stat.values.append(KeyValue("front left diag", str(bool(err & (1 << 1)))))
158 stat.values.append(KeyValue("aft right diag", str(bool(err & (1 << 2)))))
159 stat.values.append(KeyValue("front right diag", str(bool(err & (1 << 3)))))
161 stat.values.append(KeyValue("aft left stall", str(bool(err & (1 << 4)))))
162 stat.values.append(KeyValue("front left stall", str(bool(err & (1 << 5)))))
163 stat.values.append(KeyValue("aft right stall", str(bool(err & (1 << 6)))))
164 stat.values.append(KeyValue("front right stall", str(bool(err & (1 << 7)))))
166 msg.status.append(stat)
167 self.pub_diag.publish(msg)
169 def get_voltage(self):
170 volt = struct.unpack(">h", i2c_read_reg(0x52, 0x09, 2))[0]/100.0
172 msg = DiagnosticArray()
173 msg.header.stamp = rospy.Time.now()
174 stat = DiagnosticStatus()
175 stat.name = "Voltage"
176 stat.level = DiagnosticStatus.ERROR if volt < 7 else DiagnosticStatus.OK
177 stat.message = "%.2fV" % volt
179 msg.status.append(stat)
180 self.pub_diag.publish(msg)
184 speed_trans, speed_rot, posx, posy, angle = struct.unpack(">fffff", i2c_read_reg(0x50, 0x38, 20))
185 current_time = rospy.Time.now()
187 # since all odometry is 6DOF we'll need a quaternion created from yaw
188 odom_quat = tf.transformations.quaternion_from_euler(0, 0, angle)
190 # first, we'll publish the transform over tf
191 if self.tf_broadcaster is not None:
192 self.tf_broadcaster.sendTransform((posx, posy, 0.0), odom_quat, current_time, "base_footprint", "odom")
194 # next, we'll publish the odometry message over ROS
196 odom.header.stamp = current_time
197 odom.header.frame_id = "odom"
200 odom.pose.pose.position.x = posx
201 odom.pose.pose.position.y = posy
202 odom.pose.pose.position.z = 0.0
203 odom.pose.pose.orientation.x = odom_quat[0]
204 odom.pose.pose.orientation.y = odom_quat[1]
205 odom.pose.pose.orientation.z = odom_quat[2]
206 odom.pose.pose.orientation.w = odom_quat[3]
207 odom.pose.covariance[0] = 1e-3 # x
208 odom.pose.covariance[7] = 1e-3 # y
209 odom.pose.covariance[14] = 1e6 # z
210 odom.pose.covariance[21] = 1e6 # rotation about X axis
211 odom.pose.covariance[28] = 1e6 # rotation about Y axis
212 odom.pose.covariance[35] = 0.03 # rotation about Z axis
215 odom.child_frame_id = "base_footprint"
216 odom.twist.twist.linear.x = speed_trans
217 odom.twist.twist.linear.y = 0.0
218 odom.twist.twist.angular.z = speed_rot
219 odom.twist.covariance[0] = 1e-3 # x
220 odom.twist.covariance[7] = 1e-3 # y
221 odom.twist.covariance[14] = 1e6 # z
222 odom.twist.covariance[21] = 1e6 # rotation about X axis
223 odom.twist.covariance[28] = 1e6 # rotation about Y axis
224 odom.twist.covariance[35] = 0.03 # rotation about Z axis
226 # publish the message
227 self.pub_odom.publish(odom)
230 def set_speed(self, trans, rot):
231 i2c_write_reg(0x50, 0x50, struct.pack(">ff", trans, rot))
233 def cmdVelReceived(self, msg):
234 rospy.logdebug("Set new cmd_vel:", msg.linear.x, msg.angular.z)
235 self.cmd_vel = (msg.linear.x, msg.angular.z) # commit speed on next update cycle
236 rospy.logdebug("Set new cmd_vel done")
238 # http://rn-wissen.de/wiki/index.php/Sensorarten#Sharp_GP2D12
239 def get_dist_ir(self, num):
241 s = struct.pack("B", num)
251 val = struct.unpack(">H", s)[0]
254 def start_dist_srf(self, num):
256 s = struct.pack("B", num)
260 def read_dist_srf(self, num):
261 return struct.unpack(">H", i2c_read_reg(0x52, num, 2))[0]/1000.0
263 def send_range(self, pub, frame_id, typ, dist, min_range, max_range, fov_deg):
265 msg.header.stamp = rospy.Time.now()
266 msg.header.frame_id = frame_id
267 msg.radiation_type = typ
268 msg.field_of_view = fov_deg*pi/180
269 msg.min_range = min_range
270 msg.max_range = max_range
274 def get_dist_left(self):
275 if self.pub_range_left.get_num_connections() > 0:
276 dist = self.get_dist_ir(0x1)
278 self.send_range(self.pub_range_left, "ir_left", Range.INFRARED, 30.553/(dist - -67.534), 0.04, 0.3, 1)
280 def get_dist_right(self):
281 if self.pub_range_right.get_num_connections() > 0:
282 dist = self.get_dist_ir(0x3)
284 self.send_range(self.pub_range_right, "ir_right", Range.INFRARED, 17.4/(dist - 69), 0.04, 0.3, 1)
286 def get_dist_forward(self):
287 if self.pub_range_fwd.get_num_connections() > 0:
288 dist = self.read_dist_srf(0x15)
289 self.send_range(self.pub_range_fwd, "sonar_forward", Range.ULTRASOUND, dist, 0.04, 6, 40)
290 self.start_dist_srf(0x5) # get next value
292 def get_dist_backward(self):
293 if self.pub_range_bwd.get_num_connections() > 0:
294 dist = self.read_dist_srf(0x17)
295 self.send_range(self.pub_range_bwd, "sonar_backward", Range.ULTRASOUND, dist, 0.04, 6, 40)
296 self.start_dist_srf(0x7) # get next value
298 def led_stripe_received(self, msg):
300 self.pStripe.set(led.num, red=led.red, green=led.green, blue=led.blue)
301 self.pStripe.update()
304 if __name__ == "__main__":