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