├── .clang-format ├── .codecov.yml ├── .github └── ISSUE_TEMPLATE │ ├── bug_report.md │ └── feature_request.md ├── .gitignore ├── .travis.yml ├── CMakeLists.txt ├── LICENSE ├── README.md ├── docs ├── .gitignore ├── Doxyfile ├── Makefile ├── conf.py ├── index.rst ├── pages │ ├── ActionClient.rst │ ├── Arrays.rst │ ├── Examples.rst │ ├── ImageTransport.rst │ ├── Logging.rst │ ├── Publishers.rst │ ├── Quickstart.rst │ ├── Ros-Singleton.rst │ ├── Services.rst │ ├── Subscribers.rst │ ├── Tf-Transforms.rst │ └── Time.rst └── requirements.txt ├── examples ├── README.md ├── action_client.qml ├── image_subscriber.qml ├── logging.qml ├── publisher.qml ├── service.qml ├── subscriber.qml ├── tf_transforms.qml ├── time.qml └── urdf_tutorial_control.qml ├── export_qml_ros_plugin.sh.em ├── include └── qml_ros_plugin │ ├── action_client.h │ ├── array.h │ ├── babel_fish_dispenser.h │ ├── console.h │ ├── conversion │ └── qvariant_yaml_conversion.h │ ├── goal_handle.h │ ├── helpers │ └── rolling_average.h │ ├── image_buffer.h │ ├── image_transport_manager.h │ ├── image_transport_subscriber.h │ ├── io.h │ ├── message_conversions.h │ ├── node_handle.h │ ├── package.h │ ├── publisher.h │ ├── qml_ros_conversion.h │ ├── qobject_ros.h │ ├── ros.h │ ├── service.h │ ├── subscriber.h │ ├── tf_transform.h │ ├── tf_transform_listener.h │ ├── time.h │ └── topic_info.h ├── package.xml ├── qmldir ├── src ├── action_client.cpp ├── array.cpp ├── babel_fish_dispenser.cpp ├── console.cpp ├── goal_handle.cpp ├── image_buffer.cpp ├── image_transport_manager.cpp ├── image_transport_subscriber.cpp ├── io.cpp ├── message_conversions.cpp ├── node_handle.cpp ├── package.cpp ├── publisher.cpp ├── qml_ros_plugin.cpp ├── qobject_ros.cpp ├── ros.cpp ├── service.cpp ├── subscriber.cpp ├── tf_transform.cpp ├── tf_transform_listener.cpp └── time.cpp └── test ├── action_server.cpp ├── all_tests.test ├── common.h ├── communication.cpp ├── image_conversions.cpp ├── image_transport_subscriber.cpp ├── io.cpp ├── logging.cpp ├── message_comparison.h ├── message_conversions.cpp ├── package.cpp ├── ros_life_cycle.cpp ├── spinning.cpp ├── test_communication.test ├── test_image_conversions.test ├── test_image_transport_subscriber.test ├── test_io.test ├── test_io ├── .gitignore └── test.yaml ├── test_logging.test ├── test_message_conversions.test ├── test_package.test ├── test_packages ├── poor_people │ └── package.xml ├── rich_people │ └── package.xml ├── rick_astley │ └── package.xml └── world │ └── package.xml ├── test_ros_life_cycle.test └── test_spinning.test /.clang-format: -------------------------------------------------------------------------------- 1 | BasedOnStyle: LLVM 2 | AllowShortBlocksOnASingleLine: Always 3 | AllowShortLoopsOnASingleLine: true 4 | AlwaysBreakTemplateDeclarations: Yes 5 | BreakBeforeBraces: Linux 6 | ColumnLimit: 100 7 | PenaltyBreakComment: 1000 8 | PenaltyExcessCharacter: 10 9 | SpaceAfterTemplateKeyword: false 10 | SpaceInEmptyBlock: true 11 | SpacesInConditionalStatement: true 12 | SpacesInParentheses: true 13 | UseTab: Never 14 | -------------------------------------------------------------------------------- /.codecov.yml: -------------------------------------------------------------------------------- 1 | codecov: 2 | require_ci_to_pass: yes 3 | 4 | coverage: 5 | precision: 2 6 | round: down 7 | 8 | ignore: 9 | - "devel" 10 | - "docs" 11 | - "examples" 12 | - "test" 13 | - "**/qml_ros_plugin.cpp" 14 | -------------------------------------------------------------------------------- /.github/ISSUE_TEMPLATE/bug_report.md: -------------------------------------------------------------------------------- 1 | --- 2 | name: Bug report 3 | about: Create a report to help us improve 4 | title: '' 5 | labels: bug 6 | assignees: '' 7 | 8 | --- 9 | 10 | **Describe the bug** 11 | A clear and concise description of what the bug is. 12 | 13 | **To Reproduce** 14 | Steps to reproduce the behavior: 15 | 1. Go to '...' 16 | 2. Click on '....' 17 | 3. Scroll down to '....' 18 | 4. See error 19 | 20 | **Expected behavior** 21 | A clear and concise description of what you expected to happen. 22 | 23 | **Screenshots** 24 | If applicable, add screenshots to help explain your problem. 25 | 26 | **Desktop (please complete the following information):** 27 | - OS: [e.g. Ubuntu 18.04] 28 | - ROS Version [e.g. Melodic] 29 | 30 | **Additional context** 31 | Add any other context about the problem here. 32 | 33 | **Note** 34 | ``` 35 | Please style error logs or code like this 36 | ``` 37 | -------------------------------------------------------------------------------- /.github/ISSUE_TEMPLATE/feature_request.md: -------------------------------------------------------------------------------- 1 | --- 2 | name: Feature request 3 | about: Suggest an idea for this project 4 | title: '' 5 | labels: enhancement 6 | assignees: '' 7 | 8 | --- 9 | 10 | **Is your feature request related to a problem? Please describe.** 11 | A clear and concise description of what the problem is. Ex. I'm always frustrated when [...] 12 | 13 | **Describe the solution you'd like** 14 | A clear and concise description of what you want to happen. 15 | 16 | **Describe alternatives you've considered** 17 | A clear and concise description of any alternative solutions or features you've considered. 18 | 19 | **Additional context** 20 | Add any other context or screenshots about the feature request here. 21 | -------------------------------------------------------------------------------- /.gitignore: -------------------------------------------------------------------------------- 1 | .vscode/ 2 | .idea/ 3 | cmake-build-*/ 4 | build/ 5 | 6 | *.qmlc 7 | -------------------------------------------------------------------------------- /.travis.yml: -------------------------------------------------------------------------------- 1 | ################################################################################ 2 | 3 | cache: 4 | - apt 5 | 6 | # Build all valid Ubuntu/ROS combinations available on Travis VMs. 7 | language: cpp 8 | os: linux 9 | matrix: 10 | include: 11 | - name: "Bionic melodic AMD64" 12 | arch: amd64 13 | dist: bionic 14 | env: 15 | - ROS_DISTRO=melodic 16 | - ROS_PYTHON_PKGS="python-catkin-pkg python-catkin-tools python-rosdep python-wstool" 17 | - name: "Focal noetic AMD64" 18 | arch: amd64 19 | dist: focal 20 | env: 21 | - ROS_DISTRO=noetic 22 | - ROS_PYTHON_PKGS="python3-catkin-pkg python3-catkin-tools python3-osrf-pycommon python3-rosdep python3-wstool" 23 | 24 | # Configuration variables. All variables are global now, but this can be used to 25 | # trigger a build matrix for different ROS distributions if desired. 26 | env: 27 | global: 28 | - CI_BUILD_PROJECT_NAME=qml_ros_plugin 29 | - ROS_CI_DESKTOP="`lsb_release -cs`" # e.g. [trusty|xenial|...] 30 | - CI_SOURCE_PATH=$(pwd) 31 | - ROS_PARALLEL_JOBS='-j8 -l6' 32 | # Set the python path manually to include /usr/-/python2.7/dist-packages 33 | # as this is where apt-get installs python packages. 34 | - PYTHONPATH=$PYTHONPATH:/usr/lib/python2.7/dist-packages:/usr/local/lib/python2.7/dist-packages 35 | 36 | ################################################################################ 37 | 38 | # Install system dependencies, namely a very barebones ROS setup. 39 | before_install: 40 | - sudo sh -c "echo \"deb http://packages.ros.org/ros/ubuntu $ROS_CI_DESKTOP main\" > /etc/apt/sources.list.d/ros-latest.list" 41 | - sudo apt-key adv --keyserver 'hkp://keyserver.ubuntu.com:80' --recv-key C1CF6E31E6BADE8868B172B4F42ED6FBAB17C654 42 | - sudo apt-get update -qq 43 | - sudo apt-get install dpkg 44 | - sudo apt-get install -y $ROS_PYTHON_PKGS ros-$ROS_DISTRO-ros-base ros-$ROS_DISTRO-code-coverage 45 | - source /opt/ros/$ROS_DISTRO/setup.bash 46 | # Prepare rosdep to install dependencies. 47 | - sudo rosdep init 48 | - rosdep update 49 | 50 | # Create a catkin workspace with the package under integration. 51 | install: 52 | - mkdir -p ~/catkin_ws/src 53 | - cd ~/catkin_ws/src 54 | - catkin init 55 | # Create the devel/setup.bash (run catkin_make with an empty workspace) and 56 | # source it to set the path variables. 57 | - cd ~/catkin_ws 58 | - catkin build 59 | - source devel/setup.bash 60 | # Add the package under integration to the workspace using a symlink. 61 | - cd ~/catkin_ws/src 62 | - ln -s $CI_SOURCE_PATH . 63 | 64 | # Install all dependencies 65 | before_script: 66 | # package depdencies: install using rosdep. 67 | - cd ~/catkin_ws 68 | - rosdep install -y --from-paths src --ignore-src --rosdistro $ROS_DISTRO 69 | 70 | # Compile and test (mark the build as failed if any step fails). 71 | # 72 | # NOTE on testing: `catkin_make run_tests` will show the output of the tests 73 | # (gtest, nosetest, etc..) but always returns 0 (success) even if a test 74 | # fails. Running `catkin_test_results` aggregates all the results and returns 75 | # non-zero when a test fails (which notifies Travis the build failed). 76 | script: 77 | - source /opt/ros/$ROS_DISTRO/setup.bash 78 | - cd ~/catkin_ws 79 | - catkin build 80 | # Run the tests, ensuring the path is set correctly. 81 | - source devel/setup.bash 82 | - catkin run_tests $CI_BUILD_PROJECT_NAME && catkin_test_results 83 | # Generate coverage 84 | - catkin clean -y 85 | - catkin build $CI_BUILD_PROJECT_NAME -DENABLE_COVERAGE_TESTING=ON -DCMAKE_BUILD_TYPE=Debug 86 | - catkin build $CI_BUILD_PROJECT_NAME --no-deps -DENABLE_COVERAGE_TESTING=ON -DCMAKE_BUILD_TYPE=Debug -v --catkin-make-args ${CI_BUILD_PROJECT_NAME}_coverage 87 | - bash <(curl -s https://codecov.io/bash) -f ./build/$CI_BUILD_PROJECT_NAME/${CI_BUILD_PROJECT_NAME}_coverage.info -R ./src/$CI_BUILD_PROJECT_NAME 88 | -------------------------------------------------------------------------------- /LICENSE: -------------------------------------------------------------------------------- 1 | MIT License 2 | 3 | Copyright (c) 2019 Stefan Fabian 4 | 5 | Permission is hereby granted, free of charge, to any person obtaining a copy 6 | of this software and associated documentation files (the "Software"), to deal 7 | in the Software without restriction, including without limitation the rights 8 | to use, copy, modify, merge, publish, distribute, sublicense, and/or sell 9 | copies of the Software, and to permit persons to whom the Software is 10 | furnished to do so, subject to the following conditions: 11 | 12 | The above copyright notice and this permission notice shall be included in all 13 | copies or substantial portions of the Software. 14 | 15 | THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR 16 | IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, 17 | FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE 18 | AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER 19 | LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, 20 | OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE 21 | SOFTWARE. 22 | -------------------------------------------------------------------------------- /docs/.gitignore: -------------------------------------------------------------------------------- 1 | _build/ 2 | html/ 3 | latex/ 4 | xml/ 5 | -------------------------------------------------------------------------------- /docs/Doxyfile: -------------------------------------------------------------------------------- 1 | PROJECT_NAME="QML ROS Plugin" 2 | # List the source input folders from which the documentation is generated here 3 | INPUT=../include 4 | RECURSIVE=YES 5 | GENERATE_HTML=YES 6 | GENERATE_XML=YES 7 | XML_OUTPUT=xml 8 | XML_PROGRAMLISTING=NO 9 | CASE_SENSE_NAMES=NO 10 | HIDE_UNDOC_RELATIONS=YES 11 | # Removes warning if a method is not documented 12 | WARN_IF_UNDOCUMENTED=NO 13 | # Removes warning and Q_INVOKABLE flag for Q_INVOKABLE marked methods 14 | MACRO_EXPANSION=YES 15 | EXPAND_ONLY_PREDEF=YES 16 | PREDEFINED= Q_INVOKABLE= \ 17 | Q_PROPERTY(x)= \ 18 | Q_GADGET= 19 | HIDE_SCOPE_NAMES=YES 20 | 21 | -------------------------------------------------------------------------------- /docs/Makefile: -------------------------------------------------------------------------------- 1 | # Minimal makefile for Sphinx documentation 2 | # 3 | 4 | # You can set these variables from the command line, and also 5 | # from the environment for the first two. 6 | SPHINXOPTS ?= 7 | SPHINXBUILD ?= python3 -msphinx # sphinx-build 8 | SOURCEDIR = . 9 | BUILDDIR = _build 10 | 11 | # Put it first so that "make" without argument is like "make help". 12 | help: 13 | @$(SPHINXBUILD) -M help "$(SOURCEDIR)" "$(BUILDDIR)" $(SPHINXOPTS) $(O) 14 | 15 | .PHONY: help Makefile 16 | 17 | # Catch-all target: route all unknown targets to Sphinx using the new 18 | # "make mode" option. $(O) is meant as a shortcut for $(SPHINXOPTS). 19 | %: Makefile 20 | doxygen 21 | @$(SPHINXBUILD) -M $@ "$(SOURCEDIR)" "$(BUILDDIR)" $(SPHINXOPTS) $(O) 22 | -------------------------------------------------------------------------------- /docs/conf.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | # Configuration file for the Sphinx documentation builder. 3 | # 4 | # This file only contains a selection of the most common options. For a full 5 | # list see the documentation: 6 | # https://www.sphinx-doc.org/en/master/usage/configuration.html 7 | 8 | # -- Path setup -------------------------------------------------------------- 9 | 10 | # If extensions (or modules to document with autodoc) are in another directory, 11 | # add these directories to sys.path here. If the directory is relative to the 12 | # documentation root, use os.path.abspath to make it absolute, like shown here. 13 | # 14 | import os 15 | # import sys 16 | # sys.path.insert(0, os.path.abspath('.')) 17 | 18 | on_rtd = os.environ.get('READTHEDOCS', None) == 'True' 19 | 20 | if not on_rtd: 21 | import sphinx_rtd_theme 22 | html_theme = 'sphinx_rtd_theme' 23 | html_theme_path = [sphinx_rtd_theme.get_html_theme_path()] 24 | else: 25 | from subprocess import call 26 | call('doxygen') 27 | 28 | # -- Project information ----------------------------------------------------- 29 | 30 | project = 'QML ROS Plugin' 31 | copyright = '2019-2021, Stefan Fabian' 32 | author = 'Stefan Fabian' 33 | 34 | 35 | # -- General configuration --------------------------------------------------- 36 | 37 | # Add any Sphinx extension module names here, as strings. They can be 38 | # extensions coming with Sphinx (named 'sphinx.ext.*') or your custom 39 | # ones. 40 | extensions = [ 41 | "breathe", 42 | "sphinx.ext.autosectionlabel", 43 | "sphinx.ext.todo" 44 | ] 45 | 46 | todo_include_todos = True 47 | 48 | # Breathe Configuration 49 | breathe_projects = {"project": os.path.abspath("xml")} 50 | breathe_default_project = "project" 51 | 52 | # If true, current module path is prepended to all description unit titles 53 | # such as functions 54 | add_module_names = False 55 | 56 | # Add any paths that contain templates here, relative to this directory. 57 | templates_path = ['_templates'] 58 | 59 | # List of patterns, relative to source directory, that match files and 60 | # directories to ignore when looking for source files. 61 | # This pattern also affects html_static_path and html_extra_path. 62 | exclude_patterns = [] 63 | 64 | 65 | # -- Options for HTML output ------------------------------------------------- 66 | 67 | # Add any paths that contain custom static files (such as style sheets) here, 68 | # relative to this directory. They are copied after the builtin static files, 69 | # so a file named "default.css" will overwrite the builtin "default.css". 70 | html_static_path = [] 71 | 72 | # Tell sphinx what the primary language being documented is. 73 | primary_domain = 'cpp' 74 | 75 | # Tell sphinx what the pygments highlight language should be. 76 | highlight_language = 'cpp' 77 | -------------------------------------------------------------------------------- /docs/index.rst: -------------------------------------------------------------------------------- 1 | .. QML ROS Plugin documentation master file, created by 2 | sphinx-quickstart on Mon Oct 7 22:07:25 2019. 3 | You can adapt this file completely to your liking, but it should at least 4 | contain the root `toctree` directive. 5 | 6 | Welcome to QML ROS Plugin's documentation! 7 | ========================================== 8 | 9 | .. toctree:: 10 | :maxdepth: 3 11 | :caption: Table of Contents 12 | :glob: 13 | :hidden: 14 | 15 | pages/* 16 | 17 | For instructions on how to setup the QML ROS plugin and a quick getting 18 | started guide, check the :doc:`pages/Quickstart`. 19 | 20 | More in-depth examples can be found in the examles folder as described in 21 | :doc:`pages/Examples`. 22 | -------------------------------------------------------------------------------- /docs/pages/ActionClient.rst: -------------------------------------------------------------------------------- 1 | ============ 2 | ActionClient 3 | ============ 4 | 5 | An action client can be used to send goals to an ActionServer. 6 | One ActionClient has to have a single type of action but can send multiple goals simultaneously. 7 | Process can be tracked using either a goal handle manually or using callbacks. 8 | 9 | An ActionClient can be created using the :ref:`Ros Singleton` as follows: 10 | 11 | .. code-block:: qml 12 | 13 | Item { 14 | // ... 15 | property var fibonacciClient: Ros.createActionClient("actionlib_tutorials/FibonacciAction", "fibonacci") 16 | // ... 17 | } 18 | 19 | In this example an action client is created using the ``actionlib_tutorials/FibonacciAction`` action 20 | (it is important to use the complete action type here, not any part like the ActionGoal) using the name 21 | fibonacci on which an ActionServer should be registered (You can use the actionlib_tutorials fibonacci_server). 22 | 23 | To send a goal, you can use the sendGoal function: 24 | 25 | .. code-block:: qml 26 | 27 | goal_handle = fibonacciClient.sendGoal({ order: numberInput.value }, function (goal_handle) { 28 | // Do something when the goal transitions, e.g., update the status 29 | if (goal_handle.commState == ActionCommStates.DONE) { 30 | // Goal is terminated, we can access the terminalState 31 | switch (handle.terminalState.state) { 32 | case ActionTerminalStates.RECALLED: 33 | // Handle recalled 34 | break 35 | case ActionTerminalStates.REJECTED: 36 | // Handle rejected 37 | break 38 | case ActionTerminalStates.PREEMPTED: 39 | // Handle preempted 40 | break 41 | case ActionTerminalStates.ABORTED: 42 | // Handle aborted 43 | break 44 | case ActionTerminalStates.SUCCEEDED: 45 | // Handle succeeded 46 | break 47 | case ActionTerminalStates.LOST: 48 | // Handle lost 49 | break 50 | } 51 | } 52 | }, function (goal_handle, feedback) { 53 | // Feedback callback. Called whenever feedback is received from the action server 54 | }) 55 | 56 | The ``sendGoal`` function takes 3 parameters: the goal, a transition callback and a feedback callback. 57 | Both callbacks are optional. It returns a GoalHandle which can be used query to state of the goal or 58 | to cancel the goal. The goal_handle passed to the callbacks and the one returned are the same. 59 | 60 | API 61 | --- 62 | 63 | .. doxygenclass:: qml_ros_plugin::ActionClient 64 | :members: 65 | 66 | .. doxygenclass:: qml_ros_plugin::GoalHandle 67 | :members: 68 | 69 | .. doxygenclass:: qml_ros_plugin::TerminalState 70 | :members: 71 | -------------------------------------------------------------------------------- /docs/pages/Arrays.rst: -------------------------------------------------------------------------------- 1 | ====== 2 | Arrays 3 | ====== 4 | Due to the lazy copy mechanism, arrays differ from the standard access above. 5 | Because the array is not copied into a QML compatible array container, 6 | access happens with methods. 7 | 8 | **Example**: Instead of ``path.to.array[1].someproperty``, you would write 9 | ``path.to.array.at(1).someproperty``. 10 | 11 | If you need the array as a javascript array, you can use :cpp:func:`toArray ` to copy 12 | the entire array and return it as a javascript array. 13 | The copy is only performed on the first call, subsequent calls should have 14 | less overhead. 15 | 16 | API 17 | --- 18 | .. doxygenclass:: qml_ros_plugin::Array 19 | :members: 20 | -------------------------------------------------------------------------------- /docs/pages/Examples.rst: -------------------------------------------------------------------------------- 1 | ======== 2 | Examples 3 | ======== 4 | 5 | You can find the described example QML files in the 6 | `qml_ros_plugin repo examples directory `_. 7 | 8 | Subscriber 9 | ========== 10 | 11 | The subscriber example demonstrates how to create a ``Subscriber`` in QML 12 | using the *QML ROS Plugin*. 13 | 14 | You can run the example using the ``qmlscene`` executable: 15 | 16 | .. code-block:: 17 | 18 | qmlscene subscriber.qml 19 | 20 | Publisher 21 | ========= 22 | 23 | The publisher example publishes an ``std_msgs/Int32`` message on the topic that 24 | the subscriber example subscribes to. 25 | Coincidentally, the two examples can very well be used together. 26 | 27 | To run, run: 28 | 29 | .. code-block:: 30 | 31 | qmlscene publisher.qml 32 | 33 | URDF Tutorial UI 34 | ================ 35 | 36 | This example combines several of the functionalities provided by this library 37 | and presents a user interface for the ``urdf_sim_tutorial`` diff drive example. 38 | 39 | First, launch the example: 40 | 41 | .. code-block:: 42 | 43 | roslaunch urdf_sim_tutorial 13-diffdrive.launch 44 | 45 | Next, launch the example UI: 46 | 47 | .. code-block:: 48 | 49 | qmlscene urdf_tutorial_combined.qml 50 | 51 | It provides a top down view on the position of the robot and sliders to control 52 | the forward and angular movement. 53 | 54 | Logging 55 | ======= 56 | 57 | This example demonstrates the logging functionality detailed in :ref:`Logging`. 58 | The "Output logging level" sets the minimum logging level that is printed whereas the 59 | "Message logging level" sets the level of the message that is logged when you click 60 | the `Log` button. 61 | 62 | To run, run: 63 | 64 | .. code-block:: 65 | 66 | qmlscene logging.qml 67 | -------------------------------------------------------------------------------- /docs/pages/ImageTransport.rst: -------------------------------------------------------------------------------- 1 | ============== 2 | ImageTransport 3 | ============== 4 | 5 | Seeing what the robot sees is one of the most important features of any user interface. 6 | To enable this, this library provides the :cpp:class:`ImageTransportSubscriber `. 7 | It allows easy subscription of camera messages and provides them in a QML native format as a VideoSource. 8 | 9 | Example: 10 | 11 | .. code-block:: qml 12 | 13 | ImageTransportSubscriber { 14 | id: imageSubscriber 15 | // Enter a valid image topic here 16 | topic: "/front_rgbd_cam/color/image_rect_color" 17 | // This is the default transport, change if compressed is not available 18 | defaultTransport: "compressed" 19 | } 20 | 21 | VideoOutput { 22 | anchors.fill: parent 23 | // Can be used in increments of 90 to rotate the video 24 | orientation: 90 25 | source: imageSubscriber 26 | } 27 | 28 | The :cpp:class:`ImageTransportSubscriber ` can be used as the source of a 29 | ``VideoOutput`` to display the camera images as they are received. 30 | Additionally, it can be configured to show a blank image after x milliseconds using the ``timeout`` property which is set 31 | to 3000ms (3s) by default. This can be disabled by setting the ``timeout`` to 0. 32 | If you do not want the full camera rate, you can throttle the rate by setting ``throttleRate`` to a value greater than 0 33 | (which is the default and disables throttling). E.g. a rate of 0.2 would show a new frame every 5 seconds. 34 | Since there is no ROS functionality for a throttled subscription, this means the ``image_transport::Subscriber`` is shut 35 | down and newly subscribed for each frame. This comes at some overhead, hence, it should only be used to throttle to low 36 | rates <1. 37 | To avoid all throttled subscribers subscribing at the same time causing huge network spikes, the throttled rates are 38 | load balanced by default. This can be disabled globally using 39 | :cpp:func:`ImageTransportManager::setLoadBalancingEnabled ` 40 | which is available in QML using the singleton ``ImageTransportManager``. 41 | 42 | API 43 | --- 44 | 45 | .. doxygenclass:: qml_ros_plugin::ImageTransportSubscriber 46 | :members: 47 | 48 | .. doxygenclass:: qml_ros_plugin::ImageTransportManagerSingletonWrapper 49 | :members: 50 | -------------------------------------------------------------------------------- /docs/pages/Logging.rst: -------------------------------------------------------------------------------- 1 | ======= 2 | Logging 3 | ======= 4 | 5 | Logging is done using the :ref:`Ros Singleton`. 6 | 7 | Output 8 | ------ 9 | 10 | To log a message you can use one of the following methods ``debug``, ``info``, ``warn``, ``error`` and ``fatal``. 11 | 12 | .. code-block:: qml 13 | 14 | Button { 15 | // ... 16 | onClicked: Ros.info("Button clicked.") 17 | } 18 | 19 | This will produce the following output: 20 | 21 | :: code-block:: bash 22 | 23 | [ INFO] [1583062360.048922959]: Button clicked. 24 | 25 | and publish the following on ``/rosout`` (unless ``NoRosout`` was specified in the ``RosInitOptions``). 26 | 27 | :: code-block:: bash 28 | 29 | header: 30 | seq: 1 31 | stamp: 32 | secs: 1583062360 33 | nsecs: 49001300 34 | frame_id: '' 35 | level: 2 36 | name: "/qml_logging_demo" 37 | msg: "Button clicked." 38 | file: "/home/stefan/qml_ros_plugin/examples/logging.qml" 39 | function: "onClicked" 40 | line: 130 41 | topics: [/rosout] 42 | 43 | The ``file``, ``function`` and ``line`` info is automatically extracted when you call the log function. 44 | 45 | Set Verbosity 46 | ------------- 47 | 48 | You can change the verbosity, i.e., the minimal level of logging message that is printed 49 | (and published if enabled), using ``Ros.console.setLoggerLevel``. 50 | By default the logging level is set to `Info`. 51 | To enable debug messages you can set it to `Debug` as follows: 52 | 53 | .. code-block:: qml 54 | 55 | Ros.console.setLoggerLevel(Ros.console.defaultName, RosConsoleLevels.Debug); 56 | 57 | The first argument to that method is the name of the console to which the logging is printed. 58 | These are identifiers used by ros to enable you to change the verbosity of a submodule of your node using 59 | ``rqt_console``. 60 | 61 | | You can optionally change to which console you're writing by passing a second 62 | argument to the logging function, e.g., ``debug("Some message", "ros.my_pkg.my_submodule")``. 63 | | This name should contain only letters, numbers, dots and underscores. 64 | | **Important:** The name has to start with "``ros.``". 65 | 66 | By default the value of ``Ros.console.defaultName`` is used which evaluates to ``ros.qml_ros_plugin``. 67 | 68 | Possible values for the console level are: ``Debug``, ``Info``, ``Warn``, ``Error`` and ``Fatal``. 69 | -------------------------------------------------------------------------------- /docs/pages/Publishers.rst: -------------------------------------------------------------------------------- 1 | ========== 2 | Publishers 3 | ========== 4 | 5 | A Publisher is used to publish messages on a given topic for delivery 6 | to subscribers. 7 | 8 | Simple Example 9 | -------------- 10 | Contrary to Subscribers, a Publisher can not be instantiated but can be 11 | created using a factory method of the Ros singleton. 12 | 13 | .. code-block:: qml 14 | :linenos: 15 | 16 | /* ... */ 17 | ApplicationWindow { 18 | property var intPublisher: Ros.advertise("std_msgs/Int32", "/intval", 10, false) 19 | /* ... */ 20 | } 21 | 22 | In order, the arguments are the ``type``, the ``topic``, the ``queueSize`` and whether 23 | or not the topic ``isLatched``. 24 | 25 | To publish a message using our Publisher, we can simply use the 26 | ``intPublisher`` variable. 27 | 28 | .. code-block:: qml 29 | :linenos: 30 | 31 | SpinBox { 32 | id: numberInput 33 | } 34 | 35 | Button { 36 | onClicked: { 37 | intPublisher.publish({ data: numberInput.value }) 38 | } 39 | } 40 | 41 | where we pass an object with a data field containing the (integer) number of the ``SpinBox``. 42 | This is according to the ``std_msgs/Int32`` `message definition `_. 43 | 44 | API 45 | --- 46 | 47 | Publisher 48 | ========= 49 | .. doxygenclass:: qml_ros_plugin::Publisher 50 | :members: 51 | -------------------------------------------------------------------------------- /docs/pages/Quickstart.rst: -------------------------------------------------------------------------------- 1 | ========== 2 | Quickstart 3 | ========== 4 | 5 | This library provides convenient access of ROS concepts and functionalities 6 | in QML. 7 | 8 | Installation 9 | ============ 10 | 11 | From Source 12 | ----------- 13 | 14 | To install ``qml_ros_plugin`` from source, clone the 15 | `repo `_. 16 | Next, open a terminal and ``cd`` into the repo folder. 17 | To install create a build folder, ``cd`` into that folder and run 18 | ``cmake ..`` followed by ``sudo make install``. 19 | 20 | :: 21 | 22 | mkdir build && cd build 23 | cmake .. 24 | sudo make install 25 | 26 | Usage 27 | ===== 28 | 29 | To use the plugin import ``Ros`` in QML. 30 | 31 | .. code-block:: qml 32 | 33 | import Ros 1.0 34 | 35 | Now, you can use the provided components such as ``Subscriber`` and 36 | ``TfTransform`` and the Ros singleton to create a ``Publisher`` or the 37 | ``Service`` singleton to call a service. 38 | 39 | As a simple example, a ``Subscriber`` can be created as follows: 40 | 41 | .. code-block:: qml 42 | :linenos: 43 | 44 | Subscriber { 45 | id: mySubscriber 46 | topic: "/intval" 47 | } 48 | 49 | For more in-depth examples, check out the :ref:`Examples` section. 50 | 51 | Initialization 52 | -------------- 53 | Before a ``Subscriber`` can receive messages, a ``Publisher`` can publish 54 | messages, etc. the node has to be initialized. 55 | If your application calls ``ros::init`` on startup, you don't have to do 56 | anything. However, in cases where you can't call ``ros::init`` from the C++ 57 | entry function, you can use the ``init`` function of the ``Ros`` singleton: 58 | 59 | .. code-block:: qml 60 | :linenos: 61 | 62 | ApplicationWindow { 63 | /* ... */ 64 | Component.onCompleted: { 65 | Ros.init("node_name"); 66 | } 67 | } 68 | 69 | Shutdown 70 | -------- 71 | To make your application quit when ROS shuts down, e.g., because of a 72 | ``Ctrl+C`` in the console or a ``rosnode kill`` request, you can connect 73 | to the ``Shutdown`` signal: 74 | 75 | .. code-block:: qml 76 | :linenos: 77 | 78 | ApplicationWindow { 79 | Connections { 80 | target: Ros 81 | onShutdown: Qt.quit() 82 | } 83 | /* ... */ 84 | } 85 | 86 | For more on that, check out the :ref:`Ros Singleton`. 87 | -------------------------------------------------------------------------------- /docs/pages/Ros-Singleton.rst: -------------------------------------------------------------------------------- 1 | ============= 2 | Ros Singleton 3 | ============= 4 | 5 | The ``Ros`` singleton provides interfaces to static methods and convenience 6 | methods. 7 | 8 | In QML it is available as ``Ros``, e.g.: 9 | 10 | .. code-block:: qml 11 | 12 | if (Ros.ok()) console.log("Ros is ok!") 13 | 14 | ROS Initialization 15 | ------------------ 16 | 17 | If you can not or for whatever reason do not want to initialize ROS in your 18 | C++ entry, you can also do it in QML, e.g., in the ``onCompleted`` handler: 19 | 20 | .. code-block:: qml 21 | 22 | Component.onCompleted: { 23 | Ros.init("node_name") 24 | } 25 | 26 | You can also conditionally initialize by checking if it was already initialized using ``Ros.isInitialized``. 27 | As described in the API documentation for :cpp:func:`Ros.init `, you can pass either just the 28 | node name or additionally use provided command line args instead of the command 29 | line args provided to your executable. In both cases, you can also pass the 30 | following ``RosInitOptions`` options: 31 | 32 | * | ``NoSigintHandler``: 33 | | Don't install a SIGINT (e.g., ``Ctrl+C`` on terminal) handler. 34 | * | ``AnonymousName``: 35 | | Anonymize the node name. Adds a random number to the node's name to make it unique. 36 | * | ``NoRosout``: 37 | | Don't broadcast rosconsole output to the /rosout topic. See :doc:`Logging` 38 | 39 | .. code-block:: qml 40 | 41 | Component.onCompleted: { 42 | Ros.init("node_name", RosInitOptions.AnonymousName | RosInitOptions.NoRosout) 43 | } 44 | 45 | Wait For Message 46 | ---------------- 47 | 48 | If you only require a single message from a topic, you can use the ``Ros.waitForMessageAsync`` method which asynchronously 49 | waits for a message on the given topic with an optional maximum duration to wait and once a message is received or the 50 | maximum wait duration elapsed, the callback method is called with the received message or null if the waiting timeouted. 51 | 52 | .. code-block:: qml 53 | 54 | Ros.waitForMessageAsync("/some_topic", 10000 /* wait for maximum 10 seconds */, function (msg) { 55 | if (!msg) { 56 | // Handle timeout 57 | return 58 | } 59 | // Handle message 60 | } 61 | 62 | Query Topics 63 | ------------ 64 | 65 | You can also use the Ros singleton to query the available topics. 66 | Currently, three methods are provided: 67 | 68 | * | ``QStringList queryTopics( const QString &datatype = QString())`` 69 | | Queries a list of topics with the given datatype or all topics if no type provided. 70 | * | ``QList queryTopicInfo()`` 71 | | Retrieves a list of all advertised topics including their datatype. See :cpp:class:`TopicInfo` 72 | * | ``QString queryTopicType( const QString &name )`` 73 | | Reterieves the datatype for a given topic. 74 | 75 | Example: 76 | 77 | .. code-block:: qml 78 | 79 | // Retrieves a list of topics with the type sensor_msgs/Image 80 | var topics = Ros.queryTopics("sensor_msgs/Image") 81 | // Another slower and less clean method of this would be 82 | var cameraTopics = [] 83 | var topics = Ros.queryTopicInfo() 84 | for (var i = 0; i < topics.length; ++i) { 85 | if (topics[i].datatype == "sensor_msgs/Image") cameraTopics.push(topics[i].name) 86 | } 87 | // The type of a specific topic can be retrieved as follows 88 | var datatype = Ros.queryTopicType("/topic/that/i/care/about") 89 | // Using this we can make an even worse implementation of the same functionality 90 | var cameraTopics = [] 91 | var topics = Ros.queryTopics() // Gets all topics 92 | for (var i = 0; i < topics.length; ++i) { 93 | if (Ros.queryTopicType(topics[i]) == "sensor_msgs/Image") cameraTopics.push(topics[i]) 94 | } 95 | 96 | Create Empty Message 97 | -------------------- 98 | You can also create empty messages and service requests as javascript objects using the ``Ros`` singleton. 99 | 100 | .. code-block:: qml 101 | 102 | var message = Ros.createEmptyMessage("geometry_msgs/Point") 103 | // This creates an empty instance of the mssage, we can override the fields 104 | message.x = 1; message.y = 2; message.z = 1 105 | // However, note that we do not call custom message constructors, hence, if the message has different default values 106 | // they will not be set here. This is a rarely known feature and not used often in ROS 1, though. 107 | 108 | // Same can be done with service requests 109 | var serviceRequest = Ros.createEmptyServiceRequest("std_srvs/SetBool") 110 | // This creates an empty instance of the service request with all members set to their default, we can override the fields 111 | serviceRequest.data = true 112 | 113 | Package API 114 | ----------- 115 | The package property provides a wrapper for ``ros::package``. 116 | 117 | .. code-block:: qml 118 | 119 | // Retrieve a list of all packages 120 | var packages = Ros.package.getAll() 121 | // Get the fully-qualified path to a specific package 122 | var path = Ros.package.getPath("some_pkg") 123 | // Get plugins for a package as a map [package_name -> [values]] 124 | var plugins = Ros.package.getPlugins("rviz", "plugin") 125 | 126 | Console 127 | ------- 128 | The Ros singleton also provides access to the ``Ros`` logging functionality. 129 | See `Logging`:ref:. 130 | 131 | IO 132 | -- 133 | You can also save and read data that can be serialized in the yaml format using: 134 | 135 | .. code-block:: qml 136 | 137 | var obj = {"key": [1, 2, 3], "other": "value"} 138 | if (!Ros.io.writeYaml("/home/user/file.yaml", obj)) 139 | Ros.error("Could not write file!") 140 | // and read it back 141 | obj = Ros.io.readYaml("/home/user/file.yaml") 142 | if (!obj) Ros.error("Failed to load file!") 143 | 144 | API 145 | --- 146 | .. doxygenclass:: qml_ros_plugin::Package 147 | :members: 148 | 149 | .. doxygenclass:: qml_ros_plugin::TopicInfo 150 | :members: 151 | 152 | .. doxygenclass:: qml_ros_plugin::IO 153 | :members: 154 | 155 | .. doxygenclass:: qml_ros_plugin::RosQmlSingletonWrapper 156 | :members: 157 | -------------------------------------------------------------------------------- /docs/pages/Services.rst: -------------------------------------------------------------------------------- 1 | ======== 2 | Services 3 | ======== 4 | 5 | Currently, there is no service client or service server implementation (It's on 6 | my todo-list, though). 7 | However, there is a ``Service`` singleton that can be used to call 8 | a service. 9 | 10 | Here's a short modified example of the service example provided in the 11 | :doc:`Examples`. 12 | 13 | .. code-block:: qml 14 | 15 | Button { 16 | onClicked: { 17 | var result = Service.call("/add_two_ints", "roscpp_tutorials/TwoInts", 18 | { a: inputA.value, b: inputB.value }) 19 | textResult.text = !!result ? ("Result: " + result.sum) : "Failed" 20 | } 21 | } 22 | 23 | The first argument is the ``service`` that is called, the second is the ``type`` 24 | of the service, and the final argument is the ``request`` that is sent. 25 | 26 | The service either returns ``false`` if the call failed, ``true`` if the call 27 | was successful but the service description has an empty return message, and the 28 | return message of the service otherwise. 29 | 30 | A service call is blocking and it is usually not a good idea to make blocking work 31 | on the UI thread. For that reason, there is also the ``callAsync`` method which 32 | runs the service call on a new separate thread and is additionally passed an 33 | optional callback which is called after the service call completed. 34 | 35 | .. code-block:: qml 36 | 37 | Button { 38 | onClicked: { 39 | textResult.text = "Loading..." 40 | Service.callAsync( 41 | "/add_two_ints", "roscpp_tutorials/TwoInts", 42 | { a: inputA.value, b: inputB.value }, 43 | function (result) { 44 | textResult.text = !!result ? ("Result: " + result.sum) : "Failed" 45 | }) 46 | } 47 | } 48 | 49 | API 50 | --- 51 | 52 | .. doxygenclass:: qml_ros_plugin::Service 53 | :members: -------------------------------------------------------------------------------- /docs/pages/Subscribers.rst: -------------------------------------------------------------------------------- 1 | =========== 2 | Subscribers 3 | =========== 4 | 5 | A subscriber listens for messages on a given topic. 6 | If you only require a single message, you can check out ``Ros.waitForMessageAsync`` in the ``Ros`` singleton. 7 | 8 | Simple example 9 | -------------- 10 | First, let's start with a simple example: 11 | 12 | .. code-block:: qml 13 | :linenos: 14 | 15 | Subscriber { 16 | id: mySubscriber 17 | topic: "/intval" 18 | } 19 | 20 | This creates a subscriber object that is now available and subscribed 21 | to ``/intval``. 22 | Let's assume the topic publishes an ``std_msgs/Int32`` message. 23 | 24 | The ``std_msgs/Int32`` message is defined as follows: 25 | 26 | .. code-block:: 27 | 28 | int32 data 29 | 30 | We can display the published value using a text field: 31 | 32 | .. code-block:: qml 33 | :linenos: 34 | 35 | Text { 36 | text: "Published value was: " + mySubscriber.message.data 37 | } 38 | 39 | Whenever a new message is received on ``/intval`` the message property 40 | is updated and the change is propagated to the text field. Thus, the text 41 | field will always display the last received value. 42 | 43 | Full example 44 | ------------ 45 | In most cases, the above Subscriber is sufficient. However, the Subscriber 46 | has more properties to give you more fine-grained control. 47 | 48 | .. code-block:: qml 49 | :linenos: 50 | 51 | Subscriber { 52 | id: mySubscriber 53 | ns: "~" // Namespace 54 | topic: "/intval" 55 | throttleRate: 30 // Update rate of message property in Hz 56 | queueSize: 10 57 | running: true 58 | onNewMessage: doStuff(message) 59 | } 60 | 61 | The namespace ``ns`` property enables you to set the namespace of 62 | the ``ros::NodeHandle`` that is created to subscribe to the given topic. 63 | 64 | The ``queueSize`` property controls how many incoming messages are queued for 65 | processing before the oldest are dropped. 66 | 67 | The ``throttleRate`` limits the rate in which QML receives updates from the given topic. 68 | By default the Subscriber polls with 20 Hz on the UI thread and will notify of property changes with at most this rate. 69 | This is to reduce load and prevent race conditions that could otherwise update the message while QML is using it since 70 | the subscriber is receiving messages in a background thread by default. 71 | 72 | Using the ``running`` property, the subscriber can be enabled and disabled. 73 | If the property is set to ``false``, the subscriber is shut down until it is 74 | set to ``true`` again and subscribes to the topic again. 75 | For example, the state of a Subscriber can be toggled using a button: 76 | 77 | .. code-block:: qml 78 | :linenos: 79 | 80 | Button { 81 | id: myButton 82 | state: "active" 83 | onClicked: { 84 | mySubscriber.running = !mySubscriber.running 85 | state = state == "active" ? "paused" : "active" 86 | } 87 | states: [ 88 | State { 89 | name: "active" 90 | PropertyChanges { 91 | target: myButton 92 | text: "Unsubscribe" 93 | } 94 | }, 95 | State { 96 | name: "paused" 97 | PropertyChanges { 98 | target: myButton 99 | text: "Subscribe" 100 | } 101 | } 102 | ] 103 | } 104 | 105 | Whenever a new message is received, the newMessage signal is emitted and the 106 | message is passed and can be accessed as ``message`` which technically refers 107 | to the received message and not the message property of the Subscriber. 108 | Untechnically, they are usually the same, though. 109 | 110 | Finally, there's also the messageType property which holds the type of the last 111 | received message, e.g., ``std_msgs/Int32``. 112 | 113 | API 114 | --- 115 | 116 | .. doxygenclass:: qml_ros_plugin::Subscriber 117 | :members: 118 | -------------------------------------------------------------------------------- /docs/pages/Tf-Transforms.rst: -------------------------------------------------------------------------------- 1 | ============= 2 | Tf Transforms 3 | ============= 4 | 5 | There are two methods for looking up **tf2** transforms. 6 | 7 | Component 8 | --------- 9 | The ``TfTransform`` component can be used to subscribe to transforms between 10 | two frames. 11 | 12 | .. code-block:: qml 13 | 14 | TfTransform { 15 | id: tfTransform 16 | active: true // This is the default, if false no updates will be received 17 | sourceFrame: "base_link" 18 | targetFrame: "odom" 19 | } 20 | 21 | Static 22 | ------ 23 | You can use the ``TfTransformListener`` singleton to look up transforms if you 24 | just need it once. 25 | 26 | .. code-block:: qml 27 | 28 | Button { 29 | text: "Look Up" 30 | onClicked: { 31 | var transformStamped = TfTransformListener.lookUpTransform(inputTargetFrame.text, inputSourceFrame.text) 32 | if (!transformStamped.valid) 33 | { 34 | transformResult.text = "Transform from '" + inputSourceFrame.text + "' to '" + inputTargetFrame.text + "' was not valid!\n" + 35 | "Exception: " + transformStamped.exception + "\nMessage: " + transformStamped.message 36 | return 37 | } 38 | transformResult.text = "Position:\n" + printVector3(transformStamped.transform.translation) + "\nOrientation:\n" + printRotation(transformStamped.transform.rotation) 39 | } 40 | } 41 | 42 | Use the provided ``Time.now()`` static methods to look up at specific time 43 | points. For the latest, you can pass ``new Date(0)``. 44 | Be aware that in ``ros::Duration`` the ``double`` constructor argument 45 | represents seconds whereas here the duration is given in milliseconds. 46 | 47 | 48 | .. Warning:: Be aware that `canLookUp` can return a ``boolean`` value or 49 | a ``string`` error message. You should explicitly test for that since strings 50 | are truthy, too. 51 | 52 | API 53 | --- 54 | 55 | .. doxygenclass:: qml_ros_plugin::TfTransformListener 56 | :members: 57 | 58 | .. doxygenclass:: qml_ros_plugin::TfTransform 59 | :members: 60 | -------------------------------------------------------------------------------- /docs/pages/Time.rst: -------------------------------------------------------------------------------- 1 | ==== 2 | Time 3 | ==== 4 | 5 | To preserve the accuracy and allow for compatible serialization of message objects, custom 6 | :cpp:class:`Time ` and :cpp:class:`WallTime ` anonymous datatypes were 7 | introduced. 8 | This :cpp:class:`Time ` datatype is used for time fields in received messages and can be obtained 9 | using the :cpp:class:`Time ` singleton. 10 | 11 | Example: 12 | 13 | .. code-block:: qml 14 | 15 | property var currentTime: Time.now() 16 | property var currentWallTime: WallTime.now() 17 | 18 | The :cpp:class:`Time ` singleton wraps most static methods of ``ros::Time`` whereas the 19 | instances obtained using either :cpp:func:`Time.now() ` or 20 | :cpp:func:`Time.create() ` contain the instance methods and properties 21 | for ``sec`` and ``nsec``. 22 | 23 | Both wrapper types can be converted to QML/JavaScript ``Date`` objects using the :cpp:func:`toJSDate() ` 24 | function at the cost of micro- and nanosecond accuracy. 25 | 26 | Please note that due to limitations in QML and JavaScript mathematical operations for Time and WallTime are not possible. 27 | 28 | API 29 | --- 30 | .. doxygenclass:: qml_ros_plugin::Time 31 | :members: 32 | 33 | .. doxygenclass:: qml_ros_plugin::WallTime 34 | :members: 35 | 36 | .. doxygenclass:: qml_ros_plugin::TimeSingleton 37 | :members: 38 | 39 | .. doxygenclass:: qml_ros_plugin::WallTimeSingleton 40 | :members: 41 | -------------------------------------------------------------------------------- /docs/requirements.txt: -------------------------------------------------------------------------------- 1 | breathe 2 | -------------------------------------------------------------------------------- /examples/README.md: -------------------------------------------------------------------------------- 1 | # Examples 2 | Examples on how to use the QML ROS Plugin 3 | 4 | | Dependencies | | 5 | | --- | --- | 6 | | qmlscene | `sudo apt install qmlscene`| 7 | | QtMultimedia | `sudo apt install qml-module-qtmultimedia` | 8 | | QtQuick 2 | `sudo apt install qml-module-qtquick2` | 9 | | QtQuick.Controls 2 | `sudo apt install qml-module-qtquick-controls2` | 10 | | QtQuick.Layouts | `sudo apt install qml-module-qtquick-layouts` | 11 | | QtQuick.Window 2 | `sudo apt install qml-module-qtquick-window2` | 12 | 13 | Run using: `qmlscene FILE` 14 | 15 | **Example:** 16 | ``` 17 | qmlscene publisher.qml 18 | ``` 19 | ---------- 20 | **Note:** 21 | For the `tf_transforms.qml` and `urdf_tutorial_combined.qml`, you can use the following simulation: 22 | ``` 23 | roslaunch urdf_sim_tutorial 13-diffdrive.launch 24 | ``` 25 | -------------------------------------------------------------------------------- /examples/action_client.qml: -------------------------------------------------------------------------------- 1 | import QtQuick 2.3 2 | import QtQuick.Controls 2.2 3 | import QtQuick.Controls.Material 2.2 4 | import QtQuick.Layouts 1.0 5 | import Ros 1.0 6 | 7 | ApplicationWindow { 8 | id: page 9 | width: 620 10 | height: 400 11 | 12 | // This connection makes sure the application exits if this ROS node is requested to shutdown 13 | Connections { 14 | target: Ros 15 | onShutdown: Qt.quit() 16 | } 17 | 18 | // Arguments are: Message Type, Topic, Queue Size 19 | property var fibonacciClient: Ros.createActionClient("actionlib_tutorials/FibonacciAction", "fibonacci") 20 | property var goal_handle 21 | property string status: "DONE" 22 | property string terminalStatus: "Not in DONE yet" 23 | property string terminalStatusText: "" 24 | property string feedback: "[]" 25 | property string result: "[]" 26 | 27 | function updateStatus(handle) { 28 | switch (handle.commState) { 29 | case ActionCommStates.WAITING_FOR_GOAL_ACK: 30 | status = "WAITING_FOR_GOAL_ACK" 31 | break 32 | case ActionCommStates.PENDING: 33 | status = "PENDING" 34 | break 35 | case ActionCommStates.ACTIVE: 36 | status = "ACTIVE" 37 | break 38 | case ActionCommStates.WAITING_FOR_RESULT: 39 | status = "WAITING_FOR_RESULT" 40 | break 41 | case ActionCommStates.WAITING_FOR_CANCEL_ACK: 42 | status = "WAITING_FOR_CANCEL_ACK" 43 | break 44 | case ActionCommStates.RECALLING: 45 | status = "RECALLING" 46 | break 47 | case ActionCommStates.PREEMPTING: 48 | status = "PREEMPTING" 49 | break 50 | case ActionCommStates.DONE: 51 | status = "DONE" 52 | // The terminalState should only be used if the comm state is DONE. 53 | switch (handle.terminalState.state) { 54 | case ActionTerminalStates.RECALLED: 55 | terminalStatus = "RECALLED" 56 | break 57 | case ActionTerminalStates.REJECTED: 58 | terminalStatus = "REJECTED" 59 | break 60 | case ActionTerminalStates.PREEMPTED: 61 | terminalStatus = "PREEMPTED" 62 | break 63 | case ActionTerminalStates.ABORTED: 64 | terminalStatus = "ABORTED" 65 | break 66 | case ActionTerminalStates.SUCCEEDED: 67 | terminalStatus = "SUCCEEDED" 68 | break 69 | case ActionTerminalStates.LOST: 70 | terminalStatus = "LOST" 71 | break 72 | } 73 | // Empty in the example but that's how you'd get the goal text 74 | terminalStatusText = handle.terminalState.text 75 | break 76 | } 77 | } 78 | 79 | GridLayout { 80 | columns: 2 81 | anchors.fill: parent 82 | anchors.margins: 12 83 | Text { 84 | Layout.fillWidth: true 85 | Layout.columnSpan: 2 86 | text: "Enter an integer to send it to the fibonacci tutorial action server:" 87 | } 88 | 89 | SpinBox { 90 | id: numberInput 91 | Layout.margins: 12 92 | } 93 | 94 | GridLayout { 95 | Layout.fillWidth: true 96 | Layout.preferredWidth: parent.width * 2 / 3 97 | columns: 2 98 | Text { 99 | text: "Status:" 100 | } 101 | Text { 102 | text: status || "" 103 | } 104 | Text { 105 | text: "Terminal Status:" 106 | } 107 | Text { 108 | text: terminalStatus || "" 109 | } 110 | Text { 111 | text: "Terminal Status Text:" 112 | } 113 | Text { 114 | text: terminalStatusText || "" 115 | } 116 | Text { 117 | text: "Feedback:" 118 | } 119 | Text { 120 | Layout.fillWidth: true 121 | text: feedback || "" 122 | } 123 | Text { 124 | text: "Result:" 125 | } 126 | Text { 127 | text: result || "" 128 | } 129 | } 130 | 131 | Button { 132 | id: activeButton 133 | state: "ready" 134 | onClicked: { 135 | if (state == "sending") { 136 | goal_handle.cancel(); 137 | return 138 | } 139 | state = "sending" 140 | terminalStatus = "Not in DONE yet" 141 | terminalStatusText = "" 142 | goal_handle = fibonacciClient.sendGoal({ order: numberInput.value }, function (goal_handle) { 143 | updateStatus(goal_handle) 144 | if (goal_handle.commState == ActionCommStates.DONE) { 145 | activeButton.state = "ready" 146 | page.result = "[" 147 | var result = goal_handle.getResult() 148 | for (var i = 0; i < result.sequence.length; ++i) { 149 | page.result += result.sequence.at(i) 150 | if (i != result.sequence.length - 1) page.result += ", " 151 | } 152 | page.result += "]" 153 | } 154 | }, function (goal_handle, feedback) { 155 | var newFeedback = "[" 156 | for (var i = 0; i < feedback.sequence.length; ++i) 157 | newFeedback += feedback.sequence.at(i) + (i == feedback.sequence.length - 1 ? "]" : ", ") 158 | page.feedback = newFeedback 159 | }) 160 | } 161 | states: [ 162 | State { 163 | name: "ready" 164 | PropertyChanges { 165 | target: activeButton 166 | text: "Send" 167 | } 168 | }, 169 | State { 170 | name: "sending" 171 | PropertyChanges { 172 | target: activeButton 173 | text: "Cancel" 174 | } 175 | } 176 | ] 177 | } 178 | 179 | Text { 180 | text: "Is connected: " + (fibonacciClient.connected ? "true" : "false") 181 | } 182 | } 183 | 184 | Component.onCompleted: { 185 | // Initialize ROS with the given name. The command line args are passed by the plugin 186 | // Optionally, you can call init with a string list ["arg1", "arg2"] and the name to use those 187 | // args instead of the ones supplied by the command line. 188 | Ros.init("qml_action_client_demo") 189 | } 190 | } 191 | -------------------------------------------------------------------------------- /examples/image_subscriber.qml: -------------------------------------------------------------------------------- 1 | import QtQuick 2.3 2 | import QtQuick.Controls 2.2 3 | import QtQuick.Controls.Material 2.2 4 | import QtQuick.Layouts 1.0 5 | import QtMultimedia 5.4 6 | import Ros 1.0 7 | 8 | ApplicationWindow { 9 | id: page 10 | width: 620 11 | height: 400 12 | 13 | // This connection makes sure the application exits if this ROS node is requested to shutdown 14 | Connections { 15 | target: Ros 16 | onShutdown: Qt.quit() 17 | } 18 | 19 | ImageTransportSubscriber { 20 | id: imageSubscriber 21 | // Enter a valid image topic here 22 | topic: "/front_rgbd_cam/color/image_rect_color" 23 | // This is the default transport, change if compressed is not available 24 | defaultTransport: "compressed" 25 | } 26 | 27 | VideoOutput { 28 | anchors.fill: parent 29 | // Can be used in increments of 90 to rotate the video 30 | orientation: 90 31 | source: imageSubscriber 32 | } 33 | 34 | Component.onCompleted: { 35 | // Initialize ROS with the given name. The command line args are passed by the plugin 36 | // Optionally, you can call init with a string list ["arg1", "arg2"] and the name to use those 37 | // args instead of the ones supplied by the command line. 38 | Ros.init("qml_image_subscriber_demo") 39 | } 40 | 41 | } 42 | -------------------------------------------------------------------------------- /examples/logging.qml: -------------------------------------------------------------------------------- 1 | import QtQuick 2.3 2 | import QtQuick.Controls 2.2 3 | import QtQuick.Controls.Material 2.2 4 | import QtQuick.Layouts 1.0 5 | import Ros 1.0 6 | 7 | ApplicationWindow { 8 | id: page 9 | width: 620 10 | height: 400 11 | 12 | // This connection makes sure the application exits if this ROS node is requested to shutdown 13 | Connections { 14 | target: Ros 15 | onShutdown: { 16 | Qt.quit() 17 | } 18 | } 19 | 20 | ButtonGroup { 21 | id: outputLoggingLevelGroup 22 | onCheckedButtonChanged: { 23 | switch (checkedButton.text) { 24 | case 'Debug': 25 | Ros.console.setLoggerLevel(Ros.console.defaultName, RosConsoleLevels.Debug); 26 | break; 27 | case 'Info': 28 | Ros.console.setLoggerLevel(Ros.console.defaultName, RosConsoleLevels.Info); 29 | break; 30 | case 'Warn': 31 | Ros.console.setLoggerLevel(Ros.console.defaultName, RosConsoleLevels.Warn); 32 | break; 33 | case 'Error': 34 | Ros.console.setLoggerLevel(Ros.console.defaultName, RosConsoleLevels.Error); 35 | break; 36 | case 'Fatal': 37 | Ros.console.setLoggerLevel(Ros.console.defaultName, RosConsoleLevels.Fatal); 38 | break; 39 | } 40 | } 41 | } 42 | ButtonGroup { id: messageLoggingLevelGroup } 43 | 44 | GridLayout { 45 | anchors.fill: parent 46 | columns: 5 47 | 48 | // Output logging level 49 | Text { 50 | Layout.columnSpan: parent.columns 51 | text: "Output logging level" 52 | } 53 | 54 | RadioButton { 55 | ButtonGroup.group: outputLoggingLevelGroup 56 | text: "Debug" 57 | } 58 | 59 | RadioButton { 60 | ButtonGroup.group: outputLoggingLevelGroup 61 | text: "Info" 62 | checked: true 63 | } 64 | 65 | RadioButton { 66 | ButtonGroup.group: outputLoggingLevelGroup 67 | text: "Warn" 68 | } 69 | 70 | RadioButton { 71 | ButtonGroup.group: outputLoggingLevelGroup 72 | text: "Error" 73 | } 74 | 75 | RadioButton { 76 | ButtonGroup.group: outputLoggingLevelGroup 77 | text: "Fatal" 78 | } 79 | 80 | // Message logging level 81 | Text { 82 | Layout.columnSpan: parent.columns 83 | text: "Message logging level" 84 | } 85 | 86 | RadioButton { 87 | ButtonGroup.group: messageLoggingLevelGroup 88 | text: "Debug" 89 | } 90 | 91 | RadioButton { 92 | ButtonGroup.group: messageLoggingLevelGroup 93 | text: "Info" 94 | checked: true 95 | } 96 | 97 | RadioButton { 98 | ButtonGroup.group: messageLoggingLevelGroup 99 | text: "Warn" 100 | } 101 | 102 | RadioButton { 103 | ButtonGroup.group: messageLoggingLevelGroup 104 | text: "Error" 105 | } 106 | 107 | RadioButton { 108 | ButtonGroup.group: messageLoggingLevelGroup 109 | text: "Fatal" 110 | } 111 | 112 | 113 | TextField { 114 | id: logMessageField 115 | Layout.columnSpan: 4 116 | Layout.fillWidth: true 117 | Layout.margins: 4 118 | placeholderText: "Enter a message to log" 119 | } 120 | 121 | Button { 122 | text: "Log" 123 | 124 | onClicked: { 125 | switch (messageLoggingLevelGroup.checkedButton.text) { 126 | case 'Debug': 127 | Ros.debug(logMessageField.text); 128 | break; 129 | case 'Info': 130 | Ros.info(logMessageField.text); 131 | break; 132 | case 'Warn': 133 | Ros.warn(logMessageField.text); 134 | break; 135 | case 'Error': 136 | Ros.error(logMessageField.text); 137 | break; 138 | case 'Fatal': 139 | Ros.fatal(logMessageField.text); 140 | break; 141 | default: 142 | Ros.fatal("Unexpected logging level") 143 | } 144 | } 145 | } 146 | } 147 | 148 | Component.onCompleted: { 149 | // Initialize ROS with the given name. The command line args are passed by the plugin 150 | // Optionally, you can call init with a string list ["arg1", "arg2"] and the name to use those 151 | // args instead of the ones supplied by the command line. 152 | Ros.init("qml_logging_demo") 153 | } 154 | 155 | } 156 | -------------------------------------------------------------------------------- /examples/publisher.qml: -------------------------------------------------------------------------------- 1 | import QtQuick 2.3 2 | import QtQuick.Controls 2.2 3 | import QtQuick.Controls.Material 2.2 4 | import QtQuick.Layouts 1.0 5 | import Ros 1.0 6 | 7 | ApplicationWindow { 8 | id: page 9 | width: 620 10 | height: 400 11 | 12 | // This connection makes sure the application exits if this ROS node is requested to shutdown 13 | Connections { 14 | target: Ros 15 | onShutdown: Qt.quit() 16 | } 17 | 18 | // Arguments are: Message Type, Topic, Queue Size 19 | property var intPublisher: Ros.advertise("std_msgs/Int32", "/intval", 10) 20 | 21 | ColumnLayout { 22 | anchors.fill: parent 23 | anchors.margins: 12 24 | Text { 25 | text: "Enter an integer to publish it on /intval:" 26 | } 27 | 28 | SpinBox { 29 | id: numberInput 30 | Layout.margins: 12 31 | } 32 | 33 | Button { 34 | id: activeButton 35 | state: "ready" 36 | onClicked: { 37 | state = "sending" 38 | intPublisher.publish({ data: numberInput.value }) 39 | state = "ready" 40 | } 41 | states: [ 42 | State { 43 | name: "ready" 44 | PropertyChanges { 45 | target: activeButton 46 | text: "Send" 47 | } 48 | }, 49 | State { 50 | name: "sending" 51 | PropertyChanges { 52 | target: activeButton 53 | text: "Sending" 54 | } 55 | } 56 | ] 57 | } 58 | 59 | Text { 60 | text: "Is advertised: " + (intPublisher.isAdvertised ? "true" : "false") 61 | } 62 | 63 | Text { 64 | id: subscriberText 65 | property var count: 0 66 | text: "Subscribers: " + count 67 | 68 | Connections { 69 | target: intPublisher 70 | onConnected: { 71 | ++subscriberText.count 72 | } 73 | onDisconnected: { 74 | --subscriberText.count 75 | } 76 | } 77 | } 78 | } 79 | 80 | Component.onCompleted: { 81 | // Initialize ROS with the given name. The command line args are passed by the plugin 82 | // Optionally, you can call init with a string list ["arg1", "arg2"] and the name to use those 83 | // args instead of the ones supplied by the command line. 84 | Ros.init("qml_publisher_demo") 85 | } 86 | 87 | } 88 | -------------------------------------------------------------------------------- /examples/service.qml: -------------------------------------------------------------------------------- 1 | import QtQuick 2.3 2 | import QtQuick.Controls 2.2 3 | import QtQuick.Controls.Material 2.2 4 | import QtQuick.Layouts 1.0 5 | import Ros 1.0 6 | 7 | ApplicationWindow { 8 | id: page 9 | width: 620 10 | height: 400 11 | 12 | // This connection makes sure the application exits if this ROS node is requested to shutdown 13 | Connections { 14 | target: Ros 15 | onShutdown: Qt.quit() 16 | } 17 | 18 | GridLayout { 19 | anchors.fill: parent 20 | anchors.margins: 12 21 | columns: 2 22 | Text { 23 | text: "For this example,\n run the following in a separate terminal:" 24 | } 25 | 26 | TextInput { 27 | readOnly: true 28 | selectByMouse: true 29 | text: "rosrun roscpp_tutorials add_two_ints_server" 30 | } 31 | 32 | Text { 33 | Layout.alignment: Qt.AlignRight 34 | text: "A:" 35 | } 36 | 37 | SpinBox { 38 | id: inputA 39 | Layout.margins: 12 40 | } 41 | 42 | Text { 43 | Layout.alignment: Qt.AlignRight 44 | text: "B:" 45 | } 46 | 47 | SpinBox { 48 | id: inputB 49 | Layout.margins: 12 50 | } 51 | 52 | Button { 53 | id: activeButton 54 | state: "ready" 55 | onClicked: { 56 | state = "sending" 57 | var result = Service.call("/add_two_ints", "roscpp_tutorials/TwoInts", 58 | { a: inputA.value, b: inputB.value }) 59 | textResult.text = !!result ? ("Result: " + result.sum) : "Failed" 60 | state = "ready" 61 | } 62 | states: [ 63 | State { 64 | name: "ready" 65 | PropertyChanges { 66 | target: activeButton 67 | text: "Call Service" 68 | } 69 | }, 70 | State { 71 | name: "sending" 72 | PropertyChanges { 73 | target: activeButton 74 | text: "Processing" 75 | } 76 | } 77 | ] 78 | } 79 | 80 | Text { 81 | id: textResult 82 | text: "No result yet" 83 | } 84 | } 85 | 86 | Component.onCompleted: { 87 | // Initialize ROS with the given name. The command line args are passed by the plugin 88 | // Optionally, you can call init with a string list ["arg1", "arg2"] and the name to use those 89 | // args instead of the ones supplied by the command line. 90 | Ros.init("qml_service_demo") 91 | } 92 | 93 | } 94 | -------------------------------------------------------------------------------- /examples/subscriber.qml: -------------------------------------------------------------------------------- 1 | import QtQuick 2.3 2 | import QtQuick.Controls 2.2 3 | import QtQuick.Controls.Material 2.2 4 | import QtQuick.Layouts 1.0 5 | import Ros 1.0 6 | 7 | ApplicationWindow { 8 | id: page 9 | width: 620 10 | height: 400 11 | 12 | // This connection makes sure the application exits if this ROS node is requested to shutdown 13 | Connections { 14 | target: Ros 15 | onShutdown: Qt.quit() 16 | } 17 | 18 | Subscriber { 19 | id: mySubscriber 20 | topic: "/intval" 21 | } 22 | 23 | ColumnLayout { 24 | anchors.fill: parent 25 | anchors.margins: 12 26 | Text { 27 | text: "Paste the following in a terminal and run it:" 28 | } 29 | TextInput { 30 | Layout.margins: 12 31 | readOnly: true 32 | selectByMouse: true 33 | text: "i=0; while [ 1 ]; do rostopic pub -1 /intval std_msgs/Int32 \"data: $i\"; sleep 1; let i++; done" 34 | } 35 | 36 | Text { 37 | text: "Received:\n" + 38 | " Message type: " + mySubscriber.messageType + "\n" + 39 | " Message content: " + (mySubscriber.message ? mySubscriber.message.data : "No message received yet") + "\n" + 40 | " Running: " + mySubscriber.running 41 | } 42 | 43 | Button { 44 | id: activeButton 45 | state: "active" 46 | onClicked: { 47 | mySubscriber.running = !mySubscriber.running 48 | state = state == "active" ? "paused" : "active" 49 | } 50 | states: [ 51 | State { 52 | name: "active" 53 | PropertyChanges { 54 | target: activeButton 55 | text: "Unsubscribe" 56 | } 57 | }, 58 | State { 59 | name: "paused" 60 | PropertyChanges { 61 | target: activeButton 62 | text: "Subscribe" 63 | } 64 | } 65 | ] 66 | } 67 | } 68 | 69 | Component.onCompleted: { 70 | // Initialize ROS with the given name. The command line args are passed by the plugin 71 | // Optionally, you can call init with a string list ["arg1", "arg2"] and the name to use those 72 | // args instead of the ones supplied by the command line. 73 | Ros.init("qml_subscriber_demo") 74 | } 75 | 76 | } 77 | -------------------------------------------------------------------------------- /examples/tf_transforms.qml: -------------------------------------------------------------------------------- 1 | import QtQuick 2.3 2 | import QtQuick.Controls 2.2 3 | import QtQuick.Controls.Material 2.2 4 | import QtQuick.Layouts 1.0 5 | import Ros 1.0 6 | 7 | ApplicationWindow { 8 | id: page 9 | width: 800 10 | height: 600 11 | 12 | // This connection makes sure the application exits if this ROS node is requested to shutdown 13 | Connections { 14 | target: Ros 15 | onShutdown: Qt.quit() 16 | } 17 | 18 | TfTransform { 19 | id: tfTransform 20 | active: true // This is the default, if false no updates will be received 21 | sourceFrame: "base_link" 22 | targetFrame: "odom" 23 | } 24 | 25 | // Helper functions to print the translation and rotation of the transform 26 | function printVector3(pos) { 27 | return " x: " + pos.x.toFixed(3) + "\n y: " + pos.y.toFixed(3) + "\n z: " + pos.z.toFixed(3) 28 | } 29 | 30 | function printRotation(q) { 31 | return " w: " + q.w.toFixed(4) + "\n x: " + q.x.toFixed(4) + "\n y: " + q.y.toFixed(4) + "\n z: " + q.z.toFixed(4) 32 | } 33 | 34 | function extractYaw(q) { 35 | return Math.atan2(2 * (q.w * q.z + q.x * q.y), 1 - 2 * (q.y * q.y + q.z * q.z)) 36 | } 37 | 38 | GridLayout { 39 | id: grid 40 | anchors.fill: parent 41 | columns: 2 42 | rows: 2 43 | 44 | Canvas { 45 | Layout.row: 0 46 | Layout.column: 0 47 | Layout.fillHeight: true 48 | Layout.fillWidth: true 49 | Layout.margins: 4 50 | width: grid.width / 2 51 | 52 | onPaint: { 53 | var ctx = getContext("2d") 54 | ctx.resetTransform() 55 | ctx.fillStyle = Qt.rgba(0.8, 0.8, 0.8, 1) 56 | ctx.fillRect(0, 0, width, height) 57 | var scaling = width > height ? height: width 58 | // Switch translation x and y because we wan't movement in x direction to be on the y axis 59 | var posX = width / 2 - tfTransform.translation.y * scaling / 16 60 | var posY = height / 2 - tfTransform.translation.x * scaling / 16 61 | ctx.save() 62 | ctx.translate(posX, posY) 63 | // Angle has to be negated because our coordinate system is mirrored Y axis from left to right instead of right 64 | // to left in a right handed coordinate system viewed from above 65 | ctx.rotate(-extractYaw(tfTransform.rotation)) 66 | ctx.beginPath() 67 | ctx.fillStyle = "rgb(255, 0, 0)" 68 | ctx.lineTo(8, 2) 69 | ctx.lineTo(-8, 2) 70 | ctx.lineTo(0, -6) 71 | ctx.closePath() 72 | ctx.fill() 73 | ctx.fillStyle = "rgb(0, 0, 255)" 74 | ctx.fillRect(-8, 2, 16, 4) 75 | ctx.restore() // Restore untransformed state 76 | ctx.translate(width / 2, height / 2) 77 | ctx.fillStyle = "rgb(0, 0, 0)" 78 | ctx.fillRect(-2, -2, 4, 4) 79 | } 80 | 81 | Timer { 82 | interval: 32; running: true; repeat: true 83 | onTriggered: parent.requestPaint() 84 | } 85 | } 86 | 87 | ColumnLayout { 88 | Layout.column: 0 89 | Layout.row: 1 90 | Layout.preferredWidth: grid.width / 2 91 | 92 | RowLayout { 93 | Layout.alignment: Qt.AlignHCenter 94 | Layout.bottomMargin: 4 95 | spacing: 12 96 | 97 | Text { 98 | Layout.alignment: Qt.AlignTop 99 | text: "Position:\n" + printVector3(tfTransform.translation) 100 | } 101 | Text { 102 | Layout.alignment: Qt.AlignTop 103 | text: "Orientation:\n" + printRotation(tfTransform.rotation) 104 | } 105 | } 106 | 107 | Text { 108 | function pad(val) { 109 | return val < 10 ? '0' + val : val 110 | } 111 | 112 | function printDateTime(d) { 113 | return pad(d.getDate()) + "." + pad(d.getMonth() + 1) + "." + d.getYear() 114 | + " " + pad(d.getHours()) + ":" + pad(d.getMinutes()) 115 | + ":" + pad(d.getSeconds()) + "." + d.getMilliseconds() 116 | } 117 | 118 | text: "Last update: " + (tfTransform.valid ? printDateTime(tfTransform.message.header.stamp) : "Never") 119 | } 120 | } 121 | 122 | ColumnLayout { 123 | id: lookUpLayout 124 | Layout.column: 1 125 | Layout.preferredWidth: grid.width / 2 126 | Text { 127 | text: "Look up your own transform:" 128 | } 129 | 130 | RowLayout { 131 | Layout.fillWidth: true 132 | Text { 133 | text: "Source Frame:" 134 | } 135 | Rectangle { 136 | Layout.alignment: Qt.AlignRight 137 | width: 120 138 | height: inputSourceFrame.height 139 | border.color: "black" 140 | border.width: 1 141 | clip: true 142 | TextInput { 143 | width: parent.width 144 | id: inputSourceFrame 145 | } 146 | } 147 | } 148 | 149 | RowLayout { 150 | Layout.fillWidth: true 151 | Text { 152 | text: "Target Frame:" 153 | } 154 | Rectangle { 155 | Layout.alignment: Qt.AlignRight 156 | width: 120 157 | height: inputTargetFrame.height 158 | border.color: "black" 159 | border.width: 1 160 | clip: true 161 | TextInput { 162 | width: parent.width 163 | id: inputTargetFrame 164 | } 165 | } 166 | } 167 | 168 | Button { 169 | text: "Look Up" 170 | onClicked: { 171 | var transform = TfTransformListener.lookUpTransform(inputTargetFrame.text, inputSourceFrame.text) 172 | if (!transform.valid) 173 | { 174 | transformResult.text = "Transform from '" + inputSourceFrame.text + "' to '" + inputTargetFrame.text + "' was not valid!\n" + 175 | "Exception: " + transform.exception + "\nMessage: " + transform.message 176 | return 177 | } 178 | transformResult.text = "Position:\n" + printVector3(transform.transform.translation) + "\nOrientation:\n" + printRotation(transform.transform.rotation) 179 | } 180 | } 181 | } 182 | 183 | Text { 184 | id: transformResult 185 | Layout.column: 1 186 | Layout.row: 1 187 | Layout.margins: 4 188 | Layout.preferredWidth: grid.width / 2 189 | wrapMode: Text.WordWrap 190 | } 191 | } 192 | 193 | 194 | Component.onCompleted: { 195 | // Initialize ROS with the given name. The command line args are passed by the plugin 196 | // Optionally, you can call init with a string list ["arg1", "arg2"] and the name to use those 197 | // args instead of the ones supplied by the command line. 198 | Ros.init("qml_tf_transforms_demo") 199 | } 200 | 201 | } 202 | -------------------------------------------------------------------------------- /examples/time.qml: -------------------------------------------------------------------------------- 1 | import QtQuick 2.3 2 | import QtQuick.Controls 2.2 3 | import QtQuick.Controls.Material 2.2 4 | import QtQuick.Layouts 1.0 5 | import Ros 1.0 6 | 7 | ApplicationWindow { 8 | id: page 9 | width: 1200 10 | height: 400 11 | 12 | // This connection makes sure the application exits if this ROS node is requested to shutdown 13 | Connections { 14 | target: Ros 15 | onShutdown: Qt.quit() 16 | } 17 | 18 | property var time: Time.now() 19 | property var wallTime: WallTime.now() 20 | 21 | GridLayout { 22 | anchors.fill: parent 23 | anchors.margins: 12 24 | columns: 2 25 | 26 | Text { text: "Time" } 27 | Text { text: "WallTime" } 28 | 29 | Text { text: "sec: " + page.time.sec } 30 | Text { text: "sec: " + page.wallTime.sec } 31 | 32 | Text { text: "nsec: " + page.time.nsec } 33 | Text { text: "nsec: " + page.wallTime.nsec } 34 | 35 | Text { text: "Date: " + page.time.toJSDate() } 36 | Text { text: "Date: " + page.wallTime.toJSDate() } 37 | 38 | Button { 39 | text: "Update" 40 | onClicked: { 41 | page.time = Time.now() 42 | page.wallTime = WallTime.now() 43 | } 44 | } 45 | } 46 | 47 | Component.onCompleted: { 48 | // Initialize ROS with the given name. The command line args are passed by the plugin 49 | // Optionally, you can call init with a string list ["arg1", "arg2"] and the name to use those 50 | // args instead of the ones supplied by the command line. 51 | Ros.init("qml_time_demo") 52 | } 53 | 54 | } 55 | -------------------------------------------------------------------------------- /examples/urdf_tutorial_control.qml: -------------------------------------------------------------------------------- 1 | import QtQuick 2.3 2 | import QtQuick.Controls 2.2 3 | import QtQuick.Controls.Material 2.2 4 | import QtQuick.Layouts 1.0 5 | import Ros 1.0 6 | 7 | ApplicationWindow { 8 | id: page 9 | width: 800 10 | height: 600 11 | 12 | // This connection makes sure the application exits if this ROS node is requested to shutdown 13 | Connections { 14 | target: Ros 15 | onShutdown: Qt.quit() 16 | } 17 | 18 | Subscriber { 19 | id: poseSubscriber 20 | topic: "/robot_pose" 21 | onMessageChanged: { 22 | console.log("MESSAGE: ", message) 23 | } 24 | } 25 | 26 | // Arguments are: Message Type, Topic, Queue Size 27 | property var cmdVelPublisher: Ros.advertise("geometry_msgs/Twist", "/r2d2_diff_drive_controller/cmd_vel", 10) 28 | 29 | TfTransform { 30 | id: tfTransform 31 | active: true // This is the default, if false no updates will be received 32 | sourceFrame: "base_link" 33 | targetFrame: "odom" 34 | } 35 | 36 | // Helper functions to print the translation and rotation of the transform 37 | function printVector3(pos) { 38 | return " x: " + pos.x.toFixed(3) + "\n y: " + pos.y.toFixed(3) + "\n z: " + pos.z.toFixed(3) 39 | } 40 | 41 | function printRotation(q) { 42 | return " w: " + q.w.toFixed(4) + "\n x: " + q.x.toFixed(4) + "\n y: " + q.y.toFixed(4) + "\n z: " + q.z.toFixed(4) 43 | } 44 | 45 | function extractYaw(q) { 46 | return Math.atan2(2 * (q.w * q.z + q.x * q.y), 1 - 2 * (q.y * q.y + q.z * q.z)) 47 | } 48 | 49 | GridLayout { 50 | id: grid 51 | anchors.fill: parent 52 | columns: 3 53 | rows: 2 54 | 55 | Canvas { 56 | Layout.row: 0 57 | Layout.column: 0 58 | Layout.fillHeight: true 59 | Layout.fillWidth: true 60 | Layout.margins: 4 61 | Layout.preferredWidth: grid.width / 2 62 | 63 | onPaint: { 64 | var ctx = getContext("2d") 65 | ctx.resetTransform() 66 | ctx.fillStyle = Qt.rgba(0.8, 0.8, 0.8, 1) 67 | ctx.fillRect(0, 0, width, height) 68 | var scaling = width > height ? height: width 69 | // Switch translation x and y because we wan't movement in x direction to be on the y axis 70 | var posX = width / 2 - tfTransform.translation.y * scaling / 16 71 | var posY = height / 2 - tfTransform.translation.x * scaling / 16 72 | ctx.save() 73 | ctx.translate(posX, posY) 74 | // Angle has to be negated because our coordinate system is mirrored Y axis from left to right instead of right 75 | // to left in a right handed coordinate system viewed from above 76 | ctx.rotate(-extractYaw(tfTransform.rotation)) 77 | ctx.beginPath() 78 | ctx.fillStyle = "rgb(255, 0, 0)" 79 | ctx.lineTo(8, 2) 80 | ctx.lineTo(-8, 2) 81 | ctx.lineTo(0, -6) 82 | ctx.closePath() 83 | ctx.fill() 84 | ctx.fillStyle = "rgb(0, 0, 255)" 85 | ctx.fillRect(-8, 2, 16, 4) 86 | ctx.restore() // Restore untransformed state 87 | ctx.translate(width / 2, height / 2) 88 | ctx.fillStyle = "rgb(0, 0, 0)" 89 | ctx.fillRect(-2, -2, 4, 4) 90 | } 91 | 92 | Timer { 93 | interval: 32; running: true; repeat: true 94 | onTriggered: parent.requestPaint() 95 | } 96 | } 97 | 98 | ColumnLayout { 99 | Layout.column: 0 100 | Layout.row: 1 101 | Layout.preferredWidth: grid.width / 2 102 | 103 | RowLayout { 104 | Layout.alignment: Qt.AlignHCenter 105 | Layout.bottomMargin: 4 106 | spacing: 12 107 | 108 | Text { 109 | Layout.alignment: Qt.AlignTop 110 | text: "Position:\n" + printVector3(tfTransform.translation) 111 | } 112 | Text { 113 | Layout.alignment: Qt.AlignTop 114 | text: "Orientation:\n" + printRotation(tfTransform.rotation) 115 | } 116 | } 117 | 118 | Text { 119 | function pad(val) { 120 | return val < 10 ? '0' + val : val 121 | } 122 | 123 | function printDateTime(d) { 124 | return pad(d.getDate()) + "." + pad(d.getMonth() + 1) + "." + d.getYear() 125 | + " " + pad(d.getHours()) + ":" + pad(d.getMinutes()) 126 | + ":" + pad(d.getSeconds()) + "." + d.getMilliseconds() 127 | } 128 | 129 | text: "Last update: " + printDateTime(tfTransform.message.header.stamp) 130 | } 131 | } 132 | 133 | Item { 134 | Layout.row: 0 135 | Layout.column: 1 136 | Layout.fillHeight: true 137 | Layout.fillWidth: true 138 | Slider { 139 | anchors.horizontalCenter: parent.horizontalCenter 140 | anchors.top: parent.top 141 | anchors.bottom: parent.bottom 142 | id: sliderForward 143 | orientation: Qt.Vertical 144 | from: -1 145 | to: 1 146 | value: 0 147 | } 148 | 149 | Button { 150 | anchors.left: sliderForward.right 151 | anchors.verticalCenter: sliderForward.verticalCenter 152 | text: "0" 153 | onClicked: sliderForward.value = 0 154 | } 155 | } 156 | 157 | ColumnLayout { 158 | Layout.row: 1 159 | Layout.column: 1 160 | Layout.preferredWidth: grid.width / 4 161 | Slider { 162 | Layout.fillWidth: true 163 | id: sliderTurn 164 | from: -3 165 | to: 3 166 | value: 0 167 | } 168 | 169 | Button { 170 | Layout.alignment: Qt.AlignHCenter 171 | text: "0" 172 | onClicked: sliderTurn.value = 0 173 | } 174 | } 175 | 176 | Subscriber { 177 | id: cmdVelSubscriber 178 | topic: "/r2d2_diff_drive_controller/cmd_vel" 179 | } 180 | 181 | Text { 182 | Layout.row: 0 183 | Layout.column: 2 184 | Layout.margins: 12 185 | Layout.alignment: Qt.AlignHCenter 186 | text: "Linear:\n" + printVector3(cmdVelSubscriber.message.linear) 187 | + "\nAngular:\n" + printVector3(cmdVelSubscriber.message.angular) 188 | } 189 | } 190 | 191 | // Timer is bound to animation timer which is usually set to 60 fps so resolution will be at best 16ms 192 | Timer { 193 | interval: 32; running: true; repeat: true; 194 | // Angular has to be inverted because right is positive 195 | onTriggered: page.cmdVelPublisher.publish({ linear: { x: sliderForward.value }, angular: { z: -sliderTurn.value } }) 196 | } 197 | 198 | Component.onCompleted: { 199 | // Initialize ROS with the given name. The command line args are passed by the plugin 200 | // Optionally, you can call init with a string list ["arg1", "arg2"] and the name to use those 201 | // args instead of the ones supplied by the command line. 202 | Ros.init("urdf_tutorial_control") 203 | } 204 | 205 | } 206 | -------------------------------------------------------------------------------- /export_qml_ros_plugin.sh.em: -------------------------------------------------------------------------------- 1 | #!/bin/bash 2 | # This script is only needed for non-global install and will add the plugin to the path 3 | # If you copy this file to add another package to the qml import path, note that the filename of this script needs to be unique! 4 | 5 | @[if DEVELSPACE]@ 6 | case $QML2_IMPORT_PATH in 7 | *"@(CATKIN_DEVEL_PREFIX)/@(CATKIN_PACKAGE_LIB_DESTINATION)/@(PROJECT_NAME)"*) ;; 8 | *) export QML2_IMPORT_PATH="@(CATKIN_DEVEL_PREFIX)/@(CATKIN_PACKAGE_LIB_DESTINATION)/@(PROJECT_NAME):${QML2_IMPORT_PATH}" 9 | esac 10 | @[else]@ 11 | case $QML2_IMPORT_PATH in 12 | *"@(CMAKE_INSTALL_PREFIX)/@(CATKIN_PACKAGE_LIB_DESTINATION)/@(PROJECT_NAME)"*) ;; 13 | *) export QML2_IMPORT_PATH="@(CMAKE_INSTALL_PREFIX)/@(CATKIN_PACKAGE_LIB_DESTINATION)/@(PROJECT_NAME):${QML2_IMPORT_PATH}" 14 | esac 15 | @[end if]@ 16 | -------------------------------------------------------------------------------- /include/qml_ros_plugin/action_client.h: -------------------------------------------------------------------------------- 1 | // Copyright (c) 2020 Stefan Fabian. All rights reserved. 2 | // Licensed under the MIT license. See LICENSE file in the project root for full license information. 3 | 4 | #ifndef QML_ROS_PLUGIN_ACTION_CLIENT_H 5 | #define QML_ROS_PLUGIN_ACTION_CLIENT_H 6 | 7 | #include "qml_ros_plugin/node_handle.h" 8 | #include "qml_ros_plugin/qobject_ros.h" 9 | 10 | #include 11 | #include 12 | 13 | #include 14 | #include 15 | 16 | namespace qml_ros_plugin 17 | { 18 | class NodeHandle; 19 | 20 | class GoalHandle; 21 | 22 | class ActionClient : public QObjectRos 23 | { 24 | Q_OBJECT 25 | // @formatter:off 26 | //! True if the ActionClient is connected to the ActionServer, false otherwise. 27 | Q_PROPERTY( bool connected READ isServerConnected NOTIFY connectedChanged ) 28 | //! The type of the action. Example: actionlib_tutorials/FibonacciAction 29 | Q_PROPERTY( QString actionType READ actionType CONSTANT ) 30 | // @formatter:on 31 | public: 32 | ActionClient( NodeHandle::Ptr nh, const QString &action_type, const QString &name ); 33 | 34 | Q_INVOKABLE bool isServerConnected() const; 35 | 36 | QString actionType() const; 37 | 38 | /*! 39 | * Sends a goal to the action server if it is connected. 40 | * 41 | * @param goal The goal that is sent to the action server. 42 | * @param transition_cb A callback that is called on every client state transition. 43 | * @param feedback_cb A callback that is called whenever feedback for this goal is received. 44 | * @return null if the action server is not connected, otherwise a GoalHandle keeping track of the state of the goal. 45 | */ 46 | Q_INVOKABLE QObject *sendGoal( const QVariantMap &goal, QJSValue transition_cb = QJSValue(), 47 | QJSValue feedback_cb = QJSValue() ); 48 | 49 | //! Cancels all goals that are currently tracked by this client. 50 | Q_INVOKABLE void cancelAllGoals(); 51 | 52 | //! Cancels all goals that were sent at and before the given ROS time by this client. 53 | //! Use Time.now() to obtain the current ROS time which can differ from the actual time. 54 | Q_INVOKABLE void cancelGoalsAtAndBeforeTime( const QDateTime &time ); 55 | 56 | signals: 57 | 58 | //! Emitted when the connected status changes, e.g., when the client connected to the server. 59 | void connectedChanged(); 60 | 61 | private slots: 62 | 63 | void checkServerConnected(); 64 | 65 | void invokeTransitionCallback( 66 | QJSValue callback, actionlib::ActionClient::GoalHandle handle ); 67 | 68 | void invokeFeedbackCallback( 69 | QJSValue callback, actionlib::ActionClient::GoalHandle handle, 70 | ros_babel_fish::BabelFishMessage::ConstPtr feedback ); 71 | 72 | private: 73 | void onRosInitialized() override; 74 | 75 | void onRosShutdown() override; 76 | 77 | ros_babel_fish::BabelFish babel_fish_; 78 | NodeHandle::Ptr nh_; 79 | QString action_type_; 80 | QString name_; 81 | std::shared_ptr> client_; 82 | QTimer connect_timer_; 83 | }; 84 | } // namespace qml_ros_plugin 85 | 86 | Q_DECLARE_METATYPE( actionlib::ActionClient::GoalHandle ); 87 | 88 | Q_DECLARE_METATYPE( ros_babel_fish::BabelFishMessage::ConstPtr ); 89 | 90 | #endif // QML_ROS_PLUGIN_ACTION_CLIENT_H 91 | -------------------------------------------------------------------------------- /include/qml_ros_plugin/array.h: -------------------------------------------------------------------------------- 1 | // Copyright (c) 2019 Stefan Fabian. All rights reserved. 2 | // Licensed under the MIT license. See LICENSE file in the project root for full license information. 3 | 4 | #ifndef QML_ROS_PLUGIN_ARRAY_H 5 | #define QML_ROS_PLUGIN_ARRAY_H 6 | 7 | #include 8 | 9 | #include 10 | #include 11 | 12 | namespace qml_ros_plugin 13 | { 14 | 15 | /*! 16 | * @brief View on an array field of a message. 17 | * This allows access on array elements with lazy copy mechanism. 18 | * Copies of an Array point to the same data and modifications of one array will be mirrored by the other. 19 | */ 20 | class Array 21 | { 22 | Q_GADGET 23 | // @formatter:off 24 | //! The length of the array, i.e., the number of elements. 25 | Q_PROPERTY( int length READ length WRITE setLength ) 26 | // @formatter:on 27 | public: 28 | Array(); 29 | 30 | Array( ros_babel_fish::TranslatedMessage::ConstPtr translated_message, 31 | const ros_babel_fish::ArrayMessageBase *message ); 32 | 33 | // Array( const Array &other ); 34 | 35 | ~Array() = default; 36 | 37 | int length() const; 38 | 39 | int size() const { return length(); } 40 | 41 | void setLength( int value ); 42 | 43 | /*! 44 | * If the index is out of the bounds of the array, an empty QVariant is returned. 45 | * 46 | * @param index Index of the retrieved element. 47 | * @return The array element at the given index. 48 | */ 49 | Q_INVOKABLE QVariant at( int index ) const; 50 | 51 | /*! 52 | * Changes the array content by removing delete_count elements at index and inserting the elements 53 | * in items. This method can be used to remove, replace or add elements to the array. 54 | * 55 | * @warning If the operation is not limited to the end of the array, it requires a deep copy of 56 | * the message array. 57 | * 58 | * @param start The index at which to start changing the array. If greater than the length of the 59 | * array, start will be set to the length of the array. If negative, it will begin that many 60 | * elements from the end of the array (with origin -1, meaning -n is the index of the nth last 61 | * element and is therefore equivalent to the index of array.length - n). If the absolute value of 62 | * start is greater than the length of the array, it will begin from index 0. 63 | * @param delete_count The number of elements to delete starting at index start. If delete_count 64 | * is greater than the number of elements after start, all elements from start to the length of 65 | * the array are removed. If delete_count is 0, no elements are removed, e.g., for a insert only 66 | * operation. 67 | * @param items The items that will be inserted at start. 68 | */ 69 | Q_INVOKABLE void spliceList( int start, int delete_count, const QVariantList &items ); 70 | 71 | /*! 72 | * Adds the given value to the end of the array. 73 | * 74 | * @param value The item that is added. 75 | */ 76 | Q_INVOKABLE void push( const QVariant &value ); 77 | 78 | /*! 79 | * Adds the given value to the front of the array. 80 | * 81 | * @warning This requires a deep copy of the message array on first call whereas appending can be 82 | * done without copying the array. 83 | * @param value The item that is added. 84 | */ 85 | Q_INVOKABLE void unshift( const QVariant &value ); 86 | 87 | /*! 88 | * Removes the last element and returns it. 89 | * @return The removed element or an empty QVariant if the array is empty. 90 | */ 91 | Q_INVOKABLE QVariant pop(); 92 | 93 | /*! 94 | * Removes the first element and returns it. 95 | * @warning This requires a deep copy of the message array on first call whereas appending can be 96 | * done without copying the array. 97 | * @return The removed element or an empty QVariant if the array is empty. 98 | */ 99 | Q_INVOKABLE QVariant shift(); 100 | 101 | /*! 102 | * Converts the array to a QVariantList which can be used in place of a JS array in QML. 103 | * This method performs a deep copy of the message array on the first call. 104 | * @return The array as a QVariantList. 105 | */ 106 | Q_INVOKABLE QVariantList toArray(); 107 | 108 | /* Internal functions */ 109 | bool _isModified( int index ) const; 110 | 111 | bool _inCache() const; 112 | 113 | const ros_babel_fish::ArrayMessageBase *_message() const; 114 | 115 | Q_INVOKABLE QVariantList toVariantList() const; 116 | 117 | private: 118 | void enlargeCache( int size ) const; 119 | 120 | void fillCache() const; 121 | 122 | struct Data { 123 | QVariantList cache; 124 | QList modified; 125 | ros_babel_fish::TranslatedMessage::ConstPtr translated_message; 126 | const ros_babel_fish::ArrayMessageBase *message = nullptr; 127 | bool all_in_cache = true; 128 | int length = 0; 129 | }; 130 | // Copies of array share the data 131 | std::shared_ptr p_; 132 | }; 133 | } // namespace qml_ros_plugin 134 | 135 | Q_DECLARE_METATYPE( qml_ros_plugin::Array ) 136 | 137 | #endif // QML_ROS_PLUGIN_ARRAY_H 138 | -------------------------------------------------------------------------------- /include/qml_ros_plugin/babel_fish_dispenser.h: -------------------------------------------------------------------------------- 1 | // Copyright (c) 2019 Stefan Fabian. All rights reserved. 2 | // Licensed under the MIT license. See LICENSE file in the project root for full license information. 3 | 4 | #ifndef QML_ROS_PLUGIN_BABEL_FISH_DISPENSER_H 5 | #define QML_ROS_PLUGIN_BABEL_FISH_DISPENSER_H 6 | 7 | #include 8 | 9 | namespace qml_ros_plugin 10 | { 11 | 12 | /*! 13 | * @brief Can be used to obtain a BabelFish that is linked to a description provider that is used for all BabelFish. 14 | * 15 | * The ros_babel_fish::DescriptionProvider is responsible for looking up message definitions and caching them, hence, 16 | * sharing an instance significantly improves performance. 17 | */ 18 | class BabelFishDispenser 19 | { 20 | BabelFishDispenser(); 21 | 22 | public: 23 | BabelFishDispenser( const BabelFishDispenser & ) = delete; 24 | 25 | void operator=( const BabelFishDispenser & ) = delete; 26 | 27 | //! @return A BabelFish instance using the shared description provider. 28 | static ros_babel_fish::BabelFish getBabelFish(); 29 | 30 | private: 31 | ros_babel_fish::BabelFish createBabelFish(); 32 | 33 | ros_babel_fish::DescriptionProvider::Ptr description_provider_; 34 | }; 35 | } // namespace qml_ros_plugin 36 | 37 | #endif // QML_ROS_PLUGIN_BABEL_FISH_DISPENSER_H 38 | -------------------------------------------------------------------------------- /include/qml_ros_plugin/console.h: -------------------------------------------------------------------------------- 1 | // Copyright (c) 2020 Stefan Fabian. All rights reserved. 2 | // Licensed under the MIT license. See LICENSE file in the project root for full license information. 3 | 4 | #ifndef QML_ROS_PLUGIN_CONSOLE_H 5 | #define QML_ROS_PLUGIN_CONSOLE_H 6 | 7 | #include 8 | #include 9 | 10 | namespace qml_ros_plugin 11 | { 12 | 13 | namespace ros_console_levels 14 | { 15 | Q_NAMESPACE 16 | 17 | enum RosConsoleLevel { 18 | Debug = ros::console::levels::Debug, 19 | Info = ros::console::levels::Info, 20 | Warn = ros::console::levels::Warn, 21 | Error = ros::console::levels::Error, 22 | Fatal = ros::console::levels::Fatal, 23 | 24 | Count = ros::console::levels::Count 25 | }; 26 | 27 | Q_ENUM_NS( RosConsoleLevel ) 28 | } // namespace ros_console_levels 29 | 30 | class Console 31 | { 32 | Q_GADGET 33 | 34 | // @formatter:off 35 | Q_PROPERTY( QString defaultName READ defaultName CONSTANT ) 36 | // @formatter:on 37 | public: 38 | /*! 39 | * Sets the logger level of the given console to the given level. 40 | * @param ros_console_name The console for which the level is changed. 41 | * @param level The new logging level. 42 | * @return True if successful, false otherwise. 43 | */ 44 | Q_INVOKABLE bool setLoggerLevel( const QString &ros_console_name, 45 | qml_ros_plugin::ros_console_levels::RosConsoleLevel level ); 46 | 47 | QString defaultName() const; 48 | }; 49 | } // namespace qml_ros_plugin 50 | 51 | Q_DECLARE_METATYPE( qml_ros_plugin::ros_console_levels::RosConsoleLevel ); 52 | Q_DECLARE_METATYPE( qml_ros_plugin::Console ); 53 | 54 | #endif // QML_ROS_PLUGIN_CONSOLE_H 55 | -------------------------------------------------------------------------------- /include/qml_ros_plugin/goal_handle.h: -------------------------------------------------------------------------------- 1 | // Copyright (c) 2020 Stefan Fabian. All rights reserved. 2 | // Licensed under the MIT license. See LICENSE file in the project root for full license information. 3 | 4 | #ifndef QML_ROS_PLUGIN_GOAL_HANDLE_H 5 | #define QML_ROS_PLUGIN_GOAL_HANDLE_H 6 | 7 | #include "qml_ros_plugin/qobject_ros.h" 8 | 9 | #include 10 | #include 11 | 12 | namespace qml_ros_plugin 13 | { 14 | 15 | namespace action_comm_states 16 | { 17 | Q_NAMESPACE 18 | 19 | enum CommState { 20 | WAITING_FOR_GOAL_ACK = actionlib::CommState::WAITING_FOR_GOAL_ACK, 21 | PENDING = actionlib::CommState::PENDING, 22 | ACTIVE = actionlib::CommState::ACTIVE, 23 | WAITING_FOR_RESULT = actionlib::CommState::WAITING_FOR_RESULT, 24 | WAITING_FOR_CANCEL_ACK = actionlib::CommState::WAITING_FOR_CANCEL_ACK, 25 | RECALLING = actionlib::CommState::RECALLING, 26 | PREEMPTING = actionlib::CommState::PREEMPTING, 27 | DONE = actionlib::CommState::DONE 28 | }; 29 | 30 | Q_ENUM_NS( CommState ) 31 | } // namespace action_comm_states 32 | 33 | namespace action_terminal_states 34 | { 35 | Q_NAMESPACE 36 | 37 | enum TerminalState { 38 | RECALLED = actionlib::TerminalState::RECALLED, 39 | REJECTED = actionlib::TerminalState::REJECTED, 40 | PREEMPTED = actionlib::TerminalState::PREEMPTED, 41 | ABORTED = actionlib::TerminalState::ABORTED, 42 | SUCCEEDED = actionlib::TerminalState::SUCCEEDED, 43 | LOST = actionlib::TerminalState::LOST, 44 | 45 | UNKNOWN 46 | }; 47 | 48 | Q_ENUM_NS( TerminalState ) 49 | } // namespace action_terminal_states 50 | 51 | class TerminalState 52 | { 53 | Q_GADGET 54 | // @formatter:off 55 | //! The terminal state in form of an ActionTerminalStates enum value: 56 | //! RECALLED, REJECTED, PREEMPTED, ABORTED, SUCCEEDED, LOST 57 | Q_PROPERTY( qml_ros_plugin::action_terminal_states::TerminalState state READ state ) 58 | //! An optional text that was returned by the ActionServer in combination with the terminal state. 59 | Q_PROPERTY( QString text READ text ) 60 | // @formatter:on 61 | public: 62 | TerminalState() : state_( action_terminal_states::UNKNOWN ) { } 63 | 64 | TerminalState( action_terminal_states::TerminalState state, QString text ) 65 | : text_( std::move( text ) ), state_( state ) 66 | { 67 | } 68 | 69 | const QString &text() const { return text_; } 70 | 71 | qml_ros_plugin::action_terminal_states::TerminalState state() const { return state_; } 72 | 73 | private: 74 | QString text_; 75 | action_terminal_states::TerminalState state_; 76 | }; 77 | 78 | class GoalHandle : public QObjectRos 79 | { 80 | Q_OBJECT 81 | // @formatter:off 82 | //! True if this handle is not tracking a goal, false otherwise 83 | Q_PROPERTY( bool expired READ expired ) 84 | //! The terminal state of this goal. Only valid if commstate == ActionCommStates.DONE. 85 | Q_PROPERTY( qml_ros_plugin::TerminalState terminalState READ terminalState ) 86 | //! The state of this goal's communication state machine. 87 | //! Possible states: 88 | //! WAITING_FOR_GOAL_ACK, PENDING, ACTIVE, WAITING_FOR_RESULT, WAITING_FOR_CANCEL_ACK, RECALLING, PREEMPTING, DONE 89 | Q_PROPERTY( qml_ros_plugin::action_comm_states::CommState commState READ commState ) 90 | // @formatter:on 91 | public: 92 | explicit GoalHandle( 93 | std::shared_ptr> client, 94 | const actionlib::ActionClient::GoalHandle &handle ); 95 | 96 | bool expired() const; 97 | 98 | qml_ros_plugin::TerminalState terminalState() const; 99 | 100 | qml_ros_plugin::action_comm_states::CommState commState() const; 101 | 102 | //! Sends a cancellation request to the ActionServer. Transitions to WAITING_FOR_CANCEL_ACK. 103 | Q_INVOKABLE void cancel(); 104 | 105 | //! Resends this goal with the same id to the ActionServer. 106 | //! Useful if you have reason to think that the goal was lost in transit. 107 | Q_INVOKABLE void resend(); 108 | 109 | //! Can be used to obtain the result returned by the ActionServer. Empty if no result received. 110 | Q_INVOKABLE QVariant getResult(); 111 | 112 | private: 113 | ros_babel_fish::BabelFish babel_fish_; 114 | // Store the client to make sure its destructed after the goal handles 115 | std::shared_ptr> client_; 116 | actionlib::ActionClient::GoalHandle goal_handle_; 117 | }; 118 | } // namespace qml_ros_plugin 119 | 120 | Q_DECLARE_METATYPE( qml_ros_plugin::action_comm_states::CommState ); 121 | 122 | Q_DECLARE_METATYPE( qml_ros_plugin::TerminalState ); 123 | 124 | Q_DECLARE_METATYPE( qml_ros_plugin::action_terminal_states::TerminalState ); 125 | 126 | #endif // QML_ROS_PLUGIN_GOAL_HANDLE_H 127 | -------------------------------------------------------------------------------- /include/qml_ros_plugin/helpers/rolling_average.h: -------------------------------------------------------------------------------- 1 | // 2 | // Created by stefan on 21.07.21. 3 | // 4 | 5 | #ifndef QML_ROS_PLUGIN_ROLLING_AVERAGE_H 6 | #define QML_ROS_PLUGIN_ROLLING_AVERAGE_H 7 | 8 | #include 9 | 10 | namespace qml_ros_plugin 11 | { 12 | 13 | template 14 | class RollingAverage 15 | { 16 | public: 17 | RollingAverage() { values_.fill( 0 ); } 18 | 19 | void add( const T &value ) 20 | { 21 | if ( count_values_ == COUNT ) 22 | sum_ -= values_[index_]; 23 | else 24 | ++count_values_; 25 | values_[index_] = value; 26 | sum_ += value; 27 | if ( ++index_ == COUNT ) 28 | index_ = 0; 29 | } 30 | 31 | T value() const { return count_values_ == 0 ? 0 : sum_ / count_values_; } 32 | 33 | operator T() const { return value(); } 34 | 35 | private: 36 | std::array values_; 37 | T sum_ = 0; 38 | size_t count_values_ = 0; 39 | size_t index_ = 0; 40 | }; 41 | } // namespace qml_ros_plugin 42 | 43 | #endif // QML_ROS_PLUGIN_ROLLING_AVERAGE_H 44 | -------------------------------------------------------------------------------- /include/qml_ros_plugin/image_buffer.h: -------------------------------------------------------------------------------- 1 | // Copyright (c) 2019 Stefan Fabian. All rights reserved. 2 | // Licensed under the MIT license. See LICENSE file in the project root for full license information. 3 | 4 | #ifndef QML_ROS_PLUGIN_IMAGE_BUFFER_H 5 | #define QML_ROS_PLUGIN_IMAGE_BUFFER_H 6 | 7 | #include 8 | #include 9 | #include 10 | 11 | namespace qml_ros_plugin 12 | { 13 | 14 | class ImageBuffer : public QAbstractVideoBuffer 15 | { 16 | public: 17 | ImageBuffer( sensor_msgs::ImageConstPtr img, 18 | const QList &supported_formats ); 19 | 20 | ~ImageBuffer() override; 21 | 22 | MapMode mapMode() const override; 23 | 24 | uchar *map( MapMode, int *num_bytes, int *bytes_per_line ) override; 25 | 26 | void unmap() override; 27 | 28 | QVideoFrame::PixelFormat format() const; 29 | 30 | private: 31 | sensor_msgs::ImageConstPtr image_; 32 | QVideoFrame::PixelFormat format_; 33 | int num_bytes_; 34 | int bytes_per_line_; 35 | unsigned char *data_; 36 | }; 37 | } // namespace qml_ros_plugin 38 | 39 | #endif // QML_ROS_PLUGIN_IMAGE_BUFFER_H 40 | -------------------------------------------------------------------------------- /include/qml_ros_plugin/image_transport_manager.h: -------------------------------------------------------------------------------- 1 | // 2 | // Created by stefan on 22.02.21. 3 | // 4 | 5 | #ifndef QML_ROS_PLUGIN_IMAGE_TRANSPORT_MANAGER_H 6 | #define QML_ROS_PLUGIN_IMAGE_TRANSPORT_MANAGER_H 7 | 8 | #include "qml_ros_plugin/node_handle.h" 9 | 10 | #include 11 | #include 12 | #include 13 | 14 | namespace qml_ros_plugin 15 | { 16 | class ImageTransportSubscriptionHandle; 17 | 18 | class ImageTransportManagerSingletonWrapper : public QObject 19 | { 20 | Q_OBJECT 21 | public: 22 | //! @copydoc ImageTransportManager::setLoadBalancingEnabled 23 | Q_INVOKABLE void setLoadBalancingEnabled( bool value ); 24 | }; 25 | 26 | /*! 27 | * Encapsulates the image transport communication to share the subscription resources, avoiding multiple conversions of 28 | * the same image and subscription overhead if multiple cameras are set to throttle. 29 | */ 30 | class ImageTransportManager 31 | { 32 | ImageTransportManager(); 33 | 34 | struct SubscriptionManager; 35 | class Subscription; 36 | class LoadBalancer; 37 | 38 | public: 39 | static ImageTransportManager &getInstance(); 40 | 41 | //! Sets whether the manager should try to balance throttled subscriptions_ to ensure they don't update at the same 42 | //! time which would result in network spikes. 43 | void setLoadBalancingEnabled( bool value ); 44 | 45 | /*! 46 | * Note: Can only be called with a ready NodeHandle! 47 | * 48 | * Subscribes to the given topic with the given settings. Makes sure that multiple subscriptions_ (especially throttled) 49 | * only result in a single (throttled) subscription. 50 | * If multiple subscriptions_ of the same topic and namespace are created, the settings of the first subscription are used. 51 | * Except for the throttle interval where the minimum value across all active subscriptions_ is used. 52 | * @param nh The NodeHandle the subscription is made from if it is the first subscribe call 53 | * @param qtopic 54 | * @param queue_size 55 | * @param transport_hints 56 | * @param callback 57 | * @param surface 58 | * @param throttle_interval 59 | * @return 60 | */ 61 | std::shared_ptr 62 | subscribe( const NodeHandle::Ptr &nh, const QString &qtopic, quint32 queue_size, 63 | const image_transport::TransportHints &transport_hints, 64 | const std::function &callback, 65 | QAbstractVideoSurface *surface = nullptr, int throttle_interval = 0 ); 66 | 67 | private: 68 | std::map> subscriptions_; 69 | std::unique_ptr load_balancer_; 70 | 71 | friend class ImageTransportSubscriptionHandle; 72 | }; 73 | 74 | class ImageTransportSubscriptionHandle 75 | { 76 | public: 77 | ~ImageTransportSubscriptionHandle(); 78 | 79 | //! The interval in ms the subscription waits between receiving images. 80 | int throttleInterval() const { return throttle_interval; } 81 | 82 | //! Set the interval in ms the subscription may wait between images. 83 | //! The images may still arrive at a higher rate if other subscriptions request it. 84 | void updateThrottleInterval( int interval ); 85 | 86 | //! The subscribed topic. Once subscribed this is the full topic name without the transport. 87 | std::string getTopic() const; 88 | 89 | //! The full latency (in ms) from camera to your display excluding drawing time. 90 | int latency() const; 91 | 92 | //! The latency (in ms) from the camera to the reception of the image in this node. 93 | int networkLatency() const; 94 | 95 | //! The latency (in ms) from the reception of the image until it is in a displayable format. 96 | int processingLatency() const; 97 | 98 | //! The framerate (in frames per second). 99 | double framerate() const; 100 | 101 | private: 102 | std::shared_ptr subscription; 103 | QAbstractVideoSurface *surface = nullptr; 104 | std::function callback; 105 | double framerate_ = 0; 106 | int throttle_interval = 0; 107 | int network_latency = -1; 108 | int processing_latency = -1; 109 | 110 | friend class ImageTransportManager; 111 | }; 112 | } // namespace qml_ros_plugin 113 | 114 | #endif // QML_ROS_PLUGIN_IMAGE_TRANSPORT_MANAGER_H 115 | -------------------------------------------------------------------------------- /include/qml_ros_plugin/image_transport_subscriber.h: -------------------------------------------------------------------------------- 1 | // Copyright (c) 2019 Stefan Fabian. All rights reserved. 2 | // Licensed under the MIT license. See LICENSE file in the project root for full license information. 3 | 4 | #ifndef QML_ROS_PLUGIN_IMAGE_TRANSPORT_SUBSCRIBER_H 5 | #define QML_ROS_PLUGIN_IMAGE_TRANSPORT_SUBSCRIBER_H 6 | 7 | #include "qml_ros_plugin/node_handle.h" 8 | #include "qml_ros_plugin/qobject_ros.h" 9 | 10 | #include 11 | #include 12 | #include 13 | #include 14 | 15 | #include 16 | #include 17 | #include 18 | 19 | namespace qml_ros_plugin 20 | { 21 | 22 | class ImageTransportSubscriptionHandle; 23 | 24 | class ImageTransportSubscriber : public QObjectRos 25 | { 26 | Q_OBJECT 27 | // @formatter:off 28 | //! Interface for QML. This is the surface the images are passed to. 29 | Q_PROPERTY( QAbstractVideoSurface *videoSurface READ videoSurface WRITE setVideoSurface ) 30 | //! The image base topic (without image_raw etc.). This value may change once the subscriber is 31 | //! connected and private topic names or remappings were evaluated. 32 | Q_PROPERTY( QString topic READ topic WRITE setTopic NOTIFY topicChanged ) 33 | //! The default transport passed as transport hint. May be overridden by a parameter. (Default: compressed) 34 | Q_PROPERTY( QString defaultTransport READ defaultTransport WRITE setDefaultTransport NOTIFY 35 | defaultTransportChanged ) 36 | //! Whether or not this ImageTransportSubscriber is subscribed to the given topic 37 | Q_PROPERTY( bool subscribed READ subscribed NOTIFY subscribedChanged ) 38 | //! The latency from the sender to the received time in ms not including the conversion latency before displaying. 39 | //! This latency is based on the ROS time of the sending and receiving machines, hence, they need to be synchronized. 40 | Q_PROPERTY( int networkLatency READ networkLatency NOTIFY networkLatencyChanged ) 41 | //! The latency (in ms) from the reception of the image until it is in a displayable format. 42 | Q_PROPERTY( int processingLatency READ processingLatency NOTIFY processingLatencyChanged ) 43 | //! The full latency (in ms) from the camera to your display excluding drawing time. 44 | Q_PROPERTY( int latency READ latency NOTIFY latencyChanged ) 45 | //! The framerate of the received camera frames in frames per second. 46 | Q_PROPERTY( double framerate READ framerate NOTIFY framerateChanged ) 47 | //! The timeout when no image is received until a blank frame is served. Set to 0 to disable and 48 | //! always show last frame. Default is 3000 ms. 49 | Q_PROPERTY( int timeout READ timeout WRITE setTimeout NOTIFY timeoutChanged ) 50 | //! The update rate to throttle image receiving in images per second. Set to 0 to disable 51 | //! throttling. Default is 0 (disabled). 52 | Q_PROPERTY( double throttleRate READ throttleRate WRITE setThrottleRate NOTIFY throttleRateChanged ) 53 | //! Whether the subscriber is active or not. Setting to false will shut down subscribers 54 | Q_PROPERTY( bool enabled READ enabled WRITE setEnabled NOTIFY enabledChanged ) 55 | //! The playback state of this video source. Can be modified with play and pause 56 | Q_PROPERTY( QMediaPlayer::State playbackState READ playbackState NOTIFY playbackStateChanged ) 57 | // @formatter:on 58 | public: 59 | ImageTransportSubscriber( NodeHandle::Ptr nh, QString topic, quint32 queue_size ); 60 | 61 | ImageTransportSubscriber(); 62 | 63 | QAbstractVideoSurface *videoSurface() const; 64 | 65 | void setVideoSurface( QAbstractVideoSurface *surface ); 66 | 67 | QString topic() const; 68 | 69 | void setTopic( const QString &value ); 70 | 71 | const QString &defaultTransport() const; 72 | 73 | void setDefaultTransport( const QString &value ); 74 | 75 | bool subscribed() const; 76 | 77 | int timeout() const; 78 | 79 | void setTimeout( int value ); 80 | 81 | double throttleRate() const; 82 | 83 | void setThrottleRate( double value ); 84 | 85 | bool enabled() const; 86 | 87 | void setEnabled( bool value ); 88 | 89 | double framerate() const; 90 | 91 | int latency() const; 92 | 93 | int networkLatency() const; 94 | 95 | int processingLatency() const; 96 | 97 | QMediaPlayer::State playbackState() const; 98 | 99 | //! Starts playing the stream. If not enabled, will set enabled to true. 100 | Q_INVOKABLE void play(); 101 | 102 | //! Pauses the stream. Will not shut down the subscriber and therefore be quicker to resume at 103 | //! the cost of still consuming bandwidth. 104 | Q_INVOKABLE void pause(); 105 | 106 | //! Shuts down the subscriber. Similar as setEnabled. 107 | Q_INVOKABLE void stop(); 108 | 109 | signals: 110 | 111 | void topicChanged(); 112 | 113 | void defaultTransportChanged(); 114 | 115 | void subscribedChanged(); 116 | 117 | void timeoutChanged(); 118 | 119 | void throttleRateChanged(); 120 | 121 | void framerateChanged(); 122 | 123 | void latencyChanged(); 124 | 125 | void networkLatencyChanged(); 126 | 127 | void processingLatencyChanged(); 128 | 129 | void enabledChanged(); 130 | 131 | void playbackStateChanged( QMediaPlayer::State playbackState ); 132 | 133 | private slots: 134 | 135 | void onNodeHandleReady(); 136 | 137 | void onNoImageTimeout(); 138 | 139 | void presentFrame( const QVideoFrame &frame ); 140 | 141 | private: 142 | void onRosShutdown() override; 143 | 144 | void initSubscriber(); 145 | 146 | void shutdownSubscriber(); 147 | 148 | QTimer no_image_timer_; 149 | QVideoSurfaceFormat format_; 150 | QString topic_; 151 | QString default_transport_; 152 | QVideoFrame last_frame_; 153 | NodeHandle::Ptr nh_; 154 | std::shared_ptr subscription_; 155 | QAbstractVideoSurface *surface_ = nullptr; 156 | ros::Time last_frame_timestamp_; 157 | double last_framerate_ = 0; 158 | quint32 queue_size_; 159 | int throttle_interval_ = 0; 160 | int last_network_latency_ = -1; 161 | int last_processing_latency_ = -1; 162 | int timeout_ = 3000; 163 | bool subscribed_ = false; 164 | bool enabled_ = true; 165 | bool paused_ = false; 166 | }; 167 | } // namespace qml_ros_plugin 168 | 169 | #endif // QML_ROS_PLUGIN_IMAGE_TRANSPORT_SUBSCRIBER_H 170 | -------------------------------------------------------------------------------- /include/qml_ros_plugin/io.h: -------------------------------------------------------------------------------- 1 | // Copyright (c) 2020 Stefan Fabian. All rights reserved. 2 | // Licensed under the MIT license. See LICENSE file in the project root for full license information. 3 | 4 | #ifndef QML_ROS_PLUGIN_IO_H 5 | #define QML_ROS_PLUGIN_IO_H 6 | 7 | #include 8 | 9 | namespace qml_ros_plugin 10 | { 11 | 12 | class IO 13 | { 14 | Q_GADGET 15 | public: 16 | /*! 17 | * Writes the given value to the given path in the yaml format. 18 | * @param path The path to the file. 19 | * @param value The value to write. 20 | * @return True if successful, false otherwise. 21 | */ 22 | Q_INVOKABLE bool writeYaml( QString path, const QVariant &value ); 23 | 24 | /*! 25 | * Reads a yaml file and returns the content in a QML compatible structure of 'QVariantMap's and 'QVariantList's. 26 | * @param path The path to the file. 27 | * @return A variant containing the file content or false. 28 | */ 29 | Q_INVOKABLE QVariant readYaml( QString path ); 30 | }; 31 | } // namespace qml_ros_plugin 32 | 33 | Q_DECLARE_METATYPE( qml_ros_plugin::IO ); 34 | 35 | #endif // QML_ROS_PLUGIN_IO_H 36 | -------------------------------------------------------------------------------- /include/qml_ros_plugin/message_conversions.h: -------------------------------------------------------------------------------- 1 | // Copyright (c) 2019 Stefan Fabian. All rights reserved. 2 | // Licensed under the MIT license. See LICENSE file in the project root for full license information. 3 | 4 | #ifndef QML_ROS_PLUGIN_MESSAGE_CONVERSIONS_H 5 | #define QML_ROS_PLUGIN_MESSAGE_CONVERSIONS_H 6 | 7 | #include 8 | #include 9 | #include 10 | #include 11 | 12 | namespace qml_ros_plugin 13 | { 14 | 15 | /*! 16 | * @brief Converts between QVariant and ROS messages. 17 | * 18 | * Most types have a clear correspondence, e.g., all int fields smaller or equal to 32bit are mapped to int, all uint 19 | * smaller or equal to 32bit are mapped to uint. Larger are mapped to qlonglong and qulonglong (64bit). 20 | * 21 | * Noteworthy, however, are ros::Time and ros::Duration which are somewhat of a special case. 22 | * Whereas ros::Time is mapped to QDateTime, the difference of two datetimes in JS and QML is stored as double 23 | * representing the milliseconds. 24 | */ 25 | namespace conversion 26 | { 27 | template 28 | T &obtainValueAsReference( QVariant &value ) 29 | { 30 | return *reinterpret_cast( value.data() ); 31 | } 32 | 33 | template 34 | const T &obtainValueAsConstReference( const QVariant &value ) 35 | { 36 | return *reinterpret_cast( value.data() ); 37 | } 38 | 39 | QVariantMap msgToMap( const std_msgs::Header &msg ); 40 | 41 | QVariantMap msgToMap( const geometry_msgs::Vector3 &msg ); 42 | 43 | QVariantMap msgToMap( const geometry_msgs::Quaternion &msg ); 44 | 45 | QVariantMap msgToMap( const geometry_msgs::Transform &msg ); 46 | 47 | QVariantMap msgToMap( const geometry_msgs::TransformStamped &msg ); 48 | 49 | QVariantMap msgToMap( const actionlib_msgs::GoalID &msg ); 50 | 51 | QVariantMap msgToMap( const actionlib_msgs::GoalStatus &msg ); 52 | 53 | QVariant msgToMap( const ros_babel_fish::TranslatedMessage::ConstPtr &msg ); 54 | 55 | QVariant msgToMap( const ros_babel_fish::TranslatedMessage::ConstPtr &storage, 56 | const ros_babel_fish::Message &msg ); 57 | 58 | QVariant msgToMap( const ros_babel_fish::Message &msg ); 59 | 60 | bool fillMessage( ros_babel_fish::Message &msg, const QVariant &value ); 61 | 62 | bool fillMessage( ros_babel_fish::BabelFish &fish, ros_babel_fish::Message &msg, 63 | const QVariant &value ); 64 | } // namespace conversion 65 | } // namespace qml_ros_plugin 66 | 67 | #endif // QML_ROS_PLUGIN_MESSAGE_CONVERSIONS_H 68 | -------------------------------------------------------------------------------- /include/qml_ros_plugin/node_handle.h: -------------------------------------------------------------------------------- 1 | // Copyright (c) 2019 Stefan Fabian. All rights reserved. 2 | // Licensed under the MIT license. See LICENSE file in the project root for full license information. 3 | 4 | #ifndef QML_ROS_PLUGIN_NODE_HANDLE_H 5 | #define QML_ROS_PLUGIN_NODE_HANDLE_H 6 | 7 | #include "qml_ros_plugin/qobject_ros.h" 8 | #include 9 | 10 | namespace qml_ros_plugin 11 | { 12 | 13 | class NodeHandle : public QObjectRos, public std::enable_shared_from_this 14 | { 15 | Q_OBJECT 16 | 17 | // @formatter:off 18 | //! The NodeHandle namespace. Only valid after isReady is true. 19 | Q_PROPERTY( QString ns READ ns ) 20 | // @formatter:on 21 | public: 22 | typedef std::shared_ptr Ptr; 23 | typedef std::shared_ptr ConstPtr; 24 | 25 | explicit NodeHandle( std::string ns = std::string() ); 26 | 27 | explicit NodeHandle( std::shared_ptr queue, std::string ns = std::string() ); 28 | 29 | Q_INVOKABLE QObject *advertise( const QString &type, const QString &topic, quint32 queue_size, 30 | bool latch = false ); 31 | 32 | bool isReady() const; 33 | 34 | ros::NodeHandle &nodeHandle(); 35 | 36 | QString ns() const; 37 | 38 | signals: 39 | 40 | void ready(); 41 | 42 | protected: 43 | void onRosInitialized() override; 44 | 45 | std::shared_ptr queue_; 46 | std::unique_ptr nh_; 47 | std::string ns_; 48 | }; 49 | } // namespace qml_ros_plugin 50 | 51 | #endif // QML_ROS_PLUGIN_NODE_HANDLE_H 52 | -------------------------------------------------------------------------------- /include/qml_ros_plugin/package.h: -------------------------------------------------------------------------------- 1 | // Copyright (c) 2020 Stefan Fabian. All rights reserved. 2 | // Licensed under the MIT license. See LICENSE file in the project root for full license information. 3 | 4 | #ifndef QML_ROS_PLUGIN_PACKAGE_H 5 | #define QML_ROS_PLUGIN_PACKAGE_H 6 | 7 | #include 8 | 9 | namespace qml_ros_plugin 10 | { 11 | 12 | /*! 13 | * A wrapper for ros::package 14 | */ 15 | class Package 16 | { 17 | Q_GADGET 18 | 19 | public: 20 | /*! 21 | * Runs a command of the form 'rospack '. (This does not make a subprocess call!) 22 | * @param cmd The command passed to rospack. 23 | * @return The output of the command as a string. 24 | */ 25 | Q_INVOKABLE QString command( const QString &cmd ); 26 | 27 | /*! 28 | * Queries the path to a package. 29 | * @param package_name The name of the package. 30 | * @return The fully-qualified path to the given package or an empty string if the package is not found. 31 | */ 32 | Q_INVOKABLE QString getPath( const QString &package_name ); 33 | 34 | /*! 35 | * @return A list of all packages. 36 | */ 37 | Q_INVOKABLE QStringList getAll(); 38 | 39 | /*! 40 | * Queries for all plugins exported for a given package. 41 | * 42 | * @code{.xml} 43 | * 44 | * 45 | * 46 | * 47 | * @endcode 48 | * 49 | * To query for rviz plugins you would pass 'rviz' as the name and 'plugin' as the attribute. 50 | * 51 | * @param name The name of the export tag. 52 | * @param attribute The name of the attribute for the value is obtained. 53 | * @param force_recrawl Forces rospack to rediscover everything on the system before running the search. 54 | * @return A map with the name of the package exporting something for name as the key (string) and a QStringList 55 | * containing all exported values as the value. 56 | */ 57 | Q_INVOKABLE QVariantMap getPlugins( const QString &name, const QString &attribute, 58 | bool force_recrawl = false ); 59 | }; 60 | } // namespace qml_ros_plugin 61 | 62 | Q_DECLARE_METATYPE( qml_ros_plugin::Package ); 63 | 64 | #endif // QML_ROS_PLUGIN_PACKAGE_H 65 | -------------------------------------------------------------------------------- /include/qml_ros_plugin/publisher.h: -------------------------------------------------------------------------------- 1 | // Copyright (c) 2019 Stefan Fabian. All rights reserved. 2 | // Licensed under the MIT license. See LICENSE file in the project root for full license information. 3 | 4 | #ifndef QML_ROS_PLUGIN_PUBLISHER_H 5 | #define QML_ROS_PLUGIN_PUBLISHER_H 6 | 7 | #include "qml_ros_plugin/node_handle.h" 8 | 9 | #include 10 | #include 11 | #include 12 | #include 13 | 14 | #include 15 | 16 | #include 17 | #include 18 | 19 | namespace qml_ros_plugin 20 | { 21 | 22 | class Publisher : public QObject 23 | { 24 | Q_OBJECT 25 | // @formatter:off 26 | //! The type of the published messages, e.g., geometry_msgs/Pose. 27 | Q_PROPERTY( QString type READ type ) 28 | //! The topic this Publisher publishes messages on. This property is only valid if the publisher is already advertised! 29 | Q_PROPERTY( QString topic READ topic ) 30 | //! Whether or not this Publisher is latched. A latched Publisher always sends the last message to new subscribers. 31 | Q_PROPERTY( bool isLatched READ isLatched ) 32 | //! The queue size of this Publisher. This is the maximum number of messages that are queued for delivery to subscribers at a time. 33 | Q_PROPERTY( quint32 queueSize READ queueSize ) 34 | //! Whether or not this publisher has advertised its existence on its topic. 35 | //! Reasons for not being advertised include ROS not being initialized yet. 36 | Q_PROPERTY( bool isAdvertised READ isAdvertised NOTIFY advertised ) 37 | // @formatter:on 38 | public: 39 | Publisher( NodeHandle::Ptr nh, QString type, QString topic, uint32_t queue_size, bool latch ); 40 | 41 | ~Publisher() override; 42 | 43 | QString topic() const; 44 | 45 | const QString &type() const; 46 | 47 | bool isLatched() const; 48 | 49 | quint32 queueSize() const; 50 | 51 | bool isAdvertised() const; 52 | 53 | //! @return The number of subscribers currently connected to this Publisher. 54 | Q_INVOKABLE unsigned int getNumSubscribers(); 55 | 56 | /*! 57 | * Sends a message to subscribers currently connected to this Publisher. 58 | * @param msg The message that is published. 59 | * @return True if the message was sent successfully, false otherwise. 60 | */ 61 | Q_INVOKABLE bool publish( const QVariantMap &msg ); 62 | 63 | signals: 64 | 65 | /*! 66 | * Fired once this Publisher was advertised. 67 | * This is either done at construction or immediately after ROS is initialized. 68 | * Since this is only fired once, you should check if the Publisher is already advertised using the isAdvertised property. 69 | */ 70 | void advertised(); 71 | 72 | //! Fired whenever a new subscriber connects to this Publisher. 73 | void connected(); 74 | 75 | //! Fired whenever a subscriber disconnects from this Publisher. 76 | void disconnected(); 77 | 78 | protected slots: 79 | 80 | void onNodeHandleReady(); 81 | 82 | protected: 83 | void advertise(); 84 | 85 | void onSubscriberConnected( const ros::SingleSubscriberPublisher &pub ); 86 | 87 | void onSubscriberDisconnected( const ros::SingleSubscriberPublisher &pub ); 88 | 89 | NodeHandle::Ptr nh_; 90 | ros::Publisher publisher_; 91 | ros_babel_fish::BabelFish babel_fish_; 92 | 93 | bool is_advertised_; 94 | QString type_; 95 | std::string std_type_; 96 | QString topic_; 97 | bool is_latched_; 98 | uint32_t queue_size_; 99 | }; 100 | } // namespace qml_ros_plugin 101 | 102 | #endif // QML_ROS_PLUGIN_PUBLISHER_H 103 | -------------------------------------------------------------------------------- /include/qml_ros_plugin/qml_ros_conversion.h: -------------------------------------------------------------------------------- 1 | // Copyright (c) 2019 Stefan Fabian. All rights reserved. 2 | // Licensed under the MIT license. See LICENSE file in the project root for full license information. 3 | 4 | #ifndef QML_ROS_PLUGIN_QML_ROS_CONVERSION_H 5 | #define QML_ROS_PLUGIN_QML_ROS_CONVERSION_H 6 | 7 | #include 8 | #include 9 | #include 10 | 11 | namespace qml_ros_plugin 12 | { 13 | 14 | inline ros::Duration qmlToRosDuration( double milliseconds ) 15 | { 16 | return ros::Duration( milliseconds * 1E-3 ); 17 | } 18 | 19 | inline ros::Time qmlToRosTime( double milliseconds_since_epoch ) 20 | { 21 | return ros::Time( milliseconds_since_epoch * 1E-3 ); 22 | } 23 | 24 | inline ros::Time qmlToRosTime( const QDateTime &time ) 25 | { 26 | if ( !time.isValid() ) 27 | return ros::Time( 0 ); 28 | qint64 msecs = time.toMSecsSinceEpoch(); 29 | uint32_t secs = msecs / 1000; 30 | return { secs, static_cast( msecs - 1000 * secs ) * 1000 * 1000 }; 31 | } 32 | 33 | inline double rosToQmlDuration( const ros::Duration &duration ) 34 | { 35 | return duration.sec * 1E3 + duration.nsec * 1E-6; 36 | } 37 | 38 | inline QDateTime rosToQmlTime( const ros::Time &time ) 39 | { 40 | // Always round down because otherwise high precision stuff like tf might fail due to, e.g., look up into future 41 | return QDateTime::fromMSecsSinceEpoch( time.sec * 1E3 + time.nsec * 1E-6 ); 42 | } 43 | 44 | inline QDateTime rosToQmlTime( const ros::WallTime &time ) 45 | { 46 | return QDateTime::fromMSecsSinceEpoch( time.sec * 1E3 + time.nsec * 1E-6 ); 47 | } 48 | } // namespace qml_ros_plugin 49 | 50 | #endif // QML_ROS_PLUGIN_QML_ROS_CONVERSION_H 51 | -------------------------------------------------------------------------------- /include/qml_ros_plugin/qobject_ros.h: -------------------------------------------------------------------------------- 1 | // Copyright (c) 2019 Stefan Fabian. All rights reserved. 2 | // Licensed under the MIT license. See LICENSE file in the project root for full license information. 3 | 4 | #ifndef QML_ROS_PLUGIN_QOBJECT_ROS_H 5 | #define QML_ROS_PLUGIN_QOBJECT_ROS_H 6 | 7 | #include 8 | 9 | namespace qml_ros_plugin 10 | { 11 | 12 | /*! 13 | * Base class for QObjects that require ROS functionality. 14 | * Provides virtual methods that are called once ROS was initialized and once it was shutdown to 15 | * enable initialization and clean-up of of functionality that requires ROS. 16 | */ 17 | class QObjectRos : public QObject 18 | { 19 | Q_OBJECT 20 | public: 21 | explicit QObjectRos( QObject *parent = nullptr ); 22 | 23 | ~QObjectRos() override; 24 | 25 | //! @return Whether or not this object is initialized. 26 | bool isInitialized() const; 27 | 28 | protected: 29 | /*! 30 | * Called once ROS was initialized in this application. 31 | * 32 | * Override to perform initialization of functionality that depends on ROS. 33 | */ 34 | virtual void onRosInitialized() { } 35 | 36 | /*! 37 | * Called once ROS or the application shuts down. 38 | * 39 | * Override to perform clean-up of functionality that depends on ROS, e.g., if the destruction 40 | * order does not guarantee destruction before required ROS objects are destructed. 41 | */ 42 | virtual void onRosShutdown() { } 43 | 44 | public slots: 45 | void _initialize(); 46 | 47 | void _shutdown(); 48 | 49 | private: 50 | bool is_initialized_; 51 | }; 52 | } // namespace qml_ros_plugin 53 | 54 | #endif // QML_ROS_PLUGIN_QOBJECT_ROS_H 55 | -------------------------------------------------------------------------------- /include/qml_ros_plugin/service.h: -------------------------------------------------------------------------------- 1 | // Copyright (c) 2019 Stefan Fabian. All rights reserved. 2 | // Licensed under the MIT license. See LICENSE file in the project root for full license information. 3 | 4 | #ifndef QML_ROS_PLUGIN_SERVICE_H 5 | #define QML_ROS_PLUGIN_SERVICE_H 6 | 7 | #include 8 | #include 9 | 10 | #include 11 | 12 | namespace qml_ros_plugin 13 | { 14 | 15 | class Service : public QObject 16 | { 17 | Q_OBJECT 18 | public: 19 | Service(); 20 | 21 | /*! 22 | * Calls a service and returns the result. 23 | * 24 | * @param service The service topic. 25 | * @param type The type of the service, e.g., "roscpp_tutorials/TwoInts" 26 | * @param req The service request, i.e., a filled request message of the service type, e.g., "roscpp_tutorials/TwoIntsRequest" 27 | * @return False, if request was not successful, true if the response message is empty and the translated service 28 | * response, e.g., "roscpp_tutorials/TwoIntsResponse", otherwise. 29 | */ 30 | Q_INVOKABLE QVariant call( const QString &service, const QString &type, const QVariantMap &req ); 31 | 32 | /*! 33 | * Calls a service asynchronously returning immediately. 34 | * Once the service call finishes, the optional callback is called with the result if provided. 35 | * 36 | * @param service The service topic. 37 | * @param type The type of the service, e.g., "roscpp_tutorials/TwoInts" 38 | * @param req The service request, i.e., a filled request message of the service type, e.g., "roscpp_tutorials/TwoIntsRequest" 39 | * @param callback The callback that is called once the service has finished. 40 | */ 41 | Q_INVOKABLE void callAsync( const QString &service, const QString &type, const QVariantMap &req, 42 | const QJSValue &callback = QJSValue() ); 43 | 44 | private slots: 45 | void invokeCallback( int id, QVariant result ); 46 | 47 | private: 48 | // Store callbacks in map as they may not be copied to a different thread 49 | QMap callbacks_; 50 | ros_babel_fish::BabelFish babel_fish_; 51 | int id_counter_; 52 | }; 53 | } // namespace qml_ros_plugin 54 | 55 | #endif // QML_ROS_PLUGIN_SERVICE_H 56 | -------------------------------------------------------------------------------- /include/qml_ros_plugin/subscriber.h: -------------------------------------------------------------------------------- 1 | // Copyright (c) 2019 Stefan Fabian. All rights reserved. 2 | // Licensed under the MIT license. See LICENSE file in the project root for full license information. 3 | 4 | #ifndef QML_ROS_PLUGIN_SUBSCRIBER_H 5 | #define QML_ROS_PLUGIN_SUBSCRIBER_H 6 | 7 | #include "qml_ros_plugin/node_handle.h" 8 | #include "qml_ros_plugin/qobject_ros.h" 9 | 10 | #include 11 | #include 12 | #include 13 | 14 | #include 15 | #include 16 | 17 | #include 18 | #include 19 | 20 | namespace qml_ros_plugin 21 | { 22 | class NodeHandle; 23 | 24 | class Subscriber : public QObjectRos 25 | { 26 | Q_OBJECT 27 | // @formatter:off 28 | //! The topic this subscriber subscribes to. 29 | Q_PROPERTY( QString topic READ topic WRITE setTopic NOTIFY topicChanged ) 30 | //! The maximum number of messages that are queued for processing. Default: 10 31 | Q_PROPERTY( quint32 queueSize READ queueSize WRITE setQueueSize NOTIFY queueSizeChanged ) 32 | 33 | //! The namespace of the NodeHandle created for this subscriber. 34 | Q_PROPERTY( QString ns READ ns WRITE setNs NOTIFY nsChanged ) 35 | 36 | //! The last message that was received by this subscriber. 37 | Q_PROPERTY( QVariant message READ message NOTIFY messageChanged ) 38 | 39 | //! The type of the last received message, e.g., geometry_msgs/Pose. 40 | Q_PROPERTY( QString messageType READ messageType NOTIFY messageTypeChanged ) 41 | 42 | //! Limits the frequency in which the notification for an updated message is emitted. Default: 20 Hz 43 | Q_PROPERTY( int throttleRate READ throttleRate WRITE setThrottleRate NOTIFY throttleRateChanged ) 44 | 45 | //! Controls whether or not the subscriber is currently running, i.e., able to receive messages. Default: true 46 | Q_PROPERTY( bool running READ running WRITE setRunning NOTIFY runningChanged ) 47 | // @formatter:on 48 | public: 49 | Subscriber(); 50 | 51 | explicit Subscriber( NodeHandle::Ptr nh, QString topic, quint32 queue_size, bool running = true ); 52 | 53 | ~Subscriber() override; 54 | 55 | QString topic() const; 56 | 57 | void setTopic( const QString &value ); 58 | 59 | quint32 queueSize() const; 60 | 61 | void setQueueSize( quint32 value ); 62 | 63 | QString ns() const; 64 | 65 | void setNs( const QString &value ); 66 | 67 | bool running() const; 68 | 69 | void setRunning( bool value ); 70 | 71 | int throttleRate() const; 72 | 73 | void setThrottleRate( int value ); 74 | 75 | const QVariant &message() const; 76 | 77 | const QString &messageType() const; 78 | 79 | //! @return The number of publishers this subscriber is connected to. 80 | Q_INVOKABLE unsigned int getNumPublishers(); 81 | 82 | signals: 83 | 84 | //! Emitted when the topic changed. 85 | void topicChanged(); 86 | 87 | //! Emitted when the queueSize changed. 88 | void queueSizeChanged(); 89 | 90 | //! Emitted when the namespace ns changed. 91 | void nsChanged(); 92 | 93 | //! Emitted when the throttle rate was changed. 94 | void throttleRateChanged(); 95 | 96 | //! Emitted if the running state of this subscriber changed. 97 | void runningChanged(); 98 | 99 | //! Emitted whenever a new message was received. 100 | void messageChanged(); 101 | 102 | //! Emitted whenever the type of the last received message changed. 103 | void messageTypeChanged(); 104 | 105 | /*! 106 | * Emitted whenever a new message was received. 107 | * @param message The received message. 108 | */ 109 | void newMessage( QVariant message ); 110 | 111 | protected slots: 112 | 113 | void subscribe(); 114 | 115 | void updateMessage(); 116 | 117 | protected: 118 | void initTimer(); 119 | 120 | void onRosInitialized() override; 121 | 122 | void shutdown(); 123 | 124 | void messageCallback( const ros_babel_fish::BabelFishMessage::ConstPtr &msg ); 125 | 126 | NodeHandle::Ptr nh_; 127 | ros::Subscriber subscriber_; 128 | ros_babel_fish::BabelFish babel_fish_; 129 | ros_babel_fish::BabelFishMessage::ConstPtr last_message_; 130 | std::mutex message_mutex_; 131 | QTimer throttle_timer_; 132 | bool running_; 133 | bool is_subscribed_; 134 | 135 | QString topic_; 136 | QString message_type_; 137 | QVariant message_; 138 | quint32 queue_size_; 139 | int throttle_rate_ = 20; 140 | }; 141 | } // namespace qml_ros_plugin 142 | 143 | #endif // QML_ROS_PLUGIN_SUBSCRIBER_H 144 | -------------------------------------------------------------------------------- /include/qml_ros_plugin/tf_transform.h: -------------------------------------------------------------------------------- 1 | // Copyright (c) 2019 Stefan Fabian. All rights reserved. 2 | // Licensed under the MIT license. See LICENSE file in the project root for full license information. 3 | 4 | #ifndef QML_ROS_PLUGIN_TF_TRANSFORM_H 5 | #define QML_ROS_PLUGIN_TF_TRANSFORM_H 6 | 7 | #include 8 | #include 9 | #include 10 | #include 11 | 12 | namespace boost 13 | { 14 | namespace signals2 15 | { 16 | class connection; 17 | } 18 | } // namespace boost 19 | 20 | namespace qml_ros_plugin 21 | { 22 | /*! 23 | * Represents a tf transform between source and target frame. 24 | */ 25 | class TfTransform : public QObject 26 | { 27 | Q_OBJECT 28 | // @formatter:off 29 | //! The source frame of the tf transform, i.e., the frame where the data originated. 30 | Q_PROPERTY( QString sourceFrame READ sourceFrame WRITE setSourceFrame NOTIFY sourceFrameChanged ) 31 | 32 | //! The target frame of the tf transform, i.e., the frame to which the data should be transformed. 33 | Q_PROPERTY( QString targetFrame READ targetFrame WRITE setTargetFrame NOTIFY targetFrameChanged ) 34 | 35 | //! Whether this tf transform is enabled, i.e., receiving transform updates. 36 | Q_PROPERTY( bool enabled READ enabled WRITE setEnabled NOTIFY enabledChanged ) 37 | //! Alias for enabled 38 | Q_PROPERTY( bool active READ enabled WRITE setEnabled NOTIFY enabledChanged ) 39 | 40 | //! The last received transform as a geometry_msgs/TransformStamped with an added boolean valid 41 | //! field and optional error fields. See TfTransformListener::lookUpTransform 42 | Q_PROPERTY( QVariantMap transform READ message NOTIFY messageChanged ) 43 | //! An alias for transform. 44 | Q_PROPERTY( QVariantMap message READ message NOTIFY messageChanged ) 45 | 46 | //! The translation part of the tf transform as a vector with x, y, z fields. Zero if no valid transform available (yet). 47 | Q_PROPERTY( QVariant translation READ translation NOTIFY translationChanged ) 48 | 49 | //! The rotation part of the tf transform as a quaternion with w, x, y, z fields. Identity if no valid transform available (yet). 50 | Q_PROPERTY( QVariant rotation READ rotation NOTIFY rotationChanged ) 51 | 52 | //! The maximum rate in Hz at which tf updates are processed and emitted as changed signals. 53 | //! Default: 60 Note: The rate can not exceed 1000. To disable rate limiting set to 0. 54 | Q_PROPERTY( qreal rate READ rate WRITE setRate NOTIFY rateChanged ) 55 | 56 | //! Whether the current transform, i.e., the fields message, translation and rotation are valid. 57 | Q_PROPERTY( bool valid READ valid NOTIFY validChanged ) 58 | // @formatter:on 59 | public: 60 | TfTransform(); 61 | 62 | ~TfTransform() override; 63 | 64 | const QString &sourceFrame() const; 65 | 66 | void setSourceFrame( const QString &value ); 67 | 68 | const QString &targetFrame() const; 69 | 70 | void setTargetFrame( const QString &targetFrame ); 71 | 72 | bool enabled() const; 73 | 74 | void setEnabled( bool value ); 75 | 76 | qreal rate() const; 77 | 78 | void setRate( qreal value ); 79 | 80 | const QVariantMap &message(); 81 | 82 | const QVariant &translation(); 83 | 84 | const QVariant &rotation(); 85 | 86 | bool valid(); 87 | 88 | signals: 89 | 90 | void sourceFrameChanged(); 91 | 92 | void targetFrameChanged(); 93 | 94 | void enabledChanged(); 95 | 96 | void rateChanged(); 97 | 98 | void messageChanged(); 99 | 100 | void translationChanged(); 101 | 102 | void rotationChanged(); 103 | 104 | void validChanged(); 105 | 106 | protected slots: 107 | 108 | void onTransformChanged(); 109 | 110 | void updateMessage(); 111 | 112 | protected: 113 | void subscribe(); 114 | 115 | void shutdown(); 116 | 117 | QTimer throttle_timer_; 118 | QVariantMap message_; 119 | QString source_frame_; 120 | QString target_frame_; 121 | std::chrono::system_clock::time_point last_transform_; 122 | std::chrono::milliseconds throttle_time_; 123 | bool enabled_; 124 | }; 125 | } // namespace qml_ros_plugin 126 | 127 | #endif // QML_ROS_PLUGIN_TF_TRANSFORM_H 128 | -------------------------------------------------------------------------------- /include/qml_ros_plugin/time.h: -------------------------------------------------------------------------------- 1 | // Copyright (c) 2019 Stefan Fabian. All rights reserved. 2 | // Licensed under the MIT license. See LICENSE file in the project root for full license information. 3 | 4 | #ifndef QML_ROS_PLUGIN_TIME_H 5 | #define QML_ROS_PLUGIN_TIME_H 6 | 7 | #include "qml_ros_plugin/qml_ros_conversion.h" 8 | #include "qml_ros_plugin/qobject_ros.h" 9 | 10 | #include 11 | #include 12 | 13 | namespace qml_ros_plugin 14 | { 15 | 16 | template 17 | class TimeWrapper 18 | { 19 | public: 20 | explicit TimeWrapper( const RosTime &time = RosTime() ) : time_( time ) { } 21 | 22 | quint32 sec() const { return time_.sec; } 23 | 24 | void setSec( quint32 value ) { time_.sec = value; } 25 | 26 | quint32 nsec() const { return time_.nsec; } 27 | 28 | void setNSec( quint32 value ) { time_.nsec = value; } 29 | 30 | RosTime getRosTime() const { return time_; } 31 | 32 | protected: 33 | RosTime time_; 34 | }; 35 | 36 | /*! 37 | * Represents a point in time of the robot or simulation. 38 | * 39 | * Properties: 40 | * - sec: unsigned integer containing the seconds passed since 1970 41 | * - nsec: unsigned integer containing the nanoseconds since the last second 42 | */ 43 | class Time : public TimeWrapper 44 | { 45 | Q_GADGET 46 | Q_PROPERTY( quint32 sec READ sec WRITE setSec ) 47 | Q_PROPERTY( quint32 nsec READ nsec WRITE setNSec ) 48 | public: 49 | explicit Time( const ros::Time &time = ros::Time() ) : TimeWrapper( time ) { } 50 | 51 | //! The time in seconds (since 1970) as a decimal value. (Possible loss in precision) 52 | Q_INVOKABLE double toSec() const { return time_.toSec(); } 53 | 54 | //! The time in nanoseconds (since 1970) as an unsigned integer. 55 | Q_INVOKABLE quint64 toNSec() const { return time_.toNSec(); } 56 | 57 | //! Whether the time represented by this instance is zero. 58 | Q_INVOKABLE bool isZero() const { return time_.isZero(); } 59 | 60 | //! A JS Date representing the value stored in this instance. 61 | //! Since JS Dates only have millisecond accuracy, information about microseconds and nanoseconds 62 | //! are lost. The time is always rounded down to prevent the JS Date from being in the future. 63 | Q_INVOKABLE QVariant toJSDate() const { return QVariant::fromValue( rosToQmlTime( time_ ) ); } 64 | }; 65 | 66 | /*! 67 | * Represents a point in time of the current system. 68 | * 69 | * Properties: 70 | * - sec: unsigned integer containing the seconds passed since 1970 71 | * - nsec: unsigned integer containing the nanoseconds since the last second 72 | */ 73 | class WallTime : public TimeWrapper 74 | { 75 | Q_GADGET 76 | Q_PROPERTY( quint32 sec READ sec WRITE setSec ) 77 | Q_PROPERTY( quint32 nsec READ nsec WRITE setNSec ) 78 | public: 79 | explicit WallTime( const ros::WallTime &time = ros::WallTime() ) 80 | : TimeWrapper( time ) 81 | { 82 | } 83 | 84 | //! The time in seconds (since 1970) as a decimal value. (Possible loss in precision) 85 | Q_INVOKABLE double toSec() const { return time_.toSec(); } 86 | 87 | //! The time in nanoseconds (since 1970) as an unsigned integer. 88 | Q_INVOKABLE quint64 toNSec() const { return time_.toNSec(); } 89 | 90 | //! Whether the time represented by this instance is zero. 91 | Q_INVOKABLE bool isZero() const { return time_.isZero(); } 92 | 93 | //! A JS Date representing the value stored in this instance. 94 | //! Since JS Dates only have millisecond accuracy, information about microseconds and nanoseconds 95 | //! are lost. The time is always rounded down to prevent the JS Date from being in the future. 96 | Q_INVOKABLE QVariant toJSDate() const { return QVariant::fromValue( rosToQmlTime( time_ ) ); } 97 | }; 98 | 99 | class TimeSingleton : public QObject 100 | { 101 | Q_OBJECT 102 | public: 103 | /*! 104 | * Returns the ros::Time as Time. 105 | * This can be either the simulation time or the system time. 106 | * 107 | * Before the ros::Time got valid, this method returns a zero Time. 108 | */ 109 | Q_INVOKABLE QVariant now(); 110 | 111 | //! Creates a Time instance from the given time in seconds since 1970. 112 | Q_INVOKABLE QVariant create( double t ); 113 | 114 | //! Creates a Time instance from the given time in seconds since 1970 and nanoseconds since the last full second. 115 | Q_INVOKABLE QVariant create( quint32 sec, quint32 nsec ); 116 | 117 | //! Whether the time obtained using now() is the simulation time 118 | Q_INVOKABLE bool isSimTime(); 119 | 120 | //! Whether the time obtained using now() is the system time 121 | Q_INVOKABLE bool isSystemTime(); 122 | 123 | //! Whether the time obtained with now() is currently valid. 124 | Q_INVOKABLE bool isValid(); 125 | }; 126 | 127 | class WallTimeSingleton : public QObject 128 | { 129 | Q_OBJECT 130 | public: 131 | /*! 132 | * Returns the ros::WallTime as WallTime. 133 | * This is always the system time. 134 | */ 135 | Q_INVOKABLE QVariant now(); 136 | 137 | //! Creates a WallTime instance from the given time in seconds since 1970. 138 | Q_INVOKABLE QVariant create( double t ); 139 | 140 | //! Creates a WallTime instance from the given time in seconds since 1970 and nanoseconds since the last full second. 141 | Q_INVOKABLE QVariant create( quint32 sec, quint32 nsec ); 142 | }; 143 | } // namespace qml_ros_plugin 144 | 145 | // Register Time types 146 | Q_DECLARE_METATYPE( qml_ros_plugin::Time ); 147 | 148 | Q_DECLARE_METATYPE( qml_ros_plugin::WallTime ); 149 | 150 | #endif // QML_ROS_PLUGIN_TIME_H 151 | -------------------------------------------------------------------------------- /include/qml_ros_plugin/topic_info.h: -------------------------------------------------------------------------------- 1 | // Copyright (c) 2020 Stefan Fabian. All rights reserved. 2 | // Licensed under the MIT license. See LICENSE file in the project root for full license information. 3 | 4 | #ifndef QML_ROS_PLUGIN_TOPIC_INFO_H 5 | #define QML_ROS_PLUGIN_TOPIC_INFO_H 6 | 7 | #include 8 | #include 9 | #include 10 | 11 | namespace qml_ros_plugin 12 | { 13 | 14 | class TopicInfo 15 | { 16 | Q_GADGET 17 | // @formatter:off 18 | //! The name of the topic, e.g., /front_camera/image_raw 19 | Q_PROPERTY( QString name READ name ) 20 | //! The datatype of the topic, e.g., sensor_msgs/Image 21 | Q_PROPERTY( QString datatype READ datatype ) 22 | // @formatter:on 23 | public: 24 | TopicInfo() = default; 25 | 26 | TopicInfo( QString name, QString datatype ) 27 | : name_( std::move( name ) ), datatype_( std::move( datatype ) ) 28 | { 29 | } 30 | 31 | const QString &name() const { return name_; } 32 | 33 | const QString &datatype() const { return datatype_; } 34 | 35 | private: 36 | QString name_; 37 | QString datatype_; 38 | }; 39 | } // namespace qml_ros_plugin 40 | 41 | Q_DECLARE_METATYPE( qml_ros_plugin::TopicInfo ); 42 | 43 | #endif // QML_ROS_PLUGIN_TOPIC_INFO_H 44 | -------------------------------------------------------------------------------- /package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | qml_ros_plugin 4 | 1.0.0 5 | The qml_ros_plugin package 6 | 7 | 8 | 9 | 10 | Stefan Fabian 11 | 12 | 13 | 14 | 15 | 16 | MIT 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | 26 | 27 | 28 | 29 | 30 | 31 | 32 | 33 | 34 | 35 | 36 | 37 | 38 | 39 | 40 | 41 | 42 | 43 | 44 | 45 | 46 | 47 | 48 | 49 | 50 | 51 | catkin 52 | 53 | actionlib 54 | roscpp 55 | image_transport 56 | ros_babel_fish 57 | tf2_ros 58 | libqt5-core 59 | libqt5-multimedia 60 | libqt5-qml 61 | libqt5-quick 62 | yaml-cpp 63 | qtbase5-dev 64 | qtdeclarative5-dev 65 | qtmultimedia5-dev 66 | qml-module-qtquick2 67 | roscpp_tutorials 68 | rostest 69 | ros_babel_fish_test_msgs 70 | std_srvs 71 | 72 | 73 | 74 | 75 | 76 | 77 | 78 | -------------------------------------------------------------------------------- /qmldir: -------------------------------------------------------------------------------- 1 | module Ros 2 | plugin qml_ros_plugin -------------------------------------------------------------------------------- /src/babel_fish_dispenser.cpp: -------------------------------------------------------------------------------- 1 | // Copyright (c) 2019 Stefan Fabian. All rights reserved. 2 | // Licensed under the MIT license. See LICENSE file in the project root for full license information. 3 | 4 | #include "qml_ros_plugin/babel_fish_dispenser.h" 5 | 6 | namespace qml_ros_plugin 7 | { 8 | 9 | BabelFishDispenser::BabelFishDispenser() = default; 10 | 11 | ros_babel_fish::BabelFish BabelFishDispenser::getBabelFish() 12 | { 13 | static BabelFishDispenser dispenser; 14 | return dispenser.createBabelFish(); 15 | } 16 | 17 | ros_babel_fish::BabelFish BabelFishDispenser::createBabelFish() 18 | { 19 | if ( description_provider_ != nullptr ) 20 | return ros_babel_fish::BabelFish( description_provider_ ); 21 | ros_babel_fish::BabelFish babel_fish; 22 | description_provider_ = babel_fish.descriptionProvider(); 23 | return babel_fish; 24 | } 25 | } // namespace qml_ros_plugin 26 | -------------------------------------------------------------------------------- /src/console.cpp: -------------------------------------------------------------------------------- 1 | // Copyright (c) 2020 Stefan Fabian. All rights reserved. 2 | // Licensed under the MIT license. See LICENSE file in the project root for full license information. 3 | 4 | #include "qml_ros_plugin/console.h" 5 | 6 | namespace qml_ros_plugin 7 | { 8 | 9 | bool Console::setLoggerLevel( const QString &ros_console_name, 10 | ros_console_levels::RosConsoleLevel level ) 11 | { 12 | if ( !ros::console::set_logger_level( ros_console_name.toStdString(), 13 | static_cast( level ) ) ) 14 | return false; 15 | ros::console::notifyLoggerLevelsChanged(); 16 | return true; 17 | } 18 | 19 | QString Console::defaultName() const { return ROSCONSOLE_DEFAULT_NAME; } 20 | } // namespace qml_ros_plugin 21 | -------------------------------------------------------------------------------- /src/goal_handle.cpp: -------------------------------------------------------------------------------- 1 | // Copyright (c) 2020 Stefan Fabian. All rights reserved. 2 | // Licensed under the MIT license. See LICENSE file in the project root for full license information. 3 | 4 | #include "qml_ros_plugin/goal_handle.h" 5 | #include "qml_ros_plugin/babel_fish_dispenser.h" 6 | #include "qml_ros_plugin/message_conversions.h" 7 | 8 | using namespace ros_babel_fish; 9 | using namespace qml_ros_plugin::conversion; 10 | 11 | namespace qml_ros_plugin 12 | { 13 | 14 | GoalHandle::GoalHandle( 15 | std::shared_ptr> client, 16 | const actionlib::ActionClient::GoalHandle &handle ) 17 | : client_( std::move( client ) ), goal_handle_( handle ) 18 | { 19 | babel_fish_ = BabelFishDispenser::getBabelFish(); 20 | } 21 | 22 | void GoalHandle::cancel() { goal_handle_.cancel(); } 23 | 24 | bool GoalHandle::expired() const { return goal_handle_.isExpired(); } 25 | 26 | void GoalHandle::resend() { goal_handle_.resend(); } 27 | 28 | qml_ros_plugin::action_comm_states::CommState GoalHandle::commState() const 29 | { 30 | return static_cast( 31 | goal_handle_.getCommState().state_ ); 32 | } 33 | 34 | TerminalState GoalHandle::terminalState() const 35 | { 36 | const actionlib::TerminalState &state = goal_handle_.getTerminalState(); 37 | return { static_cast( state.state_ ), 38 | QString::fromStdString( state.text_ ) }; 39 | } 40 | 41 | QVariant GoalHandle::getResult() 42 | { 43 | BabelFishMessage::ConstPtr result = goal_handle_.getResult(); 44 | if ( result == nullptr ) 45 | return {}; 46 | TranslatedMessage::Ptr translated = babel_fish_.translateMessage( result ); 47 | return msgToMap( translated, translated->translated_message->as() ); 48 | } 49 | } // namespace qml_ros_plugin 50 | -------------------------------------------------------------------------------- /src/io.cpp: -------------------------------------------------------------------------------- 1 | // Copyright (c) 2020 Stefan Fabian. All rights reserved. 2 | // Licensed under the MIT license. See LICENSE file in the project root for full license information. 3 | 4 | #include "qml_ros_plugin/io.h" 5 | #include "qml_ros_plugin/array.h" 6 | #include "qml_ros_plugin/conversion/qvariant_yaml_conversion.h" 7 | 8 | #include 9 | #include 10 | 11 | #include 12 | #include 13 | 14 | namespace qml_ros_plugin 15 | { 16 | 17 | bool IO::writeYaml( QString path, const QVariant &value ) 18 | { 19 | if ( path.contains( QRegExp( "-*://" ) ) && !path.startsWith( "file://" ) ) { 20 | ROS_ERROR( "Unsupported file path: %s", qPrintable( path ) ); 21 | return false; 22 | } 23 | if ( path.startsWith( "file://" ) ) 24 | path = path.mid( 7 ); 25 | 26 | try { 27 | std::ofstream out( qPrintable( path ) ); 28 | if ( !out ) { 29 | ROS_ERROR( "Failed to open file: %s", qPrintable( path ) ); 30 | return false; 31 | } 32 | YAML::Node yaml; 33 | yaml = value; 34 | out << yaml << std::endl; 35 | return true; 36 | } catch ( std::exception &e ) { 37 | return false; 38 | } 39 | } 40 | 41 | QVariant IO::readYaml( QString path ) 42 | { 43 | if ( path.contains( QRegExp( "-*://" ) ) && !path.startsWith( "file://" ) ) { 44 | ROS_ERROR( "Unsupported file path: %s", qPrintable( path ) ); 45 | return false; 46 | } 47 | if ( path.startsWith( "file://" ) ) 48 | path = path.mid( 7 ); 49 | 50 | try { 51 | YAML::Node node = YAML::LoadFile( path.toStdString() ); 52 | return node.as(); 53 | } catch ( std::exception &e ) { 54 | ROS_ERROR( "Caught exception '%s' while trying to read file: %s", e.what(), qPrintable( path ) ); 55 | return QVariant::fromValue( false ); 56 | } 57 | } 58 | } // namespace qml_ros_plugin 59 | -------------------------------------------------------------------------------- /src/node_handle.cpp: -------------------------------------------------------------------------------- 1 | // Copyright (c) 2019 Stefan Fabian. All rights reserved. 2 | // Licensed under the MIT license. See LICENSE file in the project root for full license information. 3 | 4 | #include "qml_ros_plugin/node_handle.h" 5 | #include "qml_ros_plugin/publisher.h" 6 | #include "qml_ros_plugin/ros.h" 7 | 8 | #include 9 | 10 | namespace qml_ros_plugin 11 | { 12 | NodeHandle::NodeHandle( std::string ns ) : ns_( std::move( ns ) ) { } 13 | 14 | NodeHandle::NodeHandle( std::shared_ptr queue, std::string ns ) 15 | : queue_( std::move( queue ) ), ns_( std::move( ns ) ) 16 | { 17 | } 18 | 19 | QObject *NodeHandle::advertise( const QString &type, const QString &topic, quint32 queue_size, 20 | bool latch ) 21 | { 22 | return new Publisher( shared_from_this(), type, topic, queue_size, latch ); 23 | } 24 | 25 | bool NodeHandle::isReady() const { return nh_ != nullptr; } 26 | 27 | ros::NodeHandle &NodeHandle::nodeHandle() { return *nh_; } 28 | 29 | void NodeHandle::onRosInitialized() 30 | { 31 | if ( nh_ != nullptr ) 32 | return; 33 | nh_.reset( new ros::NodeHandle( ns_ ) ); 34 | if ( queue_ == nullptr ) 35 | queue_ = RosQml::getInstance().callbackQueue(); 36 | nh_->setCallbackQueue( queue_.get() ); 37 | emit ready(); 38 | } 39 | 40 | QString NodeHandle::ns() const 41 | { 42 | return nh_ == nullptr ? QString() : QString::fromStdString( nh_->getNamespace() ); 43 | } 44 | } // namespace qml_ros_plugin 45 | -------------------------------------------------------------------------------- /src/package.cpp: -------------------------------------------------------------------------------- 1 | // Copyright (c) 2020 Stefan Fabian. All rights reserved. 2 | // Licensed under the MIT license. See LICENSE file in the project root for full license information. 3 | 4 | #include "qml_ros_plugin/package.h" 5 | #include "qml_ros_plugin/message_conversions.h" 6 | 7 | #include 8 | #include 9 | 10 | namespace qml_ros_plugin 11 | { 12 | 13 | QString Package::command( const QString &cmd ) 14 | { 15 | return QString::fromStdString( ros::package::command( cmd.toStdString() ) ); 16 | } 17 | 18 | QString Package::getPath( const QString &package_name ) 19 | { 20 | return QString::fromStdString( ros::package::getPath( package_name.toStdString() ) ); 21 | } 22 | 23 | QStringList Package::getAll() 24 | { 25 | QStringList result; 26 | ros::V_string result_std; 27 | if ( !ros::package::getAll( result_std ) ) { 28 | ROS_WARN_NAMED( "qml_ros_plugin", "Failed to get packages!" ); 29 | return {}; 30 | } 31 | result.reserve( result_std.size() ); 32 | for ( const auto &s : result_std ) result.append( QString::fromStdString( s ) ); 33 | return result; 34 | } 35 | 36 | QVariantMap Package::getPlugins( const QString &name, const QString &attribute, bool force_recrawl ) 37 | { 38 | std::vector> exports; 39 | ros::package::getPlugins( name.toStdString(), attribute.toStdString(), exports, force_recrawl ); 40 | QVariantMap result; 41 | for ( const auto &pair : exports ) { 42 | const QString &package = QString::fromStdString( pair.first ); 43 | const QString &value = QString::fromStdString( pair.second ); 44 | if ( result.contains( package ) ) { 45 | conversion::obtainValueAsReference( result[package] ).append( value ); 46 | continue; 47 | } 48 | result.insert( package, QStringList{ value } ); 49 | } 50 | return result; 51 | } 52 | } // namespace qml_ros_plugin 53 | -------------------------------------------------------------------------------- /src/publisher.cpp: -------------------------------------------------------------------------------- 1 | // Copyright (c) 2019 Stefan Fabian. All rights reserved. 2 | // Licensed under the MIT license. See LICENSE file in the project root for full license information. 3 | 4 | #include "qml_ros_plugin/publisher.h" 5 | #include "qml_ros_plugin/babel_fish_dispenser.h" 6 | #include "qml_ros_plugin/message_conversions.h" 7 | #include "qml_ros_plugin/node_handle.h" 8 | #include 9 | 10 | using namespace ros_babel_fish; 11 | using namespace qml_ros_plugin::conversion; 12 | 13 | namespace qml_ros_plugin 14 | { 15 | 16 | Publisher::Publisher( NodeHandle::Ptr nh, QString type, QString topic, uint32_t queue_size, 17 | bool latch ) 18 | : nh_( std::move( nh ) ), is_advertised_( false ), type_( std::move( type ) ), 19 | topic_( std::move( topic ) ), is_latched_( latch ), queue_size_( queue_size ) 20 | { 21 | std_type_ = type_.toStdString(); 22 | babel_fish_ = BabelFishDispenser::getBabelFish(); 23 | 24 | QObject::connect( nh_.get(), &NodeHandle::ready, this, &Publisher::onNodeHandleReady ); 25 | // Advertise if NodeHandle is ready, i.e., ROS was initialized and the NodeHandle is valid otherwise wait for ready 26 | if ( nh_->isReady() ) { 27 | advertise(); 28 | QObject::disconnect( nh_.get(), &NodeHandle::ready, this, &Publisher::onNodeHandleReady ); 29 | } 30 | } 31 | 32 | Publisher::~Publisher() = default; 33 | 34 | QString Publisher::topic() const { return QString::fromStdString( publisher_.getTopic() ); } 35 | 36 | const QString &Publisher::type() const { return type_; } 37 | 38 | bool Publisher::isLatched() const { return publisher_.isLatched(); } 39 | 40 | quint32 Publisher::queueSize() const { return queue_size_; } 41 | 42 | bool Publisher::isAdvertised() const { return is_advertised_; } 43 | 44 | unsigned int Publisher::getNumSubscribers() { return publisher_.getNumSubscribers(); } 45 | 46 | bool Publisher::publish( const QVariantMap &msg ) 47 | { 48 | if ( !is_advertised_ ) 49 | return false; 50 | try { 51 | Message::Ptr message = babel_fish_.createMessage( type_.toStdString() ); 52 | if ( message == nullptr ) 53 | return false; 54 | if ( !fillMessage( *message, msg ) ) 55 | return false; 56 | BabelFishMessage::Ptr bf_message = babel_fish_.translateMessage( message ); 57 | publisher_.publish( bf_message ); 58 | return true; 59 | } catch ( BabelFishMessageException &ex ) { 60 | ROS_ERROR_NAMED( "qml_ros_plugin", "Failed to publish message: %s", ex.what() ); 61 | } catch ( BabelFishException &ex ) { 62 | ROS_ERROR_NAMED( "qml_ros_plugin", "Failed to publish message: %s", ex.what() ); 63 | } 64 | return false; 65 | } 66 | 67 | void Publisher::onNodeHandleReady() 68 | { 69 | QObject::disconnect( nh_.get(), &NodeHandle::ready, this, &Publisher::onNodeHandleReady ); 70 | if ( !is_advertised_ ) 71 | advertise(); 72 | } 73 | 74 | void Publisher::advertise() 75 | { 76 | if ( is_advertised_ ) 77 | publisher_.shutdown(); 78 | if ( type_.isEmpty() ) 79 | return; 80 | if ( topic_.isEmpty() ) 81 | return; 82 | if ( queue_size_ == 0 ) 83 | return; 84 | try { 85 | ros::SubscriberStatusCallback connected_cb = 86 | boost::bind( &Publisher::onSubscriberConnected, this, _1 ); 87 | ros::SubscriberStatusCallback disconnected_cb = 88 | boost::bind( &Publisher::onSubscriberDisconnected, this, _1 ); 89 | publisher_ = babel_fish_.advertise( nh_->nodeHandle(), std_type_, topic_.toStdString(), 90 | queue_size_, is_latched_, connected_cb, disconnected_cb ); 91 | is_advertised_ = true; 92 | emit advertised(); 93 | } catch ( BabelFishMessageException &ex ) { 94 | ROS_ERROR_NAMED( "qml_ros_plugin", "Failed to create publisher: %s", ex.what() ); 95 | } catch ( BabelFishException &ex ) { 96 | ROS_ERROR_NAMED( "qml_ros_plugin", "Failed to create publisher: %s", ex.what() ); 97 | } 98 | } 99 | 100 | void Publisher::onSubscriberConnected( const ros::SingleSubscriberPublisher & ) 101 | { 102 | // auto publisher = new SingleSubscriberPublisher( pub, babel_fish_, std_type_ ); 103 | emit connected(); 104 | } 105 | 106 | void Publisher::onSubscriberDisconnected( const ros::SingleSubscriberPublisher & ) 107 | { 108 | // auto publisher = new SingleSubscriberPublisher( pub, babel_fish_, std_type_ ); 109 | emit disconnected(); 110 | } 111 | } // namespace qml_ros_plugin 112 | -------------------------------------------------------------------------------- /src/qml_ros_plugin.cpp: -------------------------------------------------------------------------------- 1 | // Copyright (c) 2019 Stefan Fabian. All rights reserved. 2 | // Licensed under the MIT license. See LICENSE file in the project root for full license information. 3 | 4 | #include "qml_ros_plugin/action_client.h" 5 | #include "qml_ros_plugin/array.h" 6 | #include "qml_ros_plugin/console.h" 7 | #include "qml_ros_plugin/goal_handle.h" 8 | #include "qml_ros_plugin/image_transport_subscriber.h" 9 | #include "qml_ros_plugin/node_handle.h" 10 | #include "qml_ros_plugin/publisher.h" 11 | #include "qml_ros_plugin/ros.h" 12 | #include "qml_ros_plugin/service.h" 13 | #include "qml_ros_plugin/subscriber.h" 14 | #include "qml_ros_plugin/tf_transform.h" 15 | #include "qml_ros_plugin/tf_transform_listener.h" 16 | #include "qml_ros_plugin/time.h" 17 | 18 | #include 19 | #include 20 | 21 | namespace qml_ros_plugin 22 | { 23 | 24 | class QmlRosPlugin : public QQmlExtensionPlugin 25 | { 26 | Q_OBJECT 27 | // @formatter:off 28 | Q_PLUGIN_METADATA( IID QQmlExtensionInterface_iid ) 29 | // @formatter:on 30 | public: 31 | void registerTypes( const char *uri ) override 32 | { 33 | Q_ASSERT( uri == QLatin1String( "Ros" ) ); 34 | qRegisterMetaType(); 35 | qRegisterMetaType::GoalHandle>(); 36 | 37 | qmlRegisterType(); 38 | QMetaType::registerConverter( &Array::toVariantList ); 39 | qmlRegisterType(); 40 | qmlRegisterType(); 41 | qmlRegisterType(); 42 | qmlRegisterType