main.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 
00003 # Software License Agreement (BSD License)
00004 #
00005 # Copyright (c) 2012, Willow Garage, Inc.
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 Willow Garage, Inc. 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 os
00036 import sys
00037 
00038 import rospy
00039 from rospkg.rospack import RosPack
00040 
00041 from qt_gui.main import Main as Base
00042 
00043 
00044 class Main(Base):
00045 
00046     def __init__(self, filename=None, ros_pack=None):
00047         rp = ros_pack or RosPack()
00048         qtgui_path = rp.get_path('qt_gui')
00049         super(Main, self).__init__(qtgui_path, invoked_filename=filename, settings_filename='rqt_gui')
00050         self._ros_pack = rp
00051 
00052     def main(self, argv=None, standalone=None, plugin_argument_provider=None):
00053         if argv is None:
00054             argv = sys.argv
00055 
00056         # ignore ROS specific remapping arguments (see http://www.ros.org/wiki/Remapping%20Arguments)
00057         argv = rospy.myargv(argv)
00058 
00059         return super(Main, self).main(argv, standalone=standalone, plugin_argument_provider=plugin_argument_provider, plugin_manager_settings_prefix=str(hash(os.environ['ROS_PACKAGE_PATH'])))
00060 
00061     def create_application(self, argv):
00062         from python_qt_binding.QtGui import QIcon
00063         app = super(Main, self).create_application(argv)
00064         logo = os.path.join(self._ros_pack.get_path('rqt_gui'), 'resource', 'rqt.png')
00065         icon = QIcon(logo)
00066         app.setWindowIcon(icon)
00067         return app
00068 
00069     def _add_plugin_providers(self):
00070         # do not import earlier as it would import Qt stuff without the proper initialization from qt_gui.main
00071         from qt_gui.recursive_plugin_provider import RecursivePluginProvider
00072         from .rospkg_plugin_provider import RospkgPluginProvider
00073         RospkgPluginProvider.rospack = self._ros_pack
00074         self.plugin_providers.append(RospkgPluginProvider('qt_gui', 'qt_gui_py::Plugin'))
00075         self.plugin_providers.append(RecursivePluginProvider(RospkgPluginProvider('qt_gui', 'qt_gui_py::PluginProvider')))
00076         self.plugin_providers.append(RecursivePluginProvider(RospkgPluginProvider('rqt_gui', 'rqt_gui_py::PluginProvider')))
00077 
00078     def _add_reload_paths(self, reload_importer):
00079         super(Main, self)._add_reload_paths(reload_importer)
00080         reload_importer.add_reload_path(os.path.join(os.path.dirname(__file__), *('..',) * 4))
00081 
00082 
00083 if __name__ == '__main__':
00084     main = Main()
00085     sys.exit(main.main())


rqt_gui
Author(s): Dirk Thomas
autogenerated on Sat Jun 8 2019 20:23:27