2 # -*- coding: iso-8859-15 -*-
10 from time import sleep
11 from i2c import i2c, i2c_write_reg, i2c_read_reg
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
24 rospy.init_node('wild_thumper')
25 prctl.set_name("wild_thumper")
26 enable_odom_tf = rospy.get_param("~enable_odom_tf", True)
28 self.tf_broadcaster = tf.broadcaster.TransformBroadcaster()
30 self.tf_broadcaster = None
31 self.dyn_conf = Server(WildThumperConfig, self.execute_dyn_reconf)
32 self.pub_odom = rospy.Publisher("odom", Odometry, queue_size=16)
33 self.pub_diag = rospy.Publisher("diagnostics", DiagnosticArray, queue_size=16)
34 self.pub_range_fwd_left = rospy.Publisher("range_forward_left", Range, queue_size=16)
35 self.pub_range_fwd_right = rospy.Publisher("range_forward_right", Range, queue_size=16)
36 self.pub_range_bwd = rospy.Publisher("range_backward", Range, queue_size=16)
37 self.pub_range_left = rospy.Publisher("range_left", Range, queue_size=16)
38 self.pub_range_right = rospy.Publisher("range_right", Range, queue_size=16)
39 self.pub_battery = rospy.Publisher("battery", BatteryState, queue_size=16)
42 self.bMotorManual = False
44 self.volt_last_warn = rospy.Time.now()
45 rospy.loginfo("Init done")
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)
50 self.bDocked_last = False
54 rate = rospy.Rate(20.0)
55 sleep(3) # wait 3s for ros to register and establish all subscriber connections before sending reset diag
56 reset_val = self.get_reset()
57 rospy.loginfo("Reset Status: 0x%x" % reset_val)
60 while not rospy.is_shutdown():
61 rospy.logdebug("Loop alive")
62 #print struct.unpack(">B", i2c_read_reg(0x50, 0xA2, 1))[0] # count test
75 self.get_dist_forward_left()
76 self.update_dist_backward()
78 elif sonar_count == 1:
79 self.get_dist_backward()
80 self.update_dist_forward_right()
82 elif sonar_count == 2:
83 self.get_dist_forward_right()
84 self.update_dist_forward_left()
87 if self.cmd_vel != None:
88 self.set_speed(self.cmd_vel[0], self.cmd_vel[1])
89 self.cur_vel = self.cmd_vel
95 def execute_dyn_reconf(self, config, level):
96 self.bClipRangeSensor = config["range_sensor_clip"]
97 self.range_sensor_max = config["range_sensor_max"]
98 self.range_sensor_fov = config["range_sensor_fov"]
99 self.odom_covar_xy = config["odom_covar_xy"]
100 self.odom_covar_angle = config["odom_covar_angle"]
101 self.rollover_protect = config["rollover_protect"]
102 self.rollover_protect_limit = config["rollover_protect_limit"]
103 self.rollover_protect_pwm = config["rollover_protect_pwm"]
104 self.bStayDocked = config["stay_docked"]
108 def imuReceived(self, msg):
109 if self.rollover_protect and (any(self.cur_vel) or self.bMotorManual):
110 (roll, pitch, yaw) = tf.transformations.euler_from_quaternion(msg.orientation.__getstate__())
111 if pitch > self.rollover_protect_limit*pi/180:
112 self.bMotorManual = True
113 i2c_write_reg(0x50, 0x1, struct.pack(">hhhh", 0, self.rollover_protect_pwm, 0, self.rollover_protect_pwm))
114 rospy.logwarn("Running forward rollver protection")
115 elif pitch < -self.rollover_protect_limit*pi/180:
116 self.bMotorManual = True
117 i2c_write_reg(0x50, 0x1, struct.pack(">hhhh", -self.rollover_protect_pwm, 0, -self.rollover_protect_pwm, 0))
118 rospy.logwarn("Running backward rollver protection")
119 elif self.bMotorManual:
120 i2c_write_reg(0x50, 0x1, struct.pack(">hhhh", 0, 0, 0, 0))
121 self.bMotorManual = False
122 self.cmd_vel = (0, 0)
123 rospy.logwarn("Rollver protection done")
126 reset = struct.unpack(">B", i2c_read_reg(0x50, 0xA0, 1))[0]
128 msg = DiagnosticArray()
129 msg.header.stamp = rospy.Time.now()
130 stat = DiagnosticStatus()
131 stat.name = "Reset reason"
132 stat.level = DiagnosticStatus.ERROR if reset & 0x0c else DiagnosticStatus.OK
133 stat.message = "0x%02x" % reset
135 wdrf = bool(reset & (1 << 3))
136 if wdrf: rospy.loginfo("Watchdog Reset")
137 borf = bool(reset & (1 << 2))
138 if borf: rospy.loginfo("Brown-out Reset Flag")
139 extrf = bool(reset & (1 << 1))
140 if extrf: rospy.loginfo("External Reset Flag")
141 porf = bool(reset & (1 << 0))
142 if porf: rospy.loginfo("Power-on Reset Flag")
143 stat.values.append(KeyValue("Watchdog Reset Flag", str(wdrf)))
144 stat.values.append(KeyValue("Brown-out Reset Flag", str(borf)))
145 stat.values.append(KeyValue("External Reset Flag", str(extrf)))
146 stat.values.append(KeyValue("Power-on Reset Flag", str(porf)))
148 msg.status.append(stat)
149 self.pub_diag.publish(msg)
153 def get_motor_err(self):
154 err = struct.unpack(">B", i2c_read_reg(0x50, 0xA1, 1))[0]
156 msg = DiagnosticArray()
157 msg.header.stamp = rospy.Time.now()
158 stat = DiagnosticStatus()
159 stat.name = "Motor: Error Status"
160 stat.level = DiagnosticStatus.ERROR if err else DiagnosticStatus.OK
161 stat.message = "0x%02x" % err
164 stat.values.append(KeyValue("aft left diag", str(bool(err & (1 << 0)))))
165 stat.values.append(KeyValue("front left diag", str(bool(err & (1 << 1)))))
166 stat.values.append(KeyValue("aft right diag", str(bool(err & (1 << 2)))))
167 stat.values.append(KeyValue("front right diag", str(bool(err & (1 << 3)))))
169 stat.values.append(KeyValue("aft left stall", str(bool(err & (1 << 4)))))
170 stat.values.append(KeyValue("front left stall", str(bool(err & (1 << 5)))))
171 stat.values.append(KeyValue("aft right stall", str(bool(err & (1 << 6)))))
172 stat.values.append(KeyValue("front right stall", str(bool(err & (1 << 7)))))
174 msg.status.append(stat)
175 self.pub_diag.publish(msg)
178 volt = struct.unpack(">h", i2c_read_reg(0x52, 0x09, 2))[0]/100.0
179 current = struct.unpack(">h", i2c_read_reg(0x52, 0x0D, 2))[0]/1000.0
181 msg = DiagnosticArray()
182 msg.header.stamp = rospy.Time.now()
183 stat = DiagnosticStatus()
185 stat.level = DiagnosticStatus.ERROR if volt < 7 or current > 5 else DiagnosticStatus.OK
186 stat.message = "%.2fV, %.2fA" % (volt, current)
188 msg.status.append(stat)
189 self.pub_diag.publish(msg)
191 if self.pub_battery.get_num_connections() > 0:
192 batmsg = BatteryState()
193 batmsg.header.stamp = rospy.Time.now()
194 batmsg.voltage = volt
195 batmsg.current = current
196 batmsg.charge = float('nan')
197 batmsg.capacity = float('nan')
198 batmsg.design_capacity = 5.0
199 batmsg.percentage = float('nan')
200 batmsg.power_supply_status = BatteryState.POWER_SUPPLY_STATUS_DISCHARGING
201 batmsg.power_supply_health = BatteryState.POWER_SUPPLY_HEALTH_UNKNOWN
202 batmsg.power_supply_technology = BatteryState.POWER_SUPPLY_TECHNOLOGY_NIMH
203 self.pub_battery.publish(batmsg)
205 if volt < 7 and (rospy.Time.now() - self.volt_last_warn).to_sec() > 10:
206 rospy.logerr("Voltage critical: %.2fV" % (volt))
207 self.volt_last_warn = rospy.Time.now()
209 self.bDocked = volt > 10.1
213 speed_trans, speed_rot, posx, posy, angle = struct.unpack(">fffff", i2c_read_reg(0x50, 0x38, 20))
214 current_time = rospy.Time.now()
216 # since all odometry is 6DOF we'll need a quaternion created from yaw
217 odom_quat = tf.transformations.quaternion_from_euler(0, 0, angle)
219 # first, we'll publish the transform over tf
220 if self.tf_broadcaster is not None:
221 self.tf_broadcaster.sendTransform((posx, posy, 0.0), odom_quat, current_time, "base_footprint", "odom")
223 # next, we'll publish the odometry message over ROS
225 odom.header.stamp = current_time
226 odom.header.frame_id = "odom"
229 odom.pose.pose.position.x = posx
230 odom.pose.pose.position.y = posy
231 odom.pose.pose.position.z = 0.0
232 odom.pose.pose.orientation.x = odom_quat[0]
233 odom.pose.pose.orientation.y = odom_quat[1]
234 odom.pose.pose.orientation.z = odom_quat[2]
235 odom.pose.pose.orientation.w = odom_quat[3]
236 odom.pose.covariance[0] = self.odom_covar_xy # x
237 odom.pose.covariance[7] = self.odom_covar_xy # y
238 odom.pose.covariance[14] = self.odom_covar_xy # z
239 odom.pose.covariance[21] = self.odom_covar_angle # rotation about X axis
240 odom.pose.covariance[28] = self.odom_covar_angle # rotation about Y axis
241 odom.pose.covariance[35] = self.odom_covar_angle # rotation about Z axis
244 odom.child_frame_id = "base_footprint"
245 odom.twist.twist.linear.x = speed_trans
246 odom.twist.twist.linear.y = 0.0
247 odom.twist.twist.linear.z = 0.0
248 odom.twist.twist.angular.z = speed_rot
249 odom.twist.covariance = odom.pose.covariance
251 # publish the message
252 self.pub_odom.publish(odom)
255 def set_speed(self, trans, rot):
256 i2c_write_reg(0x50, 0x50, struct.pack(">ff", trans, rot))
258 def cmdVelReceived(self, msg):
259 if not self.bMotorManual:
260 rospy.logdebug("Set new cmd_vel: %.2f %.2f", msg.linear.x, msg.angular.z)
261 self.cmd_vel = (msg.linear.x, msg.angular.z) # commit speed on next update cycle
262 rospy.logdebug("Set new cmd_vel done")
264 # http://rn-wissen.de/wiki/index.php/Sensorarten#Sharp_GP2D12
265 def get_dist_ir(self, num):
267 s = struct.pack("B", num)
277 val = struct.unpack(">H", s)[0]
280 def start_dist_srf(self, num):
282 s = struct.pack("B", num)
286 def read_dist_srf(self, num):
287 return struct.unpack(">H", i2c_read_reg(0x52, num, 2))[0]/1000.0
289 def send_range(self, pub, frame_id, typ, dist, min_range, max_range, fov_deg):
290 if self.bClipRangeSensor and dist > max_range:
293 msg.header.stamp = rospy.Time.now()
294 msg.header.frame_id = frame_id
295 msg.radiation_type = typ
296 msg.field_of_view = fov_deg*pi/180
297 msg.min_range = min_range
298 msg.max_range = max_range
302 def get_dist_left(self):
303 if self.pub_range_left.get_num_connections() > 0:
304 dist = self.get_dist_ir(0x1)
306 self.send_range(self.pub_range_left, "ir_left", Range.INFRARED, 30.553/(dist - -67.534), 0.04, 0.3, 1)
308 def get_dist_right(self):
309 if self.pub_range_right.get_num_connections() > 0:
310 dist = self.get_dist_ir(0x3)
312 self.send_range(self.pub_range_right, "ir_right", Range.INFRARED, 17.4/(dist - 69), 0.04, 0.3, 1)
314 def get_dist_forward_left(self):
315 if self.pub_range_fwd_left.get_num_connections() > 0:
316 dist = self.read_dist_srf(0x15)
317 self.send_range(self.pub_range_fwd_left, "sonar_forward_left", Range.ULTRASOUND, dist, 0.04, self.range_sensor_max, self.range_sensor_fov)
319 def update_dist_forward_left(self):
320 if self.pub_range_fwd_left.get_num_connections() > 0:
321 self.start_dist_srf(0x5)
323 def get_dist_backward(self):
324 if self.pub_range_bwd.get_num_connections() > 0:
325 dist = self.read_dist_srf(0x17)
326 self.send_range(self.pub_range_bwd, "sonar_backward", Range.ULTRASOUND, dist, 0.04, self.range_sensor_max, self.range_sensor_fov)
328 def update_dist_backward(self):
329 if self.pub_range_bwd.get_num_connections() > 0:
330 self.start_dist_srf(0x7)
332 def get_dist_forward_right(self):
333 if self.pub_range_fwd_right.get_num_connections() > 0:
334 dist = self.read_dist_srf(0x19)
335 self.send_range(self.pub_range_fwd_right, "sonar_forward_right", Range.ULTRASOUND, dist, 0.04, self.range_sensor_max, self.range_sensor_fov)
337 def update_dist_forward_right(self):
338 if self.pub_range_fwd_right.get_num_connections() > 0:
339 self.start_dist_srf(0xb)
341 def check_docked(self):
342 if self.bDocked and not self.bDocked_last:
343 rospy.loginfo("Docking event")
344 elif not self.bDocked and self.bDocked_last:
345 if not self.bStayDocked or self.cur_vel != (0, 0):
346 rospy.loginfo("Undocking event")
348 rospy.loginfo("Undocking event..redocking")
349 thread.start_new_thread(self.redock, ())
351 self.bDocked_last = self.bDocked
354 self.cmd_vel = (-0.1, 0)
359 self.cmd_vel = (0, 0)
361 rospy.loginfo("Redocking done")
363 rospy.logerr("Redocking failed")
366 if __name__ == "__main__":