def __init__(self, context): super(JointTrajectoryController, self).__init__(context) self.setObjectName('JointTrajectoryController') # Create QWidget and extend it with all the attributes and children # from the UI file self._widget = QWidget() rp = rospkg.RosPack() ui_file = os.path.join(rp.get_path('rqt_joint_trajectory_controller'), 'resource', 'joint_trajectory_controller.ui') loadUi(ui_file, self._widget) self._widget.setObjectName('JointTrajectoryControllerUi') ns = rospy.get_namespace()[1:-1] self._widget.controller_group.setTitle('ns: ' + ns) # Setup speed scaler speed_scaling = DoubleEditor(1.0, 100.0) speed_scaling.spin_box.setSuffix('%') speed_scaling.spin_box.setValue(50.0) speed_scaling.spin_box.setDecimals(0) speed_scaling.setEnabled(False) self._widget.speed_scaling_layout.addWidget(speed_scaling) self._speed_scaling_widget = speed_scaling speed_scaling.valueChanged.connect(self._on_speed_scaling_change) self._on_speed_scaling_change(speed_scaling.value()) # Show _widget.windowTitle on left-top of each plugin (when # it's set in _widget). This is useful when you open multiple # plugins at once. Also if you open multiple instances of your # plugin at once, these lines add number to make it easy to # tell from pane to pane. if context.serial_number() > 1: self._widget.setWindowTitle(self._widget.windowTitle() + (' (%d)' % context.serial_number())) # Add widget to the user interface context.add_widget(self._widget) # Initialize members self._jtc_name = [] # Name of selected joint trajectory controller self._cm_ns = [] # Namespace of the selected controller manager self._joint_pos = {} # name->pos map for joints of selected controller self._joint_names = [] # Ordered list of selected controller joints self._robot_joint_limits = {} # Lazily evaluated on first use # Timer for sending commands to active controller self._update_cmd_timer = QTimer(self) self._update_cmd_timer.setInterval(int(1000.0 / self._cmd_pub_freq)) self._update_cmd_timer.timeout.connect(self._update_cmd_cb) # Timer for updating the joint widgets from the controller state self._update_act_pos_timer = QTimer(self) self._update_act_pos_timer.setInterval( int(1000.0 / self._widget_update_freq)) self._update_act_pos_timer.timeout.connect(self._update_joint_widgets) # Timer for controller manager updates self._list_cm = ControllerManagerLister() self._update_cm_list_timer = QTimer(self) self._update_cm_list_timer.setInterval( int(1000.0 / self._ctrlrs_update_freq)) self._update_cm_list_timer.timeout.connect(self._update_cm_list) self._update_cm_list_timer.start() # Timer for running controller updates self._update_jtc_list_timer = QTimer(self) self._update_jtc_list_timer.setInterval( int(1000.0 / self._ctrlrs_update_freq)) self._update_jtc_list_timer.timeout.connect(self._update_jtc_list) self._update_jtc_list_timer.start() # Signal connections w = self._widget w.enable_button.toggled.connect(self._on_jtc_enabled) w.jtc_combo.currentIndexChanged[str].connect(self._on_jtc_change) w.cm_combo.currentIndexChanged[str].connect(self._on_cm_change) self._cmd_pub = None # Controller command publisher self._state_sub = None # Controller state subscriber self._list_controllers = None
def __init__(self, context): super(ControllerManager, self).__init__(context) self.setObjectName('ControllerManager') # Create QWidget and extend it with all the attributes and children # from the UI file self._widget = QWidget() rp = rospkg.RosPack() ui_file = os.path.join(rp.get_path('rqt_controller_manager'), 'resource', 'controller_manager.ui') loadUi(ui_file, self._widget) self._widget.setObjectName('ControllerManagerUi') # Pop-up that displays controller information self._popup_widget = QWidget() ui_file = os.path.join(rp.get_path('rqt_controller_manager'), 'resource', 'controller_info.ui') loadUi(ui_file, self._popup_widget) self._popup_widget.setObjectName('ControllerInfoUi') # Show _widget.windowTitle on left-top of each plugin (when # it's set in _widget). This is useful when you open multiple # plugins at once. Also if you open multiple instances of your # plugin at once, these lines add number to make it easy to # tell from pane to pane. if context.serial_number() > 1: self._widget.setWindowTitle(self._widget.windowTitle() + (' (%d)' % context.serial_number())) # Add widget to the user interface context.add_widget(self._widget) # Initialize members self._cm_ns = [] # Namespace of the selected controller manager self._controllers = [] # State of each controller self._table_model = None self._controller_lister = None # Controller manager service proxies self._load_srv = None self._unload_srv = None self._switch_srv = None # Controller state icons rospack = rospkg.RosPack() path = rospack.get_path('rqt_controller_manager') self._icons = {'running': QIcon(path + '/resource/led_green.png'), 'stopped': QIcon(path + '/resource/led_red.png'), 'uninitialized': QIcon(path + '/resource/led_off.png'), 'initialized': QIcon(path + '/resource/led_red.png')} # Controllers display table_view = self._widget.table_view table_view.setContextMenuPolicy(Qt.CustomContextMenu) table_view.customContextMenuRequested.connect(self._on_ctrl_menu) table_view.doubleClicked.connect(self._on_ctrl_info) header = table_view.horizontalHeader() header.setSectionResizeMode(QHeaderView.ResizeToContents) header.setContextMenuPolicy(Qt.CustomContextMenu) header.customContextMenuRequested.connect(self._on_header_menu) # Timer for controller manager updates self._list_cm = ControllerManagerLister() self._update_cm_list_timer = QTimer(self) self._update_cm_list_timer.setInterval(1000.0 / self._cm_update_freq) self._update_cm_list_timer.timeout.connect(self._update_cm_list) self._update_cm_list_timer.start() # Timer for running controller updates self._update_ctrl_list_timer = QTimer(self) self._update_ctrl_list_timer.setInterval(1000.0 / self._cm_update_freq) self._update_ctrl_list_timer.timeout.connect(self._update_controllers) self._update_ctrl_list_timer.start() # Signal connections w = self._widget w.cm_combo.currentIndexChanged[str].connect(self._on_cm_change)