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