31 from __future__ 
import division
 
   35 from geometry_msgs.msg 
import Twist
 
   37 from python_qt_binding 
import loadUi
 
   38 from python_qt_binding.QtCore 
import Qt, QTimer, Slot
 
   39 from python_qt_binding.QtGui 
import QKeySequence
 
   40 from python_qt_binding.QtWidgets 
import QShortcut, QWidget
 
   46     slider_factor = 1000.0
 
   49         super(RobotSteering, self).
__init__(context)
 
   50         self.setObjectName(
'RobotSteering')
 
   56         ui_file = os.path.join(
 
   57             rp.get_path(
'rqt_robot_steering'), 
'resource', 
'RobotSteering.ui')
 
   59         self.
_widget.setObjectName(
'RobotSteeringUi')
 
   60         if context.serial_number() > 1:
 
   62                 self.
_widget.windowTitle() + (
' (%d)' % context.serial_number()))
 
   63         context.add_widget(self.
_widget)
 
   65         self.
_widget.topic_line_edit.textChanged.connect(
 
   69         self.
_widget.x_linear_slider.valueChanged.connect(
 
   71         self.
_widget.z_angular_slider.valueChanged.connect(
 
   74         self.
_widget.increase_x_linear_push_button.pressed.connect(
 
   76         self.
_widget.reset_x_linear_push_button.pressed.connect(
 
   78         self.
_widget.decrease_x_linear_push_button.pressed.connect(
 
   80         self.
_widget.increase_z_angular_push_button.pressed.connect(
 
   82         self.
_widget.reset_z_angular_push_button.pressed.connect(
 
   84         self.
_widget.decrease_z_angular_push_button.pressed.connect(
 
   87         self.
_widget.max_x_linear_double_spin_box.valueChanged.connect(
 
   89         self.
_widget.min_x_linear_double_spin_box.valueChanged.connect(
 
   91         self.
_widget.max_z_angular_double_spin_box.valueChanged.connect(
 
   93         self.
_widget.min_z_angular_double_spin_box.valueChanged.connect(
 
   97         self.
shortcut_w.setContext(Qt.ApplicationShortcut)
 
  100         self.
shortcut_x.setContext(Qt.ApplicationShortcut)
 
  103         self.
shortcut_s.setContext(Qt.ApplicationShortcut)
 
  106         self.
shortcut_a.setContext(Qt.ApplicationShortcut)
 
  109         self.
shortcut_z.setContext(Qt.ApplicationShortcut)
 
  112         self.
shortcut_d.setContext(Qt.ApplicationShortcut)
 
  116             QKeySequence(Qt.SHIFT + Qt.Key_W), self.
_widget)
 
  121             QKeySequence(Qt.SHIFT + Qt.Key_X), self.
_widget)
 
  126             QKeySequence(Qt.SHIFT + Qt.Key_S), self.
_widget)
 
  131             QKeySequence(Qt.SHIFT + Qt.Key_A), self.
_widget)
 
  136             QKeySequence(Qt.SHIFT + Qt.Key_Z), self.
_widget)
 
  141             QKeySequence(Qt.SHIFT + Qt.Key_D), self.
_widget)
 
  147             QKeySequence(Qt.Key_Space), self.
_widget)
 
  151             QKeySequence(Qt.SHIFT + Qt.Key_Space), self.
_widget)
 
  155         self.
_widget.stop_push_button.setToolTip(
 
  156             self.
_widget.stop_push_button.toolTip() + 
' ' + self.tr(
'([Shift +] Space)'))
 
  157         self.
_widget.increase_x_linear_push_button.setToolTip(
 
  158             self.
_widget.increase_x_linear_push_button.toolTip() + 
' ' + self.tr(
'([Shift +] W)'))
 
  159         self.
_widget.reset_x_linear_push_button.setToolTip(
 
  160             self.
_widget.reset_x_linear_push_button.toolTip() + 
' ' + self.tr(
'([Shift +] X)'))
 
  161         self.
_widget.decrease_x_linear_push_button.setToolTip(
 
  162             self.
_widget.decrease_x_linear_push_button.toolTip() + 
' ' + self.tr(
'([Shift +] S)'))
 
  163         self.
_widget.increase_z_angular_push_button.setToolTip(
 
  164             self.
_widget.increase_z_angular_push_button.toolTip() + 
' ' + self.tr(
'([Shift +] A)'))
 
  165         self.
_widget.reset_z_angular_push_button.setToolTip(
 
  166             self.
_widget.reset_z_angular_push_button.toolTip() + 
' ' + self.tr(
'([Shift +] Z)'))
 
  167         self.
_widget.decrease_z_angular_push_button.setToolTip(
 
  168             self.
_widget.decrease_z_angular_push_button.toolTip() + 
' ' + self.tr(
'([Shift +] D)'))
 
  184             self.
_publisher = rospy.Publisher(topic, Twist, queue_size=10)
 
  186             self.
_publisher = rospy.Publisher(topic, Twist)
 
  190         if self.
_widget.x_linear_slider.value() == 0 
and \
 
  191                 self.
_widget.z_angular_slider.value() == 0:
 
  195             self.
_widget.x_linear_slider.setValue(0)
 
  196             self.
_widget.z_angular_slider.setValue(0)
 
  199         self.
_widget.current_x_linear_label.setText(
 
  200             '%0.2f m/s' % (self.
_widget.x_linear_slider.value() / RobotSteering.slider_factor))
 
  204         self.
_widget.current_z_angular_label.setText(
 
  205             '%0.2f rad/s' % (self.
_widget.z_angular_slider.value() / RobotSteering.slider_factor))
 
  209         self.
_widget.x_linear_slider.setValue(
 
  210             self.
_widget.x_linear_slider.value() + self.
_widget.x_linear_slider.singleStep())
 
  213         self.
_widget.x_linear_slider.setValue(0)
 
  216         self.
_widget.x_linear_slider.setValue(
 
  217             self.
_widget.x_linear_slider.value() - self.
_widget.x_linear_slider.singleStep())
 
  220         self.
_widget.z_angular_slider.setValue(
 
  221             self.
_widget.z_angular_slider.value() + self.
_widget.z_angular_slider.singleStep())
 
  224         self.
_widget.z_angular_slider.setValue(0)
 
  227         self.
_widget.z_angular_slider.setValue(
 
  228             self.
_widget.z_angular_slider.value() - self.
_widget.z_angular_slider.singleStep())
 
  231         self.
_widget.x_linear_slider.setMaximum(
 
  232             int(value * RobotSteering.slider_factor))
 
  235         self.
_widget.x_linear_slider.setMinimum(
 
  236             int(value * RobotSteering.slider_factor))
 
  239         self.
_widget.z_angular_slider.setMaximum(
 
  240             int(value * RobotSteering.slider_factor))
 
  243         self.
_widget.z_angular_slider.setMinimum(
 
  244             int(value * RobotSteering.slider_factor))
 
  247         self.
_widget.x_linear_slider.setValue(
 
  248             self.
_widget.x_linear_slider.value() + self.
_widget.x_linear_slider.pageStep())
 
  251         self.
_widget.x_linear_slider.setValue(
 
  252             self.
_widget.x_linear_slider.value() - self.
_widget.x_linear_slider.pageStep())
 
  255         self.
_widget.z_angular_slider.setValue(
 
  256             self.
_widget.z_angular_slider.value() + self.
_widget.z_angular_slider.pageStep())
 
  259         self.
_widget.z_angular_slider.setValue(
 
  260             self.
_widget.z_angular_slider.value() - self.
_widget.z_angular_slider.pageStep())
 
  264             self.
_widget.x_linear_slider.value() / RobotSteering.slider_factor,
 
  265             self.
_widget.z_angular_slider.value() / RobotSteering.slider_factor)
 
  271         twist.linear.x = x_linear
 
  276         twist.angular.z = z_angular
 
  279         if x_linear == 0 
and z_angular == 0:
 
  297         instance_settings.set_value(
 
  298             'topic', self.
_widget.topic_line_edit.text())
 
  299         instance_settings.set_value(
 
  300             'vx_max', self.
_widget.max_x_linear_double_spin_box.value())
 
  301         instance_settings.set_value(
 
  302             'vx_min', self.
_widget.min_x_linear_double_spin_box.value())
 
  303         instance_settings.set_value(
 
  304             'vw_max', self.
_widget.max_z_angular_double_spin_box.value())
 
  305         instance_settings.set_value(
 
  306             'vw_min', self.
_widget.min_z_angular_double_spin_box.value())
 
  309         value = instance_settings.value(
'topic', 
'/cmd_vel')
 
  310         value = rospy.get_param(
'~default_topic', value)
 
  311         self.
_widget.topic_line_edit.setText(value)
 
  313         value = self.
_widget.max_x_linear_double_spin_box.value()
 
  314         value = instance_settings.value(
'vx_max', value)
 
  315         value = rospy.get_param(
'~default_vx_max', value)
 
  316         self.
_widget.max_x_linear_double_spin_box.setValue(float(value))
 
  318         value = self.
_widget.min_x_linear_double_spin_box.value()
 
  319         value = instance_settings.value(
'vx_min', value)
 
  320         value = rospy.get_param(
'~default_vx_min', value)
 
  321         self.
_widget.min_x_linear_double_spin_box.setValue(float(value))
 
  323         value = self.
_widget.max_z_angular_double_spin_box.value()
 
  324         value = instance_settings.value(
'vw_max', value)
 
  325         value = rospy.get_param(
'~default_vw_max', value)
 
  326         self.
_widget.max_z_angular_double_spin_box.setValue(float(value))
 
  328         value = self.
_widget.min_z_angular_double_spin_box.value()
 
  329         value = instance_settings.value(
'vw_min', value)
 
  330         value = rospy.get_param(
'~default_vw_min', value)
 
  331         self.
_widget.min_z_angular_double_spin_box.setValue(float(value))