viz_module_base.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 
00003 # Software License Agreement (BSD License)
00004 #
00005 #  Copyright (c) 2011, 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 from math import degrees, radians
00036 
00037 #import roslib
00038 #roslib.load_manifest('starmac_viz')
00039 import rospy
00040 from tf import TransformBroadcaster
00041 
00042 from visualization_msgs.msg import Marker, MarkerArray
00043 
00044 from starmac_roslib.timers import Timer
00045 
00046 
00047 class VizModuleBase(object):
00048     """
00049     Abstract Base Class
00050     
00051     Visualization modules should inherit from this class.
00052     """
00053     #latest_llstatus = None
00054     latest_odom = None
00055     latest_controller_status = None
00056     modules = {}
00057     mpub = None
00058     mapub = None
00059     tfbr = None
00060     
00061     def __init__(self, id=""):
00062         self.id = id
00063         if id in VizModuleBase.modules:
00064             raise Error("Visualization module with id '%s' already exists" % id)
00065         VizModuleBase.modules[id] = self
00066         self.init_params()
00067         self.init_publishers()
00068         self.init_vars()
00069         self.init_viz()
00070         self.init_subscribers()
00071         self.init_timers()
00072 
00073     def init_params(self):
00074         self.publish_freq = rospy.get_param("~publish_freq", 15.0)
00075         self.subscriber_topic_prefix = rospy.get_param("~subscriber_topic_prefix", 'downlink/')
00076         
00077     def init_timers(self):
00078         self.publish_timer = Timer(rospy.Duration(1/self.publish_freq), self.publish_timer_callback)
00079 
00080     def init_publishers(self):
00081         VizModuleBase.mpub = rospy.Publisher('flyer_viz', Marker)
00082         VizModuleBase.mapub = rospy.Publisher('flyer_viz_array', MarkerArray)
00083         VizModuleBase.tfbr = TransformBroadcaster()
00084 
00085     def publish(self, stamp):        
00086         self.mg.publish(stamp)
00087 
00088     # Following are 'pure virtual' methods -- they _must_ be defined in the derived class
00089     def init_vars(self):
00090         raise NotImplementedError 
00091         
00092     def init_viz(self):
00093         raise NotImplementedError 
00094         
00095     def init_subscribers(self):
00096         raise NotImplementedError 
00097         
00098     def publish_timer_callback(self, event):
00099         raise NotImplementedError 
00100 
00101 
00102 
00103 


starmac_viz
Author(s): bouffard
autogenerated on Sun Jan 5 2014 11:38:25