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