quat_to_ypr.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 # Software License Agreement (BSD License)
00003 #
00004 #  Copyright (c) 2011, UC Regents
00005 #  All rights reserved.
00006 #
00007 #  Redistribution and use in source and binary forms, with or without
00008 #  modification, are permitted provided that the following conditions
00009 #  are met:
00010 #
00011 #   * Redistributions of source code must retain the above copyright
00012 #     notice, this list of conditions and the following disclaimer.
00013 #   * Redistributions in binary form must reproduce the above
00014 #     copyright notice, this list of conditions and the following
00015 #     disclaimer in the documentation and/or other materials provided
00016 #     with the distribution.
00017 #   * Neither the name of the University of California nor the names of its
00018 #     contributors may be used to endorse or promote products derived
00019 #     from this software without specific prior written permission.
00020 #
00021 #  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022 #  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023 #  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024 #  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025 #  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026 #  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027 #  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028 #  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029 #  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030 #  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031 #  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032 #  POSSIBILITY OF SUCH DAMAGE.
00033 
00034 import roslib
00035 roslib.load_manifest('starmac_tools') # change this to your package name
00036 import rospy
00037 from starmac_roslib.timers import Timer
00038 # Message imports:
00039 # Make sure corresponding packages are listed as dependencies in package manifest!
00040 from std_msgs.msg import Bool, Float64
00041 from nav_msgs.msg import Odometry
00042 from starmac_msgs.msg import EulerAnglesStamped
00043 import tf.transformations as tft
00044 import numpy as np
00045 
00046 
00047 class QuatToYPRNode(object):
00048     """
00049     Example python node including reading parameters, publishers and subscribers, and timer.
00050     """
00051     def __init__(self):
00052         # Remember that init_node hasn't been called yet so only do stuff here that
00053         # doesn't require node handles etc.
00054         pass
00055 
00056     def start(self):
00057         rospy.init_node('quat_to_ypr')
00058         self.init_params()
00059 #        self.init_vars()
00060         self.init_publishers()
00061         self.init_subscribers()
00062         #self.init_timers()
00063         rospy.spin()
00064         
00065     def init_params(self):
00066         self.euler_seq = rospy.get_param("~euler_seq", 'rzyx')
00067         self.angles_in_degrees = rospy.get_param("~angles_in_degrees", True)
00068     
00069 #    def init_vars(self):
00070 #        self.some_variable = 42.0
00071 #        self.latest_input = None
00072 
00073     def init_publishers(self):
00074         self.output_ypr_pub = rospy.Publisher('~ypr', EulerAnglesStamped)
00075         
00076     def init_subscribers(self):
00077         self.input_odom_sub = rospy.Subscriber(rospy.resolve_name('~odom'), Odometry, self.input_odom_callback)
00078       
00079 #    def init_timers(self):
00080 #        self.heartbeat_timer = Timer(rospy.Duration(1/10.0), self.heartbeat_timer_callback) # Call at 10 Hz
00081                                       
00082     def input_odom_callback(self, msg):
00083         euler_msg = EulerAnglesStamped()
00084         euler_msg.header.stamp = msg.header.stamp
00085         mppo = msg.pose.pose.orientation # shorthand
00086         quat = (mppo.x, mppo.y, mppo.z, mppo.w)
00087         ypr = tft.euler_from_quaternion(quat, self.euler_seq)
00088         euler_msg.angles.sequence = 'rzyx'
00089         euler_msg.angles.angles_in_degrees = True
00090         if self.angles_in_degrees:
00091             factor = np.degrees(1)
00092         else:
00093             factor = 1.0
00094         euler_msg.angles.ai = factor*ypr[0]
00095         euler_msg.angles.aj = factor*ypr[1]
00096         euler_msg.angles.ak = factor*ypr[2]
00097         self.output_ypr_pub.publish(euler_msg)
00098     
00099 #    def heartbeat_timer_callback(self, event):
00100 #        if event.last_real is not None:
00101 #            dt = (event.current_real - event.last_real).to_sec()
00102 #            rospy.loginfo('Heartbeat. dt = %f' % dt)
00103         
00104         
00105 if __name__ == "__main__":
00106     self = QuatToYPRNode()
00107     self.start()


starmac_tools
Author(s): bouffard
autogenerated on Sun Jan 5 2014 11:38:35