main.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 
3 # Software License Agreement (BSD License)
4 #
5 # Copyright (c) 2012, Willow Garage, Inc.
6 # All rights reserved.
7 #
8 # Redistribution and use in source and binary forms, with or without
9 # modification, are permitted provided that the following conditions
10 # are met:
11 #
12 # * Redistributions of source code must retain the above copyright
13 # notice, this list of conditions and the following disclaimer.
14 # * Redistributions in binary form must reproduce the above
15 # copyright notice, this list of conditions and the following
16 # disclaimer in the documentation and/or other materials provided
17 # with the distribution.
18 # * Neither the name of Willow Garage, Inc. nor the names of its
19 # contributors may be used to endorse or promote products derived
20 # from this software without specific prior written permission.
21 #
22 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33 # POSSIBILITY OF SUCH DAMAGE.
34 
35 import os
36 import sys
37 
38 from qt_gui.main import Main as Base
39 
40 from rospkg.rospack import RosPack
41 import rospy
42 
43 
44 class Main(Base):
45 
46  def __init__(self, filename=None, ros_pack=None, settings_filename='rqt_gui'):
47  rp = ros_pack or RosPack()
48  qtgui_path = rp.get_path('qt_gui')
49  super(Main, self).__init__(
50  qtgui_path, invoked_filename=filename, settings_filename=settings_filename)
51  self._ros_pack = rp
52 
53  def main(self, argv=None, standalone=None, plugin_argument_provider=None):
54  if argv is None:
55  argv = sys.argv
56 
57  # ignore ROS specific remapping arguments (see
58  # http://www.ros.org/wiki/Remapping%20Arguments)
59  argv = rospy.myargv(argv)
60 
61  return super(
62  Main, self).main(argv, standalone=standalone,
63  plugin_argument_provider=plugin_argument_provider,
64  plugin_manager_settings_prefix=str(
65  hash(os.environ['ROS_PACKAGE_PATH'])))
66 
67  def create_application(self, argv):
68  from python_qt_binding.QtGui import QIcon
69  app = super(Main, self).create_application(argv)
70  logo = os.path.join(self._ros_pack.get_path('rqt_gui'), 'resource', 'rqt.png')
71  icon = QIcon(logo)
72  app.setWindowIcon(icon)
73  return app
74 
76  # do not import earlier as it would import Qt stuff without the proper
77  # initialization from qt_gui.main
78  from qt_gui.recursive_plugin_provider import RecursivePluginProvider
79  from .rospkg_plugin_provider import RospkgPluginProvider
80  RospkgPluginProvider.rospack = self._ros_pack
81  self.plugin_providers.append(RospkgPluginProvider('qt_gui', 'qt_gui_py::Plugin'))
82  self.plugin_providers.append(RecursivePluginProvider(
83  RospkgPluginProvider('qt_gui', 'qt_gui_py::PluginProvider')))
84  self.plugin_providers.append(RecursivePluginProvider(
85  RospkgPluginProvider('rqt_gui', 'rqt_gui_py::PluginProvider')))
86 
87  def _add_reload_paths(self, reload_importer):
88  super(Main, self)._add_reload_paths(reload_importer)
89  reload_importer.add_reload_path(os.path.join(os.path.dirname(__file__), *('..',) * 4))
90 
91 
92 if __name__ == '__main__':
93  main = Main()
94  sys.exit(main.main())
def _add_plugin_providers(self)
def create_application(self, argv)
def main(self, argv=None, standalone=None, plugin_argument_provider=None, plugin_manager_settings_prefix='')
def __init__(self, qtgui_path, invoked_filename=None, settings_filename=None)
def _add_reload_paths(self, reload_importer)


rqt_gui
Author(s): Dirk Thomas, Michael Jeronimo
autogenerated on Mon May 16 2022 02:49:36