2 # -*- coding: iso-8859-15 -*-
8 from geometry_msgs.msg import Twist
14 rospy.init_node('wild_thumper_move_base')
15 rospy.Subscriber("cmd_vel", Twist, self.cmdVelReceived)
17 rospy.loginfo("Init done")
18 i2c_write_reg(0x50, 0x90, struct.pack("BB", 1, 1)) # switch direction
22 rate = rospy.Rate(10.0)
23 while not rospy.is_shutdown():
24 #self.get_dist_forward()
25 #self.get_dist_backward()
27 #self.get_dist_right()
30 def set_speed(self, left, right):
32 elif left < 0: left-=80
33 if right > 0: right+=80
34 elif right < 0: right-=80
36 if left > 255: left=255
37 elif left < -255: left=-255
38 if right > 255: right=255
39 elif right < -255: right=-255
42 s = struct.pack(">Bhhhh", 0x1, right, right, left, left)
46 def cmdVelReceived(self, msg):
48 rot = msg.angular.z # rad/s
50 right = rot*pi*WHEEL_DIST + trans
52 self.set_speed(left, right)
54 # http://rn-wissen.de/wiki/index.php/Sensorarten#Sharp_GP2D12
55 def get_dist_ir(self, num):
57 s = struct.pack("B", num)
67 val = struct.unpack(">H", s)[0]
68 return 15221/(val - -276.42)/100;
70 def get_dist_srf(self, num):
72 s = struct.pack("B", num)
82 return struct.unpack(">H", s)[0]/1000.0
84 def get_dist_left(self):
85 dist = self.get_dist_ir(0x1)
87 def get_dist_right(self):
88 dist = self.get_dist_ir(0x3)
90 def get_dist_forward(self):
91 dist = self.get_dist_srf(0x5)
93 def get_dist_backward(self):
94 dist = self.get_dist_srf(0x7)
97 if __name__ == "__main__":