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