]> defiant.homedns.org Git - ros_wild_thumper.git/blob - scripts/wt_node.py
pid tuning for gear ratio=1:47
[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                 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)
73                 self.run()
74         
75         def run(self):
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)
80                 i = 0
81                 while not rospy.is_shutdown():
82                         #print struct.unpack(">B", i2c_read_reg(0x50, 0xA2, 1))[0] # count test
83                         self.get_motor_err()
84                         self.get_odom()
85                         self.get_voltage()
86                         if i % 2:
87                                 self.get_dist_forward()
88                                 self.get_dist_left()
89                         else:
90                                 self.get_dist_backward()
91                                 self.get_dist_right()
92                         i+=1
93                         if self.cmd_vel != None:
94                                 self.set_speed(self.cmd_vel[0], self.cmd_vel[1])
95                                 self.cmd_vel = None
96                         rate.sleep()
97
98         def set_motor_handicap(self, front, aft): # percent
99                 if front > 100: front = 100
100                 if aft > 100: aft = 100
101                 if self.handicap_last != (front, aft):
102                         i2c_write_reg(0x50, 0x94, struct.pack(">bb", front, aft))
103                         self.handicap_last = (front, aft)
104
105         def imuReceived(self, msg):
106                 (roll, pitch, yaw) = tf.transformations.euler_from_quaternion(msg.orientation.__getstate__())
107                 if pitch > 30*pi/180:
108                         val = (100.0/60)*abs(pitch)*180/pi
109                         self.set_motor_handicap(int(val), 0)
110                 elif pitch < -30*pi/180:
111                         val = (100.0/60)*abs(pitch)*180/pi
112                         self.set_motor_handicap(0, int(val))
113                 else:
114                         self.set_motor_handicap(0, 0)
115
116         def get_reset(self):
117                 reset = struct.unpack(">B", i2c_read_reg(0x50, 0xA0, 1))[0]
118
119                 msg = DiagnosticArray()
120                 msg.header.stamp = rospy.Time.now()
121                 stat = DiagnosticStatus()
122                 stat.name = "Reset reason"
123                 stat.level = DiagnosticStatus.ERROR if reset & 0x0c else DiagnosticStatus.OK
124                 stat.message = "0x%02x" % reset
125
126                 wdrf = bool(reset & (1 << 3))
127                 if wdrf: rospy.loginfo("Watchdog Reset")
128                 borf = bool(reset & (1 << 2))
129                 if borf: rospy.loginfo("Brown-out Reset Flag")
130                 extrf = bool(reset & (1 << 1))
131                 if extrf: rospy.loginfo("External Reset Flag")
132                 porf = bool(reset & (1 << 0))
133                 if porf: rospy.loginfo("Power-on Reset Flag")
134                 stat.values.append(KeyValue("Watchdog Reset Flag", str(wdrf)))
135                 stat.values.append(KeyValue("Brown-out Reset Flag", str(borf)))
136                 stat.values.append(KeyValue("External Reset Flag", str(extrf)))
137                 stat.values.append(KeyValue("Power-on Reset Flag", str(porf)))
138
139                 msg.status.append(stat)
140                 self.pub_diag.publish(msg)
141                 return reset
142
143
144         def get_motor_err(self):
145                 err = struct.unpack(">B", i2c_read_reg(0x50, 0xA1, 1))[0]
146                 
147                 msg = DiagnosticArray()
148                 msg.header.stamp = rospy.Time.now()
149                 stat = DiagnosticStatus()
150                 stat.name = "Motor: Error Status"
151                 stat.level = DiagnosticStatus.ERROR if err else DiagnosticStatus.OK
152                 stat.message = "0x%02x" % err
153
154                 # Diag
155                 stat.values.append(KeyValue("aft left diag", str(bool(err & (1 << 0)))))
156                 stat.values.append(KeyValue("front left diag", str(bool(err & (1 << 1)))))
157                 stat.values.append(KeyValue("aft right diag", str(bool(err & (1 << 2)))))
158                 stat.values.append(KeyValue("front right diag", str(bool(err & (1 << 3)))))
159                 # Stall
160                 stat.values.append(KeyValue("aft left stall", str(bool(err & (1 << 4)))))
161                 stat.values.append(KeyValue("front left stall", str(bool(err & (1 << 5)))))
162                 stat.values.append(KeyValue("aft right stall", str(bool(err & (1 << 6)))))
163                 stat.values.append(KeyValue("front right stall", str(bool(err & (1 << 7)))))
164
165                 msg.status.append(stat)
166                 self.pub_diag.publish(msg)
167         
168         def get_voltage(self):
169                 volt = struct.unpack(">h", i2c_read_reg(0x52, 0x09, 2))[0]/100.0
170
171                 msg = DiagnosticArray()
172                 msg.header.stamp = rospy.Time.now()
173                 stat = DiagnosticStatus()
174                 stat.name = "Voltage"
175                 stat.level = DiagnosticStatus.ERROR if volt < 7 else DiagnosticStatus.OK
176                 stat.message = "%.2fV" % volt
177
178                 msg.status.append(stat)
179                 self.pub_diag.publish(msg)
180
181
182         def get_odom(self):
183                 speed_trans, speed_rot, posx, posy, angle = struct.unpack(">fffff", i2c_read_reg(0x50, 0x38, 20))
184                 current_time = rospy.Time.now()
185
186                 # since all odometry is 6DOF we'll need a quaternion created from yaw
187                 odom_quat = tf.transformations.quaternion_from_euler(0, 0, angle)
188
189                 # first, we'll publish the transform over tf
190                 if self.tf_broadcaster is not None:
191                         self.tf_broadcaster.sendTransform((posx, posy, 0.0), odom_quat, current_time, "base_footprint", "odom")
192
193                 # next, we'll publish the odometry message over ROS
194                 odom = Odometry()
195                 odom.header.stamp = current_time
196                 odom.header.frame_id = "odom"
197
198                 # set the position
199                 odom.pose.pose.position.x = posx
200                 odom.pose.pose.position.y = posy
201                 odom.pose.pose.position.z = 0.0
202                 odom.pose.pose.orientation.x = odom_quat[0]
203                 odom.pose.pose.orientation.y = odom_quat[1]
204                 odom.pose.pose.orientation.z = odom_quat[2]
205                 odom.pose.pose.orientation.w = odom_quat[3]
206                 odom.pose.covariance[0] = 1e-3 # x
207                 odom.pose.covariance[7] = 1e-3 # y
208                 odom.pose.covariance[14] = 1e6 # z
209                 odom.pose.covariance[21] = 1e6 # rotation about X axis
210                 odom.pose.covariance[28] = 1e6 # rotation about Y axis
211                 odom.pose.covariance[35] = 0.03 # rotation about Z axis
212
213                 # set the velocity
214                 odom.child_frame_id = "base_footprint"
215                 odom.twist.twist.linear.x = speed_trans
216                 odom.twist.twist.linear.y = 0.0
217                 odom.twist.twist.angular.z = speed_rot
218                 odom.twist.covariance[0] = 1e-3 # x
219                 odom.twist.covariance[7] = 1e-3 # y
220                 odom.twist.covariance[14] = 1e6 # z
221                 odom.twist.covariance[21] = 1e6 # rotation about X axis
222                 odom.twist.covariance[28] = 1e6 # rotation about Y axis
223                 odom.twist.covariance[35] = 0.03 # rotation about Z axis
224
225                 # publish the message
226                 self.pub_odom.publish(odom)
227
228         
229         def set_speed(self, trans, rot):
230                 i2c_write_reg(0x50, 0x50, struct.pack(">ff", trans, rot))
231
232         def cmdVelReceived(self, msg):
233                 self.cmd_vel = (msg.linear.x, msg.angular.z) # commit speed on next update cycle
234
235         # http://rn-wissen.de/wiki/index.php/Sensorarten#Sharp_GP2D12
236         def get_dist_ir(self, num):
237                 dev = i2c(0x52)
238                 s = struct.pack("B", num)
239                 dev.write(s)
240                 dev.close()
241
242                 sleep(2e-6)
243
244                 dev = i2c(0x52)
245                 s = dev.read(2)
246                 dev.close()
247
248                 val = struct.unpack(">H", s)[0]
249                 return val
250         
251         def start_dist_srf(self, num):
252                 dev = i2c(0x52)
253                 s = struct.pack("B", num)
254                 dev.write(s)
255                 dev.close()
256
257         def read_dist_srf(self, num):
258                 return struct.unpack(">H", i2c_read_reg(0x52, num, 2))[0]/1000.0
259
260         def send_range(self, pub, frame_id, typ, dist, min_range, max_range, fov_deg):
261                 msg = Range()
262                 msg.header.stamp = rospy.Time.now()
263                 msg.header.frame_id = frame_id
264                 msg.radiation_type = typ
265                 msg.field_of_view = fov_deg*pi/180
266                 msg.min_range = min_range
267                 msg.max_range = max_range
268                 msg.range = dist
269                 pub.publish(msg)
270
271         def get_dist_left(self):
272                 if self.pub_range_left.get_num_connections() > 0:
273                         dist = self.get_dist_ir(0x1)
274                         if dist > -67:
275                                 self.send_range(self.pub_range_left, "ir_left", Range.INFRARED, 30.553/(dist - -67.534), 0.04, 0.3, 1)
276
277         def get_dist_right(self):
278                 if self.pub_range_right.get_num_connections() > 0:
279                         dist = self.get_dist_ir(0x3)
280                         if dist > 69:
281                                 self.send_range(self.pub_range_right, "ir_right", Range.INFRARED, 17.4/(dist - 69), 0.04, 0.3, 1)
282
283         def get_dist_forward(self):
284                 if self.pub_range_fwd.get_num_connections() > 0:
285                         dist = self.read_dist_srf(0x15)
286                         self.send_range(self.pub_range_fwd, "sonar_forward", Range.ULTRASOUND, dist, 0.04, 6, 40)
287                         self.start_dist_srf(0x5) # get next value
288
289         def get_dist_backward(self):
290                 if self.pub_range_bwd.get_num_connections() > 0:
291                         dist = self.read_dist_srf(0x17)
292                         self.send_range(self.pub_range_bwd, "sonar_backward", Range.ULTRASOUND, dist, 0.04, 6, 40)
293                         self.start_dist_srf(0x7) # get next value
294         
295         def led_stripe_received(self, msg):
296                 for led in msg.leds:
297                         self.pStripe.set(led.num, red=led.red, green=led.green, blue=led.blue)
298                         self.pStripe.update()
299                 
300
301 if __name__ == "__main__":
302         MoveBase()