2 # -*- coding: iso-8859-15 -*-
9 from geometry_msgs.msg import Twist
10 from nav_msgs.msg import Odometry
11 from diagnostic_msgs.msg import DiagnosticArray, DiagnosticStatus, KeyValue
17 rospy.init_node('wild_thumper_move_base')
18 rospy.Subscriber("cmd_vel", Twist, self.cmdVelReceived)
19 self.tf_broadcaster = tf.broadcaster.TransformBroadcaster()
20 self.pub_odom = rospy.Publisher("odom", Odometry, queue_size=16)
21 self.pub_diag = rospy.Publisher("diagnostics", DiagnosticArray, queue_size=16)
23 rospy.loginfo("Init done")
24 i2c_write_reg(0x50, 0x90, struct.pack("BB", 1, 1)) # switch direction
28 rate = rospy.Rate(20.0)
29 reset_val = self.get_reset()
30 rospy.loginfo("Reset Status: 0x%x" % reset_val)
31 while not rospy.is_shutdown():
32 #print struct.unpack(">B", i2c_read_reg(0x50, 0xA2, 1))[0] # count test
36 #self.get_dist_forward()
37 #self.get_dist_backward()
39 #self.get_dist_right()
43 reset = struct.unpack(">B", i2c_read_reg(0x50, 0xA0, 1))[0]
45 msg = DiagnosticArray()
46 msg.header.stamp = rospy.Time.now()
47 stat = DiagnosticStatus()
48 stat.name = "Reset reason"
49 stat.level = DiagnosticStatus.ERROR if reset & 0x0c else DiagnosticStatus.OK
50 stat.message = "0x%02x" % reset
52 stat.values.append(KeyValue("Watchdog Reset Flag", str(bool(reset & (1 << 3)))))
53 stat.values.append(KeyValue("Brown-out Reset Flag", str(bool(reset & (1 << 2)))))
54 stat.values.append(KeyValue("External Reset Flag", str(bool(reset & (1 << 1)))))
55 stat.values.append(KeyValue("Power-on Reset Flag", str(bool(reset & (1 << 0)))))
57 msg.status.append(stat)
58 self.pub_diag.publish(msg)
62 def get_tle_err(self):
63 err = struct.unpack(">B", i2c_read_reg(0x50, 0xA1, 1))[0]
65 msg = DiagnosticArray()
66 msg.header.stamp = rospy.Time.now()
67 stat = DiagnosticStatus()
68 stat.name = "Motor: Error Status"
69 stat.level = DiagnosticStatus.ERROR if err else DiagnosticStatus.OK
70 stat.message = "0x%02x" % err
72 stat.values.append(KeyValue("Motor 1", str(bool(err & (1 << 0)))))
73 stat.values.append(KeyValue("Motor 2", str(bool(err & (1 << 1)))))
74 stat.values.append(KeyValue("Motor 3", str(bool(err & (1 << 2)))))
75 stat.values.append(KeyValue("Motor 4", str(bool(err & (1 << 3)))))
77 msg.status.append(stat)
78 self.pub_diag.publish(msg)
80 def get_voltage(self):
81 volt = struct.unpack(">h", i2c_read_reg(0x52, 0x09, 2))[0]/100.0
83 msg = DiagnosticArray()
84 msg.header.stamp = rospy.Time.now()
85 stat = DiagnosticStatus()
87 stat.level = DiagnosticStatus.ERROR if volt < 6 else DiagnosticStatus.OK
88 stat.message = "%.2fV" % volt
90 msg.status.append(stat)
91 self.pub_diag.publish(msg)
95 posx, posy, angle = struct.unpack(">fff", i2c_read_reg(0x50, 0x40, 12))
96 speed_trans, speed_rot = struct.unpack(">ff", i2c_read_reg(0x50, 0x38, 8))
97 current_time = rospy.Time.now()
99 # since all odometry is 6DOF we'll need a quaternion created from yaw
100 odom_quat = tf.transformations.quaternion_from_euler(0, 0, angle)
102 # first, we'll publish the transform over tf
103 self.tf_broadcaster.sendTransform((posx, posy, 0.0), odom_quat, current_time, "base_link", "odom")
105 # next, we'll publish the odometry message over ROS
107 odom.header.stamp = current_time
108 odom.header.frame_id = "/odom"
111 odom.pose.pose.position.x = posx
112 odom.pose.pose.position.y = posy
113 odom.pose.pose.position.z = 0.0
114 odom.pose.pose.orientation.x = odom_quat[0]
115 odom.pose.pose.orientation.y = odom_quat[1]
116 odom.pose.pose.orientation.z = odom_quat[2]
117 odom.pose.pose.orientation.w = odom_quat[3]
120 odom.child_frame_id = "base_link"
121 odom.twist.twist.linear.x = speed_trans
122 odom.twist.twist.linear.y = 0.0
123 odom.twist.twist.angular.z = speed_rot
125 # publish the message
126 self.pub_odom.publish(odom)
129 def set_speed(self, trans, rot):
130 i2c_write_reg(0x50, 0x50, struct.pack(">ff", trans, rot))
132 def cmdVelReceived(self, msg):
134 rot = msg.angular.z # rad/s
135 self.set_speed(trans, rot)
137 # http://rn-wissen.de/wiki/index.php/Sensorarten#Sharp_GP2D12
138 def get_dist_ir(self, num):
140 s = struct.pack("B", num)
150 val = struct.unpack(">H", s)[0]
151 return 15221/(val - -276.42)/100;
153 def get_dist_srf(self, num):
155 s = struct.pack("B", num)
165 return struct.unpack(">H", s)[0]/1000.0
167 def get_dist_left(self):
168 dist = self.get_dist_ir(0x1)
170 def get_dist_right(self):
171 dist = self.get_dist_ir(0x3)
173 def get_dist_forward(self):
174 dist = self.get_dist_srf(0x5)
176 def get_dist_backward(self):
177 dist = self.get_dist_srf(0x7)
180 if __name__ == "__main__":