getYaw.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 #AUTHOR: Younghun Ju <yhju@yujinrobot.comm>, <yhju83@gmail.com>
3 
4 import roslib; roslib.load_manifest('xbot_node')
5 import rospy
6 
7 from tf.transformations import euler_from_quaternion
8 from math import degrees
9 
10 from sensor_msgs.msg import Imu
11 from geometry_msgs.msg import Quaternion
12 from std_msgs.msg import Float64
13 
14 class Converter(object):
15 
16  def __init__(self):
17  rospy.init_node("getYaw", anonymous=True)
18  self.sub_imu = rospy.Subscriber("imu", Imu, self.ImuCallback)
19  self.pub_angle = rospy.Publisher("angle", Float64, queue_size=10)
20  self.pub_angle_rate = rospy.Publisher("angle_rate", Float64, queue_size=10)
21 
22  def ImuCallback(self,data):
23  quat = data.orientation
24  q = [quat.x, quat.y, quat.z, quat.w]
25  roll, pitch, yaw = euler_from_quaternion(q)
26  print "angle: " + "{0:+.4f}".format(yaw) + " rad; "\
27  + "{0:+.2f}".format(degrees(yaw)) + " deg"
28  print "rate: " + "{0:+.2f}".format(data.angular_velocity.z) + " rad/s; "\
29  + "{0:+.2f}".format(degrees(data.angular_velocity.z)) + " deg/s"
30  print '---'
31  angle = Float64()
32  angle_rate = Float64()
33  angle.data = yaw
34  angle_rate.data = data.angular_velocity.z
35  self.pub_angle.publish(angle)
36  self.pub_angle_rate.publish(angle_rate)
37 
38 if __name__ == '__main__':
39  try:
40  instance = Converter()
41  print
42  print "It prints angle and angular_velocity from Imu message of single yaw gyro."
43  print
44  rospy.spin()
45  except rospy.ROSInterruptException: pass
def __init__(self)
Definition: getYaw.py:16
def ImuCallback(self, data)
Definition: getYaw.py:22


xbot_node
Author(s): Roc, wangpeng@droid.ac.cn
autogenerated on Sat Oct 10 2020 03:28:13