Skip to content

Commit

Permalink
update from-nodes style (#348)
Browse files Browse the repository at this point in the history
  • Loading branch information
dirk-thomas committed Sep 9, 2016
1 parent 702da07 commit 2cbfb7d
Show file tree
Hide file tree
Showing 3 changed files with 48 additions and 42 deletions.
2 changes: 1 addition & 1 deletion rqt_bag/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -21,10 +21,10 @@
<run_depend>rosbag</run_depend>
<run_depend>rosgraph_msgs</run_depend>
<run_depend>roslib</run_depend>
<run_depend>rosnode</run_depend>
<run_depend>rospy</run_depend>
<run_depend version_gte="0.2.12">rqt_gui</run_depend>
<run_depend>rqt_gui_py</run_depend>
<run_depend>rosnode</run_depend>
<export>
<architecture_independent/>
<rqt_gui plugin="${prefix}/plugin.xml"/>
Expand Down
67 changes: 34 additions & 33 deletions rqt_bag/src/rqt_bag/node_selection.py
Original file line number Diff line number Diff line change
@@ -1,41 +1,40 @@
#####################################################################
# Software License Agreement (BSD License)
#
# Copyright (c) 2016, Ryohei Ueda
# All rights reserved.
# Copyright (c) 2016, Ryohei Ueda
# All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# * Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# * Redistributions in binary form must reproduce the above
# copyright notice, this list of conditions and the following
# disclaimer in the documentation and/o2r other materials provided
# with the distribution.
# * Neither the name of the Willow Garage nor the names of its
# contributors may be used to endorse or promote products derived
# from this software without specific prior written permission.
# * Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# * Redistributions in binary form must reproduce the above
# copyright notice, this list of conditions and the following
# disclaimer in the documentation and/or other materials provided
# with the distribution.
# * Neither the name of Willow Garage, Inc. nor the names of its
# contributors may be used to endorse or promote products derived
# from this software without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#####################################################################
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.

import rosgraph
import rosnode
from python_qt_binding.QtCore import Qt, Signal
from python_qt_binding.QtGui import QWidget, QHBoxLayout, QVBoxLayout, QCheckBox, QScrollArea, QPushButton
from python_qt_binding.QtCore import Qt
from python_qt_binding.QtWidgets import QWidget, QVBoxLayout, QCheckBox, QScrollArea, QPushButton


class NodeSelection(QWidget):
def __init__(self, parent):
Expand All @@ -55,17 +54,19 @@ def __init__(self, parent):
self.setLayout(self.main_vlayout)

self.selection_vlayout = QVBoxLayout(self)

self.node_list = rosnode.get_node_names()
self.node_list.sort()
for node in self.node_list:
self.addCheckBox(node)
self.main_widget.setLayout(self.selection_vlayout)
self.show()

def addCheckBox(self, node):
item = QCheckBox(node, self)
item.stateChanged.connect(lambda x: self.updateNode(x,node))
item.stateChanged.connect(lambda x: self.updateNode(x, node))
self.selection_vlayout.addWidget(item)

def updateNode(self, state, node):
if state == Qt.Checked:
self.selected_nodes.append(node)
Expand All @@ -75,8 +76,8 @@ def updateNode(self, state, node):
self.ok_button.setEnabled(True)
else:
self.ok_button.setEnabled(False)

def onButtonClicked(self):
print self.selected_nodes
master = rosgraph.Master('rqt_bag_recorder')
state = master.getSystemState()
subs = [t for t, l in state[1]
Expand Down
21 changes: 13 additions & 8 deletions rqt_bag/src/rqt_bag/topic_selection.py
Original file line number Diff line number Diff line change
Expand Up @@ -33,9 +33,10 @@
import rosgraph

from python_qt_binding.QtCore import Qt, Signal
from python_qt_binding.QtWidgets import QWidget, QHBoxLayout, QVBoxLayout, QCheckBox, QScrollArea, QPushButton
from python_qt_binding.QtWidgets import QWidget, QVBoxLayout, QCheckBox, QScrollArea, QPushButton
from .node_selection import NodeSelection


class TopicSelection(QWidget):

recordSettingsSelected = Signal(bool, list)
Expand All @@ -49,14 +50,16 @@ def __init__(self):
self.topic_list = []
self.selected_topics = []
self.items_list = []

self.area = QScrollArea(self)
self.main_widget = QWidget(self.area)
self.ok_button = QPushButton("Record", self)
self.ok_button.clicked.connect(self.onButtonClicked)
self.ok_button.setEnabled(False)

self.from_nodes_button = QPushButton("From Nodes", self)
self.from_nodes_button.clicked.connect(self.onFromNodesButtonClicked)

self.main_vlayout = QVBoxLayout(self)
self.main_vlayout.addWidget(self.area)
self.main_vlayout.addWidget(self.ok_button)
Expand All @@ -80,7 +83,7 @@ def __init__(self):
def addCheckBox(self, topic):
self.topic_list.append(topic)
item = QCheckBox(topic, self)
item.stateChanged.connect(lambda x: self.updateList(x,topic))
item.stateChanged.connect(lambda x: self.updateList(x, topic))
self.items_list.append(item)
self.selection_vlayout.addWidget(item)

Expand All @@ -89,8 +92,9 @@ def changeTopicCheckState(self, topic, state):
if item.text() == topic:
item.setCheckState(state)
return
def updateList(self, state, topic = None, force_update_state=False):
if topic is None: # The "All" checkbox was checked / unchecked

def updateList(self, state, topic=None, force_update_state=False):
if topic is None: # The "All" checkbox was checked / unchecked
if state == Qt.Checked:
self.item_all.setTristate(False)
for item in self.items_list:
Expand All @@ -106,7 +110,7 @@ def updateList(self, state, topic = None, force_update_state=False):
self.selected_topics.append(topic)
else:
self.selected_topics.remove(topic)
if self.item_all.checkState()==Qt.Checked:
if self.item_all.checkState() == Qt.Checked:
self.item_all.setCheckState(Qt.PartiallyChecked)

if self.selected_topics == []:
Expand All @@ -116,7 +120,8 @@ def updateList(self, state, topic = None, force_update_state=False):

def onButtonClicked(self):
self.close()
self.recordSettingsSelected.emit((self.item_all.checkState() == Qt.Checked), self.selected_topics)
self.recordSettingsSelected.emit(
self.item_all.checkState() == Qt.Checked, self.selected_topics)

def onFromNodesButtonClicked(self):
self.node_selection = NodeSelection(self)

0 comments on commit 2cbfb7d

Please sign in to comment.