To move my custom robot, I had to write a plugin into rqt. I don't know if Pioneer 2DX has any solution ready.
You would need to install QT 4 Designer
$ sudo apt-get install python-qt4 qt4-designer
Then you design your own GUI window
Pay attention how you name the buttons. You will use the name to connect the buttons with a specific function. My GUI window has 4 buttons
pushButton_up
pushButton_down
pushButton_left
pushButton_right
a slider on which I can choose the velocity with which I will accelerate the robot
velocitySlider
and a text field
velocityValue
which shows the currently set velocity which will be set to robot if I push the button. You can also write directly into the text field.
I have created a new package just for this feature.
robot_teleop
├── CMakeLists.txt
├── package.xml
├── plugin_description.xml
├── resource
│ └── control.ui
├── scripts
│ └── run_gui_plugin.py
├── setup.py
└── src
└── robot_teleop
├── __init__.py
└── rqt_plugin.py
The widget from the QT 4 Designer is saved in the /resource/control.ui
file.
The CMakeLists.txt
cmake_minimum_required(VERSION 2.8.3)
project(robot_teleop)
find_package(catkin REQUIRED COMPONENTS
rospy
std_msgs
rqt_gui
rqt_gui_py
)
## This macro ensures modules and global scripts declared therein get installed
## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html
catkin_python_setup()
###########
## Build ##
###########
## Specify additional locations of header files
## Your package locations should be listed before other locations
include_directories(
${catkin_INCLUDE_DIRS}
)
#############
## Install ##
#############
# all install targets should use catkin DESTINATION variables
# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html
## Mark executable scripts (Python etc.) for installation
## in contrast to setup.py, you can choose the destination
install(PROGRAMS
scripts/run_gui_plugin.py
plugin_description.xml
DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
)
plugin_description.xml
<library path="src">
<class name="GUIControllerPlugin"
type="robot_teleop.rqt_plugin.GUIControllerPlugin"
base_class_type="rqt_gui_py::Plugin">
<description>
A GUI rqt plugin for a manual robot controll.
</description>
</class>
</library>
package.xml
<?xml version="1.0"?>
<package format="2">
<name>robot_teleop</name>
<version>0.0.0</version>
<description>rqt plugin for manual control of the robot</description>
<buildtool_depend>catkin</buildtool_depend>
<build_depend>rospy</build_depend>
<build_depend>std_msgs</build_depend>
<build_export_depend>rqt_gui</build_export_depend>
<build_export_depend>rqt_gui_py</build_export_depend>
<build_export_depend>rospy</build_export_depend>
<build_export_depend>std_msgs</build_export_depend>
<exec_depend>rospy</exec_depend>
<exec_depend>std_msgs</exec_depend>
<exec_depend>python-rospkg</exec_depend>
<exec_depend>rqt_gui</exec_depend>
<exec_depend>rqt_gui_py</exec_depend>
<export>
<rqt_gui plugin="${prefix}/plugin_description.xml"/>
</export>
</package>
setup.py
#!/usr/bin/python
from distutils.core import setup
from catkin_pkg.python_setup import generate_distutils_setup
setup_args = generate_distutils_setup(
packages=['robot_teleop'],
package_dir={'': 'src'},
install_requires=[]
)
setup(**setup_args)
/scripts/run_gui_plugin.py
#!/usr/bin/env python
import sys
from robot_teleop.rqt_plugin import GUIControllerPlugin
from rqt_gui.main import Main
"""
Starts rqt plugin.
run with command:
$ rqt --standalone robot_teleop
"""
main = Main(filename='robot_teleop')
sys.exit(main.main(sys.argv, standalone='robot_teleop'))
The /src/robot_teleop/__init.py__ is an empty file. I suppose it is located where it is to tell catkin where to find the plugin.
And finaly the plugin /src/robot_teleop/rqt_plugin.py
#!/usr/bin/python
import rospy
import os
import rospkg
from qt_gui.plugin import Plugin
from python_qt_binding import loadUi
from python_qt_binding.QtWidgets import QWidget, QMessageBox
from std_msgs.msg import Float64
class GUIControllerPlugin ...
(more)