]> defiant.homedns.org Git - ros_wild_thumper.git/blob - scripts/wt_node.py
7fdf0444aead981ff55cedb43609cc122f75e001
[ros_wild_thumper.git] / scripts / wt_node.py
1 #!/usr/bin/env python
2 # -*- coding: iso-8859-15 -*-
3
4 import rospy
5 import tf
6 import struct
7 import prctl
8 import spidev
9 from time import sleep
10 from i2c import i2c, i2c_write_reg, i2c_read_reg
11 from math import *
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
17
18 WHEEL_DIST = 0.248
19
20 class LPD8806:
21         def __init__(self, bus, device, num_leds):
22                 self.spi = spidev.SpiDev()
23                 self.spi.open(bus, device)
24                 self.spi.mode=0b00
25                 self.spi.max_speed_hz=int(2e6)
26                 self.num_leds = num_leds
27                 self.latch()
28                 self.l = [(0, 0, 0)] * num_leds
29                 self.update()
30         
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)
35
36         def latch(self):
37                 self.spi.writebytes([0x0 for i in range((self.num_leds+31)/32)])
38         
39         def update(self):
40                 l = []
41                 for i in range(self.num_leds):
42                         red, green, blue = self.l[i]
43                         l.append(0x80 | green)
44                         l.append(0x80 | red)
45                         l.append(0x80 | blue)
46                 self.spi.writebytes(l)
47                 self.latch()
48
49 class MoveBase:
50         def __init__(self):
51                 rospy.init_node('wild_thumper')
52                 prctl.set_name("wild_thumper")
53                 enable_odom_tf = rospy.get_param("~enable_odom_tf", True)
54                 if enable_odom_tf:
55                         self.tf_broadcaster = tf.broadcaster.TransformBroadcaster()
56                 else:
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)
64                 self.cmd_vel = None
65                 self.set_speed(0, 0)
66                 rospy.loginfo("Init done")
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("led_stripe", LedStripe, self.led_stripe_received)
71                 self.run()
72         
73         def run(self):
74                 rate = rospy.Rate(20.0)
75                 sleep(3) # wait 3s for ros to register and establish all subscriber connections before sending reset diag
76                 reset_val = self.get_reset()
77                 rospy.loginfo("Reset Status: 0x%x" % reset_val)
78                 i = 0
79                 while not rospy.is_shutdown():
80                         #print struct.unpack(">B", i2c_read_reg(0x50, 0xA2, 1))[0] # count test
81                         self.get_tle_err()
82                         self.get_odom()
83                         self.get_voltage()
84                         if i % 2:
85                                 self.get_dist_forward()
86                                 self.get_dist_left()
87                         else:
88                                 self.get_dist_backward()
89                                 self.get_dist_right()
90                         i+=1
91                         if self.cmd_vel != None:
92                                 self.set_speed(self.cmd_vel[0], self.cmd_vel[1])
93                                 self.cmd_vel = None
94                         rate.sleep()
95
96         def get_reset(self):
97                 reset = struct.unpack(">B", i2c_read_reg(0x50, 0xA0, 1))[0]
98
99                 msg = DiagnosticArray()
100                 msg.header.stamp = rospy.Time.now()
101                 stat = DiagnosticStatus()
102                 stat.name = "Reset reason"
103                 stat.level = DiagnosticStatus.ERROR if reset & 0x0c else DiagnosticStatus.OK
104                 stat.message = "0x%02x" % reset
105
106                 wdrf = bool(reset & (1 << 3))
107                 if wdrf: rospy.loginfo("Watchdog Reset")
108                 borf = bool(reset & (1 << 2))
109                 if borf: rospy.loginfo("Brown-out Reset Flag")
110                 extrf = bool(reset & (1 << 1))
111                 if extrf: rospy.loginfo("External Reset Flag")
112                 porf = bool(reset & (1 << 0))
113                 if porf: rospy.loginfo("Power-on Reset Flag")
114                 stat.values.append(KeyValue("Watchdog Reset Flag", str(wdrf)))
115                 stat.values.append(KeyValue("Brown-out Reset Flag", str(borf)))
116                 stat.values.append(KeyValue("External Reset Flag", str(extrf)))
117                 stat.values.append(KeyValue("Power-on Reset Flag", str(porf)))
118
119                 msg.status.append(stat)
120                 self.pub_diag.publish(msg)
121                 return reset
122
123
124         def get_tle_err(self):
125                 err = struct.unpack(">B", i2c_read_reg(0x50, 0xA1, 1))[0]
126                 
127                 msg = DiagnosticArray()
128                 msg.header.stamp = rospy.Time.now()
129                 stat = DiagnosticStatus()
130                 stat.name = "Motor: Error Status"
131                 stat.level = DiagnosticStatus.ERROR if err else DiagnosticStatus.OK
132                 stat.message = "0x%02x" % err
133
134                 stat.values.append(KeyValue("aft left", str(bool(err & (1 << 0)))))
135                 stat.values.append(KeyValue("front left", str(bool(err & (1 << 1)))))
136                 stat.values.append(KeyValue("front right", str(bool(err & (1 << 2)))))
137                 stat.values.append(KeyValue("aft right", str(bool(err & (1 << 3)))))
138
139                 msg.status.append(stat)
140                 self.pub_diag.publish(msg)
141         
142         def get_voltage(self):
143                 volt = struct.unpack(">h", i2c_read_reg(0x52, 0x09, 2))[0]/100.0
144
145                 msg = DiagnosticArray()
146                 msg.header.stamp = rospy.Time.now()
147                 stat = DiagnosticStatus()
148                 stat.name = "Voltage"
149                 stat.level = DiagnosticStatus.ERROR if volt < 7 else DiagnosticStatus.OK
150                 stat.message = "%.2fV" % volt
151
152                 msg.status.append(stat)
153                 self.pub_diag.publish(msg)
154
155
156         def get_odom(self):
157                 speed_trans, speed_rot, posx, posy, angle = struct.unpack(">fffff", i2c_read_reg(0x50, 0x38, 20))
158                 current_time = rospy.Time.now()
159
160                 # since all odometry is 6DOF we'll need a quaternion created from yaw
161                 odom_quat = tf.transformations.quaternion_from_euler(0, 0, angle)
162
163                 # first, we'll publish the transform over tf
164                 if self.tf_broadcaster is not None:
165                         self.tf_broadcaster.sendTransform((posx, posy, 0.0), odom_quat, current_time, "base_footprint", "odom")
166
167                 # next, we'll publish the odometry message over ROS
168                 odom = Odometry()
169                 odom.header.stamp = current_time
170                 odom.header.frame_id = "odom"
171
172                 # set the position
173                 odom.pose.pose.position.x = posx
174                 odom.pose.pose.position.y = posy
175                 odom.pose.pose.position.z = 0.0
176                 odom.pose.pose.orientation.x = odom_quat[0]
177                 odom.pose.pose.orientation.y = odom_quat[1]
178                 odom.pose.pose.orientation.z = odom_quat[2]
179                 odom.pose.pose.orientation.w = odom_quat[3]
180                 odom.pose.covariance[0] = 1e-3 # x
181                 odom.pose.covariance[7] = 1e-3 # y
182                 odom.pose.covariance[14] = 1e6 # z
183                 odom.pose.covariance[21] = 1e6 # rotation about X axis
184                 odom.pose.covariance[28] = 1e6 # rotation about Y axis
185                 odom.pose.covariance[35] = 0.03 # rotation about Z axis
186
187                 # set the velocity
188                 odom.child_frame_id = "base_footprint"
189                 odom.twist.twist.linear.x = speed_trans
190                 odom.twist.twist.linear.y = 0.0
191                 odom.twist.twist.angular.z = speed_rot
192                 odom.twist.covariance[0] = 1e-3 # x
193                 odom.twist.covariance[7] = 1e-3 # y
194                 odom.twist.covariance[14] = 1e6 # z
195                 odom.twist.covariance[21] = 1e6 # rotation about X axis
196                 odom.twist.covariance[28] = 1e6 # rotation about Y axis
197                 odom.twist.covariance[35] = 0.03 # rotation about Z axis
198
199                 # publish the message
200                 self.pub_odom.publish(odom)
201
202         
203         def set_speed(self, trans, rot):
204                 i2c_write_reg(0x50, 0x50, struct.pack(">ff", trans, rot))
205
206         def cmdVelReceived(self, msg):
207                 self.cmd_vel = (msg.linear.x, msg.angular.z) # commit speed on next update cycle
208
209         # http://rn-wissen.de/wiki/index.php/Sensorarten#Sharp_GP2D12
210         def get_dist_ir(self, num):
211                 dev = i2c(0x52)
212                 s = struct.pack("B", num)
213                 dev.write(s)
214                 dev.close()
215
216                 sleep(2e-6)
217
218                 dev = i2c(0x52)
219                 s = dev.read(2)
220                 dev.close()
221
222                 val = struct.unpack(">H", s)[0]
223                 return val
224         
225         def start_dist_srf(self, num):
226                 dev = i2c(0x52)
227                 s = struct.pack("B", num)
228                 dev.write(s)
229                 dev.close()
230
231         def read_dist_srf(self, num):
232                 return struct.unpack(">H", i2c_read_reg(0x52, num, 2))[0]/1000.0
233
234         def send_range(self, pub, frame_id, typ, dist, min_range, max_range, fov_deg):
235                 msg = Range()
236                 msg.header.stamp = rospy.Time.now()
237                 msg.header.frame_id = frame_id
238                 msg.radiation_type = typ
239                 msg.field_of_view = fov_deg*pi/180
240                 msg.min_range = min_range
241                 msg.max_range = max_range
242                 msg.range = dist
243                 pub.publish(msg)
244
245         def get_dist_left(self):
246                 if self.pub_range_left.get_num_connections() > 0:
247                         dist = self.get_dist_ir(0x1)
248                         if dist > -67:
249                                 self.send_range(self.pub_range_left, "ir_left", Range.INFRARED, 30.553/(dist - -67.534), 0.04, 0.3, 1)
250
251         def get_dist_right(self):
252                 if self.pub_range_right.get_num_connections() > 0:
253                         dist = self.get_dist_ir(0x3)
254                         if dist > 69:
255                                 self.send_range(self.pub_range_right, "ir_right", Range.INFRARED, 17.4/(dist - 69), 0.04, 0.3, 1)
256
257         def get_dist_forward(self):
258                 if self.pub_range_fwd.get_num_connections() > 0:
259                         dist = self.read_dist_srf(0x15)
260                         self.send_range(self.pub_range_fwd, "sonar_forward", Range.ULTRASOUND, dist, 0.04, 6, 40)
261                         self.start_dist_srf(0x5) # get next value
262
263         def get_dist_backward(self):
264                 if self.pub_range_bwd.get_num_connections() > 0:
265                         dist = self.read_dist_srf(0x17)
266                         self.send_range(self.pub_range_bwd, "sonar_backward", Range.ULTRASOUND, dist, 0.04, 6, 40)
267                         self.start_dist_srf(0x7) # get next value
268         
269         def led_stripe_received(self, msg):
270                 for led in msg.leds:
271                         self.pStripe.set(led.num, red=led.red, green=led.green, blue=led.blue)
272                         self.pStripe.update()
273                 
274
275 if __name__ == "__main__":
276         MoveBase()