NavSts2Odom.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 '''
00003 Created on Feb 04, 2013
00004 
00005 @author: dnad
00006 '''
00007 import rospy;
00008 from auv_msgs.msg import NavSts;
00009 from nav_msgs.msg import Odometry
00010 import tf
00011 import math
00012       
00013 class MessageTransformer:
00014     def __init__(self):
00015         rospy.Subscriber("stateHat", NavSts, self.onNavSts);
00016         self.pub = rospy.Publisher("uwsim_hook", Odometry);
00017         self.listener = tf.TransformListener();
00018         self.broadcaster = tf.TransformBroadcaster();
00019         self.base_frame = rospy.get_param("~base_frame","base_link");
00020            
00021     def onNavSts(self,data):   
00022         q = tf.transformations.quaternion_from_euler(math.pi, 0, math.pi/2)
00023         self.broadcaster.sendTransform((0,0,0), q.conjugate(), rospy.Time.now(), "uwsim_frame", "local");
00024         
00025         try:
00026             (trans,rot) = self.listener.lookupTransform("uwsim_frame", self.base_frame, rospy.Time(0))
00027             
00028             odom = Odometry();  
00029             odom.twist.twist.linear.x = data.body_velocity.x;
00030             odom.twist.twist.linear.y = data.body_velocity.y;
00031             odom.twist.twist.linear.z = data.body_velocity.z;
00032             odom.twist.twist.angular.x = data.orientation_rate.roll;
00033             odom.twist.twist.angular.y = data.orientation_rate.pitch;
00034             odom.twist.twist.angular.z = data.orientation_rate.yaw;
00035             odom.child_frame_id = self.base_frame; 
00036             odom.pose.pose.orientation.x = rot[0];
00037             odom.pose.pose.orientation.y = rot[1];
00038             odom.pose.pose.orientation.z = rot[2];
00039             odom.pose.pose.orientation.w = rot[3];
00040             odom.pose.pose.position.x = trans[0];
00041             odom.pose.pose.position.y = trans[1];
00042             odom.pose.pose.position.z = trans[2];
00043             odom.header.stamp = rospy.Time.now();
00044             odom.header.frame_id = "local";
00045             
00046             self.pub.publish(odom);
00047             
00048         except (tf.LookupException, tf.ConnectivityException, tf.ExtrapolationException):
00049             None
00050 
00051 if __name__ == "__main__":
00052     rospy.init_node("navsts2UWSim");
00053     tr = MessageTransformer();
00054     rospy.spin();
00055         
00056         


labust_uwsim
Author(s): Gyula Nagy
autogenerated on Sun Mar 1 2015 12:12:43