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
12 from sensor_msgs.msg import Imu
18 rospy.init_node('wild_thumper_move_base')
19 rospy.Subscriber("cmd_vel", Twist, self.cmdVelReceived)
20 rospy.Subscriber("imu", Imu, self.imuReceived)
21 self.tf_broadcaster = tf.broadcaster.TransformBroadcaster()
22 self.pub_odom = rospy.Publisher("odom", Odometry, queue_size=16)
23 self.pub_diag = rospy.Publisher("diagnostics", DiagnosticArray, queue_size=16)
25 rospy.loginfo("Init done")
26 i2c_write_reg(0x50, 0x90, struct.pack("BB", 1, 1)) # switch direction
30 rate = rospy.Rate(20.0)
31 reset_val = self.get_reset()
32 rospy.loginfo("Reset Status: 0x%x" % reset_val)
33 while not rospy.is_shutdown():
34 #print struct.unpack(">B", i2c_read_reg(0x50, 0xA2, 1))[0] # count test
38 #self.get_dist_forward()
39 #self.get_dist_backward()
41 #self.get_dist_right()
44 def set_motor_handicap(self, front, aft): # percent
45 i2c_write_reg(0x50, 0x94, struct.pack(">bb", front, aft))
47 def imuReceived(self, msg):
48 (roll, pitch, yaw) = tf.transformations.euler_from_quaternion(msg.orientation.__getstate__())
50 val = (100/90)*abs(pitch)*180/pi
51 print "aft handicap", val
52 self.set_motor_handicap(0, val)
53 elif pitch < -30*pi/180:
54 val = (100/90)*abs(pitch)*180/pi
55 print "front handicap", val
56 self.set_motor_handicap(val, 0)
58 self.set_motor_handicap(0, 0)
61 reset = struct.unpack(">B", i2c_read_reg(0x50, 0xA0, 1))[0]
63 msg = DiagnosticArray()
64 msg.header.stamp = rospy.Time.now()
65 stat = DiagnosticStatus()
66 stat.name = "Reset reason"
67 stat.level = DiagnosticStatus.ERROR if reset & 0x0c else DiagnosticStatus.OK
68 stat.message = "0x%02x" % reset
70 stat.values.append(KeyValue("Watchdog Reset Flag", str(bool(reset & (1 << 3)))))
71 stat.values.append(KeyValue("Brown-out Reset Flag", str(bool(reset & (1 << 2)))))
72 stat.values.append(KeyValue("External Reset Flag", str(bool(reset & (1 << 1)))))
73 stat.values.append(KeyValue("Power-on Reset Flag", str(bool(reset & (1 << 0)))))
75 msg.status.append(stat)
76 self.pub_diag.publish(msg)
80 def get_tle_err(self):
81 err = struct.unpack(">B", i2c_read_reg(0x50, 0xA1, 1))[0]
83 msg = DiagnosticArray()
84 msg.header.stamp = rospy.Time.now()
85 stat = DiagnosticStatus()
86 stat.name = "Motor: Error Status"
87 stat.level = DiagnosticStatus.ERROR if err else DiagnosticStatus.OK
88 stat.message = "0x%02x" % err
90 stat.values.append(KeyValue("aft left", str(bool(err & (1 << 0)))))
91 stat.values.append(KeyValue("front left", str(bool(err & (1 << 1)))))
92 stat.values.append(KeyValue("front right", str(bool(err & (1 << 2)))))
93 stat.values.append(KeyValue("aft right", str(bool(err & (1 << 3)))))
95 msg.status.append(stat)
96 self.pub_diag.publish(msg)
98 def get_voltage(self):
99 volt = struct.unpack(">h", i2c_read_reg(0x52, 0x09, 2))[0]/100.0
101 msg = DiagnosticArray()
102 msg.header.stamp = rospy.Time.now()
103 stat = DiagnosticStatus()
104 stat.name = "Voltage"
105 stat.level = DiagnosticStatus.ERROR if volt < 7 else DiagnosticStatus.OK
106 stat.message = "%.2fV" % volt
108 msg.status.append(stat)
109 self.pub_diag.publish(msg)
113 posx, posy, angle = struct.unpack(">fff", i2c_read_reg(0x50, 0x40, 12))
114 speed_trans, speed_rot = struct.unpack(">ff", i2c_read_reg(0x50, 0x38, 8))
115 current_time = rospy.Time.now()
117 # since all odometry is 6DOF we'll need a quaternion created from yaw
118 odom_quat = tf.transformations.quaternion_from_euler(0, 0, angle)
120 # first, we'll publish the transform over tf
121 self.tf_broadcaster.sendTransform((posx, posy, 0.0), odom_quat, current_time, "base_link", "odom")
123 # next, we'll publish the odometry message over ROS
125 odom.header.stamp = current_time
126 odom.header.frame_id = "/odom"
129 odom.pose.pose.position.x = posx
130 odom.pose.pose.position.y = posy
131 odom.pose.pose.position.z = 0.0
132 odom.pose.pose.orientation.x = odom_quat[0]
133 odom.pose.pose.orientation.y = odom_quat[1]
134 odom.pose.pose.orientation.z = odom_quat[2]
135 odom.pose.pose.orientation.w = odom_quat[3]
138 odom.child_frame_id = "base_link"
139 odom.twist.twist.linear.x = speed_trans
140 odom.twist.twist.linear.y = 0.0
141 odom.twist.twist.angular.z = speed_rot
143 # publish the message
144 self.pub_odom.publish(odom)
147 def set_speed(self, trans, rot):
148 i2c_write_reg(0x50, 0x50, struct.pack(">ff", trans, rot))
150 def cmdVelReceived(self, msg):
152 rot = msg.angular.z # rad/s
153 self.set_speed(trans, rot)
155 # http://rn-wissen.de/wiki/index.php/Sensorarten#Sharp_GP2D12
156 def get_dist_ir(self, num):
158 s = struct.pack("B", num)
168 val = struct.unpack(">H", s)[0]
169 return 15221/(val - -276.42)/100;
171 def get_dist_srf(self, num):
173 s = struct.pack("B", num)
183 return struct.unpack(">H", s)[0]/1000.0
185 def get_dist_left(self):
186 dist = self.get_dist_ir(0x1)
188 def get_dist_right(self):
189 dist = self.get_dist_ir(0x3)
191 def get_dist_forward(self):
192 dist = self.get_dist_srf(0x5)
194 def get_dist_backward(self):
195 dist = self.get_dist_srf(0x7)
198 if __name__ == "__main__":