fake_vicon_output.py
Go to the documentation of this file.
00001 #!/usr/bin/env rosh
00002 
00003 # Software License Agreement (BSD License)
00004 #
00005 #  Copyright (c) 2010, UC Regents
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 University of California 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 import tf.transformations as tft
00036 import numpy as np
00037 r = Rate(50)
00038 dummy_msg = msg.geometry_msgs.TransformStamped()
00039 dummy_msg.transform.rotation.w = 1.0
00040 dummy_msg.header.frame_id = '/enu'
00041 dummy_msg.child_frame_id = '/pelican1/flyer_vicon'
00042 tfl=transforms._config.listener
00043 while (True):
00044     dummy_msg.header.stamp = now()
00045     try:
00046         t_imu_vicon, q_imu_vicon = tfl.lookupTransform('/pelican1/flyer_imu','/pelican1/flyer_vicon',now())
00047         T_imu_vicon = np.dot(tft.translation_matrix(t_imu_vicon),tft.quaternion_matrix(q_imu_vicon)) 
00048     except:
00049         loginfo('exception trying to get vicon-imu')
00050     try:
00051         latest_autosequence_info = topics.pelican1.control_mode_autosequence.info[0]
00052         if latest_autosequence_info is not None:
00053             # oh this is so annoying..
00054             T_ned_imu_norot = tft.translation_matrix([latest_autosequence_info.north_cmd,
00055                                                 latest_autosequence_info.east_cmd,0])
00056             T_ned_imu = np.dot(T_ned_imu_norot,tft.quaternion_matrix(tft.quaternion_from_euler(np.radians(latest_autosequence_info.yaw_cmd), 0, 0, 'rzyx')))
00057             T_enu_ned = tft.euler_matrix(np.radians(180),0,np.radians(-90),'rxyz')
00058             T_enu_imu = np.dot(T_enu_ned, T_ned_imu)
00059             T_enu_vicon = np.dot(T_enu_imu,T_imu_vicon)
00060             q = tft.quaternion_from_matrix(T_enu_vicon)
00061             dummy_msg.transform.translation.x = T_enu_vicon[0,3]
00062             dummy_msg.transform.translation.y = T_enu_vicon[1,3]
00063             #q = tft.quaternion_from_euler(-np.radians(90.0), 0, 0, 'rzyx')
00064             dummy_msg.transform.rotation.x = q[0]
00065             dummy_msg.transform.rotation.y = q[1]
00066             dummy_msg.transform.rotation.z = q[2]
00067             dummy_msg.transform.rotation.w = q[3]
00068     except:
00069         loginfo('exception 2')
00070     #loginfo('Publishing dummy vicon message')
00071     topics['/pelican1/vicon_recv_direct/output'](dummy_msg)
00072     r.sleep()


flyer_common
Author(s): Patrick Bouffard
autogenerated on Sun Jan 5 2014 11:37:49