2 # -*- coding: iso-8859-15 -*-
10 from geometry_msgs.msg import Twist
11 from nav_msgs.msg import Odometry
12 from diagnostic_msgs.msg import DiagnosticArray, DiagnosticStatus, KeyValue
13 from sensor_msgs.msg import Imu, Range
19 rospy.init_node('wild_thumper')
20 prctl.set_name("wild_thumper")
21 rospy.Subscriber("cmd_vel_out", Twist, self.cmdVelReceived)
22 rospy.Subscriber("imu", Imu, self.imuReceived)
23 enable_odom_tf = rospy.get_param("~enable_odom_tf", True)
25 self.tf_broadcaster = tf.broadcaster.TransformBroadcaster()
27 self.tf_broadcaster = None
28 self.pub_odom = rospy.Publisher("odom", Odometry, queue_size=16)
29 self.pub_diag = rospy.Publisher("diagnostics", DiagnosticArray, queue_size=16)
30 self.pub_range_fwd = rospy.Publisher("range_forward", Range, queue_size=16)
31 self.pub_range_bwd = rospy.Publisher("range_backward", Range, queue_size=16)
32 self.pub_range_left = rospy.Publisher("range_left", Range, queue_size=16)
33 self.pub_range_right = rospy.Publisher("range_right", Range, queue_size=16)
35 rospy.loginfo("Init done")
36 i2c_write_reg(0x50, 0x90, struct.pack("BB", 1, 1)) # switch direction
37 self.handicap_last = (-1, -1)
41 rate = rospy.Rate(20.0)
42 reset_val = self.get_reset()
43 rospy.loginfo("Reset Status: 0x%x" % reset_val)
45 while not rospy.is_shutdown():
46 #print struct.unpack(">B", i2c_read_reg(0x50, 0xA2, 1))[0] # count test
51 self.get_dist_forward()
54 self.get_dist_backward()
59 def set_motor_handicap(self, front, aft): # percent
60 if self.handicap_last != (front, aft):
61 i2c_write_reg(0x50, 0x94, struct.pack(">bb", front, aft))
62 self.handicap_last = (front, aft)
64 def imuReceived(self, msg):
65 (roll, pitch, yaw) = tf.transformations.euler_from_quaternion(msg.orientation.__getstate__())
67 val = (100.0/65)*abs(pitch)*180/pi
68 self.set_motor_handicap(int(val), 0)
69 elif pitch < -30*pi/180:
70 val = (100.0/65)*abs(pitch)*180/pi
71 self.set_motor_handicap(0, int(val))
73 self.set_motor_handicap(0, 0)
76 reset = struct.unpack(">B", i2c_read_reg(0x50, 0xA0, 1))[0]
78 msg = DiagnosticArray()
79 msg.header.stamp = rospy.Time.now()
80 stat = DiagnosticStatus()
81 stat.name = "Reset reason"
82 stat.level = DiagnosticStatus.ERROR if reset & 0x0c else DiagnosticStatus.OK
83 stat.message = "0x%02x" % reset
85 stat.values.append(KeyValue("Watchdog Reset Flag", str(bool(reset & (1 << 3)))))
86 stat.values.append(KeyValue("Brown-out Reset Flag", str(bool(reset & (1 << 2)))))
87 stat.values.append(KeyValue("External Reset Flag", str(bool(reset & (1 << 1)))))
88 stat.values.append(KeyValue("Power-on Reset Flag", str(bool(reset & (1 << 0)))))
90 msg.status.append(stat)
91 self.pub_diag.publish(msg)
95 def get_tle_err(self):
96 err = struct.unpack(">B", i2c_read_reg(0x50, 0xA1, 1))[0]
98 msg = DiagnosticArray()
99 msg.header.stamp = rospy.Time.now()
100 stat = DiagnosticStatus()
101 stat.name = "Motor: Error Status"
102 stat.level = DiagnosticStatus.ERROR if err else DiagnosticStatus.OK
103 stat.message = "0x%02x" % err
105 stat.values.append(KeyValue("aft left", str(bool(err & (1 << 0)))))
106 stat.values.append(KeyValue("front left", str(bool(err & (1 << 1)))))
107 stat.values.append(KeyValue("front right", str(bool(err & (1 << 2)))))
108 stat.values.append(KeyValue("aft right", str(bool(err & (1 << 3)))))
110 msg.status.append(stat)
111 self.pub_diag.publish(msg)
113 def get_voltage(self):
114 volt = struct.unpack(">h", i2c_read_reg(0x52, 0x09, 2))[0]/100.0
116 msg = DiagnosticArray()
117 msg.header.stamp = rospy.Time.now()
118 stat = DiagnosticStatus()
119 stat.name = "Voltage"
120 stat.level = DiagnosticStatus.ERROR if volt < 7 else DiagnosticStatus.OK
121 stat.message = "%.2fV" % volt
123 msg.status.append(stat)
124 self.pub_diag.publish(msg)
128 posx, posy, angle = struct.unpack(">fff", i2c_read_reg(0x50, 0x40, 12))
129 speed_trans, speed_rot = struct.unpack(">ff", i2c_read_reg(0x50, 0x38, 8))
130 current_time = rospy.Time.now()
132 # since all odometry is 6DOF we'll need a quaternion created from yaw
133 odom_quat = tf.transformations.quaternion_from_euler(0, 0, angle)
135 # first, we'll publish the transform over tf
136 if self.tf_broadcaster is not None:
137 self.tf_broadcaster.sendTransform((posx, posy, 0.0), odom_quat, current_time, "base_footprint", "odom")
139 # next, we'll publish the odometry message over ROS
141 odom.header.stamp = current_time
142 odom.header.frame_id = "odom"
145 odom.pose.pose.position.x = posx
146 odom.pose.pose.position.y = posy
147 odom.pose.pose.position.z = 0.0
148 odom.pose.pose.orientation.x = odom_quat[0]
149 odom.pose.pose.orientation.y = odom_quat[1]
150 odom.pose.pose.orientation.z = odom_quat[2]
151 odom.pose.pose.orientation.w = odom_quat[3]
152 odom.pose.covariance[0] = 1e-3 # x
153 odom.pose.covariance[7] = 1e-3 # y
154 odom.pose.covariance[14] = 1e6 # z
155 odom.pose.covariance[21] = 1e6 # rotation about X axis
156 odom.pose.covariance[28] = 1e6 # rotation about Y axis
157 odom.pose.covariance[35] = 0.03 # rotation about Z axis
160 odom.child_frame_id = "base_footprint"
161 odom.twist.twist.linear.x = speed_trans
162 odom.twist.twist.linear.y = 0.0
163 odom.twist.twist.angular.z = speed_rot
164 odom.twist.covariance[0] = 1e-3 # x
165 odom.twist.covariance[7] = 1e-3 # y
166 odom.twist.covariance[14] = 1e6 # z
167 odom.twist.covariance[21] = 1e6 # rotation about X axis
168 odom.twist.covariance[28] = 1e6 # rotation about Y axis
169 odom.twist.covariance[35] = 0.03 # rotation about Z axis
171 # publish the message
172 self.pub_odom.publish(odom)
175 def set_speed(self, trans, rot):
176 i2c_write_reg(0x50, 0x50, struct.pack(">ff", trans, rot))
178 def cmdVelReceived(self, msg):
180 rot = msg.angular.z # rad/s
181 self.set_speed(trans, rot)
183 # http://rn-wissen.de/wiki/index.php/Sensorarten#Sharp_GP2D12
184 def get_dist_ir(self, num):
186 s = struct.pack("B", num)
196 val = struct.unpack(">H", s)[0]
199 def start_dist_srf(self, num):
201 s = struct.pack("B", num)
205 def read_dist_srf(self, num):
207 s = struct.pack("B", num)
215 return struct.unpack(">H", s)[0]/1000.0
217 def send_range(self, pub, frame_id, typ, dist, min_range, max_range, fov_deg):
219 msg.header.stamp = rospy.Time.now()
220 msg.header.frame_id = frame_id
221 msg.radiation_type = typ
222 msg.field_of_view = fov_deg*pi/180
223 msg.min_range = min_range
224 msg.max_range = max_range
228 def get_dist_left(self):
229 if self.pub_range_left.get_num_connections() > 0:
230 dist = 30.553/(self.get_dist_ir(0x1) - -67.534)
231 self.send_range(self.pub_range_left, "ir_left", Range.INFRARED, dist, 0.04, 0.3, 1)
233 def get_dist_right(self):
234 if self.pub_range_right.get_num_connections() > 0:
235 dist = 17.4/(self.get_dist_ir(0x3) - 69)
236 self.send_range(self.pub_range_right, "ir_right", Range.INFRARED, dist, 0.04, 0.3, 1)
238 def get_dist_forward(self):
239 if self.pub_range_fwd.get_num_connections() > 0:
240 dist = self.read_dist_srf(0x15)
241 self.send_range(self.pub_range_fwd, "sonar_forward", Range.ULTRASOUND, dist, 0.04, 6, 30)
242 self.start_dist_srf(0x5) # get next value
244 def get_dist_backward(self):
245 if self.pub_range_bwd.get_num_connections() > 0:
246 dist = self.read_dist_srf(0x17)
247 self.send_range(self.pub_range_bwd, "sonar_backward", Range.ULTRASOUND, dist, 0.04, 6, 30)
248 self.start_dist_srf(0x7) # get next value
251 if __name__ == "__main__":