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