]> defiant.homedns.org Git - ros_wild_thumper.git/blob - scripts/move_base.py
c4da5d02fa239c586ca2ecc499693aea7a58bd38
[ros_wild_thumper.git] / scripts / move_base.py
1 #!/usr/bin/env python
2 # -*- coding: iso-8859-15 -*-
3
4 import rospy
5 import tf
6 import struct
7 from i2c import *
8 from math import *
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
13
14 WHEEL_DIST = 0.248
15
16 class MoveBase:
17         def __init__(self):
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)
24                 self.set_speed(0, 0)
25                 rospy.loginfo("Init done")
26                 i2c_write_reg(0x50, 0x90, struct.pack("BB", 1, 1)) # switch direction
27                 self.handicap_last = (-1, -1)
28                 self.run()
29         
30         def run(self):
31                 rate = rospy.Rate(20.0)
32                 reset_val = self.get_reset()
33                 rospy.loginfo("Reset Status: 0x%x" % reset_val)
34                 while not rospy.is_shutdown():
35                         #print struct.unpack(">B", i2c_read_reg(0x50, 0xA2, 1))[0] # count test
36                         self.get_tle_err()
37                         self.get_odom()
38                         self.get_voltage()
39                         #self.get_dist_forward()
40                         #self.get_dist_backward()
41                         #self.get_dist_left()
42                         #self.get_dist_right()
43                         rate.sleep()
44
45         def set_motor_handicap(self, front, aft): # percent
46                 if self.handicap_last != (front, aft):
47                         i2c_write_reg(0x50, 0x94, struct.pack(">bb", front, aft))
48                         self.handicap_last = (front, aft)
49
50         def imuReceived(self, msg):
51                 (roll, pitch, yaw) = tf.transformations.euler_from_quaternion(msg.orientation.__getstate__())
52                 if pitch > 30*pi/180:
53                         val = (100.0/65)*abs(pitch)*180/pi
54                         self.set_motor_handicap(0, int(val))
55                 elif pitch < -30*pi/180:
56                         val = (100.0/65)*abs(pitch)*180/pi
57                         self.set_motor_handicap(int(val), 0)
58                 else:
59                         self.set_motor_handicap(0, 0)
60
61         def get_reset(self):
62                 reset = struct.unpack(">B", i2c_read_reg(0x50, 0xA0, 1))[0]
63
64                 msg = DiagnosticArray()
65                 msg.header.stamp = rospy.Time.now()
66                 stat = DiagnosticStatus()
67                 stat.name = "Reset reason"
68                 stat.level = DiagnosticStatus.ERROR if reset & 0x0c else DiagnosticStatus.OK
69                 stat.message = "0x%02x" % reset
70
71                 stat.values.append(KeyValue("Watchdog Reset Flag", str(bool(reset & (1 << 3)))))
72                 stat.values.append(KeyValue("Brown-out Reset Flag", str(bool(reset & (1 << 2)))))
73                 stat.values.append(KeyValue("External Reset Flag", str(bool(reset & (1 << 1)))))
74                 stat.values.append(KeyValue("Power-on Reset Flag", str(bool(reset & (1 << 0)))))
75
76                 msg.status.append(stat)
77                 self.pub_diag.publish(msg)
78                 return reset
79
80
81         def get_tle_err(self):
82                 err = struct.unpack(">B", i2c_read_reg(0x50, 0xA1, 1))[0]
83                 
84                 msg = DiagnosticArray()
85                 msg.header.stamp = rospy.Time.now()
86                 stat = DiagnosticStatus()
87                 stat.name = "Motor: Error Status"
88                 stat.level = DiagnosticStatus.ERROR if err else DiagnosticStatus.OK
89                 stat.message = "0x%02x" % err
90
91                 stat.values.append(KeyValue("aft left", str(bool(err & (1 << 0)))))
92                 stat.values.append(KeyValue("front left", str(bool(err & (1 << 1)))))
93                 stat.values.append(KeyValue("front right", str(bool(err & (1 << 2)))))
94                 stat.values.append(KeyValue("aft right", str(bool(err & (1 << 3)))))
95
96                 msg.status.append(stat)
97                 self.pub_diag.publish(msg)
98         
99         def get_voltage(self):
100                 volt = struct.unpack(">h", i2c_read_reg(0x52, 0x09, 2))[0]/100.0
101
102                 msg = DiagnosticArray()
103                 msg.header.stamp = rospy.Time.now()
104                 stat = DiagnosticStatus()
105                 stat.name = "Voltage"
106                 stat.level = DiagnosticStatus.ERROR if volt < 7 else DiagnosticStatus.OK
107                 stat.message = "%.2fV" % volt
108
109                 msg.status.append(stat)
110                 self.pub_diag.publish(msg)
111
112
113         def get_odom(self):
114                 posx, posy, angle = struct.unpack(">fff", i2c_read_reg(0x50, 0x40, 12))
115                 speed_trans, speed_rot = struct.unpack(">ff", i2c_read_reg(0x50, 0x38, 8))
116                 current_time = rospy.Time.now()
117
118                 # since all odometry is 6DOF we'll need a quaternion created from yaw
119                 odom_quat = tf.transformations.quaternion_from_euler(0, 0, angle)
120
121                 # first, we'll publish the transform over tf
122                 #self.tf_broadcaster.sendTransform((posx, posy, 0.0), odom_quat, current_time, "base_footprint", "odom")
123
124                 # next, we'll publish the odometry message over ROS
125                 odom = Odometry()
126                 odom.header.stamp = current_time
127                 odom.header.frame_id = "/odom"
128
129                 # set the position
130                 odom.pose.pose.position.x = posx
131                 odom.pose.pose.position.y = posy
132                 odom.pose.pose.position.z = 0.0
133                 odom.pose.pose.orientation.x = odom_quat[0]
134                 odom.pose.pose.orientation.y = odom_quat[1]
135                 odom.pose.pose.orientation.z = odom_quat[2]
136                 odom.pose.pose.orientation.w = odom_quat[3]
137                 odom.pose.covariance[0] = 1e-3 # x
138                 odom.pose.covariance[7] = 1e-3 # y
139                 odom.pose.covariance[14] = 1e-3 # z
140                 odom.pose.covariance[21] = 0.1 # rotation about X axis
141                 odom.pose.covariance[28] = 0.1 # rotation about Y axis
142                 odom.pose.covariance[35] = 0.1 # rotation about Z axis
143
144                 # set the velocity
145                 odom.child_frame_id = "base_footprint"
146                 odom.twist.twist.linear.x = speed_trans
147                 odom.twist.twist.linear.y = 0.0
148                 odom.twist.twist.angular.z = speed_rot
149                 odom.twist.covariance[0] = 1e-3 # x
150                 odom.twist.covariance[7] = 1e-3 # y
151                 odom.twist.covariance[14] = 1e-3 # z
152                 odom.twist.covariance[21] = 0.1 # rotation about X axis
153                 odom.twist.covariance[28] = 0.1 # rotation about Y axis
154                 odom.twist.covariance[35] = 0.1 # rotation about Z axis
155
156                 # publish the message
157                 self.pub_odom.publish(odom)
158
159         
160         def set_speed(self, trans, rot):
161                 i2c_write_reg(0x50, 0x50, struct.pack(">ff", trans, rot))
162
163         def cmdVelReceived(self, msg):
164                 trans = msg.linear.x
165                 rot = msg.angular.z # rad/s
166                 self.set_speed(trans, rot)
167
168         # http://rn-wissen.de/wiki/index.php/Sensorarten#Sharp_GP2D12
169         def get_dist_ir(self, num):
170                 dev = i2c(0x52)
171                 s = struct.pack("B", num)
172                 dev.write(s)
173                 dev.close()
174
175                 sleep(2e-6)
176
177                 dev = i2c(0x52)
178                 s = dev.read(2)
179                 dev.close()
180
181                 val = struct.unpack(">H", s)[0]
182                 return 15221/(val - -276.42)/100;
183         
184         def get_dist_srf(self, num):
185                 dev = i2c(0x52)
186                 s = struct.pack("B", num)
187                 dev.write(s)
188                 dev.close()
189
190                 sleep(50e-3)
191
192                 dev = i2c(0x52)
193                 s = dev.read(2)
194                 dev.close()
195
196                 return struct.unpack(">H", s)[0]/1000.0
197
198         def get_dist_left(self):
199                 dist = self.get_dist_ir(0x1)
200
201         def get_dist_right(self):
202                  dist = self.get_dist_ir(0x3)
203
204         def get_dist_forward(self):
205                 dist = self.get_dist_srf(0x5)
206
207         def get_dist_backward(self):
208                 dist = self.get_dist_srf(0x7)
209
210
211 if __name__ == "__main__":
212         MoveBase()