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
19 from std_srvs.srv import SetBool, SetBoolResponse
22 BATTERY_CAPACITY_FULL = 2.750 # Ah, NiMH=2.750, LiFePO4=3.100
27 rospy.init_node('wild_thumper')
28 prctl.set_name("wild_thumper")
29 enable_odom_tf = rospy.get_param("~enable_odom_tf", True)
31 self.tf_broadcaster = tf.broadcaster.TransformBroadcaster()
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_range_left = rospy.Publisher("range_left", Range, queue_size=16)
41 self.pub_range_right = rospy.Publisher("range_right", Range, queue_size=16)
42 self.pub_battery = rospy.Publisher("battery", BatteryState, queue_size=16)
45 self.bMotorManual = False
47 self.volt_last_warn = rospy.Time.now()
48 i2c_write_reg(0x50, 0x90, struct.pack("BB", 1, 1)) # switch direction
49 rospy.Subscriber("cmd_vel_out", Twist, self.cmdVelReceived)
50 rospy.Subscriber("imu", Imu, self.imuReceived)
51 rospy.Service('~manipulator_enable', SetBool, self.enableManipulator)
53 self.bDocked_last = False
54 self.battery_capacity = BATTERY_CAPACITY_FULL*3600 # As
55 rospy.loginfo("Init done")
59 rate = rospy.Rate(UPDATE_RATE)
60 sleep(3) # wait 3s for ros to register and establish all subscriber connections before sending reset diag
61 reset_val = self.get_reset()
62 rospy.loginfo("Reset Status: 0x%x" % reset_val)
65 i2c_write_reg(0x50, 0xA4, struct.pack("B", 1)) # enable Watchdog
66 while not rospy.is_shutdown():
67 rospy.logdebug("Loop alive")
68 #print "Watchdog", struct.unpack(">B", i2c_read_reg(0x50, 0xA4, 1))[0]
69 #print struct.unpack(">B", i2c_read_reg(0x50, 0xA2, 1))[0] # count test
82 self.get_dist_forward_left()
83 self.update_dist_backward()
85 elif sonar_count == 1:
86 self.get_dist_backward()
87 self.update_dist_forward_right()
89 elif sonar_count == 2:
90 self.get_dist_forward_right()
91 self.update_dist_forward_left()
94 if self.cmd_vel != None:
95 self.set_speed(self.cmd_vel[0], self.cmd_vel[1])
96 self.cur_vel = self.cmd_vel
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.range_sensor_fov = config["range_sensor_fov"]
106 self.odom_covar_xy = config["odom_covar_xy"]
107 self.odom_covar_angle = config["odom_covar_angle"]
108 self.rollover_protect = config["rollover_protect"]
109 self.rollover_protect_limit = config["rollover_protect_limit"]
110 self.rollover_protect_pwm = config["rollover_protect_pwm"]
111 self.bStayDocked = config["stay_docked"]
115 def imuReceived(self, msg):
116 if self.rollover_protect and (any(self.cur_vel) or self.bMotorManual):
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")
133 reset = struct.unpack(">B", i2c_read_reg(0x50, 0xA0, 1))[0]
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
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)))
155 msg.status.append(stat)
156 self.pub_diag.publish(msg)
160 def get_motor_err(self):
161 err = struct.unpack(">B", i2c_read_reg(0x50, 0xA1, 1))[0]
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
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)))))
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)))))
181 msg.status.append(stat)
182 self.pub_diag.publish(msg)
185 volt = struct.unpack(">h", i2c_read_reg(0x52, 0x09, 2))[0]/100.0
186 current = struct.unpack(">h", i2c_read_reg(0x52, 0x0D, 2))[0]/1000.0
188 msg = DiagnosticArray()
189 msg.header.stamp = rospy.Time.now()
190 stat = DiagnosticStatus()
192 stat.level = DiagnosticStatus.ERROR if volt < 7 or current > 5 else DiagnosticStatus.OK
193 stat.message = "%.2fV, %.2fA" % (volt, current)
195 msg.status.append(stat)
196 self.pub_diag.publish(msg)
198 if volt < 7 and (rospy.Time.now() - self.volt_last_warn).to_sec() > 10:
199 rospy.logerr("Voltage critical: %.2fV" % (volt))
200 self.volt_last_warn = rospy.Time.now()
202 self.bDocked = volt > 10.1
203 self.update_capacity(volt, current)
205 if self.pub_battery.get_num_connections() > 0:
206 batmsg = BatteryState()
207 batmsg.header.stamp = rospy.Time.now()
208 batmsg.voltage = volt
209 batmsg.current = current
210 batmsg.charge = self.battery_capacity/3600.0
211 batmsg.capacity = float('nan')
212 batmsg.design_capacity = BATTERY_CAPACITY_FULL
213 batmsg.percentage = batmsg.charge/batmsg.design_capacity
214 batmsg.power_supply_status = BatteryState.POWER_SUPPLY_STATUS_DISCHARGING
215 batmsg.power_supply_health = BatteryState.POWER_SUPPLY_HEALTH_UNKNOWN
216 batmsg.power_supply_technology = BatteryState.POWER_SUPPLY_TECHNOLOGY_NIMH
217 batmsg.present = True
218 self.pub_battery.publish(batmsg)
220 def update_capacity(self, volt, current):
222 self.battery_capacity = BATTERY_CAPACITY_FULL*3600
224 self.battery_capacity -= current/UPDATE_RATE
227 speed_trans, speed_rot, posx, posy, angle = struct.unpack(">fffff", i2c_read_reg(0x50, 0x38, 20))
228 current_time = rospy.Time.now()
230 # since all odometry is 6DOF we'll need a quaternion created from yaw
231 odom_quat = tf.transformations.quaternion_from_euler(0, 0, angle)
233 # first, we'll publish the transform over tf
234 if self.tf_broadcaster is not None:
235 self.tf_broadcaster.sendTransform((posx, posy, 0.0), odom_quat, current_time, "base_footprint", "odom")
237 # next, we'll publish the odometry message over ROS
239 odom.header.stamp = current_time
240 odom.header.frame_id = "odom"
243 odom.pose.pose.position.x = posx
244 odom.pose.pose.position.y = posy
245 odom.pose.pose.position.z = 0.0
246 odom.pose.pose.orientation.x = odom_quat[0]
247 odom.pose.pose.orientation.y = odom_quat[1]
248 odom.pose.pose.orientation.z = odom_quat[2]
249 odom.pose.pose.orientation.w = odom_quat[3]
250 odom.pose.covariance[0] = self.odom_covar_xy # x
251 odom.pose.covariance[7] = self.odom_covar_xy # y
252 odom.pose.covariance[14] = self.odom_covar_xy # z
253 odom.pose.covariance[21] = self.odom_covar_angle # rotation about X axis
254 odom.pose.covariance[28] = self.odom_covar_angle # rotation about Y axis
255 odom.pose.covariance[35] = self.odom_covar_angle # rotation about Z axis
258 odom.child_frame_id = "base_footprint"
259 odom.twist.twist.linear.x = speed_trans
260 odom.twist.twist.linear.y = 0.0
261 odom.twist.twist.linear.z = 0.0
262 odom.twist.twist.angular.z = speed_rot
263 odom.twist.covariance = odom.pose.covariance
265 # publish the message
266 self.pub_odom.publish(odom)
269 def set_speed(self, trans, rot):
270 i2c_write_reg(0x50, 0x50, struct.pack(">ff", trans, rot))
272 def cmdVelReceived(self, msg):
273 if not self.bMotorManual:
274 rospy.logdebug("Set new cmd_vel: %.2f %.2f", msg.linear.x, msg.angular.z)
275 self.cmd_vel = (msg.linear.x, msg.angular.z) # commit speed on next update cycle
276 rospy.logdebug("Set new cmd_vel done")
278 # http://rn-wissen.de/wiki/index.php/Sensorarten#Sharp_GP2D12
279 def get_dist_ir(self, num):
281 s = struct.pack("B", num)
291 val = struct.unpack(">H", s)[0]
294 def start_dist_srf(self, num):
296 s = struct.pack("B", num)
300 def read_dist_srf(self, num):
301 return struct.unpack(">H", i2c_read_reg(0x52, num, 2))[0]/1000.0
303 def send_range(self, pub, frame_id, typ, dist, min_range, max_range, fov_deg):
304 if self.bClipRangeSensor and dist > max_range:
307 msg.header.stamp = rospy.Time.now()
308 msg.header.frame_id = frame_id
309 msg.radiation_type = typ
310 msg.field_of_view = fov_deg*pi/180
311 msg.min_range = min_range
312 msg.max_range = max_range
316 def get_dist_left(self):
317 if self.pub_range_left.get_num_connections() > 0:
318 dist = self.get_dist_ir(0x1)
320 self.send_range(self.pub_range_left, "ir_left", Range.INFRARED, 30.553/(dist - -67.534), 0.04, 0.3, 1)
322 def get_dist_right(self):
323 if self.pub_range_right.get_num_connections() > 0:
324 dist = self.get_dist_ir(0x3)
326 self.send_range(self.pub_range_right, "ir_right", Range.INFRARED, 17.4/(dist - 69), 0.04, 0.3, 1)
328 def get_dist_forward_left(self):
329 if self.pub_range_fwd_left.get_num_connections() > 0:
330 dist = self.read_dist_srf(0x15)
331 self.send_range(self.pub_range_fwd_left, "sonar_forward_left", Range.ULTRASOUND, dist, 0.04, self.range_sensor_max, self.range_sensor_fov)
333 def update_dist_forward_left(self):
334 if self.pub_range_fwd_left.get_num_connections() > 0:
335 self.start_dist_srf(0x5)
337 def get_dist_backward(self):
338 if self.pub_range_bwd.get_num_connections() > 0:
339 dist = self.read_dist_srf(0x17)
340 self.send_range(self.pub_range_bwd, "sonar_backward", Range.ULTRASOUND, dist, 0.04, self.range_sensor_max, self.range_sensor_fov)
342 def update_dist_backward(self):
343 if self.pub_range_bwd.get_num_connections() > 0:
344 self.start_dist_srf(0x7)
346 def get_dist_forward_right(self):
347 if self.pub_range_fwd_right.get_num_connections() > 0:
348 dist = self.read_dist_srf(0x19)
349 self.send_range(self.pub_range_fwd_right, "sonar_forward_right", Range.ULTRASOUND, dist, 0.04, self.range_sensor_max, self.range_sensor_fov)
351 def update_dist_forward_right(self):
352 if self.pub_range_fwd_right.get_num_connections() > 0:
353 self.start_dist_srf(0xb)
355 def check_docked(self):
356 if self.bDocked and not self.bDocked_last:
357 rospy.loginfo("Docking event")
358 elif not self.bDocked and self.bDocked_last:
359 if not self.bStayDocked or self.cur_vel != (0, 0):
360 rospy.loginfo("Undocking event")
362 rospy.loginfo("Undocking event..redocking")
363 thread.start_new_thread(self.redock, ())
365 self.bDocked_last = self.bDocked
368 self.cmd_vel = (-0.1, 0)
373 self.cmd_vel = (0, 0)
375 rospy.loginfo("Redocking done")
377 rospy.logerr("Redocking failed")
379 def enableManipulator(self, msg):
380 rospy.loginfo("Set Manipulator: %d", msg.data)
381 i2c_write_reg(0x52, 0x0f, chr(msg.data))
382 return SetBoolResponse(True, "")
384 if __name__ == "__main__":