00001 #!/usr/bin/env python 00002 00003 # Software License Agreement (BSD License) 00004 # 00005 # Copyright (c) 2012, Yujin Robot 00006 # All rights reserved. 00007 # 00008 # Redistribution and use in source and binary forms, with or without 00009 # modification, are permitted provided that the following conditions 00010 # are met: 00011 # 00012 # * Redistributions of source code must retain the above copyright 00013 # notice, this list of conditions and the following disclaimer. 00014 # * Redistributions in binary form must reproduce the above 00015 # copyright notice, this list of conditions and the following 00016 # disclaimer in the documentation and/or other materials provided 00017 # with the distribution. 00018 # * Neither the name of the Yujin Robot nor the names of its 00019 # contributors may be used to endorse or promote products derived 00020 # from this software without specific prior written permission. 00021 # 00022 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00023 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00024 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00025 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00026 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00027 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00028 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00029 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00030 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00031 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00032 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00033 # POSSIBILITY OF SUCH DAMAGE. 00034 # 00035 # Continuously print angle and angular velocity from Imu messages 00036 00037 00038 import roslib; roslib.load_manifest('kobuki_testsuite') 00039 import rospy 00040 import sys 00041 00042 from tf.transformations import euler_from_quaternion 00043 from math import degrees 00044 00045 from sensor_msgs.msg import Imu 00046 from geometry_msgs.msg import Quaternion 00047 00048 00049 def ImuCallback(data): 00050 quat = data.orientation 00051 q = [quat.x, quat.y, quat.z, quat.w] 00052 roll, pitch, yaw = euler_from_quaternion(q) 00053 sys.stdout.write("\r\033[1mGyro Angle\033[0m: [" + "{0:+.4f}".format(yaw) + " rad] ["\ 00054 + "{0: >+7.2f}".format(degrees(yaw)) + " deg]"\ 00055 + " \033[1mRate\033[0m: [" + "{0:+.4f}".format(data.angular_velocity.z) + " rad/s] ["\ 00056 + "{0: >+7.2f}".format(degrees(data.angular_velocity.z)) + " deg/s] ") 00057 # http://docs.python.org/library/string.html#formatexamples 00058 sys.stdout.flush() 00059 00060 rospy.init_node("test_gyro") 00061 rospy.Subscriber("/mobile_base/sensors/imu_data", Imu, ImuCallback) 00062 rospy.spin() 00063 print '' # for clean output