├── CMakeLists.txt
├── LICENSE
├── README.md
├── docker
├── Dockerfile
└── docker-compose.yml
├── package.xml
├── requirements.txt
├── scripts
├── msg_to_geotiff.py
├── navsatfix_test_pub
└── start_qgis_ros
├── setup.cfg
├── setup.py
└── src
└── qgis_ros
├── __init__.py
├── core
├── __init__.py
├── bagging.py
├── crs.py
├── helpers.py
├── ros_vector_provider.py
├── translator_registry.py
└── translators
│ ├── __init__.py
│ ├── geometry_msgs.py
│ ├── json_transport.py
│ ├── nav_msgs.py
│ ├── sensor_msgs.py
│ ├── std_msgs.py
│ ├── translator.py
│ └── wireless_msgs.py
├── metadata.txt
├── qgis_ros_toolbox.py
├── styles
├── global_state.qml
├── nogo_map.qml
├── pose_arrow.qml
├── pose_heatmap.qml
└── slam_map.qml
└── ui
├── __init__.py
├── bagfile_dialog.py
├── bagfile_dialog.ui
├── data_loader_widget.py
├── data_loader_widget.ui
├── ros_master_dialog.py
└── ros_master_dialog.ui
/CMakeLists.txt:
--------------------------------------------------------------------------------
1 | cmake_minimum_required(VERSION 2.8.3)
2 | project(qgis_ros)
3 |
4 | find_package(catkin REQUIRED COMPONENTS
5 | )
6 |
7 | catkin_package()
8 |
9 | catkin_python_setup()
10 |
11 | include_directories(
12 | ${catkin_INCLUDE_DIRS}
13 | )
14 |
15 | install(
16 | PROGRAMS
17 | scripts/start_qgis_ros
18 | scripts/navsatfix
19 | DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
20 | )
21 |
22 | install(
23 | FILES
24 | requirements.txt
25 | DESTINATION
26 | ${CATKIN_PACKAGE_SHARE_DESTINATION}
27 | )
28 |
--------------------------------------------------------------------------------
/LICENSE:
--------------------------------------------------------------------------------
1 | MIT License
2 |
3 | Copyright (c) 2018 Locus Robotics
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 |
--------------------------------------------------------------------------------
/README.md:
--------------------------------------------------------------------------------
1 | # QGIS-ROS
2 |
3 | **Warning: This package is not currently maintained and may not work without some additional technical care. It looks like a newer version of QGIS has changed a bunch of the Python interfaces. Try using QGIS 3.10 or perhaps a bit older. PRs are welcome!**
4 |
5 | A QGIS plugin for interacting with data from ROS topics and bags.
6 |
7 | The ROSCon 2018 Presentation on QGIS-ROS can be found here: https://vimeo.com/293539252. The presentation PDF can be found here: https://roscon.ros.org/2018/presentations/ROSCon2018_UnleashingGISToolbox.pdf
8 |
9 | ## Requirements
10 |
11 | - Ubuntu >= 16.04
12 | - Python 3.5
13 | - QGIS >= 3.1
14 | - ROS 1
15 |
16 | QGIS can be installed from [the QGIS download page.][1] You need to add a PPA if using Ubuntu 16.04.
17 |
18 | ## Installation (source)
19 |
20 | ```bash
21 | cd ~/my_ros_ws/src/
22 | git clone git@github.com:locusrobotics/qgis_ros.git
23 | git clone git@github.com:clearpathrobotics/wireless.git
24 | git clone git@github.com:locusrobotics/json_transport.git
25 | catkin build
26 |
27 | cd ~/my_ros_ws/src/qgis_ros
28 | pip3 install -r requirements.txt
29 | ```
30 |
31 | ## Usage (source)
32 |
33 | ```bash
34 | rosrun qgis_ros start_qgis_ros
35 | ```
36 |
37 | Once QGIS is loaded, navigate to Plugins -> Installed -> and enable QGIS_ROS with the checkbox. You only need to do this once.
38 |
39 | With custom ROS Message Translators:
40 |
41 | ```bash
42 | export QGIS_ROS_EXTRA_TRANSLATORS='custompythonmodule.translators'
43 | rosrun qgis_ros start_qgis_ros
44 | ```
45 |
46 | ## Usage (docker)
47 |
48 | It can often be very tricky to comfortably resolve all dependencies in your workspace because of the combination of ROS1, Python3, GDAL 2, and QGIS.
49 |
50 | It uses a lazy/reckless way to expose X server to the container. For alternatives, check out the [ROS Docker GUI Tutorial][2].
51 |
52 | ```
53 | cd ~/my_catkin_ws/src/qgis_ros/docker
54 | docker-compose build
55 | xhost +local:root
56 | docker-compose up
57 | xhost -local:root # Remember to remove X server permissions after!
58 | ```
59 |
60 | To use extra translators, you'll need to mount a volume with them and/or extend the image.
61 |
62 | ## ROS Message Translators
63 |
64 | QGIS is able to read and write data from hundreds of formats and sources by translating these formats into a common in-memory format. In order to represent ROS messages in this format, we target common interchange formats (GeoJSON and GeoTIFF) to make it easy to extend. If you want to make use of a custom ROS message type, all you have to do is:
65 |
66 | 1. subclass `qgis_ros.core.translators.Translator`
67 | 2. implement a `translate` function that accepts a ROS message and returns a GeoJSON-like dict or a path to a GeoTIFF on disk
68 | 3. Add the `VectorTranslatorMixin` or `RasterTranslatorMixin`
69 | 4. Register before launching by setting the envvar `QGIS_ROS_EXTRA_TRANSLATORS` to a python module path to an iterable of translators.
70 |
71 | Check out the source code for more details.
72 |
73 | ## Troubleshooting
74 |
75 | ### My topic does not appear in the list of topics
76 |
77 | Only topics that have ROS Message Translators will appear. Not every message has been implemented. If your message is custom, look above for how to create a custom translator. If it is standard to ROS, create an issue or raise a Pull Request with a new one.TODO: add an example to the ROSCon presentation repository and link here.
78 | 51
79 |
80 | ## Contributions
81 |
82 | Contributions are appreciated. Please open a pull request.
83 |
84 | Developers will notice that `camelCase` is being used in Python. This may seem unusual, but PyQT and QGIS both use `camelCase`.So we follow that standard in accordance with PEP8.
85 |
86 | ## Contact
87 |
88 | Queries that don't fit well as GitHub issues can be directed to Andrew Blakey at ablakey@locusrobotics.com
89 |
90 | Being a robogeographer is a lonely life. If there are any others out there, don't hesitate to say hi!
91 |
92 | [1]: https://qgis.org/en/site/forusers/download.html
93 | [2]: http://wiki.ros.org/docker/Tutorials/GUI
94 |
--------------------------------------------------------------------------------
/docker/Dockerfile:
--------------------------------------------------------------------------------
1 | FROM osrf/ros:lunar-desktop-full-xenial
2 |
3 | ### Installing system packages (system owner's responsibility)
4 | RUN apt update && \
5 | apt install -y wget software-properties-common python3-pip python-catkin-tools
6 |
7 | ### Installing QGIS (QGIS docs responsibility: https://qgis.org/en/site/forusers/alldownloads.html#debian-ubuntu)
8 | RUN sh -c 'echo "deb http://qgis.org/ubuntugis xenial main" >> /etc/apt/sources.list'
9 | RUN wget -O - http://qgis.org/downloads/qgis-2017.gpg.key | gpg --import; exit 0
10 | RUN gpg --export --armor CAEB3DC3BDF7FB45 | apt-key add -
11 | RUN add-apt-repository -y ppa:ubuntugis/ubuntugis-unstable && \
12 | apt update && \
13 | apt install -y gdal-bin python-gdal python3-gdal qgis
14 |
15 | RUN pip3 install rospkg
16 |
17 | ### Installing QGIS_ROS (QGIS_ROS docs responsibility: https://github.com/locusrobotics/qgis_ros)
18 | RUN mkdir -p ~/catkin_ws/src
19 | RUN /bin/bash -c " \
20 | source /opt/ros/lunar/setup.bash && \
21 | cd ~/catkin_ws/ && \
22 | catkin init && \
23 | git clone http://github.com/locusrobotics/qgis_ros.git src/qgis_ros && \
24 | git clone http://github.com/clearpathrobotics/wireless.git src/wireless && \
25 | rosdep install --from-paths src --ignore-src -yi && \
26 | pip3 install msgpack && \
27 | catkin build"
28 |
--------------------------------------------------------------------------------
/docker/docker-compose.yml:
--------------------------------------------------------------------------------
1 | version: '3'
2 | services:
3 | qgis_ros_test:
4 | build: .
5 | environment:
6 | - DISPLAY
7 | - QT_X11_NO_MITSHM=1
8 | volumes:
9 | - "/tmp/.X11-unix:/tmp/.X11-unix:rw"
10 | command: /bin/bash -c "source ~/catkin_ws/devel/setup.bash && rosrun qgis_ros start_qgis_ros"
11 |
--------------------------------------------------------------------------------
/package.xml:
--------------------------------------------------------------------------------
1 |
2 |
3 | qgis_ros
4 | 0.0.1
5 | QGIS plugin for accessing real-time and bagged ROS data
6 |
7 | Andrew Blakey
8 | Proprietary
9 |
10 | catkin
11 |
12 | geometry_msgs
13 | json_transport
14 | nav_msgs
15 | rospack
16 |
17 |
18 |
--------------------------------------------------------------------------------
/requirements.txt:
--------------------------------------------------------------------------------
1 | msgpack
2 | rospkg
3 |
--------------------------------------------------------------------------------
/scripts/msg_to_geotiff.py:
--------------------------------------------------------------------------------
1 | #!/usr/bin/env python3.5
2 | import argparse
3 | from pathlib import Path
4 | import numpy
5 | import gdal
6 | import osr
7 | import json
8 |
9 |
10 | PROJ4_SIMPLE = '+proj=tmerc \
11 | +lat_0=0 \
12 | +lon_0=0 \
13 | +k=1 \
14 | +x_0=0 \
15 | +y_0=0 \
16 | +ellps=WGS84 \
17 | +towgs84=0,0,0,0,0,0,0 \
18 | +units=m \
19 | +no_defs'
20 |
21 |
22 | if __name__ == '__main__':
23 | parser = argparse.ArgumentParser(description='Get message from an OccupancyGrid topic and save it as a geotiff.')
24 | parser.add_argument('input', type=Path)
25 | parser.add_argument('output', type=Path)
26 |
27 | args = parser.parse_args()
28 |
29 | with args.input.open('r') as f:
30 | data = json.load(f)
31 |
32 | rows = data['height']
33 | cols = data['width']
34 | resolution = data['resolution']
35 | bands = 1
36 | originX = data['origin_x']
37 | originY = data['origin_y']
38 |
39 | npData = numpy.reshape(data['data'], (rows, cols))
40 | driver = gdal.GetDriverByName('GTiff')
41 | outRaster = driver.Create(str(args.output), cols, rows, bands, gdal.GDT_Byte)
42 | outRaster.SetGeoTransform((originX, resolution, 0, originY, 0, resolution)) # TODO Explain magic numbers.
43 | outBand = outRaster.GetRasterBand(1)
44 | outBand.WriteArray(npData)
45 | outRasterSRS = osr.SpatialReference()
46 | outRasterSRS.ImportFromProj4(PROJ4_SIMPLE)
47 | outRaster.SetProjection(outRasterSRS.ExportToWkt())
48 | outBand.FlushCache()
49 | outRaster = None # Free up underlying C++ memory.
50 |
--------------------------------------------------------------------------------
/scripts/navsatfix_test_pub:
--------------------------------------------------------------------------------
1 | #!/usr/bin/env python3
2 | """
3 | An example publisher of basic NavSatFix data, mostly for testing.
4 | """
5 | from random import random
6 |
7 | import rospy
8 | from sensor_msgs.msg import NavSatFix
9 |
10 |
11 | def navsatfix_test_pub():
12 | pub = rospy.Publisher("navsat", NavSatFix, queue_size=1)
13 | rospy.init_node("navsatfix_test_pub")
14 |
15 | rate = rospy.Rate(1)
16 |
17 | longitude = 0
18 |
19 | while not rospy.is_shutdown():
20 | pub.publish(latitude=0, longitude=longitude)
21 | longitude += random()
22 | rate.sleep()
23 |
24 |
25 | if __name__ == "__main__":
26 | try:
27 | navsatfix_test_pub()
28 | except rospy.ROSInterruptException:
29 | pass
30 |
--------------------------------------------------------------------------------
/scripts/start_qgis_ros:
--------------------------------------------------------------------------------
1 | #!/usr/bin/env bash
2 | export QGIS_PLUGINPATH=$(catkin_find --first-only qgis_ros src)
3 | # Point to the directory that contains the QGIS plugin (python package).
4 | # TODO: Therefore this will not work when installed.
5 | qgis
6 |
--------------------------------------------------------------------------------
/setup.cfg:
--------------------------------------------------------------------------------
1 | [pep8]
2 | max-line-length = 120
3 |
4 | [flake8]
5 | max-line-length = 120
6 |
--------------------------------------------------------------------------------
/setup.py:
--------------------------------------------------------------------------------
1 | #!/usr/bin/env python
2 |
3 | from distutils.core import setup
4 | from catkin_pkg.python_setup import generate_distutils_setup
5 |
6 | setup_args = generate_distutils_setup(
7 | packages=[
8 | 'qgis_ros',
9 | 'qgis_ros.core',
10 | 'qgis_ros.core.translators',
11 | 'qgis_ros.ui'
12 | ],
13 | package_dir={'': 'src'})
14 |
15 | setup(**setup_args)
16 |
--------------------------------------------------------------------------------
/src/qgis_ros/__init__.py:
--------------------------------------------------------------------------------
1 | # TODO: monkeypatch function.
2 | import sys
3 | sys.argv = []
4 |
5 |
6 | def classFactory(iface):
7 | from .qgis_ros_toolbox import QgisRos
8 | return QgisRos(iface)
9 |
--------------------------------------------------------------------------------
/src/qgis_ros/core/__init__.py:
--------------------------------------------------------------------------------
1 | from .ros_vector_provider import ROSVectorProvider
2 | from .translator_registry import TranslatorRegistry
3 |
4 | __all__ = [
5 | 'ROSVectorProvider',
6 | 'TranslatorRegistry'
7 | ]
8 |
--------------------------------------------------------------------------------
/src/qgis_ros/core/bagging.py:
--------------------------------------------------------------------------------
1 | import rosbag
2 |
3 | from . import TranslatorRegistry
4 |
5 |
6 | def getTopicsFromBag(filePath):
7 | '''Returns a tuple of tuples (name, type, count) from all topics found in bag.'''
8 | with rosbag.Bag(filePath, 'r') as bag:
9 | topicTuples = bag.get_type_and_topic_info()[1] # Tuple entry 1 is a dict of metadata.
10 |
11 | t = [(k, v.msg_type, v.message_count) for k, v in topicTuples.items()]
12 | t.sort(key=lambda k: k[0])
13 | return t
14 |
15 |
16 | def getBagDataAsLayer(filePath, topicName, topicType, sampleInterval=1, takeLast=False, progressCallback=None):
17 | '''Returns a collection of messages from a bag.
18 | Invokes a progress callback every 1000 elements as this can be long running.
19 | '''
20 | count = 0
21 | messages = []
22 | extraProperties = []
23 |
24 | with rosbag.Bag(filePath, 'r') as bag:
25 | for topic, message, time in bag.read_messages(topics=topicName):
26 | count += 1
27 | if count % sampleInterval == 0: # Append every sampleInterval message.
28 | messages.append(message)
29 | extraProperties.append({'bagTimestamp': time.to_sec()})
30 |
31 | # Invoke progress callback every 1000 messages.
32 | if count % 1000 == 0 and progressCallback:
33 | progressCallback(count)
34 |
35 | if takeLast:
36 | messages = [messages[-1]]
37 | extraProperties = [extraProperties[-1]]
38 |
39 | translator = TranslatorRegistry.instance().get(topicType)
40 | return translator.createLayer(topicName, rosMessages=messages, extraProperties=extraProperties)
41 |
--------------------------------------------------------------------------------
/src/qgis_ros/core/crs.py:
--------------------------------------------------------------------------------
1 | from qgis.core import QgsCoordinateReferenceSystem
2 |
3 |
4 | PROJ4_SIMPLE = '+proj=tmerc \
5 | +lat_0=0 \
6 | +lon_0=0 \
7 | +k=1 \
8 | +x_0=0 \
9 | +y_0=0 \
10 | +ellps=WGS84 \
11 | +towgs84=0,0,0,0,0,0,0 \
12 | +units=m \
13 | +no_defs'
14 |
15 | PROJ4_WGS84 = '+proj=longlat +datum=WGS84 +no_defs'
16 |
17 | simpleCrs = QgsCoordinateReferenceSystem('PROJ4:' + PROJ4_SIMPLE)
18 | wgs84Crs = QgsCoordinateReferenceSystem('PROJ4:' + PROJ4_WGS84)
19 |
20 | proj4CrsDict = {'simple': PROJ4_SIMPLE, 'wgs84': PROJ4_WGS84}
21 | crsDict = {'simple': simpleCrs, 'wgs84': wgs84Crs}
22 |
--------------------------------------------------------------------------------
/src/qgis_ros/core/helpers.py:
--------------------------------------------------------------------------------
1 | import json
2 | import math
3 |
4 | from qgis.PyQt.QtCore import QTextCodec
5 | from qgis.core import QgsJsonUtils
6 |
7 |
8 | def featuresToQgs(features):
9 | '''Accepts a list of geojson Features and returns a tuple of (features, fields)'''
10 | fc = {'type': 'FeatureCollection', 'features': features}
11 | fcString = json.dumps(fc)
12 | codec = QTextCodec.codecForName("UTF-8")
13 | fields = QgsJsonUtils.stringToFields(fcString, codec)
14 | features = QgsJsonUtils.stringToFeatureList(fcString, fields, codec)
15 |
16 | return (features, fields)
17 |
18 |
19 | def parseUrlArgs(argString):
20 | args = argString.split('&') # list of arg strings.
21 | args = dict([a.split('=') for a in args]) # dict of args.
22 |
23 | # Convert string booleans.
24 | for k, v in args.items():
25 | if v.lower() in ('yes', 'true'):
26 | args[k] = True
27 | elif v.lower() in ('no', 'false'):
28 | args[k] = False
29 |
30 | return args
31 |
32 |
33 | def quaternionToYaw(q):
34 | '''Returns the yaw in radians of a quaternion.
35 | Reimplements part of euler_from_quaternion from the tf package because tf doesn't play well in Python 3.
36 | '''
37 | t0 = 2.0 * (q.w * q.z + q.x * q.y)
38 | t1 = 1.0 - 2.0 * (q.y**2 + q.z**2)
39 | return math.atan2(t0, t1)
40 |
--------------------------------------------------------------------------------
/src/qgis_ros/core/ros_vector_provider.py:
--------------------------------------------------------------------------------
1 | # Developed based on: https://github.com/qgis/QGIS/blob/master/tests/src/python/provider_python.py
2 | from threading import RLock
3 | import rospy
4 | from qgis.core import (
5 | QgsFields,
6 | QgsVectorLayer,
7 | QgsFeatureRequest,
8 | QgsFeature,
9 | QgsGeometry,
10 | QgsProject,
11 | QgsExpression,
12 | QgsExpressionContext,
13 | QgsExpressionContextUtils,
14 | QgsCoordinateTransform,
15 | QgsRectangle,
16 | QgsVectorDataProvider,
17 | QgsAbstractFeatureSource,
18 | QgsAbstractFeatureIterator,
19 | QgsFeatureIterator,
20 | QgsSpatialIndex,
21 | QgsDataProvider
22 | )
23 |
24 | from PyQt5.QtCore import pyqtSignal
25 |
26 | from .crs import crsDict
27 | from .translator_registry import TranslatorRegistry
28 | from .helpers import featuresToQgs, parseUrlArgs
29 |
30 | # TODO: Make a non-global version.
31 | # This limits all ROSVectorProvider classes from updating the canvas more than once per second.
32 | DATA_UPDATE_THROTTLE = 2.0 # float seconds
33 | global last_global_refresh
34 | last_global_refresh = 0
35 |
36 |
37 | class ROSVectorProvider(QgsVectorDataProvider):
38 |
39 | fieldsUpdated = pyqtSignal()
40 |
41 | @classmethod
42 | def providerKey(cls):
43 | return 'rosvectorprovider'
44 |
45 | @classmethod
46 | def description(cls):
47 | return 'ROS Vector Provider'
48 |
49 | @classmethod
50 | def createProvider(cls, uri, providerOptions):
51 | return ROSVectorProvider(uri, providerOptions)
52 |
53 | def __init__(self, uri='', providerOptions=QgsDataProvider.ProviderOptions()):
54 | '''Set up the Data Provider.
55 |
56 | uri contains the topic name, topic type.
57 | Example uri: 'foo/my_pose?type=geometry_msgs/PoseStamped'
58 | '''
59 | try:
60 | self._topic, argString = uri.split('?')
61 | except IndexError:
62 | raise ValueError('uri Cannot be parsed. Is it valid? uri: {}'.format(uri))
63 |
64 | # Parse string of arguments into dict of python types.
65 | args = parseUrlArgs(argString)
66 | super().__init__(uri)
67 |
68 | self._translator = TranslatorRegistry.instance().get(args['type'])
69 |
70 | # There's no source for a reasonable collection of native types so we just steal from another provider.
71 | mlayer = QgsVectorLayer('Polygon?crs=epsg:4326', 'ml', 'memory') # Wrong url but doesn't matter.
72 | nativeTypes = mlayer.dataProvider().nativeTypes()
73 | self.setNativeTypes(nativeTypes)
74 |
75 | self._uri = uri
76 | self._fields = QgsFields()
77 | self._wkbType = self._translator.geomType # TODO: if unknown, infer it.
78 | self._features = {}
79 | self._extent = QgsRectangle()
80 | self._extent.setMinimal()
81 | self._subset_string = ''
82 | self._spatialindex = None
83 | self._provider_options = providerOptions
84 | self.next_feature_id = 0 # TODO: Consider a generator for a better numbering approach.
85 | self._lock = RLock()
86 | self._subscriber = None
87 |
88 | self.keepOlderMessages = args.get('keepOlderMessages', False)
89 | self._handledMessageCount = 0
90 | self.sampleInterval = int(args.get('sampleInterval', 1))
91 | self.crsName = args.get('crsName')
92 |
93 | if args.get('index'):
94 | self.createSpatialIndex()
95 |
96 | if args.get('subscribe'):
97 | self._subscriber = rospy.Subscriber(self._topic, self._translator.messageType, self._handleMessage)
98 | else:
99 | msg = rospy.wait_for_message(self._topic, self._translator.messageType, timeout=5)
100 | self._handleMessage(msg)
101 |
102 | def _handleMessage(self, msg):
103 | self._handledMessageCount += 1
104 | # Skip message if not on interval.
105 | if (self._handledMessageCount - 1) % self.sampleInterval: # -1 so that first message is handled.
106 | return
107 |
108 | features = self._translator.translate(msg)
109 | qgsFeatures, fields = featuresToQgs(features)
110 |
111 | # TODO: check if fields changed and emit a signal only then.
112 | self._fields = fields
113 | self.fieldsUpdated.emit()
114 |
115 | # If we're not accumulating history, clear features first.
116 | if not self.keepOlderMessages:
117 | self.next_feature_id = 0
118 | self._features = {} # Clear features.
119 |
120 | try:
121 | self._setFeatures(qgsFeatures)
122 | except RuntimeError:
123 | self._cleanup()
124 |
125 | # Throttle data update to avoid over-stressing QGIS runtime. Consider alleviating this.
126 | global last_global_refresh
127 | now = rospy.get_time()
128 | if now - last_global_refresh > DATA_UPDATE_THROTTLE:
129 | last_global_refresh = now
130 | self.dataChanged.emit() # TODO: remove occasional flicker when this happens.
131 |
132 | def _cleanup(self):
133 | ''' Clean up ROS subscriber connection.
134 | The provider is owned by the QgsVectorLayer, which is owned by QGIS internals (layer registry)
135 | When a layer is removed, it gets deleted and cleaned up. However, there's no clean way to perform
136 | cleanup activities on the Python side before the underlying C++ object is deleted, thus making this
137 | object unstable. A RuntimeError is raised when this is detected. We'll perform cleanup at that point.
138 | '''
139 | if self._subscriber:
140 | self._subscriber.unregister()
141 | self._subscriber = None
142 |
143 | def featureSource(self):
144 | with self._lock:
145 | return ROSVectorFeatureSource(self)
146 |
147 | def dataSourceUri(self, expandAuthConfig=True):
148 | return self._uri
149 |
150 | def storageType(self):
151 | return "ROS Topic"
152 |
153 | def getFeatures(self, request=QgsFeatureRequest()):
154 | with self._lock:
155 | return QgsFeatureIterator(ROSVectorFeatureIterator(ROSVectorFeatureSource(self), request))
156 |
157 | def uniqueValues(self, fieldIndex, limit=1):
158 | with self._lock:
159 | results = set()
160 | if fieldIndex >= 0 and fieldIndex < self._fields.count():
161 | req = QgsFeatureRequest()
162 | req.setFlags(QgsFeatureRequest.NoGeometry)
163 | req.setSubsetOfAttributes([fieldIndex])
164 | for f in self.getFeatures(req):
165 | results.add(f.attributes()[fieldIndex])
166 | return results
167 |
168 | def wkbType(self):
169 | return self._wkbType
170 |
171 | def featureCount(self):
172 | with self._lock:
173 | if not self.subsetString():
174 | return len(self._features)
175 | else:
176 | req = QgsFeatureRequest()
177 | req.setFlags(QgsFeatureRequest.NoGeometry)
178 | req.setSubsetOfAttributes([])
179 | return len([f for f in self.getFeatures(req)])
180 |
181 | def fields(self):
182 | with self._lock:
183 | return self._fields
184 |
185 | def _setFeatures(self, flist, flags=None):
186 | with self._lock:
187 | added = False
188 | f_added = []
189 |
190 | if self._spatialindex is not None:
191 | for f in self._features.values():
192 | self._spatialindex.deleteFeature(f)
193 |
194 | for _f in flist:
195 | self._features[self.next_feature_id] = _f
196 | _f.setId(self.next_feature_id)
197 | self.next_feature_id += 1
198 | added = True
199 | f_added.append(_f)
200 |
201 | if self._spatialindex is not None:
202 | self._spatialindex.insertFeature(_f)
203 |
204 | if f_added:
205 | self.clearMinMaxCache()
206 | self.updateExtents()
207 |
208 | return added, f_added
209 |
210 | def allFeatureIds(self):
211 | with self._lock:
212 | return list(self._features.keys())
213 |
214 | def subsetString(self):
215 | return self._subset_string
216 |
217 | def setSubsetString(self, subsetString):
218 | if subsetString == self._subset_string:
219 | return True
220 | self._subset_string = subsetString
221 | self.updateExtents()
222 | self.clearMinMaxCache()
223 | self.dataChanged.emit()
224 | return True
225 |
226 | def supportsSubsetString(self):
227 | return True
228 |
229 | def createSpatialIndex(self):
230 | if self._spatialindex is None:
231 | self._spatialindex = QgsSpatialIndex()
232 | for f in self._features.values():
233 | self._spatialindex.insertFeature(f)
234 | return True
235 |
236 | def capabilities(self):
237 | return QgsVectorDataProvider.SelectAtId | QgsVectorDataProvider.CreateSpatialIndex
238 |
239 | def name(self):
240 | return self.providerKey()
241 |
242 | def extent(self):
243 | if self._extent.isEmpty() and self._features:
244 | self._extent.setMinimal()
245 | if not self._subset_string:
246 | # fast way - iterate through all features
247 | for feat in self._features.values():
248 | if feat.hasGeometry():
249 | self._extent.combineExtentWith(feat.geometry().boundingBox())
250 | else:
251 | for f in self.getFeatures(QgsFeatureRequest().setSubsetOfAttributes([])):
252 | if f.hasGeometry():
253 | self._extent.combineExtentWith(f.geometry().boundingBox())
254 |
255 | elif not self._features:
256 | self._extent.setMinimal()
257 | return QgsRectangle(self._extent)
258 |
259 | def updateExtents(self):
260 | self._extent.setMinimal()
261 |
262 | def isValid(self):
263 | return True
264 |
265 | def crs(self):
266 | return crsDict[self.crsName]
267 |
268 |
269 | class ROSVectorFeatureIterator(QgsAbstractFeatureIterator):
270 |
271 | def __init__(self, source, request):
272 | super().__init__(request)
273 | self._request = request if request is not None else QgsFeatureRequest()
274 | self._source = source
275 | self._index = 0
276 | self._transform = QgsCoordinateTransform()
277 | if self._request.destinationCrs().isValid() and self._request.destinationCrs() != self._source._provider.crs():
278 | self._transform = QgsCoordinateTransform(
279 | self._source._provider.crs(),
280 | self._request.destinationCrs(),
281 | self._request.transformContext()
282 | )
283 | try:
284 | self._filter_rect = self.filterRectToSourceCrs(self._transform)
285 | except Exception as e:
286 | self.close()
287 | return
288 | self._filter_rect = self.filterRectToSourceCrs(self._transform)
289 | if not self._filter_rect.isNull():
290 | self._select_rect_geom = QgsGeometry.fromRect(self._filter_rect)
291 | self._select_rect_engine = QgsGeometry.createGeometryEngine(self._select_rect_geom.constGet())
292 | self._select_rect_engine.prepareGeometry()
293 | else:
294 | self._select_rect_engine = None
295 | self._select_rect_geom = None
296 | self._feature_id_list = None
297 | if self._filter_rect is not None and self._source._provider._spatialindex is not None:
298 | self._feature_id_list = self._source._provider._spatialindex.intersects(self._filter_rect)
299 |
300 | def fetchFeature(self, f):
301 | """fetch next feature, return true on success"""
302 | # virtual bool nextFeature( QgsFeature &f );
303 | if self._index < 0:
304 | f.setValid(False)
305 | return False
306 | try:
307 | found = False
308 | while not found:
309 | _f = self._source._features[list(self._source._features.keys())[self._index]]
310 | self._index += 1
311 |
312 | if self._feature_id_list is not None and _f.id() not in self._feature_id_list:
313 | continue
314 |
315 | if not self._filter_rect.isNull():
316 | if not _f.hasGeometry():
317 | continue
318 | if self._request.flags() & QgsFeatureRequest.ExactIntersect:
319 | # do exact check in case we're doing intersection
320 | if not self._select_rect_engine.intersects(_f.geometry().constGet()):
321 | continue
322 | else:
323 | if not _f.geometry().boundingBox().intersects(self._filter_rect):
324 | continue
325 |
326 | self._source._expression_context.setFeature(_f)
327 | if self._request.filterType() == QgsFeatureRequest.FilterExpression:
328 | if not self._request.filterExpression().evaluate(self._source._expression_context):
329 | continue
330 | if self._source._subset_expression:
331 | if not self._source._subset_expression.evaluate(self._source._expression_context):
332 | continue
333 | elif self._request.filterType() == QgsFeatureRequest.FilterFids:
334 | if not _f.id() in self._request.filterFids():
335 | continue
336 | elif self._request.filterType() == QgsFeatureRequest.FilterFid:
337 | if _f.id() != self._request.filterFid():
338 | continue
339 | f.setGeometry(_f.geometry())
340 | self.geometryToDestinationCrs(f, self._transform)
341 | f.setFields(_f.fields())
342 | f.setAttributes(_f.attributes())
343 | f.setValid(_f.isValid())
344 | f.setId(_f.id())
345 | return True
346 | except IndexError as e:
347 | f.setValid(False)
348 | return False
349 |
350 | def __iter__(self):
351 | """Returns self as an iterator object"""
352 | self._index = 0
353 | return self
354 |
355 | def __next__(self):
356 | """Returns the next value till current is lower than high"""
357 | f = QgsFeature()
358 | if not self.nextFeature(f):
359 | raise StopIteration
360 | else:
361 | return f
362 |
363 | def rewind(self):
364 | """reset the iterator to the starting position"""
365 | # virtual bool rewind() = 0;
366 | if self._index < 0:
367 | return False
368 | self._index = 0
369 | return True
370 |
371 | def close(self):
372 | """end of iterating: free the resources / lock"""
373 | # virtual bool close() = 0;
374 | self._index = -1
375 | return True
376 |
377 |
378 | class ROSVectorFeatureSource(QgsAbstractFeatureSource):
379 |
380 | def __init__(self, provider):
381 | super(ROSVectorFeatureSource, self).__init__()
382 | self._provider = provider
383 | self._features = provider._features
384 |
385 | self._expression_context = QgsExpressionContext()
386 | self._expression_context.appendScope(QgsExpressionContextUtils.globalScope())
387 | self._expression_context.appendScope(QgsExpressionContextUtils.projectScope(QgsProject.instance()))
388 | self._expression_context.setFields(self._provider.fields())
389 | if self._provider.subsetString():
390 | self._subset_expression = QgsExpression(self._provider.subsetString())
391 | self._subset_expression.prepare(self._expression_context)
392 | else:
393 | self._subset_expression = None
394 |
395 | def getFeatures(self, request):
396 | return QgsFeatureIterator(ROSVectorFeatureIterator(self, request))
397 |
--------------------------------------------------------------------------------
/src/qgis_ros/core/translator_registry.py:
--------------------------------------------------------------------------------
1 | import importlib
2 | import os
3 |
4 | from qgis.core import QgsMessageLog
5 |
6 | from .translators import builtinTranslators
7 |
8 |
9 | class TranslatorRegistry(object):
10 | '''A registry of all installed ROS data translators.
11 |
12 | Implemented as singleton to remain consistent with how QGIS handles these kinds of components.
13 | '''
14 |
15 | _instance = None
16 |
17 | @staticmethod
18 | def instance():
19 | if TranslatorRegistry._instance is None:
20 | TranslatorRegistry()
21 | return TranslatorRegistry._instance
22 |
23 | def __init__(self):
24 | if TranslatorRegistry._instance is None:
25 | TranslatorRegistry._instance = self
26 | else:
27 | raise Exception('Cannot re-instantiate singleton.') # TODO: better exception type.
28 |
29 | self._translators = {}
30 |
31 | # Register all built-in translators.
32 | for t in builtinTranslators:
33 | self.register(t)
34 |
35 | # Register extra translators found in QGIS_ROS_EXTRA_TRANSLATORS.
36 | translatorPaths = os.environ.get('QGIS_ROS_EXTRA_TRANSLATORS', '').split(',')
37 | for p in translatorPaths:
38 | # Skip empty strings.
39 | if p == '':
40 | continue
41 |
42 | try:
43 | m = importlib.import_module(p)
44 | except ModuleNotFoundError:
45 | QgsMessageLog.logMessage('Could not find QGIS_ROS_EXTRA_TRANSLATORS module: {}. Skipping.'.format(p))
46 | continue
47 |
48 | try:
49 | translators = getattr(m, 'translators')
50 | except AttributeError:
51 | QgsMessageLog.logMessage(
52 | 'Could not find translator for QGIS_ROS_EXTRA_TRANSLATORS module: {}. Skipping.'.format(p))
53 | continue
54 |
55 | # Register found translators.
56 | for t in translators:
57 | self.register(t)
58 |
59 | def register(self, translator):
60 | # TODO: log every registration.
61 | if translator.messageType._type in self._translators:
62 | raise ValueError('Type {} already registered.'.format(translator.messageType._type))
63 | self._translators[translator.messageType._type] = translator
64 |
65 | @property
66 | def translatableTypeNames(self):
67 | return self._translators.keys()
68 |
69 | def get(self, name):
70 | try:
71 | return self._translators[name]
72 | except KeyError:
73 | raise KeyError('{} not available in list of registered translators.'.format(name))
74 |
--------------------------------------------------------------------------------
/src/qgis_ros/core/translators/__init__.py:
--------------------------------------------------------------------------------
1 | from .translator import Translator, VectorTranslatorMixin, RasterTranslatorMixin
2 |
3 | from .geometry_msgs import Pose2DTranslator, PoseStampedTranslator
4 | from .json_transport import JSONTransportTranslator
5 | from .nav_msgs import OccupancyGridTranslator, OdometryTranslator
6 | from .sensor_msgs import NavSatFixTranslator
7 | from .std_msgs import StringTranslator
8 | from .wireless_msgs import ConnectionTranslator
9 |
10 |
11 | __all__ = [
12 | 'Translator',
13 | 'VectorTranslatorMixin',
14 | 'RasterTranslatorMixin',
15 | 'TableTranslatorMixin',
16 | 'builtinTranslators'
17 | ]
18 |
19 |
20 | builtinTranslators = (
21 | ConnectionTranslator,
22 | JSONTransportTranslator,
23 | NavSatFixTranslator,
24 | OccupancyGridTranslator,
25 | OdometryTranslator,
26 | Pose2DTranslator,
27 | PoseStampedTranslator,
28 | StringTranslator
29 | )
30 |
--------------------------------------------------------------------------------
/src/qgis_ros/core/translators/geometry_msgs.py:
--------------------------------------------------------------------------------
1 | from geometry_msgs.msg import Pose2D, PoseStamped
2 | from .translator import Translator, VectorTranslatorMixin
3 | from ..helpers import quaternionToYaw
4 |
5 |
6 | class Pose2DTranslator(Translator, VectorTranslatorMixin):
7 |
8 | messageType = Pose2D
9 | geomType = Translator.GeomTypes.Point
10 |
11 | @staticmethod
12 | def translate(msg):
13 | return [{
14 | 'type': 'Feature',
15 | 'geometry': {
16 | 'type': 'Point',
17 | 'coordinates': [msg.x, msg.y]
18 | },
19 | 'properties': {
20 | 'theta': msg.theta
21 | }
22 | }]
23 |
24 |
25 | class PoseStampedTranslator(Translator, VectorTranslatorMixin):
26 |
27 | messageType = PoseStamped
28 | geomType = Translator.GeomTypes.Point
29 |
30 | @staticmethod
31 | def translate(msg):
32 | return [{
33 | 'type': 'Feature',
34 | 'geometry': {
35 | 'type': 'Point',
36 | 'coordinates': [msg.pose.position.x, msg.pose.position.y]
37 | },
38 | 'properties': {
39 | 'yaw': quaternionToYaw(msg.pose.orientation),
40 | 'stamp': msg.header.stamp.to_sec(),
41 | }
42 | }]
43 |
--------------------------------------------------------------------------------
/src/qgis_ros/core/translators/json_transport.py:
--------------------------------------------------------------------------------
1 | import json_transport
2 | from .translator import Translator, VectorTranslatorMixin
3 |
4 |
5 | class JSONTransportTranslator(Translator, VectorTranslatorMixin):
6 |
7 | messageType = json_transport.PackedJson
8 |
9 | # geomType = Translator.GeomTypes.Unknown # Need to detect this from the first message.
10 | geomType = Translator.GeomTypes.Polygon # TODO: revert this.
11 |
12 | @staticmethod
13 | def translate(msg):
14 | # Attempt to detect GeoJSON in a JSON message.
15 | msg = msg.data
16 |
17 | if isinstance(msg, list):
18 | geojson_msg = msg
19 | elif isinstance(msg, dict) and msg.get('type') == 'FeatureCollection':
20 | geojson_msg = msg.get('features')
21 | else:
22 | raise ValueError('JSON message is not valid GeoJSON.')
23 |
24 | return geojson_msg
25 |
--------------------------------------------------------------------------------
/src/qgis_ros/core/translators/nav_msgs.py:
--------------------------------------------------------------------------------
1 | import uuid
2 | import json
3 | from pathlib import Path
4 | import subprocess
5 |
6 | from catkin.find_in_workspaces import find_in_workspaces as catkin_find
7 | from nav_msgs.msg import OccupancyGrid, Odometry
8 |
9 | from .translator import Translator, RasterTranslatorMixin, VectorTranslatorMixin
10 | from ..helpers import quaternionToYaw
11 |
12 |
13 | class OdometryTranslator(Translator, VectorTranslatorMixin):
14 |
15 | messageType = Odometry
16 | geomType = Translator.GeomTypes.Point
17 |
18 | @staticmethod
19 | def translate(msg):
20 | return [{
21 | 'type': 'Feature',
22 | 'geometry': {
23 | 'type': 'Point',
24 | 'coordinates': [msg.pose.pose.position.x, msg.pose.pose.position.y]
25 | },
26 | 'properties': {
27 | 'yaw': quaternionToYaw(msg.pose.pose.orientation),
28 | 'stamp': msg.header.stamp.to_sec(),
29 | }
30 | }]
31 |
32 |
33 | class OccupancyGridTranslator(Translator, RasterTranslatorMixin):
34 | '''A really terrible implementation to generate rasters from ROS topics.
35 |
36 | This is because of an unresolved issue where GDAL's underlying C++ implementation crashes unexplainably
37 | when used in this context. As its own process it works fine.
38 | https://issues.qgis.org/issues/19252
39 | '''
40 |
41 | messageType = OccupancyGrid
42 |
43 | @staticmethod
44 | def translate(msg):
45 | datafile = '/tmp/{}.json'.format(uuid.uuid4())
46 |
47 | data = {
48 | 'height': msg.info.height,
49 | 'width': msg.info.width,
50 | 'resolution': msg.info.resolution,
51 | 'origin_x': msg.info.origin.position.x,
52 | 'origin_y': msg.info.origin.position.y,
53 | 'data': msg.data
54 | }
55 |
56 | # Save the message data to be read by external translator.
57 | with open(datafile, 'w') as f:
58 | json.dump(data, f)
59 |
60 | # Run external translator.
61 | geotiffFilename = '/tmp/{}.tif'.format(uuid.uuid4())
62 |
63 | script_dir = catkin_find(project='qgis_ros', path='scripts', first_match_only=True)[0]
64 | rasterize_script = Path(script_dir) / 'msg_to_geotiff.py'
65 |
66 | subprocess.check_call([str(rasterize_script), datafile, geotiffFilename])
67 |
68 | # Return filename.
69 | return geotiffFilename
70 |
--------------------------------------------------------------------------------
/src/qgis_ros/core/translators/sensor_msgs.py:
--------------------------------------------------------------------------------
1 | from sensor_msgs.msg import NavSatFix
2 | from .translator import Translator, VectorTranslatorMixin
3 |
4 |
5 | class NavSatFixTranslator(Translator, VectorTranslatorMixin):
6 |
7 | messageType = NavSatFix
8 | geomType = Translator.GeomTypes.Point
9 | crsName = 'wgs84'
10 |
11 | @staticmethod
12 | def translate(msg):
13 | return [{
14 | 'type': 'Feature',
15 | 'geometry': {
16 | 'type': 'Point',
17 | 'coordinates': [msg.longitude, msg.latitude]
18 | },
19 | 'properties': {
20 | 'stamp': msg.header.stamp.to_sec(),
21 | }
22 | }]
23 |
--------------------------------------------------------------------------------
/src/qgis_ros/core/translators/std_msgs.py:
--------------------------------------------------------------------------------
1 | from std_msgs.msg import String
2 | from .translator import Translator, TableTranslatorMixin
3 |
4 |
5 | class StringTranslator(Translator, TableTranslatorMixin):
6 |
7 | messageType = String
8 | geomType = Translator.GeomTypes.NoGeometry
9 |
10 | @staticmethod
11 | def translate(msg):
12 | return [{
13 | 'type': 'Feature',
14 | 'properties': {
15 | 'data': msg.data
16 | }
17 | }]
18 |
--------------------------------------------------------------------------------
/src/qgis_ros/core/translators/translator.py:
--------------------------------------------------------------------------------
1 | from qgis.core import QgsVectorLayer, QgsRasterLayer, QgsWkbTypes
2 | import rospy
3 | from ..crs import proj4CrsDict
4 | from ..helpers import featuresToQgs
5 |
6 |
7 | class Translator(object):
8 | '''A base class for all translators.
9 | Reimplement `createLayer` to return a new QgsVectorLayer or QgsRasterLayer with the desired data provider.
10 | Or use one of the existing mixins: VectorTranslatorMixin or RasterTranslatorMixin.
11 |
12 | Reimplement `translate` to accept a ROS message and return a GeoJSON object or filename of GeoTiff.
13 | '''
14 |
15 | GeomTypes = QgsWkbTypes
16 | messageType = None
17 | geomType = GeomTypes.Unknown
18 | crsName = 'simple'
19 |
20 |
21 | class RasterTranslatorMixin(object):
22 | '''Translate input raster data to a GeoTIFF format.
23 |
24 | Does not support subscription because we have not implemented a rosrasterprovider.
25 | '''
26 |
27 | dataModelType = 'Raster'
28 |
29 | @classmethod
30 | def createLayer(cls, topicName, rosMessages=None, **kwargs):
31 | '''Creates a raster layer from a ROS message.
32 | Unlike vector data, raster layers cannot currently be subscribed to.
33 | '''
34 | if rosMessages:
35 | msg = rosMessages[0]
36 | else:
37 | msg = rospy.wait_for_message(topicName, cls.messageType, 10)
38 |
39 | geotiffFilename = cls.translate(msg)
40 | layer = QgsRasterLayer(geotiffFilename, topicName)
41 | return layer
42 |
43 |
44 | class VectorTranslatorMixin(object):
45 | '''handles vector topic data.
46 |
47 | Creates and returns a layer using the rosvectorprovider, which knows how to
48 | subscribe to or capture the latest message from a vector topic.
49 | '''
50 |
51 | dataModelType = 'Vector'
52 |
53 | @classmethod
54 | def createLayer(cls, topicName, rosMessages=None, extraProperties=None, subscribe=False, keepOlderMessages=False,
55 | sampleInterval=1):
56 | if rosMessages:
57 | # Features were passed in, so it's a static data layer.
58 | geomType = QgsWkbTypes.displayString(cls.geomType) # Get string version of geomtype enum.
59 | uri = '{}?crs=PROJ4:{}'.format(geomType, proj4CrsDict[cls.crsName])
60 | layer = QgsVectorLayer(uri, topicName, 'memory')
61 |
62 | # Convert from ROS messages to GeoJSON Features to QgsFeatures.
63 | features = []
64 | for n, m in enumerate(rosMessages):
65 | translatedFeatures = cls.translate(m) # Append one or more features.
66 |
67 | # Optionally merge extra properties like bag timestamps in to features created by this message.
68 | if extraProperties is not None:
69 | for f in translatedFeatures:
70 | f['properties'].update(extraProperties[n])
71 |
72 | features += translatedFeatures
73 |
74 | qgsFeatures, fields = featuresToQgs(features)
75 | layer.dataProvider().addAttributes(fields)
76 | layer.dataProvider().addFeatures(qgsFeatures)
77 | layer.updateFields() # Required, otherwise the layer will not re-read field metadata.
78 | return layer
79 | else:
80 | # No features, it must be a ROS topic to get data from.
81 | uri = '{}?type={}&index=no&subscribe={}&keepOlderMessages={}&sampleInterval={}&crsName={}'.format(
82 | topicName,
83 | cls.messageType._type,
84 | subscribe,
85 | keepOlderMessages,
86 | sampleInterval,
87 | cls.crsName,
88 | )
89 | layer = QgsVectorLayer(uri, topicName, 'rosvectorprovider')
90 |
91 | # Need to monitor when data is changed and call updateFields in order to capture the new fields
92 | # that are discovered on the first and possibly future messages. Without this, the layer will never
93 | # expose any of the field data available.
94 | # TODO: Find a cleaner way to signal this update and only call it when actual field changes occur.
95 | layer.dataChanged.connect(layer.updateFields)
96 | return layer
97 |
98 |
99 | class TableTranslatorMixin(VectorTranslatorMixin):
100 | '''Handles non-spatial attribute data.
101 |
102 | Behaves the same as a VectorTranslatorMixin because we use the same provider to handle
103 | subscribing and all that ROS stuff. It just naturally supports GeoJSON Feature data without
104 | geometry.
105 | '''
106 |
107 | dataModelType = 'Table'
108 |
--------------------------------------------------------------------------------
/src/qgis_ros/core/translators/wireless_msgs.py:
--------------------------------------------------------------------------------
1 | from wireless_msgs.msg import Connection
2 | from .translator import Translator, TableTranslatorMixin
3 |
4 |
5 | class ConnectionTranslator(Translator, TableTranslatorMixin):
6 |
7 | messageType = Connection
8 | geomType = Translator.GeomTypes.NoGeometry
9 |
10 | @staticmethod
11 | def translate(msg):
12 |
13 | # Some forks of wireless_msgs/Connection have a header.
14 | try:
15 | seq = msg.header.seq
16 | stamp = msg.header.stamp.to_sec()
17 | except AttributeError:
18 | seq = None
19 | stamp = None
20 |
21 | return [{
22 | 'type': 'Feature',
23 | 'properties': {
24 | 'bitrate': msg.bitrate,
25 | 'txpower': msg.txpower,
26 | 'link_quality_raw': msg.link_quality_raw,
27 | 'link_quality': msg.link_quality,
28 | 'signal_level': msg.signal_level,
29 | 'noise_level': msg.noise_level,
30 | 'essid': msg.essid,
31 | 'bssid': msg.bssid,
32 | 'frequency': msg.frequency,
33 | 'seq': seq,
34 | 'stamp': stamp
35 | }
36 | }]
37 |
--------------------------------------------------------------------------------
/src/qgis_ros/metadata.txt:
--------------------------------------------------------------------------------
1 | # This file contains metadata for your plugin. Since
2 | # version 2.0 of QGIS this is the proper way to supply
3 | # information about a plugin. The old method of
4 | # embedding metadata in __init__.py will
5 | # is no longer supported since version 2.0.
6 |
7 | # This file should be included when you package your plugin.# Mandatory items:
8 |
9 | [general]
10 | name=QGIS ROS
11 | qgisMinimumVersion=3.0
12 | description=Tools for interacting with ROS environments.
13 | version=0.1
14 | author=Andrew Blakey
15 | email=ablakey@gmail.com
16 |
17 | about=No description for now.
18 |
19 | tracker=http://bugs
20 | repository=http://repo
21 | # End of mandatory metadata
22 |
23 | # Recommended items:
24 |
25 | # Uncomment the following line and add your changelog:
26 | # changelog=
27 |
28 | # Tags are comma separated with spaces allowed
29 | tags=python
30 |
31 | homepage=http://homepage
32 | category=Plugins
33 | icon=icon.png
34 | # experimental flag
35 | experimental=True
36 |
37 | # deprecated flag (applies to the whole plugin, not just a single version)
38 | deprecated=False
39 |
40 |
--------------------------------------------------------------------------------
/src/qgis_ros/qgis_ros_toolbox.py:
--------------------------------------------------------------------------------
1 | import os.path
2 |
3 | from PyQt5 import QtWidgets
4 | from qgis.core import QgsProviderRegistry, QgsProviderMetadata
5 |
6 | from .ui import ROSMasterDialog, BagfileDialog
7 | from .core import ROSVectorProvider
8 |
9 |
10 | class QgisRos(object):
11 | '''The parent plugin object.
12 |
13 | Initializes both UI and non-UI elements for QGIS-ROS. This includes a toolbar (and associated drop-down menu),
14 | which are connected to instances of each window, created eagerly. The ROSVectorProvider is also registered,
15 | allowing data layers to be created using it.
16 |
17 | A ROS node is *not* initialized unless explicitly requested by the user. This allows a user to use ROS bags in an
18 | environment where a ROS master is not
19 | '''
20 |
21 | AUTO_REFRESH_INTERVAL = 1000 # milliseconds
22 |
23 | def __init__(self, iface):
24 | self.iface = iface
25 | self.plugin_dir = os.path.dirname(__file__)
26 |
27 | # Register all actions for cleanup on plugin unload.
28 | self.actions = []
29 |
30 | self.menu = 'QGIS-ROS'
31 | self.toolbar = self.iface.addToolBar('QGIS-ROS')
32 | self.toolbar.setObjectName('QGIS-ROS')
33 |
34 | # Register the ROS vector data provider.
35 | metadata = QgsProviderMetadata(
36 | ROSVectorProvider.providerKey(),
37 | ROSVectorProvider.description(),
38 | ROSVectorProvider.createProvider)
39 | QgsProviderRegistry.instance().registerProvider(metadata)
40 |
41 | # Eager init dialogs and preserve state when re-opened in the future.
42 | self.bagFileDialog = BagfileDialog()
43 | self.rosMasterDialog = ROSMasterDialog()
44 |
45 | def initGui(self):
46 | toolbarButtons = [
47 | ('Load Bag Data...', self.bagFileDialog),
48 | ('Load Topic Data...', self.rosMasterDialog)
49 | ]
50 |
51 | # Assemble the toolbar buttons.
52 | for button in toolbarButtons:
53 | action = QtWidgets.QAction(button[0], self.iface.mainWindow())
54 | action.triggered.connect(button[1].show)
55 | self.toolbar.addAction(action)
56 | self.iface.addPluginToMenu(self.menu, action)
57 | self.actions.append(action)
58 |
59 | def unload(self):
60 | for action in self.actions:
61 | self.iface.removePluginMenu('QGIS-ROS', action)
62 | self.iface.removeToolBarIcon(action)
63 | del self.toolbar # Deref to ensure C++ cleanup.
64 |
--------------------------------------------------------------------------------
/src/qgis_ros/styles/global_state.qml:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
8 |
9 |
10 |
11 |
12 |
13 |
14 |
15 |
16 |
17 |
18 |
19 |
20 |
21 |
22 |
23 |
24 |
25 |
26 |
28 |
31 |
32 |
33 |
34 |
35 |
36 |
37 |
38 |
39 |
40 |
41 |
42 |
43 |
44 |
45 |
46 |
47 |
48 |
49 | 0
50 | 0
51 | 1
52 |
53 |
54 |
55 |
56 |
57 |
58 |
59 |
61 |
62 |
63 |
64 |
65 |
66 |
67 |
68 |
69 |
70 |
71 |
72 |
73 |
74 |
75 |
76 |
77 |
78 |
79 |
80 |
81 |
82 |
83 |
84 |
85 |
86 |
87 |
88 |
89 |
90 |
91 |
92 |
93 |
94 |
95 |
96 |
97 |
98 |
99 |
100 |
101 |
102 |
103 |
104 |
105 |
106 |
107 |
108 |
109 |
110 |
111 |
112 |
113 |
114 |
115 |
116 |
117 |
118 |
119 |
120 |
121 |
122 |
123 |
124 |
125 |
126 |
127 |
128 |
129 |
130 |
131 |
132 |
133 |
134 |
135 |
136 |
137 |
138 |
139 |
140 |
141 |
142 |
143 |
144 |
145 |
146 |
147 |
148 |
149 | 0
150 |
151 |
168 | 0
169 | generatedlayout
170 |
171 |
172 |
173 |
174 |
175 |
176 |
177 |
178 |
179 |
180 |
181 |
182 |
183 |
184 |
185 |
186 |
187 |
188 |
189 |
190 | robot_name
191 |
192 | 0
193 |
194 |
--------------------------------------------------------------------------------
/src/qgis_ros/styles/nogo_map.qml:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 | None
8 | WholeRaster
9 | Estimated
10 | 0.02
11 | 0.98
12 | 2
13 |
14 |
15 |
16 |
17 |
18 |
19 |
20 |
21 |
22 |
23 |
24 | 0
25 |
26 |
--------------------------------------------------------------------------------
/src/qgis_ros/styles/pose_arrow.qml:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
8 |
9 |
10 |
11 |
12 |
13 |
14 |
15 |
16 |
17 |
18 |
19 |
20 |
21 |
22 |
23 |
24 |
25 |
26 |
27 |
28 |
29 |
30 |
32 |
35 |
36 |
37 |
38 |
39 |
40 |
41 |
42 |
43 |
44 |
45 |
46 |
47 |
48 |
49 |
50 |
51 |
52 |
53 |
54 |
55 |
56 |
57 |
58 |
59 |
60 |
61 |
62 |
63 |
64 |
65 |
67 |
68 |
69 |
70 |
71 |
72 |
73 |
74 |
75 |
76 |
77 |
78 |
79 |
80 | 0
81 | 0
82 | 1
83 |
84 |
85 |
86 |
87 |
88 |
89 |
90 |
92 |
93 |
94 |
95 |
96 |
97 |
98 |
99 |
100 |
101 |
102 |
103 |
104 |
105 |
106 |
107 |
108 |
109 |
110 |
111 |
112 |
113 |
114 |
115 |
116 |
117 |
118 |
119 |
120 |
121 |
122 |
123 |
124 |
125 |
126 |
127 |
128 |
129 |
130 |
131 |
132 |
133 |
134 |
135 |
136 |
137 |
138 |
139 |
140 |
141 |
142 |
143 |
144 | 0
145 |
146 |
163 | 0
164 | generatedlayout
165 |
166 |
167 |
168 |
169 |
170 |
171 |
172 |
173 |
174 |
175 |
176 |
177 |
178 |
179 | stamp
180 |
181 | 0
182 |
183 |
--------------------------------------------------------------------------------
/src/qgis_ros/styles/pose_heatmap.qml:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
8 |
9 |
10 |
11 |
12 |
13 |
14 | stamp
15 |
16 |
17 |
18 |
19 |
20 | 0
21 | 0
22 | 1
23 |
24 |
25 |
26 |
27 |
28 |
29 |
30 |
32 |
33 |
34 |
35 |
36 |
37 |
38 |
39 |
40 |
41 |
42 |
43 |
44 |
45 |
46 |
47 |
48 |
49 |
50 |
51 |
52 |
53 |
54 |
55 |
56 |
57 |
58 |
59 |
60 |
61 |
62 |
63 |
64 |
65 |
66 |
67 |
68 |
69 |
70 |
71 |
72 |
73 |
74 |
75 |
76 |
77 |
78 |
79 |
80 |
81 |
82 |
83 |
84 |
85 |
86 |
87 |
88 |
89 |
90 |
91 |
92 |
93 |
94 |
95 |
96 |
97 |
98 |
99 |
100 |
101 |
102 |
103 |
104 |
105 |
106 |
107 |
108 |
109 |
110 |
111 |
112 |
113 |
114 |
115 |
116 |
117 |
118 |
119 |
120 | 0
121 |
122 |
139 | 0
140 | generatedlayout
141 |
142 |
143 |
144 |
145 |
146 |
147 |
148 |
149 |
150 |
151 |
152 |
153 |
154 |
155 |
156 |
157 |
158 |
159 |
160 |
161 |
162 |
163 | stamp
164 |
165 | 0
166 |
167 |
--------------------------------------------------------------------------------
/src/qgis_ros/styles/slam_map.qml:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 | MinMax
8 | WholeRaster
9 | Estimated
10 | 0.02
11 | 0.98
12 | 2
13 |
14 |
15 | 0
16 | 100
17 | StretchToMinimumMaximum
18 |
19 |
20 |
21 |
22 |
23 |
24 | 0
25 |
26 |
--------------------------------------------------------------------------------
/src/qgis_ros/ui/__init__.py:
--------------------------------------------------------------------------------
1 | from .data_loader_widget import DataLoaderWidget
2 | from .ros_master_dialog import ROSMasterDialog
3 | from .bagfile_dialog import BagfileDialog
4 |
5 |
6 | __all__ = [
7 | 'ROSMasterDialog',
8 | 'DataLoaderWidget',
9 | 'BagfileDialog'
10 | ]
11 |
--------------------------------------------------------------------------------
/src/qgis_ros/ui/bagfile_dialog.py:
--------------------------------------------------------------------------------
1 | from pathlib import Path
2 | import os
3 | import threading
4 |
5 | from PyQt5 import uic
6 | from PyQt5.QtWidgets import QDialog, QFileDialog
7 | from PyQt5.QtCore import pyqtSignal, pyqtSlot
8 |
9 | from qgis.core import QgsProject
10 |
11 | from ..core import bagging, TranslatorRegistry
12 |
13 | FORM_CLASS, _ = uic.loadUiType(str(Path(os.path.dirname(__file__)) / 'bagfile_dialog.ui'))
14 |
15 |
16 | class BagfileDialog(QDialog, FORM_CLASS):
17 |
18 | layerCreated = pyqtSignal(object)
19 | bagContentsRetrieved = pyqtSignal(object)
20 | layerLoadProgress = pyqtSignal(int)
21 |
22 | def __init__(self, parent=None):
23 | super(BagfileDialog, self).__init__(parent)
24 | self.setupUi(self)
25 |
26 | self.openBagButton.clicked.connect(self._getBagFileTopics)
27 | self.addLayerButton.clicked.connect(self._createLayerFromSelected)
28 | self.unloadBagButton.clicked.connect(self._unloadBag)
29 |
30 | self.bagContentsRetrieved.connect(self._tabulateBagContents)
31 | self.layerCreated.connect(self._addCreatedLayer)
32 | self.layerLoadProgress.connect(self._updateLoadProgress)
33 | self.takeRadioGroup.buttonClicked.connect(self._updateRadioSelection)
34 |
35 | # Update UI depending on what the selected layer's data type is.
36 | self.dataLoaderWidget.selectedTopicChanged.connect(self._updateDataLoadingOptions)
37 |
38 | self._bagFilePath = None
39 |
40 | def _getBagFileTopics(self):
41 | # Load topic metadata from bag.
42 | filePath, _ = QFileDialog.getOpenFileName(parent=self, filter='Bagfiles (*.bag);;All Files (*)')
43 |
44 | if not filePath:
45 | return
46 |
47 | self._bagFilePath = filePath
48 | self.openBagButton.setText('Opening...')
49 | self.openBagButton.setEnabled(False)
50 |
51 | threading.Thread(name='getBagTopicsThread', target=self._getBagContentsWorker).start()
52 |
53 | def _getBagContentsWorker(self):
54 | '''Get bagfile contents in a thread.
55 |
56 | This can take a long time depending on size of bag.
57 |
58 | Must use a signal to pass results back as UI components can only safely
59 | be manipulated in the main thread.
60 | '''
61 | topicMetadata = bagging.getTopicsFromBag(self._bagFilePath)
62 | self.bagContentsRetrieved.emit(topicMetadata)
63 |
64 | @pyqtSlot(object)
65 | def _tabulateBagContents(self, metadata):
66 | self.currentBagPathLabel.setText(self._bagFilePath)
67 | self.dataLoaderWidget.setTopics(metadata)
68 | self.stackedWidget.setCurrentWidget(self.dataLoaderWidgetContainer)
69 | self.openBagButton.setText('Open Bag...')
70 | self.openBagButton.setEnabled(True)
71 | self.unloadBagButton.setEnabled(True)
72 |
73 | def _createLayerFromSelected(self):
74 | self.addLayerButton.setText('Loading...')
75 | self.addLayerButton.setEnabled(False)
76 |
77 | threading.Thread(name='createLayerThread', target=self._createLayerWorker).start()
78 |
79 | def _createLayerWorker(self):
80 | topicName, topicType = self.dataLoaderWidget.getSelectedTopic()
81 |
82 | # Defaults for taking all messages.
83 | sampleInterval = 1
84 | takeLast = False
85 |
86 | if self.takeSampleRadio.isChecked(): # Take sample.
87 | sampleInterval = self.sampleIntervalBox.value()
88 | elif self.takeLastRadio.isChecked(): # Take last.
89 | takeLast = True
90 |
91 | layer = bagging.getBagDataAsLayer(
92 | self._bagFilePath,
93 | topicName,
94 | topicType,
95 | sampleInterval=sampleInterval,
96 | takeLast=takeLast,
97 | progressCallback=self.layerLoadProgress.emit
98 | )
99 |
100 | self.layerCreated.emit(layer) # Need to add layer from main thread.
101 |
102 | self.addLayerButton.setText('Add Layer')
103 | self.addLayerButton.setEnabled(True)
104 |
105 | @pyqtSlot(object)
106 | def _addCreatedLayer(self, layer):
107 | QgsProject.instance().addMapLayer(layer)
108 |
109 | @pyqtSlot(int)
110 | def _updateLoadProgress(self, progress):
111 | self.addLayerButton.setText(str(progress))
112 |
113 | def _unloadBag(self):
114 | '''Frees up any resources from the bag, resets view and state.'''
115 | self._bagFilePath = None
116 | self.currentBagPathLabel.setText('No bag selected')
117 | self.dataLoaderWidget.setTopics(None)
118 | self.stackedWidget.setCurrentWidget(self.bagSelectionWidget)
119 | self.unloadBagButton.setEnabled(False)
120 |
121 | def _updateRadioSelection(self):
122 | '''When radio group changes, enable/disable the sample interval.'''
123 | if self.takeSampleRadio.isChecked():
124 | self.sampleIntervalGroup.setEnabled(True)
125 | else:
126 | self.sampleIntervalGroup.setEnabled(False)
127 |
128 | def _updateDataLoadingOptions(self):
129 | '''Adjust the available loading options if a raster is selected.
130 |
131 | Raster data types aren't subscriptable. Must use Take Latest instead.
132 | '''
133 | name, topicType = self.dataLoaderWidget.getSelectedTopic()
134 | dataModelType = TranslatorRegistry.instance().get(topicType).dataModelType
135 | isRaster = dataModelType == 'Raster'
136 |
137 | self.takeAllRadio.setEnabled(not isRaster)
138 | self.takeSampleRadio.setEnabled(not isRaster)
139 | self.takeLastRadio.setChecked(isRaster)
140 |
141 | self._updateRadioSelection()
142 |
--------------------------------------------------------------------------------
/src/qgis_ros/ui/bagfile_dialog.ui:
--------------------------------------------------------------------------------
1 |
2 |
3 | Dialog
4 |
5 |
6 |
7 | 0
8 | 0
9 | 1200
10 | 747
11 |
12 |
13 |
14 |
15 | 0
16 | 0
17 |
18 |
19 |
20 | Load Bag Data
21 |
22 |
23 | -
24 |
25 |
26 |
-
27 |
28 |
29 | Bag:
30 |
31 |
32 |
33 | -
34 |
35 |
36 |
37 | 75
38 | true
39 |
40 |
41 |
42 | No bag selected
43 |
44 |
45 |
46 | -
47 |
48 |
49 | Qt::Horizontal
50 |
51 |
52 |
53 | 40
54 | 20
55 |
56 |
57 |
58 |
59 | -
60 |
61 |
62 | false
63 |
64 |
65 | Unload Bag
66 |
67 |
68 |
69 |
70 |
71 |
72 | -
73 |
74 |
75 | 1
76 |
77 |
78 |
79 |
-
80 |
81 |
82 |
83 | 0
84 | 0
85 |
86 |
87 |
88 |
89 | -
90 |
91 |
92 |
93 | 0
94 | 0
95 |
96 |
97 |
98 |
-
99 |
100 |
101 |
102 | 0
103 | 0
104 |
105 |
106 |
107 | Options
108 |
109 |
110 |
-
111 |
112 |
113 |
-
114 |
115 |
116 | Take every message from the bagfile
117 |
118 |
119 | Take All
120 |
121 |
122 | true
123 |
124 |
125 | takeRadioGroup
126 |
127 |
128 |
129 | -
130 |
131 |
132 | Take only the most recent message (typically for latched data)
133 |
134 |
135 | Take Last
136 |
137 |
138 | false
139 |
140 |
141 | takeRadioGroup
142 |
143 |
144 |
145 | -
146 |
147 |
148 | Take every nth message from the bagfile.
149 |
150 |
151 | Take Sample
152 |
153 |
154 | takeRadioGroup
155 |
156 |
157 |
158 |
159 |
160 |
161 | -
162 |
163 |
164 | false
165 |
166 |
167 |
-
168 |
169 |
170 | Record only every nth message from the bagfile.
171 |
172 |
173 | Sample Interval:
174 |
175 |
176 |
177 | -
178 |
179 |
180 | Record only every nth message from the bagfile.
181 |
182 |
183 | 1
184 |
185 |
186 | 100000
187 |
188 |
189 |
190 |
191 |
192 |
193 |
194 |
195 |
196 | -
197 |
198 |
199 | Qt::Horizontal
200 |
201 |
202 |
203 | 40
204 | 20
205 |
206 |
207 |
208 |
209 | -
210 |
211 |
212 | Add selected layer to the QGIS layer manager pane
213 |
214 |
215 | Add Layer
216 |
217 |
218 |
219 | -
220 |
221 |
222 | Qt::Horizontal
223 |
224 |
225 |
226 | 40
227 | 20
228 |
229 |
230 |
231 |
232 |
233 |
234 |
235 |
236 |
237 |
238 |
239 | -
240 |
241 |
242 |
243 | 0
244 | 0
245 |
246 |
247 |
248 | Open Bag...
249 |
250 |
251 |
252 |
253 |
254 |
255 |
256 |
257 |
258 |
259 |
260 | DataLoaderWidget
261 | QWidget
262 | qgis_ros/ui/data_loader_widget.h
263 | 1
264 |
265 |
266 |
267 |
268 |
269 |
270 |
271 |
272 |
--------------------------------------------------------------------------------
/src/qgis_ros/ui/data_loader_widget.py:
--------------------------------------------------------------------------------
1 | import os
2 | from pathlib import Path
3 |
4 | from PyQt5 import uic
5 |
6 | from PyQt5.QtWidgets import QWidget, QTableWidgetItem, QHeaderView
7 | from PyQt5.QtCore import pyqtSignal
8 |
9 | from ..core import TranslatorRegistry
10 |
11 | FORM_CLASS, _ = uic.loadUiType(str(Path(os.path.dirname(__file__)) / 'data_loader_widget.ui'))
12 |
13 |
14 | class DataLoaderWidget(QWidget, FORM_CLASS):
15 |
16 | selectedTopicChanged = pyqtSignal()
17 |
18 | def __init__(self, parent=None):
19 | super(DataLoaderWidget, self).__init__(parent)
20 | self._showMessageCount = False
21 | self.setupUi(self)
22 |
23 | self.tableWidget.itemSelectionChanged.connect(self.selectedTopicChanged)
24 |
25 | def setTopics(self, topicMetadata):
26 | '''Populates table with a new set of topicMetadata.'''
27 | self.tableWidget.clearContents()
28 |
29 | if topicMetadata is None:
30 | return
31 |
32 | # Filter untranslatable topicMetadata
33 | topicMetadata = [t for t in topicMetadata if t[1] in TranslatorRegistry.instance().translatableTypeNames]
34 |
35 | # Populate table.
36 | self.tableWidget.setRowCount(len(topicMetadata))
37 | for row, topicMetadata in enumerate(topicMetadata):
38 | dataModelType = TranslatorRegistry.instance().get(topicMetadata[1]).dataModelType
39 | self.tableWidget.setItem(row, 0, QTableWidgetItem(topicMetadata[0]))
40 | self.tableWidget.setItem(row, 1, QTableWidgetItem(topicMetadata[1]))
41 | self.tableWidget.setItem(row, 2, QTableWidgetItem(dataModelType))
42 |
43 | try:
44 | self.tableWidget.setItem(row, 3, QTableWidgetItem(str(topicMetadata[2])))
45 | except Exception:
46 | pass # No data count available.
47 |
48 | header = self.tableWidget.horizontalHeader()
49 | header.setSectionResizeMode(0, QHeaderView.ResizeToContents)
50 | header.setSectionResizeMode(1, QHeaderView.ResizeToContents)
51 | header.setSectionResizeMode(2, QHeaderView.ResizeToContents)
52 |
53 | def getSelectedTopic(self):
54 | row = self.tableWidget.currentRow()
55 | topicName = self.tableWidget.item(row, 0).text()
56 | topicType = self.tableWidget.item(row, 1).text()
57 |
58 | return topicName, topicType
59 |
--------------------------------------------------------------------------------
/src/qgis_ros/ui/data_loader_widget.ui:
--------------------------------------------------------------------------------
1 |
2 |
3 | DataLoaderWidget
4 |
5 |
6 |
7 | 0
8 | 0
9 | 838
10 | 777
11 |
12 |
13 |
14 | QGIS ROS
15 |
16 |
17 | -
18 |
19 |
20 | QAbstractItemView::SingleSelection
21 |
22 |
23 | QAbstractItemView::SelectRows
24 |
25 |
26 | true
27 |
28 |
29 | 0
30 |
31 |
32 | 4
33 |
34 |
35 | true
36 |
37 |
38 | true
39 |
40 |
41 | true
42 |
43 |
44 | true
45 |
46 |
47 | true
48 |
49 |
50 | false
51 |
52 |
53 |
54 | Topic Name
55 |
56 |
57 |
58 |
59 | Message Type
60 |
61 |
62 |
63 |
64 | Data Type
65 |
66 |
67 |
68 |
69 | Count
70 |
71 |
72 |
73 |
74 |
75 |
76 |
77 |
78 |
79 |
--------------------------------------------------------------------------------
/src/qgis_ros/ui/ros_master_dialog.py:
--------------------------------------------------------------------------------
1 | from pathlib import Path
2 | import os
3 | import threading
4 |
5 | from PyQt5 import uic
6 | from PyQt5.QtWidgets import QDialog
7 | from PyQt5.QtCore import QTimer, pyqtSignal
8 |
9 | from qgis.core import QgsProject
10 |
11 | from socket import error as socket_error
12 | import rosgraph
13 | import rospy
14 |
15 | from ..core import TranslatorRegistry
16 |
17 |
18 | FORM_CLASS, _ = uic.loadUiType(str(Path(os.path.dirname(__file__)) / 'ros_master_dialog.ui'))
19 |
20 |
21 | class ROSMasterDialog(QDialog, FORM_CLASS):
22 |
23 | layerCreated = pyqtSignal(object)
24 |
25 | def __init__(self, parent=None):
26 | super(ROSMasterDialog, self).__init__(parent)
27 | self.setupUi(self)
28 | self.dataLoaderWidget.tableWidget.removeColumn(3) # Don't need "count" field.
29 |
30 | self.addLayerButton.clicked.connect(self._createLayerFromSelected)
31 | self.layerCreated.connect(self._addCreatedLayer)
32 |
33 | # Check every two seconds for a ROS master.
34 | self.checkMasterTimer = QTimer()
35 | self.checkMasterTimer.timeout.connect(self._checkForMaster)
36 | self.checkMasterTimer.start(2000)
37 |
38 | # Update UI depending on which data loading method is selected.
39 | self.subscribeRadioGroup.buttonClicked.connect(self._updateKeepOlderMessagesCheckbox)
40 |
41 | # Update UI depending on what the selected layer's data type is.
42 | self.dataLoaderWidget.selectedTopicChanged.connect(self._updateDataLoadingOptions)
43 |
44 | # Report current state of ROS MASTER search to user.
45 | masterUri = os.environ.get('ROS_MASTER_URI')
46 | if masterUri:
47 | label = 'Searching for ROS Master at: {}...'.format(masterUri)
48 | else:
49 | label = 'Environment variable `ROS_MASTER_URI` not set. Cannot initialize node.'
50 | self.checkMasterTimer.stop()
51 | self.searchMasterLabel.setText(label)
52 |
53 | def _checkForMaster(self):
54 | try:
55 | rosgraph.Master('/rostopic').getPid()
56 | except socket_error:
57 | pass # No master found.
58 | else:
59 | # Master found. Init node then update UI state.
60 | rospy.init_node('qgis_ros_toolbox')
61 | self._getAvailableTopics()
62 |
63 | self.checkMasterTimer.stop()
64 | self.currentRosMasterLabel.setText(os.environ['ROS_MASTER_URI'])
65 | self.stackedWidget.setCurrentWidget(self.dataLoaderWidgetContainer)
66 |
67 | def _getAvailableTopics(self):
68 | topicMetadata = [(topicName, topicType) for topicName, topicType in rospy.get_published_topics()]
69 | self.dataLoaderWidget.setTopics(topicMetadata)
70 |
71 | def _createLayerFromSelected(self):
72 | threading.Thread(name='createLayerThread', target=self._createLayerWorker).start()
73 |
74 | def _createLayerWorker(self):
75 | name, topicType = self.dataLoaderWidget.getSelectedTopic()
76 |
77 | subscribe = self.subscribeRadio.isChecked()
78 | keepOlderMessages = self.keepOlderMessagesCheckbox.isChecked()
79 | sampleInterval = self.sampleIntervalBox.value()
80 |
81 | translator = TranslatorRegistry.instance().get(topicType)
82 |
83 | layer = translator.createLayer(
84 | name,
85 | subscribe=subscribe,
86 | keepOlderMessages=keepOlderMessages,
87 | sampleInterval=sampleInterval
88 | )
89 |
90 | self.layerCreated.emit(layer) # Need to add layer from main thread.
91 |
92 | def _addCreatedLayer(self, layer):
93 | QgsProject.instance().addMapLayer(layer)
94 |
95 | def _updateKeepOlderMessagesCheckbox(self):
96 | self.keepOlderMessagesCheckbox.setEnabled(not self.takeLatestRadio.isChecked())
97 |
98 | def _updateDataLoadingOptions(self):
99 | '''Adjust the available loading options if a raster is selected.
100 |
101 | Raster data types aren't subscriptable. Must use Take Latest instead.
102 | '''
103 | name, topicType = self.dataLoaderWidget.getSelectedTopic()
104 | dataModelType = TranslatorRegistry.instance().get(topicType).dataModelType
105 | isRaster = dataModelType == 'Raster'
106 |
107 | self.subscribeRadio.setEnabled(not isRaster)
108 | self.takeLatestRadio.setChecked(isRaster)
109 |
110 | self._updateKeepOlderMessagesCheckbox()
111 |
--------------------------------------------------------------------------------
/src/qgis_ros/ui/ros_master_dialog.ui:
--------------------------------------------------------------------------------
1 |
2 |
3 | Dialog
4 |
5 |
6 |
7 | 0
8 | 0
9 | 1200
10 | 1000
11 |
12 |
13 |
14 |
15 | 0
16 | 0
17 |
18 |
19 |
20 | Load Topic Data
21 |
22 |
23 | -
24 |
25 |
26 |
-
27 |
28 |
29 | ROS Master:
30 |
31 |
32 |
33 | -
34 |
35 |
36 |
37 | 75
38 | true
39 |
40 |
41 |
42 | Unknown
43 |
44 |
45 |
46 | -
47 |
48 |
49 | Qt::Horizontal
50 |
51 |
52 |
53 | 40
54 | 20
55 |
56 |
57 |
58 |
59 |
60 |
61 |
62 | -
63 |
64 |
65 | 1
66 |
67 |
68 |
69 |
-
70 |
71 |
72 |
73 | 0
74 | 0
75 |
76 |
77 |
78 |
79 | -
80 |
81 |
82 |
-
83 |
84 |
85 | Options
86 |
87 |
88 |
-
89 |
90 |
91 |
-
92 |
93 |
94 | Continually capture messages published to selected topic
95 |
96 |
97 | Subscribe
98 |
99 |
100 | true
101 |
102 |
103 | subscribeRadioGroup
104 |
105 |
106 |
107 | -
108 |
109 |
110 | Take only the most recent message (typically for latched data)
111 |
112 |
113 | Take Latest
114 |
115 |
116 | false
117 |
118 |
119 | subscribeRadioGroup
120 |
121 |
122 |
123 | -
124 |
125 |
126 | Qt::Horizontal
127 |
128 |
129 |
130 | 40
131 | 20
132 |
133 |
134 |
135 |
136 |
137 |
138 |
139 | -
140 |
141 |
142 |
-
143 |
144 |
145 | When subscribed, record only every nth message
146 |
147 |
148 | Sample Interval:
149 |
150 |
151 |
152 | -
153 |
154 |
155 | When subscribed, record only every nth message
156 |
157 |
158 | 1
159 |
160 |
161 | 100
162 |
163 |
164 |
165 | -
166 |
167 |
168 | When checked, all messages are preserved as records, instead of only the latest message
169 |
170 |
171 | Qt::RightToLeft
172 |
173 |
174 | Keep older messages:
175 |
176 |
177 |
178 |
179 |
180 |
181 |
182 |
183 |
184 | -
185 |
186 |
187 | Qt::Horizontal
188 |
189 |
190 |
191 | 40
192 | 20
193 |
194 |
195 |
196 |
197 | -
198 |
199 |
200 | Add selected layer to the QGIS layer manager pane
201 |
202 |
203 | Add Layer
204 |
205 |
206 |
207 | -
208 |
209 |
210 | Qt::Horizontal
211 |
212 |
213 |
214 | 40
215 | 20
216 |
217 |
218 |
219 |
220 |
221 |
222 |
223 |
224 |
225 |
226 |
227 | -
228 |
229 |
230 | Searching for ROS Master...
231 |
232 |
233 | Qt::AlignCenter
234 |
235 |
236 |
237 |
238 |
239 |
240 |
241 |
242 |
243 |
244 |
245 | DataLoaderWidget
246 | QWidget
247 | qgis_ros/ui/data_loader_widget.h
248 | 1
249 |
250 |
251 |
252 |
253 |
254 |
255 |
256 |
257 |
--------------------------------------------------------------------------------