]> defiant.homedns.org Git - ros_wild_thumper.git/blob - scripts/move_base.py
added diagnostic msg
[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
13 WHEEL_DIST = 0.248
14
15 class MoveBase:
16         def __init__(self):
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)
22                 self.set_speed(0, 0)
23                 rospy.loginfo("Init done")
24                 i2c_write_reg(0x50, 0x90, struct.pack("BB", 1, 1)) # switch direction
25                 self.run()
26         
27         def run(self):
28                 rate = rospy.Rate(20.0)
29                 while not rospy.is_shutdown():
30                         self.get_tle_err()
31                         #self.get_odom()
32                         #self.get_dist_forward()
33                         #self.get_dist_backward()
34                         #self.get_dist_left()
35                         #self.get_dist_right()
36                         rate.sleep()
37
38         def get_tle_err(self):
39                 err = struct.unpack(">B", i2c_read_reg(0x50, 0x94, 1))[0]
40                 
41                 msg = DiagnosticArray()
42                 msg.header.stamp = rospy.Time.now()
43                 stat = DiagnosticStatus()
44                 stat.name = "Motor: Error Status"
45                 stat.level = DiagnosticStatus.OK if not err else DiagnosticStatus.ERROR
46                 stat.message = "OK" if not err else "Error"
47
48                 stat.values.append(KeyValue("Motor 1", str(bool(err & (1 << 0)))))
49                 stat.values.append(KeyValue("Motor 2", str(bool(err & (1 << 1)))))
50                 stat.values.append(KeyValue("Motor 3", str(bool(err & (1 << 2)))))
51                 stat.values.append(KeyValue("Motor 4", str(bool(err & (1 << 3)))))
52
53                 msg.status.append(stat)
54                 self.pub_diag.publish(msg)
55
56
57         def get_odom(self):
58                 posx, posy, angle = struct.unpack(">fff", i2c_read_reg(0x50, 0x40, 12))
59                 speed_trans, speed_rot = struct.unpack(">ff", i2c_read_reg(0x50, 0x38, 8))
60                 current_time = rospy.Time.now()
61
62                 # since all odometry is 6DOF we'll need a quaternion created from yaw
63                 odom_quat = tf.transformations.quaternion_from_euler(0, 0, angle)
64
65                 # first, we'll publish the transform over tf
66                 self.tf_broadcaster.sendTransform((posx, posy, 0.0), odom_quat, current_time, "base_link", "odom")
67
68                 # next, we'll publish the odometry message over ROS
69                 odom = Odometry()
70                 odom.header.stamp = current_time
71                 odom.header.frame_id = "/odom"
72
73                 # set the position
74                 odom.pose.pose.position.x = posx
75                 odom.pose.pose.position.y = posy
76                 odom.pose.pose.position.z = 0.0
77                 odom.pose.pose.orientation.x = odom_quat[0]
78                 odom.pose.pose.orientation.y = odom_quat[1]
79                 odom.pose.pose.orientation.z = odom_quat[2]
80                 odom.pose.pose.orientation.w = odom_quat[3]
81
82                 # set the velocity
83                 odom.child_frame_id = "base_link"
84                 odom.twist.twist.linear.x = speed_trans
85                 odom.twist.twist.linear.y = 0.0
86                 odom.twist.twist.angular.z = speed_rot
87
88                 # publish the message
89                 self.pub_odom.publish(odom)
90
91         
92         def set_speed(self, trans, rot):
93                 i2c_write_reg(0x50, 0x50, struct.pack(">ff", trans, rot))
94
95         def cmdVelReceived(self, msg):
96                 trans = msg.linear.x
97                 rot = msg.angular.z # rad/s
98                 self.set_speed(trans, rot)
99
100         # http://rn-wissen.de/wiki/index.php/Sensorarten#Sharp_GP2D12
101         def get_dist_ir(self, num):
102                 dev = i2c(0x52)
103                 s = struct.pack("B", num)
104                 dev.write(s)
105                 dev.close()
106
107                 sleep(2e-6)
108
109                 dev = i2c(0x52)
110                 s = dev.read(2)
111                 dev.close()
112
113                 val = struct.unpack(">H", s)[0]
114                 return 15221/(val - -276.42)/100;
115         
116         def get_dist_srf(self, num):
117                 dev = i2c(0x52)
118                 s = struct.pack("B", num)
119                 dev.write(s)
120                 dev.close()
121
122                 sleep(50e-3)
123
124                 dev = i2c(0x52)
125                 s = dev.read(2)
126                 dev.close()
127
128                 return struct.unpack(">H", s)[0]/1000.0
129
130         def get_dist_left(self):
131                 dist = self.get_dist_ir(0x1)
132
133         def get_dist_right(self):
134                  dist = self.get_dist_ir(0x3)
135
136         def get_dist_forward(self):
137                 dist = self.get_dist_srf(0x5)
138
139         def get_dist_backward(self):
140                 dist = self.get_dist_srf(0x7)
141
142
143 if __name__ == "__main__":
144         MoveBase()