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