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