38 import roslib; roslib.load_manifest(
'kobuki_testsuite')
42 from tf.transformations
import euler_from_quaternion
43 from math
import degrees
45 from sensor_msgs.msg
import Imu
46 from geometry_msgs.msg
import Quaternion
50 quat = data.orientation
51 q = [quat.x, quat.y, quat.z, quat.w]
52 roll, pitch, yaw = euler_from_quaternion(q)
53 sys.stdout.write(
"\r\033[1mGyro Angle\033[0m: [" +
"{0:+.4f}".format(yaw) +
" rad] ["\
54 +
"{0: >+7.2f}".format(degrees(yaw)) +
" deg]"\
55 +
" \033[1mRate\033[0m: [" +
"{0:+.4f}".format(data.angular_velocity.z) +
" rad/s] ["\
56 +
"{0: >+7.2f}".format(degrees(data.angular_velocity.z)) +
" deg/s] ")
60 rospy.init_node(
"test_gyro")
61 rospy.Subscriber(
"/mobile_base/sensors/imu_data", Imu, ImuCallback)