From 7f76e082a6fa1a6e2af832f890442faf19270265 Mon Sep 17 00:00:00 2001 From: ahcorde Date: Thu, 14 May 2020 12:33:09 +0200 Subject: [PATCH 1/2] Fixed package to run with ros2 run Signed-off-by: ahcorde --- CMakeLists.txt | 22 ---------------------- package.xml | 5 ++--- resource/rqt_plot | 0 scripts/rqt_plot | 10 ---------- setup.cfg | 4 ++++ setup.py | 43 +++++++++++++++++++++++++++++++++++-------- src/rqt_plot/main.py | 14 ++++++++++++++ 7 files changed, 55 insertions(+), 43 deletions(-) delete mode 100644 CMakeLists.txt create mode 100644 resource/rqt_plot delete mode 100755 scripts/rqt_plot create mode 100644 setup.cfg create mode 100755 src/rqt_plot/main.py diff --git a/CMakeLists.txt b/CMakeLists.txt deleted file mode 100644 index d147f19..0000000 --- a/CMakeLists.txt +++ /dev/null @@ -1,22 +0,0 @@ -cmake_minimum_required(VERSION 3.5) -project(rqt_plot) - -find_package(ament_cmake REQUIRED) -find_package(ament_cmake_python REQUIRED) - -ament_python_install_package(${PROJECT_NAME} - PACKAGE_DIR src/${PROJECT_NAME}) - -install(FILES plugin.xml - DESTINATION share/${PROJECT_NAME} -) - -install(DIRECTORY resource - DESTINATION share/${PROJECT_NAME} -) - -install(PROGRAMS scripts/rqt_plot - DESTINATION lib/${PROJECT_NAME} -) - -ament_package() diff --git a/package.xml b/package.xml index ee1b639..818137a 100644 --- a/package.xml +++ b/package.xml @@ -16,8 +16,6 @@ Dorian Scholz Dirk Thomas - ament_cmake - python_qt_binding python3-matplotlib python3-numpy @@ -30,7 +28,8 @@ std_msgs - ament_cmake + + ament_python diff --git a/resource/rqt_plot b/resource/rqt_plot new file mode 100644 index 0000000..e69de29 diff --git a/scripts/rqt_plot b/scripts/rqt_plot deleted file mode 100755 index e85b0a3..0000000 --- a/scripts/rqt_plot +++ /dev/null @@ -1,10 +0,0 @@ -#!/usr/bin/env python3 - -import sys - -from rqt_gui.main import Main -from rqt_plot.plot import Plot - -plugin = 'rqt_plot.plot.Plot' -main = Main(filename=plugin) -sys.exit(main.main(standalone=plugin, plugin_argument_provider=Plot.add_arguments)) diff --git a/setup.cfg b/setup.cfg new file mode 100644 index 0000000..721e44b --- /dev/null +++ b/setup.cfg @@ -0,0 +1,4 @@ +[develop] +script-dir=$base/lib/rqt_plot +[install] +install-scripts=$base/lib/rqt_plot diff --git a/setup.py b/setup.py index 4ab6df5..7f33b15 100644 --- a/setup.py +++ b/setup.py @@ -1,12 +1,39 @@ -#!/usr/bin/env python +from setuptools import setup -from distutils.core import setup -from catkin_pkg.python_setup import generate_distutils_setup +package_name = 'rqt_plot' -d = generate_distutils_setup( - packages=['rqt_plot', 'rqt_plot.data_plot'], +setup( + name=package_name, + version='1.0.7', + packages=[package_name, package_name + '/data_plot'], package_dir={'': 'src'}, - scripts=['scripts/rqt_plot'] + data_files=[ + ('share/ament_index/resource_index/packages', + ['resource/' + package_name]), + ('share/' + package_name + '/resource', + ['resource/plot.ui']), + ('share/' + package_name, ['package.xml']), + ('share/' + package_name, ['plugin.xml']), + ], + install_requires=['setuptools'], + zip_safe=True, + author='Dorian Scholz', + maintainer='Dirk Thomas, Dorian Scholz, Austin Hendrix', + maintainer_email='dthomas@osrfoundation.org', + keywords=['ROS'], + classifiers=[ + 'Intended Audience :: Developers', + 'License :: OSI Approved :: BSD License', + 'Programming Language :: Python', + 'Topic :: Software Development', + ], + description=( + 'RQT plugin for monitoring ROS processes.' + ), + license='BSD', + entry_points={ + 'console_scripts': [ + 'rqt_plot = ' + package_name + '.main:main', + ], + }, ) - -setup(**d) diff --git a/src/rqt_plot/main.py b/src/rqt_plot/main.py new file mode 100755 index 0000000..e2ff2a1 --- /dev/null +++ b/src/rqt_plot/main.py @@ -0,0 +1,14 @@ +import sys + +from rqt_gui.main import Main +from rqt_plot.plot import Plot + + +def main(): + plugin = 'rqt_plot.plot.Plot' + main = Main(filename=plugin) + sys.exit(main.main(standalone=plugin, plugin_argument_provider=Plot.add_arguments)) + + +if __name__ == '__main__': + main() From d94abbf88a33450155a361fb102e282510e7fe22 Mon Sep 17 00:00:00 2001 From: ahcorde Date: Thu, 14 May 2020 23:29:27 +0200 Subject: [PATCH 2/2] Fixed description Signed-off-by: ahcorde --- setup.py | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/setup.py b/setup.py index 7f33b15..e94d51a 100644 --- a/setup.py +++ b/setup.py @@ -28,7 +28,8 @@ 'Topic :: Software Development', ], description=( - 'RQT plugin for monitoring ROS processes.' + 'rqt_plot provides a GUI plugin visualizing numeric values in a 2D plot ' + + 'using different plotting backends.' ), license='BSD', entry_points={