4 import roslib; roslib.load_manifest(
'xbot_node')
7 from tf.transformations
import euler_from_quaternion
8 from math
import degrees
10 from sensor_msgs.msg
import Imu
11 from geometry_msgs.msg
import Quaternion
12 from std_msgs.msg
import Float64
17 rospy.init_node(
"getYaw", anonymous=
True)
19 self.
pub_angle = rospy.Publisher(
"angle", Float64, queue_size=10)
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" 32 angle_rate = Float64()
34 angle_rate.data = data.angular_velocity.z
35 self.pub_angle.publish(angle)
36 self.pub_angle_rate.publish(angle_rate)
38 if __name__ ==
'__main__':
42 print "It prints angle and angular_velocity from Imu message of single yaw gyro." 45 except rospy.ROSInterruptException:
pass
def ImuCallback(self, data)