topic_transform.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 
00003 #/*********************************************************************
00004  #* topic_transform.py
00005  #*
00006  #*  Created on: Aug 29, 2014
00007  #*      Author: Filip Mandic
00008  #*
00009  #********************************************************************/
00010 
00011 #/*********************************************************************
00012 #* Software License Agreement (BSD License)
00013 #*
00014 #*  Copyright (c) 2014, LABUST, UNIZG-FER
00015 #*  All rights reserved.
00016 #*
00017 #*  Redistribution and use in source and binary forms, with or without
00018 #*  modification, are permitted provided that the following conditions
00019 #*  are met:
00020 #*
00021 #*   * Redistributions of source code must retain the above copyright
00022 #*     notice, this list of conditions and the following disclaimer.
00023 #*   * Redistributions in binary form must reproduce the above
00024 #*     copyright notice, this list of conditions and the following
00025 #*     disclaimer in the documentation and/or other materials provided
00026 #*     with the distribution.
00027 #*   * Neither the name of the LABUST nor the names of its
00028 #*     contributors may be used to endorse or promote products derived
00029 #*     from this software without specific prior written permission.
00030 #*
00031 #*  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00032 #*  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00033 #*  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00034 #*  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00035 #*  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00036 #*  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00037 #*  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00038 #*  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00039 #*  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00040 #*  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00041 #*  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00042 #*  POSSIBILITY OF SUCH DAMAGE.
00043 #*********************************************************************/
00044 
00045 #!/usr/bin/env python
00046 import rospy
00047 
00048 from misc_msgs.msg import ExternalEvent
00049 
00050 from std_msgs.msg import *
00051 from auv_msgs.msg import *
00052 
00053 class TopicTransform():
00054     
00055     def __init__(self):
00056         self.setup()
00057 
00058     def callback(self,data):
00059    
00060         tmpList = self.msg_field.split("/")
00061         
00062         parentData = data
00063 
00064         for field in tmpList:
00065             parentData = getattr(parentData,field)
00066         
00067         eventData = ExternalEvent()
00068         eventData.id = self.eventID
00069         eventData.value = parentData
00070         
00071         self.pubExternalEvent.publish(eventData)
00072         
00073     def setup(self):
00074         
00075         rospy.init_node('topic_transform', anonymous=True)
00076         
00077         topic_name = rospy.get_param('~topic_name')
00078         self.eventID = rospy.get_param('~event')
00079        
00080         tmp = ""
00081         tmp = rospy.get_param('~msg_type')  
00082         tmpList = tmp.split("/")
00083         msg_package = tmpList[0]
00084         msg_type = tmpList[1]
00085  
00086         self.msg_field = ""
00087         self.msg_field = rospy.get_param('~msg_field')
00088                 
00089         if msg_package == "std_msgs":
00090             msgType = getattr(std_msgs.msg, msg_type)
00091             
00092         elif msg_package == "auv_msgs":
00093             msgType = getattr(auv_msgs.msg, msg_type)
00094                    
00095         self.pubExternalEvent = rospy.Publisher("externalEvent", ExternalEvent, queue_size=20)
00096         
00097         rospy.Subscriber(topic_name, msgType, self.callback)
00098     
00099         rospy.spin()
00100         
00101 if __name__ == '__main__':
00102     try:
00103         TT = TopicTransform()
00104     except rospy.ROSInterruptException: pass
00105     
00106     
00107   


labust_mission
Author(s): Filip Mandic
autogenerated on Fri Aug 28 2015 11:23:04