node_controller.py
Go to the documentation of this file.
00001 #! /usr/bin/env python
00002 
00003 import rospy
00004 
00005 
00006 # Provides callback functions for the start and stop buttons
00007 class NodeController(object):
00008     '''
00009     Containing both proxy and gui instances, this class gives a control of
00010     a node on both ROS & GUI sides.
00011     '''
00012 
00013     def __init__(self, proxy, gui):
00014         '''
00015         @type proxy: rqt_launch.NodeProxy
00016         @type gui: QWidget
00017         '''
00018         self._proxy = proxy
00019 
00020         self._gui = gui
00021         self._gui.set_node_controller(self)
00022 
00023     def start_stop_slot(self, signal):
00024         '''
00025         Works as a slot particularly intended to work for
00026         QAbstractButton::toggled(checked). Internally calls
00027         NodeController.start / stop depending on `signal`.
00028 
00029         @type signal: bool
00030         '''
00031         if self._proxy.is_running():
00032             self.stop()
00033             rospy.logdebug('---start_stop_slot stOP')
00034         else:
00035             self.start()
00036             rospy.logdebug('==start_stop_slot StART')
00037 
00038     def start(self, restart=True):
00039         '''
00040         Start a ROS node as a new _process.
00041         '''
00042         rospy.logdebug('Controller.start restart={}'.format(restart))
00043 
00044         # Should be almost unreachable under current design where this 'start'
00045         # method only gets called when _proxy.is_running() returns false.
00046 
00047         if self._proxy.is_running():
00048             if not restart:
00049                 # If the node is already running and restart isn't desired,
00050                 # do nothing further.
00051                 return
00052             #TODO: Need to consider...is stopping node here
00053             # (i.e. in 'start' method) good?
00054             self.stop()
00055 
00056         # If the launch_prefix has changed, then the _process must be recreated
00057         if (self._proxy.config.launch_prefix !=
00058             self._gui._lineEdit_launch_args.text()):
00059 
00060             self._proxy.config.launch_prefix = \
00061                                      self._gui._lineEdit_launch_args.text()
00062             self._proxy.recreate_process()
00063 
00064         self._gui.set_node_started(False)
00065         self._gui.label_status.set_starting()
00066         self._proxy.start_process()
00067         self._gui.label_status.set_running()
00068         self._gui.label_spawncount.setText("({})".format(
00069                                               self._proxy.get_spawn_count()))
00070 
00071     def stop(self):
00072         '''
00073         Stop a ROS node's _process.
00074         '''
00075 
00076         #TODO: Need to check if the node is really running.
00077 
00078         #if self._proxy.is_running():
00079         self._gui.set_node_started(True)
00080         self._gui.label_status.set_stopping()
00081         self._proxy.stop_process()
00082         self._gui.label_status.set_stopped()
00083 
00084     def check_process_status(self):
00085         if self._proxy.has_died():
00086             rospy.logerr("Process died: {}".format(
00087                                                   self._proxy.get_proc_name()))
00088             self._proxy.stop_process()
00089             self._gui.set_node_started(True)
00090             if self._proxy._process.exit_code == 0:
00091                 self._gui.label_status.set_stopped()
00092             else:
00093                 self._gui.label_status.set_died()
00094 
00095             # Checks if it should be respawned
00096             if self._gui.respawn_toggle.isChecked():
00097                 rospy.loginfo("Respawning _process: {}".format(
00098                                                     self._proxy._process.name))
00099                 self._gui.label_status.set_starting()
00100                 self._proxy.start_process()
00101                 self._gui.label_status.set_running()
00102                 self._gui.label_spawncount.setText("({})".format(
00103                                              self._proxy._process.spawn_count))
00104 
00105     def get_node_widget(self):
00106         '''
00107         @rtype: QWidget
00108         '''
00109         return self._gui
00110 
00111     def is_node_running(self):
00112         return self._proxy.is_running()


rqt_launch
Author(s): Isaac Saito, Stuart Glaser
autogenerated on Tue May 2 2017 02:42:28