]> defiant.homedns.org Git - ros_wild_thumper.git/blob - scripts/wt_node.py
663a4f17774dbab88772e094c556f047246729a9
[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 dynamic_reconfigure.server import Server
16 from sensor_msgs.msg import Imu, Range, BatteryState
17 from wild_thumper.msg import LedStripe
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_left = rospy.Publisher("range_forward_left", Range, queue_size=16)
64                 self.pub_range_fwd_right = rospy.Publisher("range_forward_right", Range, queue_size=16)
65                 self.pub_range_bwd = rospy.Publisher("range_backward", Range, queue_size=16)
66                 self.pub_range_left = rospy.Publisher("range_left", Range, queue_size=16)
67                 self.pub_range_right = rospy.Publisher("range_right", Range, queue_size=16)
68                 self.pub_battery = rospy.Publisher("battery", BatteryState, queue_size=16)
69                 self.cmd_vel = None
70                 self.cur_vel = (0, 0)
71                 self.bMotorManual = False
72                 self.set_speed(0, 0)
73                 self.volt_last_warn = rospy.Time.now()
74                 rospy.loginfo("Init done")
75                 i2c_write_reg(0x50, 0x90, struct.pack("BB", 1, 1)) # switch direction
76                 self.pStripe = LPD8806(1, 0, 12)
77                 rospy.Subscriber("cmd_vel_out", Twist, self.cmdVelReceived)
78                 rospy.Subscriber("led_stripe", LedStripe, self.led_stripe_received)
79                 rospy.Subscriber("imu", Imu, self.imuReceived)
80                 self.run()
81         
82         def run(self):
83                 rate = rospy.Rate(20.0)
84                 sleep(3) # wait 3s for ros to register and establish all subscriber connections before sending reset diag
85                 reset_val = self.get_reset()
86                 rospy.loginfo("Reset Status: 0x%x" % reset_val)
87                 ir_count = 0
88                 sonar_count = 0
89                 while not rospy.is_shutdown():
90                         rospy.logdebug("Loop alive")
91                         #print struct.unpack(">B", i2c_read_reg(0x50, 0xA2, 1))[0] # count test
92                         self.get_motor_err()
93                         self.get_odom()
94                         self.get_voltage()
95
96                         if ir_count == 0:
97                                 self.get_dist_left()
98                                 ir_count+=1
99                         else:
100                                 self.get_dist_right()
101                                 ir_count=0
102
103                         if sonar_count == 0:
104                                 self.get_dist_forward_left()
105                                 self.update_dist_backward()
106                                 sonar_count+=1
107                         elif sonar_count == 1:
108                                 self.get_dist_backward()
109                                 self.update_dist_forward_right()
110                                 sonar_count+=1
111                         elif sonar_count == 2:
112                                 self.get_dist_forward_right()
113                                 self.update_dist_forward_left()
114                                 sonar_count=0
115
116                         if self.cmd_vel != None:
117                                 self.set_speed(self.cmd_vel[0], self.cmd_vel[1])
118                                 self.cur_vel = self.cmd_vel
119                                 self.cmd_vel = None
120                         rate.sleep()
121
122         def execute_dyn_reconf(self, config, level):
123                 self.bClipRangeSensor = config["range_sensor_clip"]
124                 self.range_sensor_max = config["range_sensor_max"]
125                 self.range_sensor_fov = config["range_sensor_fov"]
126                 self.odom_covar_xy = config["odom_covar_xy"]
127                 self.odom_covar_angle = config["odom_covar_angle"]
128                 self.rollover_protect = config["rollover_protect"]
129                 self.rollover_protect_limit = config["rollover_protect_limit"]
130                 self.rollover_protect_pwm = config["rollover_protect_pwm"]
131
132                 return config
133
134         def imuReceived(self, msg):
135                 if self.rollover_protect and any(self.cur_vel):
136                         (roll, pitch, yaw) = tf.transformations.euler_from_quaternion(msg.orientation.__getstate__())
137                         if pitch > self.rollover_protect_limit*pi/180:
138                                 self.bMotorManual = True
139                                 i2c_write_reg(0x50, 0x1, struct.pack(">hhhh", 0, self.rollover_protect_pwm, 0, self.rollover_protect_pwm))
140                                 rospy.logwarn("Running forward rollver protection")
141                         elif pitch < -self.rollover_protect_limit*pi/180:
142                                 self.bMotorManual = True
143                                 i2c_write_reg(0x50, 0x1, struct.pack(">hhhh", -self.rollover_protect_pwm, 0, -self.rollover_protect_pwm, 0))
144                                 rospy.logwarn("Running backward rollver protection")
145                         elif self.bMotorManual:
146                                 i2c_write_reg(0x50, 0x1, struct.pack(">hhhh", 0, 0, 0, 0))
147                                 self.bMotorManual = False
148                                 self.cmd_vel = (0, 0)
149                                 rospy.logwarn("Rollver protection done")
150
151         def get_reset(self):
152                 reset = struct.unpack(">B", i2c_read_reg(0x50, 0xA0, 1))[0]
153
154                 msg = DiagnosticArray()
155                 msg.header.stamp = rospy.Time.now()
156                 stat = DiagnosticStatus()
157                 stat.name = "Reset reason"
158                 stat.level = DiagnosticStatus.ERROR if reset & 0x0c else DiagnosticStatus.OK
159                 stat.message = "0x%02x" % reset
160
161                 wdrf = bool(reset & (1 << 3))
162                 if wdrf: rospy.loginfo("Watchdog Reset")
163                 borf = bool(reset & (1 << 2))
164                 if borf: rospy.loginfo("Brown-out Reset Flag")
165                 extrf = bool(reset & (1 << 1))
166                 if extrf: rospy.loginfo("External Reset Flag")
167                 porf = bool(reset & (1 << 0))
168                 if porf: rospy.loginfo("Power-on Reset Flag")
169                 stat.values.append(KeyValue("Watchdog Reset Flag", str(wdrf)))
170                 stat.values.append(KeyValue("Brown-out Reset Flag", str(borf)))
171                 stat.values.append(KeyValue("External Reset Flag", str(extrf)))
172                 stat.values.append(KeyValue("Power-on Reset Flag", str(porf)))
173
174                 msg.status.append(stat)
175                 self.pub_diag.publish(msg)
176                 return reset
177
178
179         def get_motor_err(self):
180                 err = struct.unpack(">B", i2c_read_reg(0x50, 0xA1, 1))[0]
181                 
182                 msg = DiagnosticArray()
183                 msg.header.stamp = rospy.Time.now()
184                 stat = DiagnosticStatus()
185                 stat.name = "Motor: Error Status"
186                 stat.level = DiagnosticStatus.ERROR if err else DiagnosticStatus.OK
187                 stat.message = "0x%02x" % err
188
189                 # Diag
190                 stat.values.append(KeyValue("aft left diag", str(bool(err & (1 << 0)))))
191                 stat.values.append(KeyValue("front left diag", str(bool(err & (1 << 1)))))
192                 stat.values.append(KeyValue("aft right diag", str(bool(err & (1 << 2)))))
193                 stat.values.append(KeyValue("front right diag", str(bool(err & (1 << 3)))))
194                 # Stall
195                 stat.values.append(KeyValue("aft left stall", str(bool(err & (1 << 4)))))
196                 stat.values.append(KeyValue("front left stall", str(bool(err & (1 << 5)))))
197                 stat.values.append(KeyValue("aft right stall", str(bool(err & (1 << 6)))))
198                 stat.values.append(KeyValue("front right stall", str(bool(err & (1 << 7)))))
199
200                 msg.status.append(stat)
201                 self.pub_diag.publish(msg)
202         
203         def get_voltage(self):
204                 volt = struct.unpack(">h", i2c_read_reg(0x52, 0x09, 2))[0]/100.0
205
206                 msg = DiagnosticArray()
207                 msg.header.stamp = rospy.Time.now()
208                 stat = DiagnosticStatus()
209                 stat.name = "Voltage"
210                 stat.level = DiagnosticStatus.ERROR if volt < 7 else DiagnosticStatus.OK
211                 stat.message = "%.2fV" % volt
212
213                 msg.status.append(stat)
214                 self.pub_diag.publish(msg)
215
216                 if self.pub_battery.get_num_connections() > 0:
217                         batmsg = BatteryState()
218                         batmsg.header.stamp = rospy.Time.now()
219                         batmsg.voltage = volt
220                         batmsg.current = float('nan')
221                         batmsg.charge = float('nan')
222                         batmsg.capacity = float('nan')
223                         batmsg.design_capacity = 5.0
224                         batmsg.percentage = float('nan')
225                         batmsg.power_supply_status = BatteryState.POWER_SUPPLY_STATUS_DISCHARGING
226                         batmsg.power_supply_health = BatteryState.POWER_SUPPLY_HEALTH_UNKNOWN
227                         batmsg.power_supply_technology = BatteryState.POWER_SUPPLY_TECHNOLOGY_NIMH
228                         self.pub_battery.publish(batmsg)
229
230                 if volt < 7 and (rospy.Time.now() - self.volt_last_warn).to_sec() > 10:
231                         rospy.logerr("Voltage critical: %.2fV" % (volt))
232                         self.volt_last_warn = rospy.Time.now()
233
234
235         def get_odom(self):
236                 speed_trans, speed_rot, posx, posy, angle = struct.unpack(">fffff", i2c_read_reg(0x50, 0x38, 20))
237                 current_time = rospy.Time.now()
238
239                 # since all odometry is 6DOF we'll need a quaternion created from yaw
240                 odom_quat = tf.transformations.quaternion_from_euler(0, 0, angle)
241
242                 # first, we'll publish the transform over tf
243                 if self.tf_broadcaster is not None:
244                         self.tf_broadcaster.sendTransform((posx, posy, 0.0), odom_quat, current_time, "base_footprint", "odom")
245
246                 # next, we'll publish the odometry message over ROS
247                 odom = Odometry()
248                 odom.header.stamp = current_time
249                 odom.header.frame_id = "odom"
250
251                 # set the position
252                 odom.pose.pose.position.x = posx
253                 odom.pose.pose.position.y = posy
254                 odom.pose.pose.position.z = 0.0
255                 odom.pose.pose.orientation.x = odom_quat[0]
256                 odom.pose.pose.orientation.y = odom_quat[1]
257                 odom.pose.pose.orientation.z = odom_quat[2]
258                 odom.pose.pose.orientation.w = odom_quat[3]
259                 odom.pose.covariance[0] = self.odom_covar_xy # x
260                 odom.pose.covariance[7] = self.odom_covar_xy # y
261                 odom.pose.covariance[14] = self.odom_covar_xy # z
262                 odom.pose.covariance[21] = self.odom_covar_angle # rotation about X axis
263                 odom.pose.covariance[28] = self.odom_covar_angle # rotation about Y axis
264                 odom.pose.covariance[35] = self.odom_covar_angle # rotation about Z axis
265
266                 # set the velocity
267                 odom.child_frame_id = "base_footprint"
268                 odom.twist.twist.linear.x = speed_trans
269                 odom.twist.twist.linear.y = 0.0
270                 odom.twist.twist.linear.z = 0.0
271                 odom.twist.twist.angular.z = speed_rot
272                 odom.twist.covariance = odom.pose.covariance
273
274                 # publish the message
275                 self.pub_odom.publish(odom)
276
277         
278         def set_speed(self, trans, rot):
279                 i2c_write_reg(0x50, 0x50, struct.pack(">ff", trans, rot))
280
281         def cmdVelReceived(self, msg):
282                 if not self.bMotorManual:
283                         rospy.logdebug("Set new cmd_vel: %.2f %.2f", msg.linear.x, msg.angular.z)
284                         self.cmd_vel = (msg.linear.x, msg.angular.z) # commit speed on next update cycle
285                         rospy.logdebug("Set new cmd_vel done")
286
287         # http://rn-wissen.de/wiki/index.php/Sensorarten#Sharp_GP2D12
288         def get_dist_ir(self, num):
289                 dev = i2c(0x52)
290                 s = struct.pack("B", num)
291                 dev.write(s)
292                 dev.close()
293
294                 sleep(2e-6)
295
296                 dev = i2c(0x52)
297                 s = dev.read(2)
298                 dev.close()
299
300                 val = struct.unpack(">H", s)[0]
301                 return val
302         
303         def start_dist_srf(self, num):
304                 dev = i2c(0x52)
305                 s = struct.pack("B", num)
306                 dev.write(s)
307                 dev.close()
308
309         def read_dist_srf(self, num):
310                 return struct.unpack(">H", i2c_read_reg(0x52, num, 2))[0]/1000.0
311
312         def send_range(self, pub, frame_id, typ, dist, min_range, max_range, fov_deg):
313                 if self.bClipRangeSensor and dist > max_range:
314                         dist = max_range
315                 msg = Range()
316                 msg.header.stamp = rospy.Time.now()
317                 msg.header.frame_id = frame_id
318                 msg.radiation_type = typ
319                 msg.field_of_view = fov_deg*pi/180
320                 msg.min_range = min_range
321                 msg.max_range = max_range
322                 msg.range = dist
323                 pub.publish(msg)
324
325         def get_dist_left(self):
326                 if self.pub_range_left.get_num_connections() > 0:
327                         dist = self.get_dist_ir(0x1)
328                         if dist > -67:
329                                 self.send_range(self.pub_range_left, "ir_left", Range.INFRARED, 30.553/(dist - -67.534), 0.04, 0.3, 1)
330
331         def get_dist_right(self):
332                 if self.pub_range_right.get_num_connections() > 0:
333                         dist = self.get_dist_ir(0x3)
334                         if dist > 69:
335                                 self.send_range(self.pub_range_right, "ir_right", Range.INFRARED, 17.4/(dist - 69), 0.04, 0.3, 1)
336
337         def get_dist_forward_left(self):
338                 if self.pub_range_fwd_left.get_num_connections() > 0:
339                         dist = self.read_dist_srf(0x15)
340                         self.send_range(self.pub_range_fwd_left, "sonar_forward_left", Range.ULTRASOUND, dist, 0.04, self.range_sensor_max, self.range_sensor_fov)
341
342         def update_dist_forward_left(self):
343                 if self.pub_range_fwd_left.get_num_connections() > 0:
344                         self.start_dist_srf(0x5)
345
346         def get_dist_backward(self):
347                 if self.pub_range_bwd.get_num_connections() > 0:
348                         dist = self.read_dist_srf(0x17)
349                         self.send_range(self.pub_range_bwd, "sonar_backward", Range.ULTRASOUND, dist, 0.04, self.range_sensor_max, self.range_sensor_fov)
350
351         def update_dist_backward(self):
352                 if self.pub_range_bwd.get_num_connections() > 0:
353                         self.start_dist_srf(0x7)
354
355         def get_dist_forward_right(self):
356                 if self.pub_range_fwd_right.get_num_connections() > 0:
357                         dist = self.read_dist_srf(0x19)
358                         self.send_range(self.pub_range_fwd_right, "sonar_forward_right", Range.ULTRASOUND, dist, 0.04, self.range_sensor_max, self.range_sensor_fov)
359
360         def update_dist_forward_right(self):
361                 if self.pub_range_fwd_right.get_num_connections() > 0:
362                         self.start_dist_srf(0xb)
363         
364         def led_stripe_received(self, msg):
365                 for led in msg.leds:
366                         self.pStripe.set(led.num, red=led.red, green=led.green, blue=led.blue)
367                         self.pStripe.update()
368                 
369
370 if __name__ == "__main__":
371         MoveBase()