configuration_dock_widget.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 #       
00003 # License: BSD
00004 #   https://raw.github.com/yujinrobot/kobuki_desktop/master/kobuki_qtestsuite/LICENSE 
00005 #
00006 ##############################################################################
00007 # Imports
00008 ##############################################################################
00009 
00010 import roslib
00011 roslib.load_manifest('kobuki_qtestsuite')
00012 import rospy
00013 
00014 from python_qt_binding.QtCore import Signal,Slot
00015 from python_qt_binding.QtGui import QDockWidget
00016 from rqt_py_common.extended_combo_box import ExtendedComboBox
00017 
00018 # Local resource imports
00019 import detail.common_rc
00020 from detail.configuration_dock_ui import Ui_configuration_dock_widget
00021 
00022 class ConfigurationDockWidget(QDockWidget):
00023 
00024     def __init__(self, parent=None):
00025         super(ConfigurationDockWidget, self).__init__(parent)
00026         
00027         self._ui = Ui_configuration_dock_widget()
00028         #self._ui.setupUi(self)
00029 
00030         
00031     def setupUi(self):
00032         self._ui.setupUi(self)
00033         _, _, topic_types = rospy.get_master().getTopicTypes()
00034         cmd_vel_topics = [ topic[0] for topic in topic_types if topic[1] == 'geometry_msgs/Twist' ]
00035         self._ui.cmd_vel_topic_combo_box.setItems.emit(sorted(cmd_vel_topics))
00036         #self.cmd_vel_publisher = rospy.Publisher(str(self.cmd_vel_topic_combo_box.currentText()), Twist)
00037         odom_topics = [ topic[0] for topic in topic_types if topic[1] == 'nav_msgs/Odometry' ]
00038         self._ui.odom_topic_combo_box.setItems.emit(sorted(odom_topics))
00039         #self.odom_subscriber = rospy.Subscriber(str(self.odom_topic_combo_box.currentText()), Odometry, self.odometry_callback)
00040         core_sensor_topics = [ topic[0] for topic in topic_types if topic[1] == 'kobuki_msgs/SensorState' ]
00041         self._ui.core_topic_combo_box.setItems.emit(sorted(core_sensor_topics))
00042         
00043     def cmd_vel_topic_name(self):
00044         return str(self._ui.cmd_vel_topic_combo_box.currentText())
00045 
00046     def odom_topic_name(self):
00047         return str(self._ui.odom_topic_combo_box.currentText())
00048 
00049     def core_sensors_topic_name(self):
00050         return str(self._ui.core_sensor_topic_combo_box.currentText())
00051 
00052     def battery_topic_name(self):
00053         return str(self._ui.core_sensor_topic_combo_box.currentText() + '/' + battery)
00054         
00055     ##########################################################################
00056     # Slot Callbacks
00057     ##########################################################################
00058     @Slot(str)
00059     def on_cmd_vel_topic_combo_box_currentIndexChanged(self, topic_name):
00060         pass
00061         # This is probably a bit broken, need to test with more than just /cmd_vel so
00062         # there is more than one option.
00063         #self.cmd_vel_publisher = rospy.Publisher(str(self.cmd_vel_topic_combo_box.currentText()), Twist)
00064 
00065     @Slot(str)
00066     def on_odom_topic_combo_box_currentIndexChanged(self, topic_name):
00067         # Need to redo the subscriber here
00068         pass
00069 
00070     @Slot(str)
00071     def on_core_topic_combo_box_currentIndexChanged(self, topic_name):
00072         pass


kobuki_qtestsuite
Author(s): Daniel Stonier
autogenerated on Thu Jun 6 2019 19:42:56