launch_main.py
Go to the documentation of this file.
1 # Software License Agreement (BSD License)
2 #
3 # Copyright (c) 2012, Willow Garage, Inc.
4 # All rights reserved.
5 #
6 # Redistribution and use in source and binary forms, with or without
7 # modification, are permitted provided that the following conditions
8 # are met:
9 #
10 # * Redistributions of source code must retain the above copyright
11 # notice, this list of conditions and the following disclaimer.
12 # * Redistributions in binary form must reproduce the above
13 # copyright notice, this list of conditions and the following
14 # disclaimer in the documentation and/or other materials provided
15 # with the distribution.
16 # * Neither the name of Willow Garage, Inc. nor the names of its
17 # contributors may be used to endorse or promote products derived
18 # from this software without specific prior written permission.
19 #
20 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
21 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
22 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
23 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
24 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
25 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
26 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
27 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
28 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
29 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
30 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
31 # POSSIBILITY OF SUCH DAMAGE.
32 #
33 # Author: Isaac Saito
34 
35 import sys
36 
37 import rospy
38 from rqt_launch.launch_widget import LaunchWidget
39 from rqt_py_common.plugin_container_widget import PluginContainerWidget
40 from rqt_py_common.rqt_roscomm_util import RqtRoscommUtil
41 
42 
43 class LaunchMain(object):
44 
45  def __init__(self, plugin_context):
46  super(LaunchMain, self).__init__()
47  self._plugin_context = plugin_context
48 
51  True, False)
52 
53  self._run_id = None
55 
56  # RqtRoscommUtil.load_parameters(self._config, '/rqt_launch')
57 
58  def get_widget(self):
59  return self._mainwidget
60 
61  def set_node_controllers(self, node_controllers):
62  self._node_controllers = node_controllers
63 
64  def load_params(self):
65  self._main_launch_widget.load_parameters()
66 
67  def start_all(self):
68  '''
69  Checks nodes that's set (via self.set_node_controllers) one by one and
70  starts one if each node is not running.
71  Then disable START ALL button and enable STOP ALL button.
72  '''
73  for n in self._node_controllers:
74  if not n.is_node_running():
75  n.start(restart=False)
76 
77  # Disable START ALL button.
78  self._main_launch_widget._pushbutton_start_all.setEnabled(False)
79  self._main_launch_widget._pushbutton_stop_all.setEnabled(True)
80 
81  def stop_all(self):
82  '''
83  Checks nodes that's set (via self.set_node_controllers) one by one and
84  stops one if each node is running.
85  Then enable START ALL button and disable STOP ALL button.
86  '''
87  for n in self._node_controllers:
88  if n.is_node_running():
89  n.stop()
90 
91  # Disable STOP ALL button.
92  self._main_launch_widget._pushbutton_start_all.setEnabled(True)
93  self._main_launch_widget._pushbutton_stop_all.setEnabled(False)
94 
96  for n in self._node_controllers:
97  n.check_process_status()
98 
99  def shutdown(self):
100  rospy.logdebug('Launchmain.shutdown')
101  self.stop_all()
102 
103  def save_settings(self, plugin_settings, instance_settings):
104  self._mainwidget.save_settings(plugin_settings, instance_settings)
105 
106  def restore_settings(self, plugin_settings, instance_settings):
107  self._mainwidget.restore_settings(plugin_settings, instance_settings)
108 
109 
110 if __name__ == '__main__':
111  # main should be used only for debug purpose.
112  # This launches this QWidget as a standalone rqt gui.
113  from rqt_gui.main import Main
114  main = Main()
115  sys.exit(main.main(sys.argv, standalone='rqt_launch'))
def save_settings(self, plugin_settings, instance_settings)
Definition: launch_main.py:103
def restore_settings(self, plugin_settings, instance_settings)
Definition: launch_main.py:106
def __init__(self, plugin_context)
Definition: launch_main.py:45
def set_node_controllers(self, node_controllers)
Definition: launch_main.py:61


rqt_launch
Author(s): Isaac Saito, Stuart Glaser
autogenerated on Wed Oct 14 2020 03:50:59