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