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)
65 rospy.loginfo("Init done")
66 i2c_write_reg(0x50, 0x90, struct.pack("BB", 1, 1)) # switch direction
67 self.handicap_last = (-1, -1)
68 self.pStripe = LPD8806(1, 0, 12)
69 rospy.Subscriber("cmd_vel_out", Twist, self.cmdVelReceived)
70 rospy.Subscriber("imu", Imu, self.imuReceived)
71 rospy.Subscriber("led_stripe", LedStripe, self.led_stripe_received)
75 rate = rospy.Rate(20.0)
76 reset_val = self.get_reset()
77 rospy.loginfo("Reset Status: 0x%x" % reset_val)
79 while not rospy.is_shutdown():
80 #print struct.unpack(">B", i2c_read_reg(0x50, 0xA2, 1))[0] # count test
85 self.get_dist_forward()
88 self.get_dist_backward()
93 def set_motor_handicap(self, front, aft): # percent
94 if self.handicap_last != (front, aft):
95 i2c_write_reg(0x50, 0x94, struct.pack(">bb", front, aft))
96 self.handicap_last = (front, aft)
98 def imuReceived(self, msg):
99 (roll, pitch, yaw) = tf.transformations.euler_from_quaternion(msg.orientation.__getstate__())
100 if pitch > 30*pi/180:
101 val = (100.0/65)*abs(pitch)*180/pi
102 self.set_motor_handicap(int(val), 0)
103 elif pitch < -30*pi/180:
104 val = (100.0/65)*abs(pitch)*180/pi
105 self.set_motor_handicap(0, int(val))
107 self.set_motor_handicap(0, 0)
110 reset = struct.unpack(">B", i2c_read_reg(0x50, 0xA0, 1))[0]
112 msg = DiagnosticArray()
113 msg.header.stamp = rospy.Time.now()
114 stat = DiagnosticStatus()
115 stat.name = "Reset reason"
116 stat.level = DiagnosticStatus.ERROR if reset & 0x0c else DiagnosticStatus.OK
117 stat.message = "0x%02x" % reset
119 wdrf = bool(reset & (1 << 3))
120 if wdrf: rospy.loginfo("Watchdog Reset")
121 borf = bool(reset & (1 << 2))
122 if borf: rospy.loginfo("Brown-out Reset Flag")
123 extrf = bool(reset & (1 << 1))
124 if extrf: rospy.loginfo("External Reset Flag")
125 porf = bool(reset & (1 << 0))
126 if porf: rospy.loginfo("Power-on Reset Flag")
127 stat.values.append(KeyValue("Watchdog Reset Flag", str(wdrf)))
128 stat.values.append(KeyValue("Brown-out Reset Flag", str(borf)))
129 stat.values.append(KeyValue("External Reset Flag", str(extrf)))
130 stat.values.append(KeyValue("Power-on Reset Flag", str(porf)))
132 msg.status.append(stat)
133 self.pub_diag.publish(msg)
137 def get_tle_err(self):
138 err = struct.unpack(">B", i2c_read_reg(0x50, 0xA1, 1))[0]
140 msg = DiagnosticArray()
141 msg.header.stamp = rospy.Time.now()
142 stat = DiagnosticStatus()
143 stat.name = "Motor: Error Status"
144 stat.level = DiagnosticStatus.ERROR if err else DiagnosticStatus.OK
145 stat.message = "0x%02x" % err
147 stat.values.append(KeyValue("aft left", str(bool(err & (1 << 0)))))
148 stat.values.append(KeyValue("front left", str(bool(err & (1 << 1)))))
149 stat.values.append(KeyValue("front right", str(bool(err & (1 << 2)))))
150 stat.values.append(KeyValue("aft right", str(bool(err & (1 << 3)))))
152 msg.status.append(stat)
153 self.pub_diag.publish(msg)
155 def get_voltage(self):
156 volt = struct.unpack(">h", i2c_read_reg(0x52, 0x09, 2))[0]/100.0
158 msg = DiagnosticArray()
159 msg.header.stamp = rospy.Time.now()
160 stat = DiagnosticStatus()
161 stat.name = "Voltage"
162 stat.level = DiagnosticStatus.ERROR if volt < 7 else DiagnosticStatus.OK
163 stat.message = "%.2fV" % volt
165 msg.status.append(stat)
166 self.pub_diag.publish(msg)
170 posx, posy, angle = struct.unpack(">fff", i2c_read_reg(0x50, 0x40, 12))
171 speed_trans, speed_rot = struct.unpack(">ff", i2c_read_reg(0x50, 0x38, 8))
172 current_time = rospy.Time.now()
174 # since all odometry is 6DOF we'll need a quaternion created from yaw
175 odom_quat = tf.transformations.quaternion_from_euler(0, 0, angle)
177 # first, we'll publish the transform over tf
178 if self.tf_broadcaster is not None:
179 self.tf_broadcaster.sendTransform((posx, posy, 0.0), odom_quat, current_time, "base_footprint", "odom")
181 # next, we'll publish the odometry message over ROS
183 odom.header.stamp = current_time
184 odom.header.frame_id = "odom"
187 odom.pose.pose.position.x = posx
188 odom.pose.pose.position.y = posy
189 odom.pose.pose.position.z = 0.0
190 odom.pose.pose.orientation.x = odom_quat[0]
191 odom.pose.pose.orientation.y = odom_quat[1]
192 odom.pose.pose.orientation.z = odom_quat[2]
193 odom.pose.pose.orientation.w = odom_quat[3]
194 odom.pose.covariance[0] = 1e-3 # x
195 odom.pose.covariance[7] = 1e-3 # y
196 odom.pose.covariance[14] = 1e6 # z
197 odom.pose.covariance[21] = 1e6 # rotation about X axis
198 odom.pose.covariance[28] = 1e6 # rotation about Y axis
199 odom.pose.covariance[35] = 0.03 # rotation about Z axis
202 odom.child_frame_id = "base_footprint"
203 odom.twist.twist.linear.x = speed_trans
204 odom.twist.twist.linear.y = 0.0
205 odom.twist.twist.angular.z = speed_rot
206 odom.twist.covariance[0] = 1e-3 # x
207 odom.twist.covariance[7] = 1e-3 # y
208 odom.twist.covariance[14] = 1e6 # z
209 odom.twist.covariance[21] = 1e6 # rotation about X axis
210 odom.twist.covariance[28] = 1e6 # rotation about Y axis
211 odom.twist.covariance[35] = 0.03 # rotation about Z axis
213 # publish the message
214 self.pub_odom.publish(odom)
217 def set_speed(self, trans, rot):
218 i2c_write_reg(0x50, 0x50, struct.pack(">ff", trans, rot))
220 def cmdVelReceived(self, msg):
222 rot = msg.angular.z # rad/s
223 self.set_speed(trans, rot)
225 # http://rn-wissen.de/wiki/index.php/Sensorarten#Sharp_GP2D12
226 def get_dist_ir(self, num):
228 s = struct.pack("B", num)
238 val = struct.unpack(">H", s)[0]
241 def start_dist_srf(self, num):
243 s = struct.pack("B", num)
247 def read_dist_srf(self, num):
248 return struct.unpack(">H", i2c_read_reg(0x52, num, 2))[0]/1000.0
250 def send_range(self, pub, frame_id, typ, dist, min_range, max_range, fov_deg):
252 msg.header.stamp = rospy.Time.now()
253 msg.header.frame_id = frame_id
254 msg.radiation_type = typ
255 msg.field_of_view = fov_deg*pi/180
256 msg.min_range = min_range
257 msg.max_range = max_range
261 def get_dist_left(self):
262 if self.pub_range_left.get_num_connections() > 0:
263 dist = self.get_dist_ir(0x1)
265 self.send_range(self.pub_range_left, "ir_left", Range.INFRARED, 30.553/(dist - -67.534), 0.04, 0.3, 1)
267 def get_dist_right(self):
268 if self.pub_range_right.get_num_connections() > 0:
269 dist = self.get_dist_ir(0x3)
271 self.send_range(self.pub_range_right, "ir_right", Range.INFRARED, 17.4/(dist - 69), 0.04, 0.3, 1)
273 def get_dist_forward(self):
274 if self.pub_range_fwd.get_num_connections() > 0:
275 dist = self.read_dist_srf(0x15)
276 self.send_range(self.pub_range_fwd, "sonar_forward", Range.ULTRASOUND, dist, 0.04, 6, 40)
277 self.start_dist_srf(0x5) # get next value
279 def get_dist_backward(self):
280 if self.pub_range_bwd.get_num_connections() > 0:
281 dist = self.read_dist_srf(0x17)
282 self.send_range(self.pub_range_bwd, "sonar_backward", Range.ULTRASOUND, dist, 0.04, 6, 40)
283 self.start_dist_srf(0x7) # get next value
285 def led_stripe_received(self, msg):
287 self.pStripe.set(led.num, red=led.red, green=led.green, blue=led.blue)
288 self.pStripe.update()
291 if __name__ == "__main__":