From 5195f0a6240ec2f96b472d8ee758ddbbbc5243dd Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Wed, 31 Jan 2024 11:52:44 -0600 Subject: [PATCH 001/263] [bot] Fingerprints: add missing FW versions from new users (#31245) --- selfdrive/car/chrysler/fingerprints.py | 3 +++ selfdrive/car/mazda/fingerprints.py | 2 -- 2 files changed, 3 insertions(+), 2 deletions(-) diff --git a/selfdrive/car/chrysler/fingerprints.py b/selfdrive/car/chrysler/fingerprints.py index f9a3fe5b10..940d73c249 100644 --- a/selfdrive/car/chrysler/fingerprints.py +++ b/selfdrive/car/chrysler/fingerprints.py @@ -395,6 +395,7 @@ FW_VERSIONS = { b'68527383AD', b'68527387AE', b'68527403AC', + b'68631938AA', b'68631942AA', ], (Ecu.srs, 0x744, None): [ @@ -459,6 +460,7 @@ FW_VERSIONS = { b'68552791AB', b'68552794AA', b'68585106AB', + b'68585107AB', b'68585108AB', b'68585109AB', b'68585112AB', @@ -508,6 +510,7 @@ FW_VERSIONS = { b'68539651AD', b'68586101AA ', b'68586105AB ', + b'68629922AC ', b'68629926AC ', ], (Ecu.transmission, 0x7e1, None): [ diff --git a/selfdrive/car/mazda/fingerprints.py b/selfdrive/car/mazda/fingerprints.py index 292f407935..aa91f0fb31 100644 --- a/selfdrive/car/mazda/fingerprints.py +++ b/selfdrive/car/mazda/fingerprints.py @@ -235,7 +235,6 @@ FW_VERSIONS = { b'PXM4-188K2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'PXM4-188K2-D\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'PXM6-188K2-E\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PXM7-188K2-E\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', ], (Ecu.fwdRadar, 0x764, None): [ b'K131-67XK2-E\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', @@ -254,7 +253,6 @@ FW_VERSIONS = { (Ecu.transmission, 0x7e1, None): [ b'PXM4-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'PXM6-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PXM7-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', ], }, } From 6010a39bf8cb030b5b10e1d0657f9291467b6872 Mon Sep 17 00:00:00 2001 From: Justin Newberry Date: Wed, 31 Jan 2024 19:43:58 -0500 Subject: [PATCH 002/263] LogReader: skip file_exists check for comma_api (#31251) * valid file * missed this one --- tools/lib/logreader.py | 23 +++++++++++++++-------- 1 file changed, 15 insertions(+), 8 deletions(-) diff --git a/tools/lib/logreader.py b/tools/lib/logreader.py index c53b9c4c79..decffccd66 100755 --- a/tools/lib/logreader.py +++ b/tools/lib/logreader.py @@ -89,28 +89,31 @@ def create_slice_from_string(s: str): return start return slice(start, end, step) -def auto_strategy(rlog_paths, qlog_paths, interactive): +def default_valid_file(fn): + return fn is not None and file_exists(fn) + +def auto_strategy(rlog_paths, qlog_paths, interactive, valid_file): # auto select logs based on availability - if any(rlog is None or not file_exists(rlog) for rlog in rlog_paths): + if any(rlog is None or not valid_file(rlog) for rlog in rlog_paths): if interactive: if input("Some rlogs were not found, would you like to fallback to qlogs for those segments? (y/n) ").lower() != "y": return rlog_paths else: cloudlog.warning("Some rlogs were not found, falling back to qlogs for those segments...") - return [rlog if (rlog is not None and file_exists(rlog)) else (qlog if (qlog is not None and file_exists(qlog)) else None) - for (rlog, qlog) in zip(rlog_paths, qlog_paths, strict=True)] + return [rlog if (valid_file(rlog)) else (qlog if (valid_file(qlog)) else None) + for (rlog, qlog) in zip(rlog_paths, qlog_paths, strict=True)] return rlog_paths -def apply_strategy(mode: ReadMode, rlog_paths, qlog_paths): +def apply_strategy(mode: ReadMode, rlog_paths, qlog_paths, valid_file=default_valid_file): if mode == ReadMode.RLOG: return rlog_paths elif mode == ReadMode.QLOG: return qlog_paths elif mode == ReadMode.AUTO: - return auto_strategy(rlog_paths, qlog_paths, False) + return auto_strategy(rlog_paths, qlog_paths, False, valid_file) elif mode == ReadMode.AUTO_INTERACIVE: - return auto_strategy(rlog_paths, qlog_paths, True) + return auto_strategy(rlog_paths, qlog_paths, True, valid_file) def parse_slice(sr: SegmentRange): s = create_slice_from_string(sr._slice) @@ -133,7 +136,11 @@ def comma_api_source(sr: SegmentRange, mode: ReadMode): rlog_paths = [route.log_paths()[seg] for seg in segs] qlog_paths = [route.qlog_paths()[seg] for seg in segs] - return apply_strategy(mode, rlog_paths, qlog_paths) + # comma api will have already checked if the file exists + def valid_file(fn): + return fn is not None + + return apply_strategy(mode, rlog_paths, qlog_paths, valid_file=valid_file) def internal_source(sr: SegmentRange, mode: ReadMode): segs = parse_slice(sr) From 7222eb3665aea9483fbaa672640c22b3f9856e22 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Wed, 31 Jan 2024 20:20:33 -0600 Subject: [PATCH 003/263] Nissan: use bus 0 to fingerprint (#31243) * Nissan: use bus 0 to fingerprint * update refs * switch OBD query to be logging instead, might want OBD logging for one more release --- selfdrive/car/nissan/values.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/selfdrive/car/nissan/values.py b/selfdrive/car/nissan/values.py index c013b2056f..d064ce894d 100644 --- a/selfdrive/car/nissan/values.py +++ b/selfdrive/car/nissan/values.py @@ -59,7 +59,7 @@ NISSAN_VERSION_RESPONSE_KWP = b'\x61\x83' NISSAN_RX_OFFSET = 0x20 FW_QUERY_CONFIG = FwQueryConfig( - requests=[request for bus, logging in ((0, True), (1, False)) for request in [ + requests=[request for bus, logging in ((0, False), (1, True)) for request in [ Request( [NISSAN_DIAGNOSTIC_REQUEST_KWP, NISSAN_VERSION_REQUEST_KWP], [NISSAN_DIAGNOSTIC_RESPONSE_KWP, NISSAN_VERSION_RESPONSE_KWP], From 5c85925e9bc5baf709f4630545a76a11e044f936 Mon Sep 17 00:00:00 2001 From: Justin Newberry Date: Wed, 31 Jan 2024 21:44:04 -0500 Subject: [PATCH 004/263] test_athenad: create with_upload_handler decorator (#31250) cleaner --- selfdrive/athena/tests/test_athenad.py | 143 +++++++++++-------------- 1 file changed, 60 insertions(+), 83 deletions(-) diff --git a/selfdrive/athena/tests/test_athenad.py b/selfdrive/athena/tests/test_athenad.py index 9c7582a260..2fecab1b1b 100755 --- a/selfdrive/athena/tests/test_athenad.py +++ b/selfdrive/athena/tests/test_athenad.py @@ -1,5 +1,5 @@ #!/usr/bin/env python3 -from functools import partial +from functools import partial, wraps import json import multiprocessing import os @@ -42,6 +42,20 @@ def seed_athena_server(host, port): with_mock_athena = partial(with_http_server, handler=HTTPRequestHandler, setup=seed_athena_server) +def with_upload_handler(func): + @wraps(func) + def wrapper(*args, **kwargs): + end_event = threading.Event() + thread = threading.Thread(target=athenad.upload_handler, args=(end_event,)) + thread.start() + try: + return func(*args, **kwargs) + finally: + end_event.set() + thread.join() + return wrapper + + class TestAthenadMethods(unittest.TestCase): @classmethod def setUpClass(cls): @@ -209,77 +223,59 @@ class TestAthenadMethods(unittest.TestCase): self.assertEqual(not_exists_resp, {'enqueued': 0, 'items': [], 'failed': ['does_not_exist.bz2']}) @with_mock_athena + @with_upload_handler def test_upload_handler(self, host): fn = self._create_file('qlog.bz2') item = athenad.UploadItem(path=fn, url=f"{host}/qlog.bz2", headers={}, created_at=int(time.time()*1000), id='', allow_cellular=True) - end_event = threading.Event() - thread = threading.Thread(target=athenad.upload_handler, args=(end_event,)) - thread.start() - athenad.upload_queue.put_nowait(item) - try: - self._wait_for_upload() - time.sleep(0.1) + self._wait_for_upload() + time.sleep(0.1) - # TODO: verify that upload actually succeeded - self.assertEqual(athenad.upload_queue.qsize(), 0) - finally: - end_event.set() + # TODO: verify that upload actually succeeded + self.assertEqual(athenad.upload_queue.qsize(), 0) + @parameterized.expand([(500, True), (412, False)]) @with_mock_athena @mock.patch('requests.put') - def test_upload_handler_retry(self, host, mock_put): - for status, retry in ((500, True), (412, False)): - mock_put.return_value.status_code = status - fn = self._create_file('qlog.bz2') - item = athenad.UploadItem(path=fn, url=f"{host}/qlog.bz2", headers={}, created_at=int(time.time()*1000), id='', allow_cellular=True) - - end_event = threading.Event() - thread = threading.Thread(target=athenad.upload_handler, args=(end_event,)) - thread.start() + @with_upload_handler + def test_upload_handler_retry(self, status, retry, mock_put, host): + mock_put.return_value.status_code = status + fn = self._create_file('qlog.bz2') + item = athenad.UploadItem(path=fn, url=f"{host}/qlog.bz2", headers={}, created_at=int(time.time()*1000), id='', allow_cellular=True) - athenad.upload_queue.put_nowait(item) - try: - self._wait_for_upload() - time.sleep(0.1) + athenad.upload_queue.put_nowait(item) + self._wait_for_upload() + time.sleep(0.1) - self.assertEqual(athenad.upload_queue.qsize(), 1 if retry else 0) - finally: - end_event.set() + self.assertEqual(athenad.upload_queue.qsize(), 1 if retry else 0) - if retry: - self.assertEqual(athenad.upload_queue.get().retry_count, 1) + if retry: + self.assertEqual(athenad.upload_queue.get().retry_count, 1) + @with_upload_handler def test_upload_handler_timeout(self): """When an upload times out or fails to connect it should be placed back in the queue""" fn = self._create_file('qlog.bz2') item = athenad.UploadItem(path=fn, url="http://localhost:44444/qlog.bz2", headers={}, created_at=int(time.time()*1000), id='', allow_cellular=True) item_no_retry = replace(item, retry_count=MAX_RETRY_COUNT) - end_event = threading.Event() - thread = threading.Thread(target=athenad.upload_handler, args=(end_event,)) - thread.start() - - try: - athenad.upload_queue.put_nowait(item_no_retry) - self._wait_for_upload() - time.sleep(0.1) - - # Check that upload with retry count exceeded is not put back - self.assertEqual(athenad.upload_queue.qsize(), 0) + athenad.upload_queue.put_nowait(item_no_retry) + self._wait_for_upload() + time.sleep(0.1) - athenad.upload_queue.put_nowait(item) - self._wait_for_upload() - time.sleep(0.1) + # Check that upload with retry count exceeded is not put back + self.assertEqual(athenad.upload_queue.qsize(), 0) - # Check that upload item was put back in the queue with incremented retry count - self.assertEqual(athenad.upload_queue.qsize(), 1) - self.assertEqual(athenad.upload_queue.get().retry_count, 1) + athenad.upload_queue.put_nowait(item) + self._wait_for_upload() + time.sleep(0.1) - finally: - end_event.set() + # Check that upload item was put back in the queue with incremented retry count + self.assertEqual(athenad.upload_queue.qsize(), 1) + self.assertEqual(athenad.upload_queue.get().retry_count, 1) + @with_upload_handler def test_cancelUpload(self): item = athenad.UploadItem(path="qlog.bz2", url="http://localhost:44444/qlog.bz2", headers={}, created_at=int(time.time()*1000), id='id', allow_cellular=True) @@ -288,18 +284,13 @@ class TestAthenadMethods(unittest.TestCase): self.assertIn(item.id, athenad.cancelled_uploads) - end_event = threading.Event() - thread = threading.Thread(target=athenad.upload_handler, args=(end_event,)) - thread.start() - try: - self._wait_for_upload() - time.sleep(0.1) + self._wait_for_upload() + time.sleep(0.1) - self.assertEqual(athenad.upload_queue.qsize(), 0) - self.assertEqual(len(athenad.cancelled_uploads), 0) - finally: - end_event.set() + self.assertEqual(athenad.upload_queue.qsize(), 0) + self.assertEqual(len(athenad.cancelled_uploads), 0) + @with_upload_handler def test_cancelExpiry(self): t_future = datetime.now() - timedelta(days=40) ts = int(t_future.strftime("%s")) * 1000 @@ -308,42 +299,28 @@ class TestAthenadMethods(unittest.TestCase): fn = self._create_file('qlog.bz2') item = athenad.UploadItem(path=fn, url="http://localhost:44444/qlog.bz2", headers={}, created_at=ts, id='', allow_cellular=True) + athenad.upload_queue.put_nowait(item) + self._wait_for_upload() + time.sleep(0.1) - end_event = threading.Event() - thread = threading.Thread(target=athenad.upload_handler, args=(end_event,)) - thread.start() - try: - athenad.upload_queue.put_nowait(item) - self._wait_for_upload() - time.sleep(0.1) - - self.assertEqual(athenad.upload_queue.qsize(), 0) - finally: - end_event.set() + self.assertEqual(athenad.upload_queue.qsize(), 0) def test_listUploadQueueEmpty(self): items = dispatcher["listUploadQueue"]() self.assertEqual(len(items), 0) @with_http_server + @with_upload_handler def test_listUploadQueueCurrent(self, host: str): fn = self._create_file('qlog.bz2') item = athenad.UploadItem(path=fn, url=f"{host}/qlog.bz2", headers={}, created_at=int(time.time()*1000), id='', allow_cellular=True) - end_event = threading.Event() - thread = threading.Thread(target=athenad.upload_handler, args=(end_event,)) - thread.start() - - try: - athenad.upload_queue.put_nowait(item) - self._wait_for_upload() - - items = dispatcher["listUploadQueue"]() - self.assertEqual(len(items), 1) - self.assertTrue(items[0]['current']) + athenad.upload_queue.put_nowait(item) + self._wait_for_upload() - finally: - end_event.set() + items = dispatcher["listUploadQueue"]() + self.assertEqual(len(items), 1) + self.assertTrue(items[0]['current']) def test_listUploadQueue(self): item = athenad.UploadItem(path="qlog.bz2", url="http://localhost:44444/qlog.bz2", headers={}, From 1ab37454009d5a40e441350e1abaa615ab36ec6d Mon Sep 17 00:00:00 2001 From: Eric Brown Date: Wed, 31 Jan 2024 19:45:10 -0700 Subject: [PATCH 005/263] GM: Fix wheel direction signals (#31258) * Fix wheel direction signals * Update name * Add comment * Remove signal value table Co-authored-by: Shane Smiskol * bump * add 3 --------- Co-authored-by: Shane Smiskol --- opendbc | 2 +- selfdrive/car/gm/carstate.py | 4 +++- 2 files changed, 4 insertions(+), 2 deletions(-) diff --git a/opendbc b/opendbc index 3cfd0bf4eb..7397e466d9 160000 --- a/opendbc +++ b/opendbc @@ -1 +1 @@ -Subproject commit 3cfd0bf4eb73953f3d179dddc1ba2c92e317188c +Subproject commit 7397e466d9cfd7f5bc1f49218b8d2afeedec582b diff --git a/selfdrive/car/gm/carstate.py b/selfdrive/car/gm/carstate.py index f7309939b1..c3d061de78 100644 --- a/selfdrive/car/gm/carstate.py +++ b/selfdrive/car/gm/carstate.py @@ -33,7 +33,9 @@ class CarState(CarStateBase): self.cruise_buttons = pt_cp.vl["ASCMSteeringButton"]["ACCButtons"] self.buttons_counter = pt_cp.vl["ASCMSteeringButton"]["RollingCounter"] self.pscm_status = copy.copy(pt_cp.vl["PSCMStatus"]) - self.moving_backward = pt_cp.vl["EBCMWheelSpdRear"]["MovingBackward"] != 0 + # This is to avoid a fault where you engage while still moving backwards after shifting to D. + # An Equinox has been seen with an unsupported status (3), so only check if either wheel is in reverse (2) + self.moving_backward = (pt_cp.vl["EBCMWheelSpdRear"]["RLWheelDir"] == 2) or (pt_cp.vl["EBCMWheelSpdRear"]["RRWheelDir"] == 2) # Variables used for avoiding LKAS faults self.loopback_lka_steering_cmd_updated = len(loopback_cp.vl_all["ASCMLKASteeringCmd"]["RollingCounter"]) > 0 From be33b0049982ade3cc639998c8142b373693c929 Mon Sep 17 00:00:00 2001 From: Justin Newberry Date: Wed, 31 Jan 2024 21:46:40 -0500 Subject: [PATCH 006/263] Jenkins: better timeout when disconnected from devices (#31256) * timeout better * timeoutes --- Jenkinsfile | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Jenkinsfile b/Jenkinsfile index e45bcd16b2..efea896d94 100644 --- a/Jenkinsfile +++ b/Jenkinsfile @@ -12,7 +12,7 @@ def retryWithDelay(int maxRetries, int delay, Closure body) { def device(String ip, String step_label, String cmd) { withCredentials([file(credentialsId: 'id_rsa', variable: 'key_file')]) { def ssh_cmd = """ -ssh -tt -o StrictHostKeyChecking=no -i ${key_file} 'comma@${ip}' /usr/bin/bash <<'END' +ssh -tt -o ConnectTimeout=30 -o ServerAliveInterval=30 -o ServerAliveCountMax=3 -o BatchMode=yes -o StrictHostKeyChecking=no -i ${key_file} 'comma@${ip}' /usr/bin/bash <<'END' set -e From 086c509fde806bb03f89765800d9667f4de6a372 Mon Sep 17 00:00:00 2001 From: Justin Newberry Date: Wed, 31 Jan 2024 21:47:49 -0500 Subject: [PATCH 007/263] Create message mocking tools (#31249) * add mocking tools * fix map renderer * use for power draw * fix those * whitespace * rename to services * fix the rate * remove --- common/mock/__init__.py | 51 +++++++++++++++++++ common/mock/generators.py | 20 ++++++++ .../controls/lib/tests/test_latcontrol.py | 4 +- selfdrive/navd/tests/test_map_renderer.py | 18 +------ selfdrive/ui/tests/test_ui/run.py | 6 +-- system/hardware/tici/tests/test_power_draw.py | 16 +----- 6 files changed, 79 insertions(+), 36 deletions(-) create mode 100644 common/mock/__init__.py create mode 100644 common/mock/generators.py diff --git a/common/mock/__init__.py b/common/mock/__init__.py new file mode 100644 index 0000000000..e0dbf45c74 --- /dev/null +++ b/common/mock/__init__.py @@ -0,0 +1,51 @@ +""" +Utilities for generating mock messages for testing. +example in common/tests/test_mock.py +""" + + +import functools +import threading +from typing import List, Union +from cereal.messaging import PubMaster +from cereal.services import SERVICE_LIST +from openpilot.common.mock.generators import generate_liveLocationKalman +from openpilot.common.realtime import Ratekeeper + + +MOCK_GENERATOR = { + "liveLocationKalman": generate_liveLocationKalman +} + + +def generate_messages_loop(services: List[str], done: threading.Event): + pm = PubMaster(services) + rk = Ratekeeper(100) + i = 0 + while not done.is_set(): + for s in services: + should_send = i % (100/SERVICE_LIST[s].frequency) == 0 + if should_send: + message = MOCK_GENERATOR[s]() + pm.send(s, message) + i += 1 + rk.keep_time() + + +def mock_messages(services: Union[List[str], str]): + if isinstance(services, str): + services = [services] + + def decorator(func): + @functools.wraps(func) + def wrapper(*args, **kwargs): + done = threading.Event() + t = threading.Thread(target=generate_messages_loop, args=(services, done)) + t.start() + try: + return func(*args, **kwargs) + finally: + done.set() + t.join() + return wrapper + return decorator diff --git a/common/mock/generators.py b/common/mock/generators.py new file mode 100644 index 0000000000..40951faf85 --- /dev/null +++ b/common/mock/generators.py @@ -0,0 +1,20 @@ +from cereal import messaging + + +LOCATION1 = (32.7174, -117.16277) +LOCATION2 = (32.7558, -117.2037) + +LLK_DECIMATION = 10 +RENDER_FRAMES = 15 +DEFAULT_ITERATIONS = RENDER_FRAMES * LLK_DECIMATION + + +def generate_liveLocationKalman(location=LOCATION1): + msg = messaging.new_message('liveLocationKalman') + msg.liveLocationKalman.positionGeodetic = {'value': [*location, 0], 'std': [0., 0., 0.], 'valid': True} + msg.liveLocationKalman.positionECEF = {'value': [0., 0., 0.], 'std': [0., 0., 0.], 'valid': True} + msg.liveLocationKalman.calibratedOrientationNED = {'value': [0., 0., 0.], 'std': [0., 0., 0.], 'valid': True} + msg.liveLocationKalman.velocityCalibrated = {'value': [0., 0., 0.], 'std': [0., 0., 0.], 'valid': True} + msg.liveLocationKalman.status = 'valid' + msg.liveLocationKalman.gpsOK = True + return msg diff --git a/selfdrive/controls/lib/tests/test_latcontrol.py b/selfdrive/controls/lib/tests/test_latcontrol.py index 248abf1d7b..866270ca60 100755 --- a/selfdrive/controls/lib/tests/test_latcontrol.py +++ b/selfdrive/controls/lib/tests/test_latcontrol.py @@ -12,7 +12,7 @@ from openpilot.selfdrive.controls.lib.latcontrol_pid import LatControlPID from openpilot.selfdrive.controls.lib.latcontrol_torque import LatControlTorque from openpilot.selfdrive.controls.lib.latcontrol_angle import LatControlAngle from openpilot.selfdrive.controls.lib.vehicle_model import VehicleModel -from openpilot.selfdrive.navd.tests.test_map_renderer import gen_llk +from openpilot.common.mock.generators import generate_liveLocationKalman class TestLatControl(unittest.TestCase): @@ -32,7 +32,7 @@ class TestLatControl(unittest.TestCase): params = log.LiveParametersData.new_message() - llk = gen_llk() + llk = generate_liveLocationKalman() for _ in range(1000): _, _, lac_log = controller.update(True, CS, VM, params, False, 1, llk) diff --git a/selfdrive/navd/tests/test_map_renderer.py b/selfdrive/navd/tests/test_map_renderer.py index a7289d02d9..b5f186dbb0 100755 --- a/selfdrive/navd/tests/test_map_renderer.py +++ b/selfdrive/navd/tests/test_map_renderer.py @@ -11,30 +11,16 @@ import cereal.messaging as messaging from typing import Any from cereal.visionipc import VisionIpcClient, VisionStreamType +from openpilot.common.mock.generators import LLK_DECIMATION, LOCATION1, LOCATION2, generate_liveLocationKalman from openpilot.selfdrive.test.helpers import with_processes -LLK_DECIMATION = 10 CACHE_PATH = "/data/mbgl-cache-navd.db" -LOCATION1 = (32.7174, -117.16277) -LOCATION2 = (32.7558, -117.2037) - RENDER_FRAMES = 15 DEFAULT_ITERATIONS = RENDER_FRAMES * LLK_DECIMATION - LOCATION1_REPEATED = [LOCATION1] * DEFAULT_ITERATIONS LOCATION2_REPEATED = [LOCATION2] * DEFAULT_ITERATIONS -def gen_llk(location=LOCATION1): - msg = messaging.new_message('liveLocationKalman') - msg.liveLocationKalman.positionGeodetic = {'value': [*location, 0], 'std': [0., 0., 0.], 'valid': True} - msg.liveLocationKalman.positionECEF = {'value': [0., 0., 0.], 'std': [0., 0., 0.], 'valid': True} - msg.liveLocationKalman.calibratedOrientationNED = {'value': [0., 0., 0.], 'std': [0., 0., 0.], 'valid': True} - msg.liveLocationKalman.velocityCalibrated = {'value': [0., 0., 0.], 'std': [0., 0., 0.], 'valid': True} - msg.liveLocationKalman.status = 'valid' - msg.liveLocationKalman.gpsOK = True - return msg - class MapBoxInternetDisabledRequestHandler(http.server.BaseHTTPRequestHandler): INTERNET_ACTIVE = True @@ -134,7 +120,7 @@ class TestMapRenderer(unittest.TestCase): if starting_frame_id is None: starting_frame_id = prev_frame_id - llk = gen_llk(location) + llk = generate_liveLocationKalman(location) self.pm.send("liveLocationKalman", llk) self.pm.wait_for_readers_to_update("liveLocationKalman", 10) self.sm.update(1000 if frame_expected else 0) diff --git a/selfdrive/ui/tests/test_ui/run.py b/selfdrive/ui/tests/test_ui/run.py index 1fea759efb..7a2ac9a110 100644 --- a/selfdrive/ui/tests/test_ui/run.py +++ b/selfdrive/ui/tests/test_ui/run.py @@ -15,10 +15,10 @@ from cereal import messaging, car, log from cereal.visionipc import VisionIpcServer, VisionStreamType from cereal.messaging import SubMaster, PubMaster +from openpilot.common.mock import mock_messages from openpilot.common.params import Params from openpilot.common.realtime import DT_MDL from openpilot.common.transformations.camera import tici_f_frame_size -from openpilot.selfdrive.navd.tests.test_map_renderer import gen_llk from openpilot.selfdrive.test.helpers import with_processes from openpilot.selfdrive.test.process_replay.vision_meta import meta_from_camera_state from openpilot.tools.webcam.camera import Camera @@ -94,12 +94,10 @@ def setup_onroad(click, pm: PubMaster): pm.send(msg.which(), msg) server.send(cam_meta.stream, IMG_BYTES, cs.frameId, cs.timestampSof, cs.timestampEof) +@mock_messages(['liveLocationKalman']) def setup_onroad_map(click, pm: PubMaster): setup_onroad(click, pm) - dat = gen_llk() - pm.send("liveLocationKalman", dat) - click(500, 500) time.sleep(UI_DELAY) # give time for the map to render diff --git a/system/hardware/tici/tests/test_power_draw.py b/system/hardware/tici/tests/test_power_draw.py index eed2ce231b..0518eec543 100755 --- a/system/hardware/tici/tests/test_power_draw.py +++ b/system/hardware/tici/tests/test_power_draw.py @@ -2,7 +2,6 @@ import pytest import unittest import time -import threading import numpy as np from dataclasses import dataclass from tabulate import tabulate @@ -10,12 +9,12 @@ from typing import List import cereal.messaging as messaging from cereal.services import SERVICE_LIST +from openpilot.common.mock import mock_messages from openpilot.selfdrive.car.car_helpers import write_car_param from openpilot.system.hardware import HARDWARE from openpilot.system.hardware.tici.power_monitor import get_power from openpilot.selfdrive.manager.process_config import managed_processes from openpilot.selfdrive.manager.manager import manager_cleanup -from openpilot.selfdrive.navd.tests.test_map_renderer import gen_llk SAMPLE_TIME = 8 # seconds to sample power @@ -37,14 +36,6 @@ PROCS = [ Proc('navmodeld', 0.05, msgs=['navModel']), ] -def send_llk_msg(done): - # Send liveLocationKalman at 20Hz - pm = messaging.PubMaster(['liveLocationKalman']) - while not done.is_set(): - msg = gen_llk() - pm.send('liveLocationKalman', msg) - time.sleep(1/20.) - @pytest.mark.tici class TestPowerDraw(unittest.TestCase): @@ -60,11 +51,9 @@ class TestPowerDraw(unittest.TestCase): def tearDown(self): manager_cleanup() + @mock_messages(['liveLocationKalman']) def test_camera_procs(self): baseline = get_power() - done = threading.Event() - thread = threading.Thread(target=send_llk_msg, args=(done,), daemon=True) - thread.start() prev = baseline used = {} @@ -82,7 +71,6 @@ class TestPowerDraw(unittest.TestCase): for msg,sock in socks.items(): msg_counts[msg] = len(messaging.drain_sock_raw(sock)) - done.set() manager_cleanup() tab = [['process', 'expected (W)', 'measured (W)', '# msgs expected', '# msgs received']] From f0b6f489489731b4d968880d6d9e5a58dbc14035 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Thu, 1 Feb 2024 02:28:00 -0600 Subject: [PATCH 008/263] Mazda: use bus 0 to fingerprint (#31261) * for testing * switch OBD port to logging * revert * cmt * cmt * remove OBD query * Update selfdrive/car/mazda/values.py --- selfdrive/car/mazda/values.py | 7 +------ selfdrive/car/tests/test_fw_fingerprint.py | 4 ++-- 2 files changed, 3 insertions(+), 8 deletions(-) diff --git a/selfdrive/car/mazda/values.py b/selfdrive/car/mazda/values.py index c95ae162f9..b43ab3df66 100644 --- a/selfdrive/car/mazda/values.py +++ b/selfdrive/car/mazda/values.py @@ -67,16 +67,11 @@ class Buttons: FW_QUERY_CONFIG = FwQueryConfig( requests=[ - Request( - [StdQueries.MANUFACTURER_SOFTWARE_VERSION_REQUEST], - [StdQueries.MANUFACTURER_SOFTWARE_VERSION_RESPONSE], - ), - # Log responses on powertrain bus + # TODO: check data to ensure ABS does not skip ISO-TP frames on bus 0 Request( [StdQueries.MANUFACTURER_SOFTWARE_VERSION_REQUEST], [StdQueries.MANUFACTURER_SOFTWARE_VERSION_RESPONSE], bus=0, - logging=True, ), ], ) diff --git a/selfdrive/car/tests/test_fw_fingerprint.py b/selfdrive/car/tests/test_fw_fingerprint.py index 620fa25691..f2de3ab770 100755 --- a/selfdrive/car/tests/test_fw_fingerprint.py +++ b/selfdrive/car/tests/test_fw_fingerprint.py @@ -246,7 +246,7 @@ class TestFwFingerprintTiming(unittest.TestCase): @pytest.mark.timeout(60) def test_fw_query_timing(self): - total_ref_time = 6.9 + total_ref_time = 6.8 brand_ref_times = { 1: { 'gm': 0.5, @@ -255,7 +255,7 @@ class TestFwFingerprintTiming(unittest.TestCase): 'ford': 0.1, 'honda': 0.55, 'hyundai': 0.65, - 'mazda': 0.2, + 'mazda': 0.1, 'nissan': 0.8, 'subaru': 0.45, 'tesla': 0.2, From 056b330e8bd1ffafdd0bd310782dd140c8f2174d Mon Sep 17 00:00:00 2001 From: Vivek Aithal Date: Thu, 1 Feb 2024 04:12:48 -0800 Subject: [PATCH 009/263] LatControlTorque: Add more inputs (#31252) * add history and state to the ff inputs * add history * resolve comments * remove history, simplify * don't compute lateral accel, roll comp always --- selfdrive/car/gm/interface.py | 8 +++---- selfdrive/car/interfaces.py | 19 ++++++++++++----- selfdrive/controls/lib/latcontrol_torque.py | 23 +++++++++++---------- 3 files changed, 30 insertions(+), 20 deletions(-) diff --git a/selfdrive/car/gm/interface.py b/selfdrive/car/gm/interface.py index af34100d74..e0f616dbf9 100755 --- a/selfdrive/car/gm/interface.py +++ b/selfdrive/car/gm/interface.py @@ -7,7 +7,7 @@ from openpilot.common.conversions import Conversions as CV from openpilot.selfdrive.car import create_button_events, get_safety_config from openpilot.selfdrive.car.gm.radar_interface import RADAR_HEADER_MSG from openpilot.selfdrive.car.gm.values import CAR, CruiseButtons, CarControllerParams, EV_CAR, CAMERA_ACC_CAR, CanBus -from openpilot.selfdrive.car.interfaces import CarInterfaceBase, TorqueFromLateralAccelCallbackType, FRICTION_THRESHOLD +from openpilot.selfdrive.car.interfaces import CarInterfaceBase, TorqueFromLateralAccelCallbackType, FRICTION_THRESHOLD, LatControlInputs from openpilot.selfdrive.controls.lib.drive_helpers import get_friction ButtonType = car.CarState.ButtonEvent.Type @@ -44,8 +44,8 @@ class CarInterface(CarInterfaceBase): else: return CarInterfaceBase.get_steer_feedforward_default - def torque_from_lateral_accel_siglin(self, lateral_accel_value: float, torque_params: car.CarParams.LateralTorqueTuning, - lateral_accel_error: float, lateral_accel_deadzone: float, friction_compensation: bool) -> float: + def torque_from_lateral_accel_siglin(self, latcontrol_inputs: LatControlInputs, torque_params: car.CarParams.LateralTorqueTuning, lateral_accel_error: float, + lateral_accel_deadzone: float, friction_compensation: bool, gravity_adjusted: bool) -> float: friction = get_friction(lateral_accel_error, lateral_accel_deadzone, FRICTION_THRESHOLD, torque_params, friction_compensation) def sig(val): @@ -58,7 +58,7 @@ class CarInterface(CarInterfaceBase): non_linear_torque_params = NON_LINEAR_TORQUE_PARAMS.get(self.CP.carFingerprint) assert non_linear_torque_params, "The params are not defined" a, b, c, _ = non_linear_torque_params - steer_torque = (sig(lateral_accel_value * a) * b) + (lateral_accel_value * c) + steer_torque = (sig(latcontrol_inputs.lateral_acceleration * a) * b) + (latcontrol_inputs.lateral_acceleration * c) return float(steer_torque) + friction def torque_from_lateral_accel(self) -> TorqueFromLateralAccelCallbackType: diff --git a/selfdrive/car/interfaces.py b/selfdrive/car/interfaces.py index 59657c5437..7ecc47f2a4 100644 --- a/selfdrive/car/interfaces.py +++ b/selfdrive/car/interfaces.py @@ -4,7 +4,7 @@ import numpy as np import tomllib from abc import abstractmethod, ABC from enum import StrEnum -from typing import Any, Dict, Optional, Tuple, List, Callable +from typing import Any, Dict, Optional, Tuple, List, Callable, NamedTuple from cereal import car from openpilot.common.basedir import BASEDIR @@ -20,7 +20,6 @@ from openpilot.selfdrive.controls.lib.vehicle_model import VehicleModel ButtonType = car.CarState.ButtonEvent.Type GearShifter = car.CarState.GearShifter EventName = car.CarEvent.EventName -TorqueFromLateralAccelCallbackType = Callable[[float, car.CarParams.LateralTorqueTuning, float, float, bool], float] MAX_CTRL_SPEED = (V_CRUISE_MAX + 4) * CV.KPH_TO_MS ACCEL_MAX = 2.0 @@ -32,6 +31,16 @@ TORQUE_OVERRIDE_PATH = os.path.join(BASEDIR, 'selfdrive/car/torque_data/override TORQUE_SUBSTITUTE_PATH = os.path.join(BASEDIR, 'selfdrive/car/torque_data/substitute.toml') +class LatControlInputs(NamedTuple): + lateral_acceleration: float + roll_compensation: float + vego: float + aego: float + + +TorqueFromLateralAccelCallbackType = Callable[[LatControlInputs, car.CarParams.LateralTorqueTuning, float, float, bool, bool], float] + + def get_torque_params(candidate): with open(TORQUE_SUBSTITUTE_PATH, 'rb') as f: sub = tomllib.load(f) @@ -130,11 +139,11 @@ class CarInterfaceBase(ABC): def get_steer_feedforward_function(self): return self.get_steer_feedforward_default - def torque_from_lateral_accel_linear(self, lateral_accel_value: float, torque_params: car.CarParams.LateralTorqueTuning, - lateral_accel_error: float, lateral_accel_deadzone: float, friction_compensation: bool) -> float: + def torque_from_lateral_accel_linear(self, latcontrol_inputs: LatControlInputs, torque_params: car.CarParams.LateralTorqueTuning, + lateral_accel_error: float, lateral_accel_deadzone: float, friction_compensation: bool, gravity_adjusted: bool) -> float: # The default is a linear relationship between torque and lateral acceleration (accounting for road roll and steering friction) friction = get_friction(lateral_accel_error, lateral_accel_deadzone, FRICTION_THRESHOLD, torque_params, friction_compensation) - return (lateral_accel_value / float(torque_params.latAccelFactor)) + friction + return (latcontrol_inputs.lateral_acceleration / float(torque_params.latAccelFactor)) + friction def torque_from_lateral_accel(self) -> TorqueFromLateralAccelCallbackType: return self.torque_from_lateral_accel_linear diff --git a/selfdrive/controls/lib/latcontrol_torque.py b/selfdrive/controls/lib/latcontrol_torque.py index 65fd1b51c5..34b0d47124 100644 --- a/selfdrive/controls/lib/latcontrol_torque.py +++ b/selfdrive/controls/lib/latcontrol_torque.py @@ -2,6 +2,7 @@ import math from cereal import log from openpilot.common.numpy_fast import interp +from openpilot.selfdrive.car.interfaces import LatControlInputs from openpilot.selfdrive.controls.lib.latcontrol import LatControl from openpilot.selfdrive.controls.lib.pid import PIDController from openpilot.selfdrive.controls.lib.vehicle_model import ACCELERATION_DUE_TO_GRAVITY @@ -38,16 +39,16 @@ class LatControlTorque(LatControl): def update(self, active, CS, VM, params, steer_limited, desired_curvature, llk): pid_log = log.ControlsState.LateralTorqueState.new_message() - if not active: output_torque = 0.0 pid_log.active = False else: + actual_curvature_vm = -VM.calc_curvature(math.radians(CS.steeringAngleDeg - params.angleOffsetDeg), CS.vEgo, params.roll) + roll_compensation = params.roll * ACCELERATION_DUE_TO_GRAVITY if self.use_steering_angle: - actual_curvature = -VM.calc_curvature(math.radians(CS.steeringAngleDeg - params.angleOffsetDeg), CS.vEgo, params.roll) + actual_curvature = actual_curvature_vm curvature_deadzone = abs(VM.calc_curvature(math.radians(self.steering_angle_deadzone_deg), CS.vEgo, 0.0)) else: - actual_curvature_vm = -VM.calc_curvature(math.radians(CS.steeringAngleDeg - params.angleOffsetDeg), CS.vEgo, params.roll) actual_curvature_llk = llk.angularVelocityCalibrated.value[2] / CS.vEgo actual_curvature = interp(CS.vEgo, [2.0, 5.0], [actual_curvature_vm, actual_curvature_llk]) curvature_deadzone = 0.0 @@ -61,15 +62,15 @@ class LatControlTorque(LatControl): low_speed_factor = interp(CS.vEgo, LOW_SPEED_X, LOW_SPEED_Y)**2 setpoint = desired_lateral_accel + low_speed_factor * desired_curvature measurement = actual_lateral_accel + low_speed_factor * actual_curvature - gravity_adjusted_lateral_accel = desired_lateral_accel - params.roll * ACCELERATION_DUE_TO_GRAVITY - torque_from_setpoint = self.torque_from_lateral_accel(setpoint, self.torque_params, setpoint, - lateral_accel_deadzone, friction_compensation=False) - torque_from_measurement = self.torque_from_lateral_accel(measurement, self.torque_params, measurement, - lateral_accel_deadzone, friction_compensation=False) + gravity_adjusted_lateral_accel = desired_lateral_accel - roll_compensation + torque_from_setpoint = self.torque_from_lateral_accel(LatControlInputs(setpoint, roll_compensation, CS.vEgo, CS.aEgo), self.torque_params, + setpoint, lateral_accel_deadzone, friction_compensation=False, gravity_adjusted=False) + torque_from_measurement = self.torque_from_lateral_accel(LatControlInputs(measurement, roll_compensation, CS.vEgo, CS.aEgo), self.torque_params, + measurement, lateral_accel_deadzone, friction_compensation=False, gravity_adjusted=False) pid_log.error = torque_from_setpoint - torque_from_measurement - ff = self.torque_from_lateral_accel(gravity_adjusted_lateral_accel, self.torque_params, - desired_lateral_accel - actual_lateral_accel, - lateral_accel_deadzone, friction_compensation=True) + ff = self.torque_from_lateral_accel(LatControlInputs(gravity_adjusted_lateral_accel, roll_compensation, CS.vEgo, CS.aEgo), self.torque_params, + desired_lateral_accel - actual_lateral_accel, lateral_accel_deadzone, friction_compensation=True, + gravity_adjusted=True) freeze_integrator = steer_limited or CS.steeringPressed or CS.vEgo < 5 output_torque = self.pid.update(pid_log.error, From 628c829d195434a99c1d83e8119cf0d4d53c167c Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Moritz=20W=C3=B6rmann?= Date: Thu, 1 Feb 2024 19:31:10 +0100 Subject: [PATCH 010/263] GH Actions PR review bot: Check only for substrings in checkbox text when validating PR template (#31262) check only for substrings in checkbox text --- .github/workflows/auto_pr_review.yaml | 9 ++++++++- 1 file changed, 8 insertions(+), 1 deletion(-) diff --git a/.github/workflows/auto_pr_review.yaml b/.github/workflows/auto_pr_review.yaml index 820801a2c7..abb6c38d6b 100644 --- a/.github/workflows/auto_pr_review.yaml +++ b/.github/workflows/auto_pr_review.yaml @@ -89,6 +89,13 @@ jobs: return subset.every((item) => superset.includes(item)); }; + // Utility function to check if a list of checkboxes is a subset of another list of checkboxes + isCheckboxSubset = (templateCheckBoxTexts, prTextCheckBoxTexts) => { + // Check if each template checkbox text is a substring of at least one PR checkbox text + // (user should be allowed to add additional text) + return templateCheckBoxTexts.every((item) => prTextCheckBoxTexts.some((element) => element.includes(item))) + } + // Get filenames of all currently checked-in PR templates const template_contents = await github.rest.repos.getContent({ owner: context.repo.owner, @@ -146,7 +153,7 @@ jobs: template.checkboxes + "]" ); if ( - isSubset(template.checkboxes, pr_checkboxes) && + isCheckboxSubset(template.checkboxes, pr_checkboxes) && isSubset(template.headings, pr_headings) ) { console.debug("Found matching template!"); From 619625625ce9dc67835aaaca266ccd66f63545e3 Mon Sep 17 00:00:00 2001 From: Vivek Aithal Date: Thu, 1 Feb 2024 12:30:43 -0800 Subject: [PATCH 011/263] CHEVROLET BOLT EUV 2022: Add a simple neural feed forward (#31266) * add simple neural feed forward * update refs * do not sample during inference in op * update refs --- selfdrive/car/gm/interface.py | 19 +++++++++-- selfdrive/car/interfaces.py | 33 +++++++++++++++++++ .../car/torque_data/neural_ff_weights.json | 1 + selfdrive/test/process_replay/ref_commit | 2 +- 4 files changed, 52 insertions(+), 3 deletions(-) create mode 100644 selfdrive/car/torque_data/neural_ff_weights.json diff --git a/selfdrive/car/gm/interface.py b/selfdrive/car/gm/interface.py index e0f616dbf9..0c78b0061d 100755 --- a/selfdrive/car/gm/interface.py +++ b/selfdrive/car/gm/interface.py @@ -1,13 +1,15 @@ #!/usr/bin/env python3 +import os from cereal import car from math import fabs, exp from panda import Panda +from openpilot.common.basedir import BASEDIR from openpilot.common.conversions import Conversions as CV from openpilot.selfdrive.car import create_button_events, get_safety_config from openpilot.selfdrive.car.gm.radar_interface import RADAR_HEADER_MSG from openpilot.selfdrive.car.gm.values import CAR, CruiseButtons, CarControllerParams, EV_CAR, CAMERA_ACC_CAR, CanBus -from openpilot.selfdrive.car.interfaces import CarInterfaceBase, TorqueFromLateralAccelCallbackType, FRICTION_THRESHOLD, LatControlInputs +from openpilot.selfdrive.car.interfaces import CarInterfaceBase, TorqueFromLateralAccelCallbackType, FRICTION_THRESHOLD, LatControlInputs, NanoFFModel from openpilot.selfdrive.controls.lib.drive_helpers import get_friction ButtonType = car.CarState.ButtonEvent.Type @@ -25,6 +27,8 @@ NON_LINEAR_TORQUE_PARAMS = { CAR.SILVERADO: [3.29974374, 1.0, 0.25571356, 0.0465122] } +NEURAL_PARAMS_PATH = os.path.join(BASEDIR, 'selfdrive/car/torque_data/neural_ff_weights.json') + class CarInterface(CarInterfaceBase): @staticmethod @@ -61,8 +65,19 @@ class CarInterface(CarInterfaceBase): steer_torque = (sig(latcontrol_inputs.lateral_acceleration * a) * b) + (latcontrol_inputs.lateral_acceleration * c) return float(steer_torque) + friction + def torque_from_lateral_accel_neural(self, latcontrol_inputs: LatControlInputs, torque_params: car.CarParams.LateralTorqueTuning, lateral_accel_error: float, + lateral_accel_deadzone: float, friction_compensation: bool, gravity_adjusted: bool) -> float: + friction = get_friction(lateral_accel_error, lateral_accel_deadzone, FRICTION_THRESHOLD, torque_params, friction_compensation) + inputs = list(latcontrol_inputs) + if gravity_adjusted: + inputs[0] += inputs[1] + return float(self.neural_ff_model.predict(inputs)) + friction + def torque_from_lateral_accel(self) -> TorqueFromLateralAccelCallbackType: - if self.CP.carFingerprint in NON_LINEAR_TORQUE_PARAMS: + if self.CP.carFingerprint == CAR.BOLT_EUV: + self.neural_ff_model = NanoFFModel(NEURAL_PARAMS_PATH, self.CP.carFingerprint) + return self.torque_from_lateral_accel_neural + elif self.CP.carFingerprint in NON_LINEAR_TORQUE_PARAMS: return self.torque_from_lateral_accel_siglin else: return self.torque_from_lateral_accel_linear diff --git a/selfdrive/car/interfaces.py b/selfdrive/car/interfaces.py index 7ecc47f2a4..b7357d2c93 100644 --- a/selfdrive/car/interfaces.py +++ b/selfdrive/car/interfaces.py @@ -1,3 +1,4 @@ +import json import os import time import numpy as np @@ -473,3 +474,35 @@ def get_interface_attr(attr: str, combine_brands: bool = False, ignore_none: boo pass return result + + +class NanoFFModel: + def __init__(self, weights_loc: str, platform: str): + self.weights_loc = weights_loc + self.platform = platform + self.load_weights(platform) + + def load_weights(self, platform: str): + with open(self.weights_loc, 'r') as fob: + self.weights = {k: np.array(v) for k, v in json.load(fob)[platform].items()} + + def relu(self, x: np.ndarray): + return np.maximum(0.0, x) + + def forward(self, x: np.ndarray): + assert x.ndim == 1 + x = (x - self.weights['input_norm_mat'][:, 0]) / (self.weights['input_norm_mat'][:, 1] - self.weights['input_norm_mat'][:, 0]) + x = self.relu(np.dot(x, self.weights['w_1']) + self.weights['b_1']) + x = self.relu(np.dot(x, self.weights['w_2']) + self.weights['b_2']) + x = self.relu(np.dot(x, self.weights['w_3']) + self.weights['b_3']) + x = np.dot(x, self.weights['w_4']) + self.weights['b_4'] + return x + + def predict(self, x: List[float], do_sample: bool = False): + x = self.forward(np.array(x)) + if do_sample: + pred = np.random.laplace(x[0], np.exp(x[1]) / self.weights['temperature']) + else: + pred = x[0] + pred = pred * (self.weights['output_norm_mat'][1] - self.weights['output_norm_mat'][0]) + self.weights['output_norm_mat'][0] + return pred diff --git a/selfdrive/car/torque_data/neural_ff_weights.json b/selfdrive/car/torque_data/neural_ff_weights.json new file mode 100644 index 0000000000..c526f07fa2 --- /dev/null +++ b/selfdrive/car/torque_data/neural_ff_weights.json @@ -0,0 +1 @@ +{"CHEVROLET BOLT EUV 2022": {"w_1": [[0.3452189564704895, -0.15614677965641022, -0.04062516987323761, -0.5960758328437805, 0.3211185932159424, 0.31732726097106934, -0.04430829733610153, -0.37327295541763306, -0.14118380844593048, 0.12712529301643372, 0.2641555070877075, -0.3451094627380371, -0.005127656273543835, 0.6185108423233032, 0.03725295141339302, 0.3763789236545563], [-0.0708412230014801, 0.3667356073856354, 0.031383827328681946, 0.1740853488445282, -0.04695861041545868, 0.018055908381938934, 0.009072160348296165, -0.23640218377113342, -0.10362917929887772, 0.022628149017691612, -0.224413201212883, 0.20718418061733246, -0.016947750002145767, -0.3872031271457672, -0.15500062704086304, -0.06375953555107117], [-0.0838046595454216, -0.0242826659232378, -0.07765661180019379, 0.028858814388513565, -0.09516210108995438, 0.008368706330657005, 0.1689300835132599, 0.015036891214549541, -0.15121428668498993, 0.1388195902109146, 0.11486363410949707, 0.0651545450091362, 0.13559958338737488, 0.04300367832183838, -0.13856294751167297, -0.058136988431215286], [-0.006249868310987949, 0.08809533715248108, -0.040690965950489044, 0.02359287068247795, -0.00766348373144865, 0.24816390872001648, -0.17360293865203857, -0.03676899895071983, -0.17564819753170013, 0.18998438119888306, -0.050583917647600174, -0.006488069426268339, 0.10649101436138153, -0.024557121098041534, -0.103276826441288, 0.18448011577129364]], "b_1": [0.2935388386249542, 0.10967712104320526, -0.014007942751049995, 0.211833655834198, 0.33605605363845825, 0.37722209095954895, -0.16615016758441925, 0.3134673535823822, 0.06695777177810669, 0.3425212800502777, 0.3769673705101013, 0.23186539113521576, 0.5770409107208252, -0.05929069593548775, 0.01839117519557476, 0.03828774020075798], "w_2": [[-0.06261160969734192, 0.010185074992477894, -0.06083013117313385, -0.04531499370932579, -0.08979734033346176, 0.3432150185108185, -0.019801849499344826, 0.3010321259498596], [0.19698476791381836, -0.009238275699317455, 0.08842222392559052, -0.09516377002000809, -0.05022778362035751, 0.13626104593276978, -0.052890390157699585, 0.15569131076335907], [0.0724768117070198, -0.09018408507108688, 0.06850195676088333, -0.025572121143341064, 0.0680626779794693, -0.07648195326328278, 0.07993496209383011, -0.059752143919467926], [1.267876386642456, -0.05755887180566788, -0.08429178595542908, 0.021366603672504425, -0.0006479775765910745, -1.4292563199996948, -0.08077696710824966, -1.414825439453125], [0.04535430669784546, 0.06555880606174469, -0.027145234867930412, -0.07661093026399612, -0.05702832341194153, 0.23650476336479187, 0.0024587824009358883, 0.20126521587371826], [0.006042032968252897, 0.042880818247795105, 0.002187949838116765, -0.017126334831118584, -0.08352015167474747, 0.19801731407642365, -0.029196614399552345, 0.23713473975658417], [-0.01644900068640709, -0.04358499124646187, 0.014584392309188843, 0.07155826687812805, -0.09354910999536514, -0.033351872116327286, 0.07138452678918839, -0.04755295440554619], [-1.1012420654296875, -0.03534531593322754, 0.02167935110628605, -0.01116552110761404, -0.08436500281095505, 1.1038788557052612, 0.027903547510504723, 1.0676132440567017], [0.03843916580080986, -0.0952216386795044, 0.039226632565259933, 0.002778085647150874, -0.020275786519050598, -0.07848760485649109, 0.04803166165947914, 0.015538203530013561], [0.018385495990514755, -0.025189843028783798, 0.0036680365446954966, -0.02105865254998207, 0.04808586835861206, 0.1575016975402832, 0.02703506126999855, 0.23039312660694122], [-0.0033881019335240126, -0.10210853815078735, -0.04877309128642082, 0.006989633198827505, 0.046798162162303925, 0.38676899671554565, -0.032304272055625916, 0.2345031052827835], [0.22092825174331665, -0.09642873704433441, 0.04499409720301628, 0.05108088254928589, -0.10191166400909424, 0.12818090617656708, -0.021021494641900063, 0.09440375864505768], [0.1212429478764534, -0.028194155544042587, -0.0981956496834755, 0.08226924389600754, 0.055346839129924774, 0.27067816257476807, -0.09064067900180817, 0.12580905854701996], [-1.6740131378173828, -0.02066155895590782, -0.05924689769744873, 0.06347910314798355, -0.07821853458881378, 1.2807466983795166, 0.04589352011680603, 1.310766577720642], [-0.09893272817134857, -0.04093599319458008, -0.02502273954451084, 0.09490344673395157, -0.0211324505507946, -0.09021010994911194, 0.07936318963766098, -0.03593116253614426], [-0.08490308374166489, -0.015558987855911255, -0.048692114651203156, -0.007421435788273811, -0.040531404316425323, 0.25889304280281067, 0.06012800335884094, 0.27946868538856506]], "b_2": [0.07973937690258026, -0.010446485131978989, -0.003066520905122161, -0.031895797699689865, 0.006032303906977177, 0.24106740951538086, -0.008969511836767197, 0.2872662842273712], "w_3": [[-1.364486813545227, -0.11682678014039993, 0.01764785870909691, 0.03926877677440643], [-0.05695437639951706, 0.05472218990325928, 0.1266128271818161, 0.09950875490903854], [0.11415273696184158, -0.10069356113672256, 0.0864749327301979, -0.043946366757154465], [-0.10138195008039474, -0.040128443390131, -0.08937158435583115, -0.0048376512713730335], [-0.0028251828625798225, -0.04743027314543724, 0.06340016424655914, 0.07277824729681015], [0.49482327699661255, -0.06410001963376999, -0.0999293103814125, -0.14250673353672028], [0.042802367359399796, 0.0015462725423276424, -0.05991362780332565, 0.1022040992975235], [0.3523194193840027, 0.07343732565641403, 0.04157765582203865, -0.12358107417821884]], "b_3": [0.2653026282787323, -0.058485131710767746, -0.0744510293006897, 0.012550175189971924], "w_4": [[0.5988775491714478, 0.09668736904859543], [-0.04360569268465042, 0.06491032242774963], [-0.11868984252214432, -0.09601487964391708], [-0.06554870307445526, -0.14189276099205017]], "b_4": [-0.08148707449436188, -2.8251802921295166], "input_norm_mat": [[-3.0, 3.0], [-3.0, 3.0], [0.0, 40.0], [-3.0, 3.0]], "output_norm_mat": [-1.0, 1.0], "temperature": 100.0}} \ No newline at end of file diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index bde2296e6b..bc79d3be9e 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -eaab6bd55c5eab33fc9a0d8de8289b912e923887 +d9a3a0d4e806b49ec537233d30926bec70308485 \ No newline at end of file From 08037594e27292ca755a211628f4141469347f82 Mon Sep 17 00:00:00 2001 From: Hoang Bui <47828508+bongbui321@users.noreply.github.com> Date: Thu, 1 Feb 2024 16:37:22 -0500 Subject: [PATCH 012/263] map: Transfer to MapLibre (#31185) * change codebase * compile * add mapboxprovider * works with map_renderer in c * remove maplibre temp * maplibre works * cleanup build.sh * x86 stuff * add lib * update release files * don't need that * tici build * tici build * add tici lib * update refs --------- Co-authored-by: Adeeb Shihadeh --- SConstruct | 9 +- release/files_common | 1 + release/files_pc | 2 - release/files_tici | 1 - selfdrive/navd/SConscript | 4 +- selfdrive/navd/map_renderer.cc | 36 +-- selfdrive/navd/map_renderer.h | 11 +- .../process_replay/model_replay_ref_commit | 2 +- selfdrive/ui/SConscript | 6 +- selfdrive/ui/qt/maps/map.cc | 39 ++- selfdrive/ui/qt/maps/map.h | 13 +- selfdrive/ui/qt/maps/map_helpers.cc | 37 +-- selfdrive/ui/qt/maps/map_helpers.h | 17 +- selfdrive/ui/qt/maps/map_panel.cc | 2 +- selfdrive/ui/qt/maps/map_panel.h | 4 +- .../mapbox-gl-native-qt/.gitattributes | 2 - .../aarch64/libqmapboxgl.so | 3 - third_party/mapbox-gl-native-qt/build.sh | 7 - .../mapbox-gl-native-qt/include/QMapbox | 1 - .../mapbox-gl-native-qt/include/QMapboxGL | 1 - .../mapbox-gl-native-qt/include/qmapbox.hpp | 147 ---------- .../mapbox-gl-native-qt/include/qmapboxgl.hpp | 277 ------------------ .../x86_64/libqmapboxgl.so | 3 - third_party/maplibre-native-qt/.gitignore | 1 + third_party/maplibre-native-qt/aarch64 | 1 + third_party/maplibre-native-qt/build.sh | 38 +++ .../include/conversion_p.hpp | 241 +++++++++++++++ .../include/export_core.hpp | 20 ++ .../include/export_location.hpp | 20 ++ .../include/export_widgets.hpp | 20 ++ .../maplibre-native-qt/include/geojson_p.hpp | 30 ++ .../maplibre-native-qt/include/gl_widget.hpp | 56 ++++ .../include/gl_widget_p.hpp | 42 +++ .../maplibre-native-qt/include/map.hpp | 205 +++++++++++++ .../include/map_observer_p.hpp | 54 ++++ .../maplibre-native-qt/include/map_p.hpp | 79 +++++ .../include/map_renderer_p.hpp | 63 ++++ .../maplibre-native-qt/include/qgeomap.hpp | 54 ++++ .../maplibre-native-qt/include/qgeomap_p.hpp | 93 ++++++ .../maplibre-native-qt/include/qmaplibre.hpp | 9 + .../include/qmaplibrewidgets.hpp | 6 + .../include/qt_mapping_engine.hpp | 31 ++ .../maplibre-native-qt/include/settings.hpp | 125 ++++++++ .../maplibre-native-qt/include/settings_p.hpp | 57 ++++ .../include/style_change_utils_p.hpp | 34 +++ .../include/texture_node.hpp | 42 +++ .../maplibre-native-qt/include/types.hpp | 206 +++++++++++++ .../maplibre-native-qt/include/utils.hpp | 28 ++ .../larch64/include/QMapLibre/Export | 1 + .../larch64/include/QMapLibre/LayerParameter | 1 + .../larch64/include/QMapLibre/Map | 1 + .../larch64/include/QMapLibre/QMapLibre | 1 + .../larch64/include/QMapLibre/Settings | 1 + .../larch64/include/QMapLibre/SourceParameter | 1 + .../larch64/include/QMapLibre/StyleParameter | 1 + .../larch64/include/QMapLibre/Types | 1 + .../larch64/include/QMapLibre/Utils | 1 + .../larch64/lib/libQMapLibre.so | 3 + .../larch64/lib/libQMapLibre.so.3.0.0 | 3 + .../x86_64/include/QMapLibre/Export | 1 + .../x86_64/include/QMapLibre/LayerParameter | 1 + .../x86_64/include/QMapLibre/Map | 1 + .../x86_64/include/QMapLibre/QMapLibre | 1 + .../x86_64/include/QMapLibre/Settings | 1 + .../x86_64/include/QMapLibre/SourceParameter | 1 + .../x86_64/include/QMapLibre/StyleParameter | 1 + .../x86_64/include/QMapLibre/Types | 1 + .../x86_64/include/QMapLibre/Utils | 1 + .../x86_64/lib/libQMapLibre.so | 1 + .../x86_64/lib/libQMapLibre.so.3.0.0 | 3 + 70 files changed, 1673 insertions(+), 535 deletions(-) delete mode 100644 third_party/mapbox-gl-native-qt/.gitattributes delete mode 100755 third_party/mapbox-gl-native-qt/aarch64/libqmapboxgl.so delete mode 100755 third_party/mapbox-gl-native-qt/build.sh delete mode 100644 third_party/mapbox-gl-native-qt/include/QMapbox delete mode 100644 third_party/mapbox-gl-native-qt/include/QMapboxGL delete mode 100644 third_party/mapbox-gl-native-qt/include/qmapbox.hpp delete mode 100644 third_party/mapbox-gl-native-qt/include/qmapboxgl.hpp delete mode 100755 third_party/mapbox-gl-native-qt/x86_64/libqmapboxgl.so create mode 100644 third_party/maplibre-native-qt/.gitignore create mode 120000 third_party/maplibre-native-qt/aarch64 create mode 100755 third_party/maplibre-native-qt/build.sh create mode 100644 third_party/maplibre-native-qt/include/conversion_p.hpp create mode 100644 third_party/maplibre-native-qt/include/export_core.hpp create mode 100644 third_party/maplibre-native-qt/include/export_location.hpp create mode 100644 third_party/maplibre-native-qt/include/export_widgets.hpp create mode 100644 third_party/maplibre-native-qt/include/geojson_p.hpp create mode 100644 third_party/maplibre-native-qt/include/gl_widget.hpp create mode 100644 third_party/maplibre-native-qt/include/gl_widget_p.hpp create mode 100644 third_party/maplibre-native-qt/include/map.hpp create mode 100644 third_party/maplibre-native-qt/include/map_observer_p.hpp create mode 100644 third_party/maplibre-native-qt/include/map_p.hpp create mode 100644 third_party/maplibre-native-qt/include/map_renderer_p.hpp create mode 100644 third_party/maplibre-native-qt/include/qgeomap.hpp create mode 100644 third_party/maplibre-native-qt/include/qgeomap_p.hpp create mode 100644 third_party/maplibre-native-qt/include/qmaplibre.hpp create mode 100644 third_party/maplibre-native-qt/include/qmaplibrewidgets.hpp create mode 100644 third_party/maplibre-native-qt/include/qt_mapping_engine.hpp create mode 100644 third_party/maplibre-native-qt/include/settings.hpp create mode 100644 third_party/maplibre-native-qt/include/settings_p.hpp create mode 100644 third_party/maplibre-native-qt/include/style_change_utils_p.hpp create mode 100644 third_party/maplibre-native-qt/include/texture_node.hpp create mode 100644 third_party/maplibre-native-qt/include/types.hpp create mode 100644 third_party/maplibre-native-qt/include/utils.hpp create mode 100644 third_party/maplibre-native-qt/larch64/include/QMapLibre/Export create mode 100644 third_party/maplibre-native-qt/larch64/include/QMapLibre/LayerParameter create mode 100644 third_party/maplibre-native-qt/larch64/include/QMapLibre/Map create mode 100644 third_party/maplibre-native-qt/larch64/include/QMapLibre/QMapLibre create mode 100644 third_party/maplibre-native-qt/larch64/include/QMapLibre/Settings create mode 100644 third_party/maplibre-native-qt/larch64/include/QMapLibre/SourceParameter create mode 100644 third_party/maplibre-native-qt/larch64/include/QMapLibre/StyleParameter create mode 100644 third_party/maplibre-native-qt/larch64/include/QMapLibre/Types create mode 100644 third_party/maplibre-native-qt/larch64/include/QMapLibre/Utils create mode 100755 third_party/maplibre-native-qt/larch64/lib/libQMapLibre.so create mode 100755 third_party/maplibre-native-qt/larch64/lib/libQMapLibre.so.3.0.0 create mode 100644 third_party/maplibre-native-qt/x86_64/include/QMapLibre/Export create mode 100644 third_party/maplibre-native-qt/x86_64/include/QMapLibre/LayerParameter create mode 100644 third_party/maplibre-native-qt/x86_64/include/QMapLibre/Map create mode 100644 third_party/maplibre-native-qt/x86_64/include/QMapLibre/QMapLibre create mode 100644 third_party/maplibre-native-qt/x86_64/include/QMapLibre/Settings create mode 100644 third_party/maplibre-native-qt/x86_64/include/QMapLibre/SourceParameter create mode 100644 third_party/maplibre-native-qt/x86_64/include/QMapLibre/StyleParameter create mode 100644 third_party/maplibre-native-qt/x86_64/include/QMapLibre/Types create mode 100644 third_party/maplibre-native-qt/x86_64/include/QMapLibre/Utils create mode 120000 third_party/maplibre-native-qt/x86_64/lib/libQMapLibre.so create mode 100755 third_party/maplibre-native-qt/x86_64/lib/libQMapLibre.so.3.0.0 diff --git a/SConstruct b/SConstruct index 3faa978087..b04e3903ed 100644 --- a/SConstruct +++ b/SConstruct @@ -145,7 +145,6 @@ else: libpath = [ f"#third_party/acados/{arch}/lib", f"#third_party/libyuv/{arch}/lib", - f"#third_party/mapbox-gl-native-qt/{arch}", "/usr/lib", "/usr/local/lib", ] @@ -208,11 +207,12 @@ env = Environment( "#third_party/json11", "#third_party/linux/include", "#third_party/snpe/include", - "#third_party/mapbox-gl-native-qt/include", "#third_party/qrcode", "#third_party", "#cereal", "#opendbc/can", + "#third_party/maplibre-native-qt/include", + f"#third_party/maplibre-native-qt/{arch}/include" ], CC='clang', @@ -318,7 +318,7 @@ try: except SCons.Errors.UserError: qt_env.Tool('qt') -qt_env['CPPPATH'] += qt_dirs + ["#selfdrive/ui/qt/"] +qt_env['CPPPATH'] += qt_dirs# + ["#selfdrive/ui/qt/"] qt_flags = [ "-D_REENTRANT", "-DQT_NO_DEBUG", @@ -331,7 +331,8 @@ qt_flags = [ "-DQT_MESSAGELOGCONTEXT", ] qt_env['CXXFLAGS'] += qt_flags -qt_env['LIBPATH'] += ['#selfdrive/ui'] +qt_env['LIBPATH'] += ['#selfdrive/ui', f"#third_party/maplibre-native-qt/{arch}/lib"] +qt_env['RPATH'] += [Dir(f"#third_party/maplibre-native-qt/{arch}/lib").srcnode().abspath] qt_env['LIBS'] = qt_libs if GetOption("clazy"): diff --git a/release/files_common b/release/files_common index cf985f682d..91945a0621 100644 --- a/release/files_common +++ b/release/files_common @@ -394,6 +394,7 @@ third_party/acados/acados_template/** third_party/bootstrap/** third_party/qt5/larch64/bin/** +third_party/maplibre-native-qt/** scripts/update_now.sh scripts/stop_updater.sh diff --git a/release/files_pc b/release/files_pc index 13f1b52166..f2bf090f2c 100644 --- a/release/files_pc +++ b/release/files_pc @@ -1,5 +1,3 @@ -third_party/mapbox-gl-native-qt/x86_64/*.so - third_party/libyuv/x86_64/** third_party/snpe/x86_64/** third_party/snpe/x86_64-linux-clang/** diff --git a/release/files_tici b/release/files_tici index 5d65ef458a..1771c45138 100644 --- a/release/files_tici +++ b/release/files_tici @@ -1,7 +1,6 @@ third_party/libyuv/larch64/** third_party/snpe/larch64** third_party/snpe/aarch64-ubuntu-gcc7.5/* -third_party/mapbox-gl-native-qt/include/* third_party/acados/larch64/** system/camerad/cameras/camera_qcom2.cc diff --git a/selfdrive/navd/SConscript b/selfdrive/navd/SConscript index c116ef1535..5a173c0351 100644 --- a/selfdrive/navd/SConscript +++ b/selfdrive/navd/SConscript @@ -1,14 +1,14 @@ Import('qt_env', 'arch', 'common', 'messaging', 'visionipc', 'cereal', 'transformations') map_env = qt_env.Clone() -libs = ['qt_widgets', 'qt_util', 'qmapboxgl', common, messaging, cereal, visionipc, transformations, +libs = ['qt_widgets', 'qt_util', 'QMapLibre', common, messaging, cereal, visionipc, transformations, 'zmq', 'capnp', 'kj', 'm', 'OpenCL', 'ssl', 'crypto', 'pthread', 'json11'] + map_env["LIBS"] if arch == 'larch64': libs.append(':libEGL_mesa.so.0') if arch in ['larch64', 'aarch64', 'x86_64']: if arch == 'x86_64': - rpath = Dir(f"#third_party/mapbox-gl-native-qt/{arch}").srcnode().abspath + rpath = Dir(f"#third_party/maplibre-native-qt/{arch}/lib").srcnode().abspath map_env["RPATH"] += [rpath, ] style_path = File("style.json").abspath diff --git a/selfdrive/navd/map_renderer.cc b/selfdrive/navd/map_renderer.cc index 543515c631..d52ee162bd 100644 --- a/selfdrive/navd/map_renderer.cc +++ b/selfdrive/navd/map_renderer.cc @@ -28,16 +28,16 @@ float get_zoom_level_for_scale(float lat, float meters_per_pixel) { return log2(num_tiles) - 1; } -QMapbox::Coordinate get_point_along_line(float lat, float lon, float bearing, float dist) { +QMapLibre::Coordinate get_point_along_line(float lat, float lon, float bearing, float dist) { float ang_dist = dist / EARTH_RADIUS_METERS; float lat1 = DEG2RAD(lat), lon1 = DEG2RAD(lon), bearing1 = DEG2RAD(bearing); float lat2 = asin(sin(lat1)*cos(ang_dist) + cos(lat1)*sin(ang_dist)*cos(bearing1)); float lon2 = lon1 + atan2(sin(bearing1)*sin(ang_dist)*cos(lat1), cos(ang_dist)-sin(lat1)*sin(lat2)); - return QMapbox::Coordinate(RAD2DEG(lat2), RAD2DEG(lon2)); + return QMapLibre::Coordinate(RAD2DEG(lat2), RAD2DEG(lon2)); } -MapRenderer::MapRenderer(const QMapboxGLSettings &settings, bool online) : m_settings(settings) { +MapRenderer::MapRenderer(const QMapLibre::Settings &settings, bool online) : m_settings(settings) { QSurfaceFormat fmt; fmt.setRenderableType(QSurfaceFormat::OpenGLES); @@ -60,8 +60,8 @@ MapRenderer::MapRenderer(const QMapboxGLSettings &settings, bool online) : m_set fbo.reset(new QOpenGLFramebufferObject(WIDTH, HEIGHT, fbo_format)); std::string style = util::read_file(STYLE_PATH); - m_map.reset(new QMapboxGL(nullptr, m_settings, fbo->size(), 1)); - m_map->setCoordinateZoom(QMapbox::Coordinate(0, 0), DEFAULT_ZOOM); + m_map.reset(new QMapLibre::Map(nullptr, m_settings, fbo->size(), 1)); + m_map->setCoordinateZoom(QMapLibre::Coordinate(0, 0), DEFAULT_ZOOM); m_map->setStyleJson(style.c_str()); m_map->createRenderer(); ever_loaded = false; @@ -70,20 +70,20 @@ MapRenderer::MapRenderer(const QMapboxGLSettings &settings, bool online) : m_set m_map->setFramebufferObject(fbo->handle(), fbo->size()); gl_functions->glViewport(0, 0, WIDTH, HEIGHT); - QObject::connect(m_map.data(), &QMapboxGL::mapChanged, [=](QMapboxGL::MapChange change) { + QObject::connect(m_map.data(), &QMapLibre::Map::mapChanged, [=](QMapLibre::Map::MapChange change) { // Ignore expected signals // https://github.com/mapbox/mapbox-gl-native/blob/cf734a2fec960025350d8de0d01ad38aeae155a0/platform/qt/include/qmapboxgl.hpp#L116 if (ever_loaded) { - if (change != QMapboxGL::MapChange::MapChangeRegionWillChange && - change != QMapboxGL::MapChange::MapChangeRegionDidChange && - change != QMapboxGL::MapChange::MapChangeWillStartRenderingFrame && - change != QMapboxGL::MapChange::MapChangeDidFinishRenderingFrameFullyRendered) { + if (change != QMapLibre::Map::MapChange::MapChangeRegionWillChange && + change != QMapLibre::Map::MapChange::MapChangeRegionDidChange && + change != QMapLibre::Map::MapChange::MapChangeWillStartRenderingFrame && + change != QMapLibre::Map::MapChange::MapChangeDidFinishRenderingFrameFullyRendered) { LOGD("New map state: %d", change); } } }); - QObject::connect(m_map.data(), &QMapboxGL::mapLoadingFailed, [=](QMapboxGL::MapLoadingFailure err_code, const QString &reason) { + QObject::connect(m_map.data(), &QMapLibre::Map::mapLoadingFailed, [=](QMapLibre::Map::MapLoadingFailure err_code, const QString &reason) { LOGE("Map loading failed with %d: '%s'\n", err_code, reason.toStdString().c_str()); }); @@ -145,7 +145,7 @@ void MapRenderer::msgUpdate() { timer->start(0); } -void MapRenderer::updatePosition(QMapbox::Coordinate position, float bearing) { +void MapRenderer::updatePosition(QMapLibre::Coordinate position, float bearing) { if (m_map.isNull()) { return; } @@ -261,10 +261,10 @@ void MapRenderer::updateRoute(QList coordinates) { initLayers(); auto route_points = coordinate_list_to_collection(coordinates); - QMapbox::Feature feature(QMapbox::Feature::LineStringType, route_points, {}, {}); + QMapLibre::Feature feature(QMapLibre::Feature::LineStringType, route_points, {}, {}); QVariantMap navSource; navSource["type"] = "geojson"; - navSource["data"] = QVariant::fromValue(feature); + navSource["data"] = QVariant::fromValue(feature); m_map->updateSource("navSource", navSource); m_map->setLayoutProperty("navLayer", "visibility", "visible"); } @@ -273,10 +273,9 @@ void MapRenderer::initLayers() { if (!m_map->layerExists("navLayer")) { LOGD("Initializing navLayer"); QVariantMap nav; - nav["id"] = "navLayer"; nav["type"] = "line"; nav["source"] = "navSource"; - m_map->addLayer(nav, "road-intersection"); + m_map->addLayer("navLayer", nav, "road-intersection"); m_map->setPaintProperty("navLayer", "line-color", QColor("grey")); m_map->setPaintProperty("navLayer", "line-width", 5); m_map->setLayoutProperty("navLayer", "line-cap", "round"); @@ -296,9 +295,10 @@ extern "C" { QApplication *app = new QApplication(argc, argv); assert(app); - QMapboxGLSettings settings; + QMapLibre::Settings settings; + settings.setProviderTemplate(QMapLibre::Settings::ProviderTemplate::MapboxProvider); settings.setApiBaseUrl(maps_host == nullptr ? MAPS_HOST : maps_host); - settings.setAccessToken(token == nullptr ? get_mapbox_token() : token); + settings.setApiKey(token == nullptr ? get_mapbox_token() : token); return new MapRenderer(settings, false); } diff --git a/selfdrive/navd/map_renderer.h b/selfdrive/navd/map_renderer.h index dc92c70b0f..fd5922b668 100644 --- a/selfdrive/navd/map_renderer.h +++ b/selfdrive/navd/map_renderer.h @@ -3,7 +3,8 @@ #include #include -#include +#include +#include #include #include #include @@ -19,7 +20,7 @@ class MapRenderer : public QObject { Q_OBJECT public: - MapRenderer(const QMapboxGLSettings &, bool online=true); + MapRenderer(const QMapLibre::Settings &, bool online=true); uint8_t* getImage(); void update(); bool loaded(); @@ -37,8 +38,8 @@ private: void publish(const double render_time, const bool loaded); void sendThumbnail(const uint64_t ts, const kj::Array &buf); - QMapboxGLSettings m_settings; - QScopedPointer m_map; + QMapLibre::Settings m_settings; + QScopedPointer m_map; void initLayers(); @@ -52,7 +53,7 @@ private: bool ever_loaded = false; public slots: - void updatePosition(QMapbox::Coordinate position, float bearing); + void updatePosition(QMapLibre::Coordinate position, float bearing); void updateRoute(QList coordinates); void msgUpdate(); }; diff --git a/selfdrive/test/process_replay/model_replay_ref_commit b/selfdrive/test/process_replay/model_replay_ref_commit index 9ec78e1401..a2f6896307 100644 --- a/selfdrive/test/process_replay/model_replay_ref_commit +++ b/selfdrive/test/process_replay/model_replay_ref_commit @@ -1 +1 @@ -4a01784a6b83a49301a68adf52bb7dcfcb7173b5 +fee90bcee1e545c7ec9a39d3c7d4e42cfefb9955 diff --git a/selfdrive/ui/SConscript b/selfdrive/ui/SConscript index a3cba124fe..4c866332f9 100644 --- a/selfdrive/ui/SConscript +++ b/selfdrive/ui/SConscript @@ -11,10 +11,6 @@ if arch == 'larch64': maps = arch in ['larch64', 'aarch64', 'x86_64'] -if maps and arch != 'larch64': - rpath = [Dir(f"#third_party/mapbox-gl-native-qt/{arch}").srcnode().abspath] - qt_env["RPATH"] += rpath - if arch == "Darwin": del base_libs[base_libs.index('OpenCL')] qt_env['FRAMEWORKS'] += ['OpenCL'] @@ -31,7 +27,7 @@ widgets_src = ["ui.cc", "qt/widgets/input.cc", "qt/widgets/wifi.cc", qt_env['CPPDEFINES'] = [] if maps: - base_libs += ['qmapboxgl'] + base_libs += ['QMapLibre'] widgets_src += ["qt/maps/map_helpers.cc", "qt/maps/map_settings.cc", "qt/maps/map.cc", "qt/maps/map_panel.cc", "qt/maps/map_eta.cc", "qt/maps/map_instructions.cc"] qt_env['CPPDEFINES'] += ["ENABLE_MAPS"] diff --git a/selfdrive/ui/qt/maps/map.cc b/selfdrive/ui/qt/maps/map.cc index db56fcdcfc..a5644bae4f 100644 --- a/selfdrive/ui/qt/maps/map.cc +++ b/selfdrive/ui/qt/maps/map.cc @@ -18,7 +18,7 @@ const float MAX_PITCH = 50; const float MIN_PITCH = 0; const float MAP_SCALE = 2; -MapWindow::MapWindow(const QMapboxGLSettings &settings) : m_settings(settings), velocity_filter(0, 10, 0.05, false) { +MapWindow::MapWindow(const QMapLibre::Settings &settings) : m_settings(settings), velocity_filter(0, 10, 0.05, false) { QObject::connect(uiState(), &UIState::uiUpdate, this, &MapWindow::updateState); map_overlay = new QWidget (this); @@ -57,10 +57,10 @@ void MapWindow::initLayers() { if (!m_map->layerExists("modelPathLayer")) { qDebug() << "Initializing modelPathLayer"; QVariantMap modelPath; - modelPath["id"] = "modelPathLayer"; + //modelPath["id"] = "modelPathLayer"; modelPath["type"] = "line"; modelPath["source"] = "modelPathSource"; - m_map->addLayer(modelPath); + m_map->addLayer("modelPathLayer", modelPath); m_map->setPaintProperty("modelPathLayer", "line-color", QColor("red")); m_map->setPaintProperty("modelPathLayer", "line-width", 5.0); m_map->setLayoutProperty("modelPathLayer", "line-cap", "round"); @@ -68,10 +68,9 @@ void MapWindow::initLayers() { if (!m_map->layerExists("navLayer")) { qDebug() << "Initializing navLayer"; QVariantMap nav; - nav["id"] = "navLayer"; nav["type"] = "line"; nav["source"] = "navSource"; - m_map->addLayer(nav, "road-intersection"); + m_map->addLayer("navLayer", nav, "road-intersection"); QVariantMap transition; transition["duration"] = 400; // ms @@ -84,10 +83,9 @@ void MapWindow::initLayers() { qDebug() << "Initializing pinLayer"; m_map->addImage("default_marker", QImage("../assets/navigation/default_marker.svg")); QVariantMap pin; - pin["id"] = "pinLayer"; pin["type"] = "symbol"; pin["source"] = "pinSource"; - m_map->addLayer(pin); + m_map->addLayer("pinLayer", pin); m_map->setLayoutProperty("pinLayer", "icon-pitch-alignment", "viewport"); m_map->setLayoutProperty("pinLayer", "icon-image", "default_marker"); m_map->setLayoutProperty("pinLayer", "icon-ignore-placement", true); @@ -100,10 +98,9 @@ void MapWindow::initLayers() { m_map->addImage("label-arrow", QImage("../assets/images/triangle.svg")); QVariantMap carPos; - carPos["id"] = "carPosLayer"; carPos["type"] = "symbol"; carPos["source"] = "carPosSource"; - m_map->addLayer(carPos); + m_map->addLayer("carPosLayer", carPos); m_map->setLayoutProperty("carPosLayer", "icon-pitch-alignment", "map"); m_map->setLayoutProperty("carPosLayer", "icon-image", "label-arrow"); m_map->setLayoutProperty("carPosLayer", "icon-size", 0.5); @@ -149,7 +146,7 @@ void MapWindow::updateState(const UIState &s) { locationd_valid = (locationd_pos.getValid() && locationd_orientation.getValid() && locationd_velocity.getValid() && pos_accurate_enough); if (locationd_valid) { - last_position = QMapbox::Coordinate(locationd_pos.getValue()[0], locationd_pos.getValue()[1]); + last_position = QMapLibre::Coordinate(locationd_pos.getValue()[0], locationd_pos.getValue()[1]); last_bearing = RAD2DEG(locationd_orientation.getValue()[2]); velocity_filter.update(std::max(10.0, locationd_velocity.getValue()[0])); } @@ -186,10 +183,10 @@ void MapWindow::updateState(const UIState &s) { if (locationd_valid) { // Update current location marker auto point = coordinate_to_collection(*last_position); - QMapbox::Feature feature1(QMapbox::Feature::PointType, point, {}, {}); + QMapLibre::Feature feature1(QMapLibre::Feature::PointType, point, {}, {}); QVariantMap carPosSource; carPosSource["type"] = "geojson"; - carPosSource["data"] = QVariant::fromValue(feature1); + carPosSource["data"] = QVariant::fromValue(feature1); m_map->updateSource("carPosSource", carPosSource); // Map bearing isn't updated when interacting, keep location marker up to date @@ -230,10 +227,10 @@ void MapWindow::updateState(const UIState &s) { qWarning() << "Updating navLayer with new route"; auto route = sm["navRoute"].getNavRoute(); auto route_points = capnp_coordinate_list_to_collection(route.getCoordinates()); - QMapbox::Feature feature(QMapbox::Feature::LineStringType, route_points, {}, {}); + QMapLibre::Feature feature(QMapLibre::Feature::LineStringType, route_points, {}, {}); QVariantMap navSource; navSource["type"] = "geojson"; - navSource["data"] = QVariant::fromValue(feature); + navSource["data"] = QVariant::fromValue(feature); m_map->updateSource("navSource", navSource); m_map->setLayoutProperty("navLayer", "visibility", "visible"); @@ -256,24 +253,24 @@ void MapWindow::resizeGL(int w, int h) { } void MapWindow::initializeGL() { - m_map.reset(new QMapboxGL(this, m_settings, size(), 1)); + m_map.reset(new QMapLibre::Map(this, m_settings, size(), 1)); if (last_position) { m_map->setCoordinateZoom(*last_position, MAX_ZOOM); } else { - m_map->setCoordinateZoom(QMapbox::Coordinate(64.31990695292795, -149.79038934046247), MIN_ZOOM); + m_map->setCoordinateZoom(QMapLibre::Coordinate(64.31990695292795, -149.79038934046247), MIN_ZOOM); } m_map->setMargins({0, 350, 0, 50}); m_map->setPitch(MIN_PITCH); m_map->setStyleUrl("mapbox://styles/commaai/clkqztk0f00ou01qyhsa5bzpj"); - QObject::connect(m_map.data(), &QMapboxGL::mapChanged, [=](QMapboxGL::MapChange change) { + QObject::connect(m_map.data(), &QMapLibre::Map::mapChanged, [=](QMapLibre::Map::MapChange change) { // set global animation duration to 0 ms so visibility changes are instant - if (change == QMapboxGL::MapChange::MapChangeDidFinishLoadingStyle) { + if (change == QMapLibre::Map::MapChange::MapChangeDidFinishLoadingStyle) { m_map->setTransitionOptions(0, 0); } - if (change == QMapboxGL::MapChange::MapChangeDidFinishLoadingMap) { + if (change == QMapLibre::Map::MapChange::MapChangeDidFinishLoadingMap) { loaded_once = true; } }); @@ -381,10 +378,10 @@ void MapWindow::updateDestinationMarker() { auto nav_dest = coordinate_from_param("NavDestination"); if (nav_dest.has_value()) { auto point = coordinate_to_collection(*nav_dest); - QMapbox::Feature feature(QMapbox::Feature::PointType, point, {}, {}); + QMapLibre::Feature feature(QMapLibre::Feature::PointType, point, {}, {}); QVariantMap pinSource; pinSource["type"] = "geojson"; - pinSource["data"] = QVariant::fromValue(feature); + pinSource["data"] = QVariant::fromValue(feature); m_map->updateSource("pinSource", pinSource); m_map->setPaintProperty("pinLayer", "visibility", "visible"); } else { diff --git a/selfdrive/ui/qt/maps/map.h b/selfdrive/ui/qt/maps/map.h index 5fe79f8b15..81ba50037a 100644 --- a/selfdrive/ui/qt/maps/map.h +++ b/selfdrive/ui/qt/maps/map.h @@ -6,7 +6,8 @@ #include #include #include -#include +#include +#include #include #include #include @@ -27,7 +28,7 @@ class MapWindow : public QOpenGLWidget { Q_OBJECT public: - MapWindow(const QMapboxGLSettings &); + MapWindow(const QMapLibre::Settings &); ~MapWindow(); private: @@ -35,8 +36,8 @@ private: void paintGL() final; void resizeGL(int w, int h) override; - QMapboxGLSettings m_settings; - QScopedPointer m_map; + QMapLibre::Settings m_settings; + QScopedPointer m_map; void initLayers(); @@ -56,8 +57,8 @@ private: int interaction_counter = 0; // Position - std::optional last_valid_nav_dest; - std::optional last_position; + std::optional last_valid_nav_dest; + std::optional last_position; std::optional last_bearing; FirstOrderFilter velocity_filter; bool locationd_valid = false; diff --git a/selfdrive/ui/qt/maps/map_helpers.cc b/selfdrive/ui/qt/maps/map_helpers.cc index 022355e3ce..3907ff7b05 100644 --- a/selfdrive/ui/qt/maps/map_helpers.cc +++ b/selfdrive/ui/qt/maps/map_helpers.cc @@ -16,24 +16,25 @@ QString get_mapbox_token() { return MAPBOX_TOKEN.isEmpty() ? CommaApi::create_jwt({}, 4 * 7 * 24 * 3600) : MAPBOX_TOKEN; } -QMapboxGLSettings get_mapbox_settings() { - QMapboxGLSettings settings; +QMapLibre::Settings get_mapbox_settings() { + QMapLibre::Settings settings; + settings.setProviderTemplate(QMapLibre::Settings::ProviderTemplate::MapboxProvider); if (!Hardware::PC()) { settings.setCacheDatabasePath(MAPS_CACHE_PATH); settings.setCacheDatabaseMaximumSize(100 * 1024 * 1024); } settings.setApiBaseUrl(MAPS_HOST); - settings.setAccessToken(get_mapbox_token()); + settings.setApiKey(get_mapbox_token()); return settings; } -QGeoCoordinate to_QGeoCoordinate(const QMapbox::Coordinate &in) { +QGeoCoordinate to_QGeoCoordinate(const QMapLibre::Coordinate &in) { return QGeoCoordinate(in.first, in.second); } -QMapbox::CoordinatesCollections model_to_collection( +QMapLibre::CoordinatesCollections model_to_collection( const cereal::LiveLocationKalman::Measurement::Reader &calibratedOrientationECEF, const cereal::LiveLocationKalman::Measurement::Reader &positionECEF, const cereal::XYZTData::Reader &line){ @@ -42,7 +43,7 @@ QMapbox::CoordinatesCollections model_to_collection( Eigen::Vector3d orient(calibratedOrientationECEF.getValue()[0], calibratedOrientationECEF.getValue()[1], calibratedOrientationECEF.getValue()[2]); Eigen::Matrix3d ecef_from_local = euler2rot(orient); - QMapbox::Coordinates coordinates; + QMapLibre::Coordinates coordinates; auto x = line.getX(); auto y = line.getY(); auto z = line.getZ(); @@ -52,28 +53,28 @@ QMapbox::CoordinatesCollections model_to_collection( coordinates.push_back({point_geodetic.lat, point_geodetic.lon}); } - return {QMapbox::CoordinatesCollection{coordinates}}; + return {QMapLibre::CoordinatesCollection{coordinates}}; } -QMapbox::CoordinatesCollections coordinate_to_collection(const QMapbox::Coordinate &c) { - QMapbox::Coordinates coordinates{c}; - return {QMapbox::CoordinatesCollection{coordinates}}; +QMapLibre::CoordinatesCollections coordinate_to_collection(const QMapLibre::Coordinate &c) { + QMapLibre::Coordinates coordinates{c}; + return {QMapLibre::CoordinatesCollection{coordinates}}; } -QMapbox::CoordinatesCollections capnp_coordinate_list_to_collection(const capnp::List::Reader& coordinate_list) { - QMapbox::Coordinates coordinates; +QMapLibre::CoordinatesCollections capnp_coordinate_list_to_collection(const capnp::List::Reader& coordinate_list) { + QMapLibre::Coordinates coordinates; for (auto const &c : coordinate_list) { coordinates.push_back({c.getLatitude(), c.getLongitude()}); } - return {QMapbox::CoordinatesCollection{coordinates}}; + return {QMapLibre::CoordinatesCollection{coordinates}}; } -QMapbox::CoordinatesCollections coordinate_list_to_collection(const QList &coordinate_list) { - QMapbox::Coordinates coordinates; +QMapLibre::CoordinatesCollections coordinate_list_to_collection(const QList &coordinate_list) { + QMapLibre::Coordinates coordinates; for (auto &c : coordinate_list) { coordinates.push_back({c.latitude(), c.longitude()}); } - return {QMapbox::CoordinatesCollection{coordinates}}; + return {QMapLibre::CoordinatesCollection{coordinates}}; } QList polyline_to_coordinate_list(const QString &polylineString) { @@ -118,7 +119,7 @@ QList polyline_to_coordinate_list(const QString &polylineString) return path; } -std::optional coordinate_from_param(const std::string ¶m) { +std::optional coordinate_from_param(const std::string ¶m) { QString json_str = QString::fromStdString(Params().get(param)); if (json_str.isEmpty()) return {}; @@ -127,7 +128,7 @@ std::optional coordinate_from_param(const std::string ¶ QJsonObject json = doc.object(); if (json["latitude"].isDouble() && json["longitude"].isDouble()) { - QMapbox::Coordinate coord(json["latitude"].toDouble(), json["longitude"].toDouble()); + QMapLibre::Coordinate coord(json["latitude"].toDouble(), json["longitude"].toDouble()); return coord; } else { return {}; diff --git a/selfdrive/ui/qt/maps/map_helpers.h b/selfdrive/ui/qt/maps/map_helpers.h index 4d6e9b5382..0f4be674f0 100644 --- a/selfdrive/ui/qt/maps/map_helpers.h +++ b/selfdrive/ui/qt/maps/map_helpers.h @@ -3,8 +3,9 @@ #include #include #include +#include +#include #include -#include #include #include "common/util.h" @@ -17,15 +18,15 @@ const QString MAPS_HOST = util::getenv("MAPS_HOST", MAPBOX_TOKEN.isEmpty() ? "ht const QString MAPS_CACHE_PATH = "/data/mbgl-cache-navd.db"; QString get_mapbox_token(); -QMapboxGLSettings get_mapbox_settings(); -QGeoCoordinate to_QGeoCoordinate(const QMapbox::Coordinate &in); -QMapbox::CoordinatesCollections model_to_collection( +QMapLibre::Settings get_mapbox_settings(); +QGeoCoordinate to_QGeoCoordinate(const QMapLibre::Coordinate &in); +QMapLibre::CoordinatesCollections model_to_collection( const cereal::LiveLocationKalman::Measurement::Reader &calibratedOrientationECEF, const cereal::LiveLocationKalman::Measurement::Reader &positionECEF, const cereal::XYZTData::Reader &line); -QMapbox::CoordinatesCollections coordinate_to_collection(const QMapbox::Coordinate &c); -QMapbox::CoordinatesCollections capnp_coordinate_list_to_collection(const capnp::List::Reader &coordinate_list); -QMapbox::CoordinatesCollections coordinate_list_to_collection(const QList &coordinate_list); +QMapLibre::CoordinatesCollections coordinate_to_collection(const QMapLibre::Coordinate &c); +QMapLibre::CoordinatesCollections capnp_coordinate_list_to_collection(const capnp::List::Reader &coordinate_list); +QMapLibre::CoordinatesCollections coordinate_list_to_collection(const QList &coordinate_list); QList polyline_to_coordinate_list(const QString &polylineString); -std::optional coordinate_from_param(const std::string ¶m); +std::optional coordinate_from_param(const std::string ¶m); std::pair map_format_distance(float d, bool is_metric); diff --git a/selfdrive/ui/qt/maps/map_panel.cc b/selfdrive/ui/qt/maps/map_panel.cc index 0a2286ff6f..c4cc20e21d 100644 --- a/selfdrive/ui/qt/maps/map_panel.cc +++ b/selfdrive/ui/qt/maps/map_panel.cc @@ -8,7 +8,7 @@ #include "selfdrive/ui/qt/util.h" #include "selfdrive/ui/ui.h" -MapPanel::MapPanel(const QMapboxGLSettings &mapboxSettings, QWidget *parent) : QFrame(parent) { +MapPanel::MapPanel(const QMapLibre::Settings &mapboxSettings, QWidget *parent) : QFrame(parent) { content_stack = new QStackedLayout(this); content_stack->setContentsMargins(0, 0, 0, 0); diff --git a/selfdrive/ui/qt/maps/map_panel.h b/selfdrive/ui/qt/maps/map_panel.h index 43a2cc7c89..190bb63446 100644 --- a/selfdrive/ui/qt/maps/map_panel.h +++ b/selfdrive/ui/qt/maps/map_panel.h @@ -1,14 +1,14 @@ #pragma once #include -#include +#include #include class MapPanel : public QFrame { Q_OBJECT public: - explicit MapPanel(const QMapboxGLSettings &settings, QWidget *parent = nullptr); + explicit MapPanel(const QMapLibre::Settings &settings, QWidget *parent = nullptr); signals: void mapPanelRequested(); diff --git a/third_party/mapbox-gl-native-qt/.gitattributes b/third_party/mapbox-gl-native-qt/.gitattributes deleted file mode 100644 index 323c737ba1..0000000000 --- a/third_party/mapbox-gl-native-qt/.gitattributes +++ /dev/null @@ -1,2 +0,0 @@ -x86_64 filter=lfs diff=lfs merge=lfs -text -larch64 filter=lfs diff=lfs merge=lfs -text diff --git a/third_party/mapbox-gl-native-qt/aarch64/libqmapboxgl.so b/third_party/mapbox-gl-native-qt/aarch64/libqmapboxgl.so deleted file mode 100755 index 508463c141..0000000000 --- a/third_party/mapbox-gl-native-qt/aarch64/libqmapboxgl.so +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:7fb33cb09b184a689eaa7f78c839d12a5bdd5b6f576d55758ec7e1246187a53f -size 9300680 diff --git a/third_party/mapbox-gl-native-qt/build.sh b/third_party/mapbox-gl-native-qt/build.sh deleted file mode 100755 index f2936fad3d..0000000000 --- a/third_party/mapbox-gl-native-qt/build.sh +++ /dev/null @@ -1,7 +0,0 @@ -#!/usr/bin/env sh -cd /tmp -git clone --recursive https://github.com/commaai/mapbox-gl-native.git -cd mapbox-gl-native -mkdir build && cd build -cmake -DMBGL_WITH_QT=ON .. -make -j$(nproc) mbgl-qt diff --git a/third_party/mapbox-gl-native-qt/include/QMapbox b/third_party/mapbox-gl-native-qt/include/QMapbox deleted file mode 100644 index a8479c09aa..0000000000 --- a/third_party/mapbox-gl-native-qt/include/QMapbox +++ /dev/null @@ -1 +0,0 @@ -#include "qmapbox.hpp" diff --git a/third_party/mapbox-gl-native-qt/include/QMapboxGL b/third_party/mapbox-gl-native-qt/include/QMapboxGL deleted file mode 100644 index 15b55a9abe..0000000000 --- a/third_party/mapbox-gl-native-qt/include/QMapboxGL +++ /dev/null @@ -1 +0,0 @@ -#include "qmapboxgl.hpp" diff --git a/third_party/mapbox-gl-native-qt/include/qmapbox.hpp b/third_party/mapbox-gl-native-qt/include/qmapbox.hpp deleted file mode 100644 index 3acc9d55e0..0000000000 --- a/third_party/mapbox-gl-native-qt/include/qmapbox.hpp +++ /dev/null @@ -1,147 +0,0 @@ -#ifndef QMAPBOX_H -#define QMAPBOX_H - -#include -#include -#include -#include -#include - -// This header follows the Qt coding style: https://wiki.qt.io/Qt_Coding_Style - -#if !defined(QT_MAPBOXGL_STATIC) -# if defined(QT_BUILD_MAPBOXGL_LIB) -# define Q_MAPBOXGL_EXPORT Q_DECL_EXPORT -# else -# define Q_MAPBOXGL_EXPORT Q_DECL_IMPORT -# endif -#else -# define Q_MAPBOXGL_EXPORT -#endif - -namespace QMapbox { - -typedef QPair Coordinate; -typedef QPair CoordinateZoom; -typedef QPair ProjectedMeters; - -typedef QVector Coordinates; -typedef QVector CoordinatesCollection; - -typedef QVector CoordinatesCollections; - -struct Q_MAPBOXGL_EXPORT Feature { - enum Type { - PointType = 1, - LineStringType, - PolygonType - }; - - /*! Class constructor. */ - Feature(Type type_ = PointType, const CoordinatesCollections& geometry_ = CoordinatesCollections(), - const QVariantMap& properties_ = QVariantMap(), const QVariant& id_ = QVariant()) - : type(type_), geometry(geometry_), properties(properties_), id(id_) {} - - Type type; - CoordinatesCollections geometry; - QVariantMap properties; - QVariant id; -}; - -struct Q_MAPBOXGL_EXPORT ShapeAnnotationGeometry { - enum Type { - LineStringType = 1, - PolygonType, - MultiLineStringType, - MultiPolygonType - }; - - /*! Class constructor. */ - ShapeAnnotationGeometry(Type type_ = LineStringType, const CoordinatesCollections& geometry_ = CoordinatesCollections()) - : type(type_), geometry(geometry_) {} - - Type type; - CoordinatesCollections geometry; -}; - -struct Q_MAPBOXGL_EXPORT SymbolAnnotation { - Coordinate geometry; - QString icon; -}; - -struct Q_MAPBOXGL_EXPORT LineAnnotation { - /*! Class constructor. */ - LineAnnotation(const ShapeAnnotationGeometry& geometry_ = ShapeAnnotationGeometry(), float opacity_ = 1.0f, - float width_ = 1.0f, const QColor& color_ = Qt::black) - : geometry(geometry_), opacity(opacity_), width(width_), color(color_) {} - - ShapeAnnotationGeometry geometry; - float opacity; - float width; - QColor color; -}; - -struct Q_MAPBOXGL_EXPORT FillAnnotation { - /*! Class constructor. */ - FillAnnotation(const ShapeAnnotationGeometry& geometry_ = ShapeAnnotationGeometry(), float opacity_ = 1.0f, - const QColor& color_ = Qt::black, const QVariant& outlineColor_ = QVariant()) - : geometry(geometry_), opacity(opacity_), color(color_), outlineColor(outlineColor_) {} - - ShapeAnnotationGeometry geometry; - float opacity; - QColor color; - QVariant outlineColor; -}; - -typedef QVariant Annotation; -typedef quint32 AnnotationID; -typedef QVector AnnotationIDs; - -enum NetworkMode { - Online, // Default - Offline, -}; - -Q_MAPBOXGL_EXPORT QVector >& defaultStyles(); - -Q_MAPBOXGL_EXPORT NetworkMode networkMode(); -Q_MAPBOXGL_EXPORT void setNetworkMode(NetworkMode); - -// This struct is a 1:1 copy of mbgl::CustomLayerRenderParameters. -struct Q_MAPBOXGL_EXPORT CustomLayerRenderParameters { - double width; - double height; - double latitude; - double longitude; - double zoom; - double bearing; - double pitch; - double fieldOfView; -}; - -class Q_MAPBOXGL_EXPORT CustomLayerHostInterface { -public: - virtual ~CustomLayerHostInterface() = default; - virtual void initialize() = 0; - virtual void render(const CustomLayerRenderParameters&) = 0; - virtual void deinitialize() = 0; -}; - -Q_MAPBOXGL_EXPORT double metersPerPixelAtLatitude(double latitude, double zoom); -Q_MAPBOXGL_EXPORT ProjectedMeters projectedMetersForCoordinate(const Coordinate &); -Q_MAPBOXGL_EXPORT Coordinate coordinateForProjectedMeters(const ProjectedMeters &); - -} // namespace QMapbox - -Q_DECLARE_METATYPE(QMapbox::Coordinate); -Q_DECLARE_METATYPE(QMapbox::Coordinates); -Q_DECLARE_METATYPE(QMapbox::CoordinatesCollection); -Q_DECLARE_METATYPE(QMapbox::CoordinatesCollections); -Q_DECLARE_METATYPE(QMapbox::Feature); - -Q_DECLARE_METATYPE(QMapbox::SymbolAnnotation); -Q_DECLARE_METATYPE(QMapbox::ShapeAnnotationGeometry); -Q_DECLARE_METATYPE(QMapbox::LineAnnotation); -Q_DECLARE_METATYPE(QMapbox::FillAnnotation); - -#endif // QMAPBOX_H diff --git a/third_party/mapbox-gl-native-qt/include/qmapboxgl.hpp b/third_party/mapbox-gl-native-qt/include/qmapboxgl.hpp deleted file mode 100644 index 337991aa1c..0000000000 --- a/third_party/mapbox-gl-native-qt/include/qmapboxgl.hpp +++ /dev/null @@ -1,277 +0,0 @@ -#ifndef QMAPBOXGL_H -#define QMAPBOXGL_H - -#include -#include -#include -#include -#include -#include -#include -#include - -#include - -class QMapboxGLPrivate; - -// This header follows the Qt coding style: https://wiki.qt.io/Qt_Coding_Style - -class Q_MAPBOXGL_EXPORT QMapboxGLSettings -{ -public: - QMapboxGLSettings(); - - enum GLContextMode { - UniqueGLContext = 0, - SharedGLContext - }; - - enum MapMode { - Continuous = 0, - Static - }; - - enum ConstrainMode { - NoConstrain = 0, - ConstrainHeightOnly, - ConstrainWidthAndHeight - }; - - enum ViewportMode { - DefaultViewport = 0, - FlippedYViewport - }; - - GLContextMode contextMode() const; - void setContextMode(GLContextMode); - - MapMode mapMode() const; - void setMapMode(MapMode); - - ConstrainMode constrainMode() const; - void setConstrainMode(ConstrainMode); - - ViewportMode viewportMode() const; - void setViewportMode(ViewportMode); - - unsigned cacheDatabaseMaximumSize() const; - void setCacheDatabaseMaximumSize(unsigned); - - QString cacheDatabasePath() const; - void setCacheDatabasePath(const QString &); - - QString assetPath() const; - void setAssetPath(const QString &); - - QString accessToken() const; - void setAccessToken(const QString &); - - QString apiBaseUrl() const; - void setApiBaseUrl(const QString &); - - QString localFontFamily() const; - void setLocalFontFamily(const QString &); - - std::function resourceTransform() const; - void setResourceTransform(const std::function &); - -private: - GLContextMode m_contextMode; - MapMode m_mapMode; - ConstrainMode m_constrainMode; - ViewportMode m_viewportMode; - - unsigned m_cacheMaximumSize; - QString m_cacheDatabasePath; - QString m_assetPath; - QString m_accessToken; - QString m_apiBaseUrl; - QString m_localFontFamily; - std::function m_resourceTransform; -}; - -struct Q_MAPBOXGL_EXPORT QMapboxGLCameraOptions { - QVariant center; // Coordinate - QVariant anchor; // QPointF - QVariant zoom; // double - QVariant bearing; // double - QVariant pitch; // double -}; - -class Q_MAPBOXGL_EXPORT QMapboxGL : public QObject -{ - Q_OBJECT - Q_PROPERTY(double latitude READ latitude WRITE setLatitude) - Q_PROPERTY(double longitude READ longitude WRITE setLongitude) - Q_PROPERTY(double zoom READ zoom WRITE setZoom) - Q_PROPERTY(double bearing READ bearing WRITE setBearing) - Q_PROPERTY(double pitch READ pitch WRITE setPitch) - Q_PROPERTY(QString styleJson READ styleJson WRITE setStyleJson) - Q_PROPERTY(QString styleUrl READ styleUrl WRITE setStyleUrl) - Q_PROPERTY(double scale READ scale WRITE setScale) - Q_PROPERTY(QMapbox::Coordinate coordinate READ coordinate WRITE setCoordinate) - Q_PROPERTY(QMargins margins READ margins WRITE setMargins) - -public: - enum MapChange { - MapChangeRegionWillChange = 0, - MapChangeRegionWillChangeAnimated, - MapChangeRegionIsChanging, - MapChangeRegionDidChange, - MapChangeRegionDidChangeAnimated, - MapChangeWillStartLoadingMap, - MapChangeDidFinishLoadingMap, - MapChangeDidFailLoadingMap, - MapChangeWillStartRenderingFrame, - MapChangeDidFinishRenderingFrame, - MapChangeDidFinishRenderingFrameFullyRendered, - MapChangeWillStartRenderingMap, - MapChangeDidFinishRenderingMap, - MapChangeDidFinishRenderingMapFullyRendered, - MapChangeDidFinishLoadingStyle, - MapChangeSourceDidChange - }; - - enum MapLoadingFailure { - StyleParseFailure, - StyleLoadFailure, - NotFoundFailure, - UnknownFailure - }; - - // Determines the orientation of the map. - enum NorthOrientation { - NorthUpwards, // Default - NorthRightwards, - NorthDownwards, - NorthLeftwards, - }; - - QMapboxGL(QObject* parent = 0, - const QMapboxGLSettings& = QMapboxGLSettings(), - const QSize& size = QSize(), - qreal pixelRatio = 1); - virtual ~QMapboxGL(); - - QString styleJson() const; - QString styleUrl() const; - - void setStyleJson(const QString &); - void setStyleUrl(const QString &); - - double latitude() const; - void setLatitude(double latitude); - - double longitude() const; - void setLongitude(double longitude); - - double scale() const; - void setScale(double scale, const QPointF ¢er = QPointF()); - - double zoom() const; - void setZoom(double zoom); - - double minimumZoom() const; - double maximumZoom() const; - - double bearing() const; - void setBearing(double degrees); - void setBearing(double degrees, const QPointF ¢er); - - double pitch() const; - void setPitch(double pitch); - void pitchBy(double pitch); - - NorthOrientation northOrientation() const; - void setNorthOrientation(NorthOrientation); - - QMapbox::Coordinate coordinate() const; - void setCoordinate(const QMapbox::Coordinate &); - void setCoordinateZoom(const QMapbox::Coordinate &, double zoom); - - void jumpTo(const QMapboxGLCameraOptions&); - - void setGestureInProgress(bool inProgress); - - void setTransitionOptions(qint64 duration, qint64 delay = 0); - - void addAnnotationIcon(const QString &name, const QImage &sprite); - - QMapbox::AnnotationID addAnnotation(const QMapbox::Annotation &); - void updateAnnotation(QMapbox::AnnotationID, const QMapbox::Annotation &); - void removeAnnotation(QMapbox::AnnotationID); - - bool setLayoutProperty(const QString &layer, const QString &property, const QVariant &value); - bool setPaintProperty(const QString &layer, const QString &property, const QVariant &value); - - bool isFullyLoaded() const; - - void moveBy(const QPointF &offset); - void scaleBy(double scale, const QPointF ¢er = QPointF()); - void rotateBy(const QPointF &first, const QPointF &second); - - void resize(const QSize &size); - - double metersPerPixelAtLatitude(double latitude, double zoom) const; - QMapbox::ProjectedMeters projectedMetersForCoordinate(const QMapbox::Coordinate &) const; - QMapbox::Coordinate coordinateForProjectedMeters(const QMapbox::ProjectedMeters &) const; - QPointF pixelForCoordinate(const QMapbox::Coordinate &) const; - QMapbox::Coordinate coordinateForPixel(const QPointF &) const; - - QMapbox::CoordinateZoom coordinateZoomForBounds(const QMapbox::Coordinate &sw, QMapbox::Coordinate &ne) const; - QMapbox::CoordinateZoom coordinateZoomForBounds(const QMapbox::Coordinate &sw, QMapbox::Coordinate &ne, double bearing, double pitch); - - void setMargins(const QMargins &margins); - QMargins margins() const; - - void addSource(const QString &sourceID, const QVariantMap& params); - bool sourceExists(const QString &sourceID); - void updateSource(const QString &sourceID, const QVariantMap& params); - void removeSource(const QString &sourceID); - - void addImage(const QString &name, const QImage &sprite); - void removeImage(const QString &name); - - void addCustomLayer(const QString &id, - QScopedPointer& host, - const QString& before = QString()); - void addLayer(const QVariantMap ¶ms, const QString& before = QString()); - bool layerExists(const QString &id); - void removeLayer(const QString &id); - - QVector layerIds() const; - - void setFilter(const QString &layer, const QVariant &filter); - QVariant getFilter(const QString &layer) const; - // When rendering on a different thread, - // should be called on the render thread. - void createRenderer(); - void destroyRenderer(); - void setFramebufferObject(quint32 fbo, const QSize &size); - -public slots: - void render(); - void connectionEstablished(); - - // Commit changes, load all the resources - // and renders the map when completed. - void startStaticRender(); - -signals: - void needsRendering(); - void mapChanged(QMapboxGL::MapChange); - void mapLoadingFailed(QMapboxGL::MapLoadingFailure, const QString &reason); - void copyrightsChanged(const QString ©rightsHtml); - - void staticRenderFinished(const QString &error); - -private: - Q_DISABLE_COPY(QMapboxGL) - - QMapboxGLPrivate *d_ptr; -}; - -Q_DECLARE_METATYPE(QMapboxGL::MapChange); -Q_DECLARE_METATYPE(QMapboxGL::MapLoadingFailure); - -#endif // QMAPBOXGL_H diff --git a/third_party/mapbox-gl-native-qt/x86_64/libqmapboxgl.so b/third_party/mapbox-gl-native-qt/x86_64/libqmapboxgl.so deleted file mode 100755 index a61c80c63d..0000000000 --- a/third_party/mapbox-gl-native-qt/x86_64/libqmapboxgl.so +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:ee37b571a5a50d07f2fd1a3150aa2842f10576e96e01278bbc060815549d57e9 -size 10219704 diff --git a/third_party/maplibre-native-qt/.gitignore b/third_party/maplibre-native-qt/.gitignore new file mode 100644 index 0000000000..9adc6681c0 --- /dev/null +++ b/third_party/maplibre-native-qt/.gitignore @@ -0,0 +1 @@ +/maplibre/ diff --git a/third_party/maplibre-native-qt/aarch64 b/third_party/maplibre-native-qt/aarch64 new file mode 120000 index 0000000000..062c65e8d9 --- /dev/null +++ b/third_party/maplibre-native-qt/aarch64 @@ -0,0 +1 @@ +larch64/ \ No newline at end of file diff --git a/third_party/maplibre-native-qt/build.sh b/third_party/maplibre-native-qt/build.sh new file mode 100755 index 0000000000..c64f0fc649 --- /dev/null +++ b/third_party/maplibre-native-qt/build.sh @@ -0,0 +1,38 @@ +#!/usr/bin/env bash +set -e + +DIR="$(cd "$(dirname "${BASH_SOURCE[0]}")" >/dev/null && pwd)" + +ARCHNAME="x86_64" +MAPLIBRE_FLAGS="-DMLN_QT_WITH_LOCATION=OFF" +if [ -f /AGNOS ]; then + ARCHNAME="larch64" + #MAPLIBRE_FLAGS="$MAPLIBRE_FLAGS -DCMAKE_SYSTEM_NAME=Android -DANDROID_ABI=arm64-v8a" +fi + +cd $DIR +if [ ! -d maplibre ]; then + git clone git@github.com:maplibre/maplibre-native-qt.git $DIR/maplibre +fi + +cd maplibre +git fetch --all +git checkout 3726266e127c1f94ad64837c9dbe03d238255816 +git submodule update --depth=1 --recursive --init + +# build +mkdir -p build +cd build +set -x +cmake $MAPLIBRE_FLAGS $DIR/maplibre +make -j$(nproc) || make -j2 || make -j1 + +INSTALL_DIR="$DIR/$ARCHNAME" +rm -rf $INSTALL_DIR +mkdir -p $INSTALL_DIR + +rm -rf $INSTALL_DIR/lib $DIR/include +mkdir -p $INSTALL_DIR/lib $INSTALL_DIR/include $DIR/include +cp -r $DIR/maplibre/build/src/core/*.so* $INSTALL_DIR/lib +cp -r $DIR/maplibre/build/src/core/include/* $INSTALL_DIR/include +cp -r $DIR/maplibre/src/**/*.hpp $DIR/include diff --git a/third_party/maplibre-native-qt/include/conversion_p.hpp b/third_party/maplibre-native-qt/include/conversion_p.hpp new file mode 100644 index 0000000000..38b03d498e --- /dev/null +++ b/third_party/maplibre-native-qt/include/conversion_p.hpp @@ -0,0 +1,241 @@ +// Copyright (C) 2023 MapLibre contributors +// Copyright (C) 2018 Mapbox, Inc. + +// SPDX-License-Identifier: BSD-2-Clause + +#pragma once + +#include "geojson_p.hpp" +#include "types.hpp" + +#include +#include + +#include +#include + +#include + +namespace mbgl::style::conversion { + +std::string convertColor(const QColor &color); + +template <> +class ConversionTraits { +public: + static bool isUndefined(const QVariant &value) { return value.isNull() || !value.isValid(); } + + static bool isArray(const QVariant &value) { +#if QT_VERSION >= QT_VERSION_CHECK(6, 0, 0) + return QMetaType::canConvert(value.metaType(), QMetaType(QMetaType::QVariantList)); +#else + return value.canConvert(QVariant::List); +#endif + } + + static std::size_t arrayLength(const QVariant &value) { return value.toList().size(); } + + static QVariant arrayMember(const QVariant &value, std::size_t i) { return value.toList()[static_cast(i)]; } + + static bool isObject(const QVariant &value) { +#if QT_VERSION >= QT_VERSION_CHECK(6, 0, 0) + return QMetaType::canConvert(value.metaType(), QMetaType(QMetaType::QVariantMap)) || + value.typeId() == QMetaType::QByteArray +#else + return value.canConvert(QVariant::Map) || value.type() == QVariant::ByteArray +#endif + || QString(value.typeName()) == QStringLiteral("QMapLibre::Feature") || + value.userType() == qMetaTypeId>() || + value.userType() == qMetaTypeId>() || + value.userType() == qMetaTypeId>(); + } + + static std::optional objectMember(const QVariant &value, const char *key) { + auto map = value.toMap(); + auto iter = map.constFind(key); + + if (iter != map.constEnd()) { + return iter.value(); + } + + return {}; + } + + template + static std::optional eachMember(const QVariant &value, Fn &&fn) { + auto map = value.toMap(); + auto iter = map.constBegin(); + + while (iter != map.constEnd()) { + std::optional result = fn(iter.key().toStdString(), QVariant(iter.value())); + if (result) { + return result; + } + + ++iter; + } + + return {}; + } + + static std::optional toBool(const QVariant &value) { +#if QT_VERSION >= QT_VERSION_CHECK(6, 0, 0) + if (value.typeId() == QMetaType::Bool) { +#else + if (value.type() == QVariant::Bool) { +#endif + return value.toBool(); + } + + return {}; + } + + static std::optional toNumber(const QVariant &value) { +#if QT_VERSION >= QT_VERSION_CHECK(6, 0, 0) + if (value.typeId() == QMetaType::Int || value.typeId() == QMetaType::Double || + value.typeId() == QMetaType::Long || value.typeId() == QMetaType::LongLong || + value.typeId() == QMetaType::ULong || value.typeId() == QMetaType::ULongLong) { +#else + if (value.type() == QVariant::Int || value.type() == QVariant::Double || value.type() == QVariant::LongLong || + value.type() == QVariant::ULongLong) { +#endif + return value.toFloat(); + } + + return {}; + } + + static std::optional toDouble(const QVariant &value) { +#if QT_VERSION >= QT_VERSION_CHECK(6, 0, 0) + if (value.typeId() == QMetaType::Int || value.typeId() == QMetaType::Double || + value.typeId() == QMetaType::Long || value.typeId() == QMetaType::LongLong || + value.typeId() == QMetaType::ULong || value.typeId() == QMetaType::ULongLong) { +#else + if (value.type() == QVariant::Int || value.type() == QVariant::Double || value.type() == QVariant::LongLong || + value.type() == QVariant::ULongLong) { +#endif + return value.toDouble(); + } + + return {}; + } + + static std::optional toString(const QVariant &value) { +#if QT_VERSION >= QT_VERSION_CHECK(6, 0, 0) + if (value.typeId() == QMetaType::QString) { + return value.toString().toStdString(); + } + + if (value.typeId() == QMetaType::QColor) { + return convertColor(value.value()); + } +#else + if (value.type() == QVariant::String) { + return value.toString().toStdString(); + } + + if (value.type() == QVariant::Color) { + return convertColor(value.value()); + } +#endif + return {}; + } + + static std::optional toValue(const QVariant &value) { +#if QT_VERSION >= QT_VERSION_CHECK(6, 0, 0) + if (value.typeId() == QMetaType::Bool) { + return {value.toBool()}; + } + + if (value.typeId() == QMetaType::QString) { + return {value.toString().toStdString()}; + } + + if (value.typeId() == QMetaType::QColor) { + return {convertColor(value.value())}; + } + + if (value.typeId() == QMetaType::Int) { + return {static_cast(value.toInt())}; + } + + if (QMetaType::canConvert(value.metaType(), QMetaType(QMetaType::Double))) { + return {value.toDouble()}; + } +#else + if (value.type() == QVariant::Bool) { + return {value.toBool()}; + } + + if (value.type() == QVariant::String) { + return {value.toString().toStdString()}; + } + + if (value.type() == QVariant::Color) { + return {convertColor(value.value())}; + } + + if (value.type() == QVariant::Int) { + return {static_cast(value.toInt())}; + } + + if (value.canConvert(QVariant::Double)) { + return {value.toDouble()}; + } +#endif + return {}; + } + + static std::optional toGeoJSON(const QVariant &value, Error &error) { + if (value.typeName() == QStringLiteral("QMapLibre::Feature")) { + return GeoJSON{QMapLibre::GeoJSON::asFeature(value.value())}; + } + + if (value.userType() == qMetaTypeId>()) { + return featureCollectionToGeoJSON(value.value>()); + } + + if (value.userType() == qMetaTypeId>()) { + return featureCollectionToGeoJSON(value.value>()); + } + + if (value.userType() == qMetaTypeId>()) { + return featureCollectionToGeoJSON(value.value>()); + } + +#if QT_VERSION >= QT_VERSION_CHECK(6, 0, 0) + if (value.typeId() != QMetaType::QByteArray) { +#else + if (value.type() != QVariant::ByteArray) { +#endif + error = {"JSON data must be in QByteArray"}; + return {}; + } + + const QByteArray data = value.toByteArray(); + return parseGeoJSON(std::string(data.constData(), data.size()), error); + } + +private: + template + static GeoJSON featureCollectionToGeoJSON(const T &features) { + mapbox::feature::feature_collection collection; + collection.reserve(static_cast(features.size())); + for (const auto &feature : features) { + collection.push_back(QMapLibre::GeoJSON::asFeature(feature)); + } + return GeoJSON{std::move(collection)}; + } +}; + +template +std::optional convert(const QVariant &value, Error &error, Args &&...args) { + return convert(Convertible(value), error, std::forward(args)...); +} + +inline std::string convertColor(const QColor &color) { + return QString::asprintf("rgba(%d,%d,%d,%lf)", color.red(), color.green(), color.blue(), color.alphaF()) + .toStdString(); +} + +} // namespace mbgl::style::conversion diff --git a/third_party/maplibre-native-qt/include/export_core.hpp b/third_party/maplibre-native-qt/include/export_core.hpp new file mode 100644 index 0000000000..bd5ad495db --- /dev/null +++ b/third_party/maplibre-native-qt/include/export_core.hpp @@ -0,0 +1,20 @@ +// Copyright (C) 2023 MapLibre contributors + +// SPDX-License-Identifier: BSD-2-Clause + +#ifndef QMAPLIBRE_CORE_EXPORT_H +#define QMAPLIBRE_CORE_EXPORT_H + +#include + +#if !defined(QT_MAPLIBRE_STATIC) +#if defined(QT_BUILD_MAPLIBRE_CORE_LIB) +#define Q_MAPLIBRE_CORE_EXPORT Q_DECL_EXPORT +#else +#define Q_MAPLIBRE_CORE_EXPORT Q_DECL_IMPORT +#endif +#else +#define Q_MAPLIBRE_CORE_EXPORT +#endif + +#endif // QMAPLIBRE_CORE_EXPORT_H diff --git a/third_party/maplibre-native-qt/include/export_location.hpp b/third_party/maplibre-native-qt/include/export_location.hpp new file mode 100644 index 0000000000..a986346884 --- /dev/null +++ b/third_party/maplibre-native-qt/include/export_location.hpp @@ -0,0 +1,20 @@ +// Copyright (C) 2023 MapLibre contributors + +// SPDX-License-Identifier: BSD-2-Clause + +#ifndef QMAPLIBRE_LOCATION_EXPORT_H +#define QMAPLIBRE_LOCATION_EXPORT_H + +#include + +#if !defined(QT_MAPLIBRE_STATIC) +#if defined(QT_BUILD_MAPLIBRE_LOCATION_LIB) +#define Q_MAPLIBRE_LOCATION_EXPORT Q_DECL_EXPORT +#else +#define Q_MAPLIBRE_LOCATION_EXPORT Q_DECL_IMPORT +#endif +#else +#define Q_MAPLIBRE_LOCATION_EXPORT +#endif + +#endif // QMAPLIBRE_LOCATION_EXPORT_H diff --git a/third_party/maplibre-native-qt/include/export_widgets.hpp b/third_party/maplibre-native-qt/include/export_widgets.hpp new file mode 100644 index 0000000000..11bc288190 --- /dev/null +++ b/third_party/maplibre-native-qt/include/export_widgets.hpp @@ -0,0 +1,20 @@ +// Copyright (C) 2023 MapLibre contributors + +// SPDX-License-Identifier: BSD-2-Clause + +#ifndef QMAPLIBRE_WIDGETS_EXPORT_H +#define QMAPLIBRE_WIDGETS_EXPORT_H + +#include + +#if !defined(QT_MAPLIBRE_STATIC) +#if defined(QT_BUILD_MAPLIBRE_WIDGETS_LIB) +#define Q_MAPLIBRE_WIDGETS_EXPORT Q_DECL_EXPORT +#else +#define Q_MAPLIBRE_WIDGETS_EXPORT Q_DECL_IMPORT +#endif +#else +#define Q_MAPLIBRE_WIDGETS_EXPORT +#endif + +#endif // QMAPLIBRE_WIDGETS_EXPORT_H diff --git a/third_party/maplibre-native-qt/include/geojson_p.hpp b/third_party/maplibre-native-qt/include/geojson_p.hpp new file mode 100644 index 0000000000..8387f70c4b --- /dev/null +++ b/third_party/maplibre-native-qt/include/geojson_p.hpp @@ -0,0 +1,30 @@ +// Copyright (C) 2023 MapLibre contributors +// Copyright (C) 2019 Mapbox, Inc. + +// SPDX-License-Identifier: BSD-2-Clause + +#pragma once + +#include "types.hpp" + +#include +#include +#include + +#include + +#include + +namespace QMapLibre::GeoJSON { + +mbgl::Point asPoint(const Coordinate &coordinate); +mbgl::MultiPoint asMultiPoint(const Coordinates &multiPoint); +mbgl::LineString asLineString(const Coordinates &lineString); +mbgl::MultiLineString asMultiLineString(const CoordinatesCollection &multiLineString); +mbgl::Polygon asPolygon(const CoordinatesCollection &polygon); +mbgl::MultiPolygon asMultiPolygon(const CoordinatesCollections &multiPolygon); +mbgl::Value asPropertyValue(const QVariant &value); +mbgl::FeatureIdentifier asFeatureIdentifier(const QVariant &id); +mbgl::GeoJSONFeature asFeature(const Feature &feature); + +} // namespace QMapLibre::GeoJSON diff --git a/third_party/maplibre-native-qt/include/gl_widget.hpp b/third_party/maplibre-native-qt/include/gl_widget.hpp new file mode 100644 index 0000000000..b2630daea7 --- /dev/null +++ b/third_party/maplibre-native-qt/include/gl_widget.hpp @@ -0,0 +1,56 @@ +// Copyright (C) 2023 MapLibre contributors + +// SPDX-License-Identifier: BSD-2-Clause + +#ifndef QMAPLIBRE_GL_WIDGET_H +#define QMAPLIBRE_GL_WIDGET_H + +#include + +#include +#include + +#include + +#include + +QT_BEGIN_NAMESPACE + +class QKeyEvent; +class QMouseEvent; +class QWheelEvent; + +QT_END_NAMESPACE + +namespace QMapLibre { + +class GLWidgetPrivate; + +class Q_MAPLIBRE_WIDGETS_EXPORT GLWidget : public QOpenGLWidget { + Q_OBJECT + +public: + explicit GLWidget(const Settings &); + ~GLWidget() override; + + Map *map(); + +protected: + // QWidget implementation. + void mousePressEvent(QMouseEvent *event) override; + void mouseMoveEvent(QMouseEvent *event) override; + void wheelEvent(QWheelEvent *event) override; + + // Q{,Open}GLWidget implementation. + void initializeGL() override; + void paintGL() override; + +private: + Q_DISABLE_COPY(GLWidget) + + std::unique_ptr d_ptr; +}; + +} // namespace QMapLibre + +#endif // QMAPLIBRE_GL_WIDGET_H diff --git a/third_party/maplibre-native-qt/include/gl_widget_p.hpp b/third_party/maplibre-native-qt/include/gl_widget_p.hpp new file mode 100644 index 0000000000..c97781fd29 --- /dev/null +++ b/third_party/maplibre-native-qt/include/gl_widget_p.hpp @@ -0,0 +1,42 @@ +// Copyright (C) 2023 MapLibre contributors + +// SPDX-License-Identifier: BSD-2-Clause + +#pragma once + +#include +#include + +#include + +QT_BEGIN_NAMESPACE + +class QKeyEvent; +class QMouseEvent; +class QWheelEvent; + +QT_END_NAMESPACE + +namespace QMapLibre { + +class GLWidgetPrivate : public QObject { + Q_OBJECT + +public: + explicit GLWidgetPrivate(QObject *parent, Settings settings); + ~GLWidgetPrivate() override; + + void handleMousePressEvent(QMouseEvent *event); + void handleMouseMoveEvent(QMouseEvent *event); + void handleWheelEvent(QWheelEvent *event) const; + + std::unique_ptr m_map{}; + Settings m_settings; + +private: + Q_DISABLE_COPY(GLWidgetPrivate); + + QPointF m_lastPos; +}; + +} // namespace QMapLibre diff --git a/third_party/maplibre-native-qt/include/map.hpp b/third_party/maplibre-native-qt/include/map.hpp new file mode 100644 index 0000000000..cd56996185 --- /dev/null +++ b/third_party/maplibre-native-qt/include/map.hpp @@ -0,0 +1,205 @@ +// Copyright (C) 2023 MapLibre contributors +// Copyright (C) 2019 Mapbox, Inc. + +// SPDX-License-Identifier: BSD-2-Clause + +#ifndef QMAPLIBRE_MAP_H +#define QMAPLIBRE_MAP_H + +#include +#include +#include + +#include +#include +#include +#include +#include +#include +#include + +#include +#include + +namespace QMapLibre { + +class MapPrivate; + +class Q_MAPLIBRE_CORE_EXPORT Map : public QObject { + Q_OBJECT + Q_PROPERTY(double latitude READ latitude WRITE setLatitude) + Q_PROPERTY(double longitude READ longitude WRITE setLongitude) + Q_PROPERTY(double zoom READ zoom WRITE setZoom) + Q_PROPERTY(double bearing READ bearing WRITE setBearing) + Q_PROPERTY(double pitch READ pitch WRITE setPitch) + Q_PROPERTY(QString styleJson READ styleJson WRITE setStyleJson) + Q_PROPERTY(QString styleUrl READ styleUrl WRITE setStyleUrl) + Q_PROPERTY(double scale READ scale WRITE setScale) + Q_PROPERTY(QMapLibre::Coordinate coordinate READ coordinate WRITE setCoordinate) + Q_PROPERTY(QMargins margins READ margins WRITE setMargins) + +public: + enum MapChange { + MapChangeRegionWillChange = 0, + MapChangeRegionWillChangeAnimated, + MapChangeRegionIsChanging, + MapChangeRegionDidChange, + MapChangeRegionDidChangeAnimated, + MapChangeWillStartLoadingMap, + MapChangeDidFinishLoadingMap, + MapChangeDidFailLoadingMap, + MapChangeWillStartRenderingFrame, + MapChangeDidFinishRenderingFrame, + MapChangeDidFinishRenderingFrameFullyRendered, + MapChangeWillStartRenderingMap, + MapChangeDidFinishRenderingMap, + MapChangeDidFinishRenderingMapFullyRendered, + MapChangeDidFinishLoadingStyle, + MapChangeSourceDidChange + }; + + enum MapLoadingFailure { + StyleParseFailure, + StyleLoadFailure, + NotFoundFailure, + UnknownFailure + }; + + // Determines the orientation of the map. + enum NorthOrientation { + NorthUpwards, // Default + NorthRightwards, + NorthDownwards, + NorthLeftwards, + }; + + explicit Map(QObject *parent = nullptr, + const Settings &settings = Settings(), + const QSize &size = QSize(), + qreal pixelRatio = 1); + ~Map() override; + + [[nodiscard]] QString styleJson() const; + [[nodiscard]] QString styleUrl() const; + + void setStyleJson(const QString &); + void setStyleUrl(const QString &); + + [[nodiscard]] double latitude() const; + void setLatitude(double latitude); + + [[nodiscard]] double longitude() const; + void setLongitude(double longitude); + + [[nodiscard]] double scale() const; + void setScale(double scale, const QPointF ¢er = QPointF()); + + [[nodiscard]] double zoom() const; + void setZoom(double zoom); + + [[nodiscard]] double minimumZoom() const; + [[nodiscard]] double maximumZoom() const; + + [[nodiscard]] double bearing() const; + void setBearing(double degrees); + void setBearing(double degrees, const QPointF ¢er); + + [[nodiscard]] double pitch() const; + void setPitch(double pitch); + void pitchBy(double pitch); + + [[nodiscard]] NorthOrientation northOrientation() const; + void setNorthOrientation(NorthOrientation); + + [[nodiscard]] Coordinate coordinate() const; + void setCoordinate(const Coordinate &coordinate); + void setCoordinateZoom(const Coordinate &coordinate, double zoom); + + void jumpTo(const CameraOptions &); + + void setGestureInProgress(bool inProgress); + + void setTransitionOptions(qint64 duration, qint64 delay = 0); + + void addAnnotationIcon(const QString &name, const QImage &sprite); + + AnnotationID addAnnotation(const Annotation &annotation); + void updateAnnotation(AnnotationID id, const Annotation &annotation); + void removeAnnotation(AnnotationID id); + + bool setLayoutProperty(const QString &layerId, const QString &propertyName, const QVariant &value); + bool setPaintProperty(const QString &layerId, const QString &propertyName, const QVariant &value); + + [[nodiscard]] bool isFullyLoaded() const; + + void moveBy(const QPointF &offset); + void scaleBy(double scale, const QPointF ¢er = QPointF()); + void rotateBy(const QPointF &first, const QPointF &second); + + void resize(const QSize &size); + + [[nodiscard]] QPointF pixelForCoordinate(const Coordinate &coordinate) const; + [[nodiscard]] Coordinate coordinateForPixel(const QPointF &pixel) const; + + [[nodiscard]] CoordinateZoom coordinateZoomForBounds(const Coordinate &sw, const Coordinate &ne) const; + [[nodiscard]] CoordinateZoom coordinateZoomForBounds(const Coordinate &sw, + const Coordinate &ne, + double bearing, + double pitch); + + void setMargins(const QMargins &margins); + [[nodiscard]] QMargins margins() const; + + void addSource(const QString &id, const QVariantMap ¶ms); + bool sourceExists(const QString &id); + void updateSource(const QString &id, const QVariantMap ¶ms); + void removeSource(const QString &id); + + void addImage(const QString &id, const QImage &sprite); + void removeImage(const QString &id); + + void addCustomLayer(const QString &id, + std::unique_ptr host, + const QString &before = QString()); + void addLayer(const QString &id, const QVariantMap ¶ms, const QString &before = QString()); + bool layerExists(const QString &id); + void removeLayer(const QString &id); + + [[nodiscard]] QVector layerIds() const; + + void setFilter(const QString &layerId, const QVariant &filter); + [[nodiscard]] QVariant getFilter(const QString &layerId) const; + // When rendering on a different thread, + // should be called on the render thread. + void createRenderer(); + void destroyRenderer(); + void setFramebufferObject(quint32 fbo, const QSize &size); + +public slots: + void render(); + void setConnectionEstablished(); + + // Commit changes, load all the resources + // and renders the map when completed. + void startStaticRender(); + +signals: + void needsRendering(); + void mapChanged(Map::MapChange); + void mapLoadingFailed(Map::MapLoadingFailure, const QString &reason); + void copyrightsChanged(const QString ©rightsHtml); + + void staticRenderFinished(const QString &error); + +private: + Q_DISABLE_COPY(Map) + + std::unique_ptr d_ptr; +}; + +} // namespace QMapLibre + +Q_DECLARE_METATYPE(QMapLibre::Map::MapChange); +Q_DECLARE_METATYPE(QMapLibre::Map::MapLoadingFailure); + +#endif // QMAPLIBRE_MAP_H diff --git a/third_party/maplibre-native-qt/include/map_observer_p.hpp b/third_party/maplibre-native-qt/include/map_observer_p.hpp new file mode 100644 index 0000000000..e68c72b17b --- /dev/null +++ b/third_party/maplibre-native-qt/include/map_observer_p.hpp @@ -0,0 +1,54 @@ +// Copyright (C) 2023 MapLibre contributors +// Copyright (C) 2019 Mapbox, Inc. + +// SPDX-License-Identifier: BSD-2-Clause + +#pragma once + +#include "map.hpp" + +#include +#include + +#include + +#include +#include + +namespace QMapLibre { + +class MapPrivate; + +class MapObserver : public QObject, public mbgl::MapObserver { + Q_OBJECT + +public: + explicit MapObserver(MapPrivate *ptr); + ~MapObserver() override; + + // mbgl::MapObserver implementation. + void onCameraWillChange(mbgl::MapObserver::CameraChangeMode mode) final; + void onCameraIsChanging() final; + void onCameraDidChange(mbgl::MapObserver::CameraChangeMode mode) final; + void onWillStartLoadingMap() final; + void onDidFinishLoadingMap() final; + void onDidFailLoadingMap(mbgl::MapLoadError error, const std::string &what) final; + void onWillStartRenderingFrame() final; + void onDidFinishRenderingFrame(mbgl::MapObserver::RenderFrameStatus status) final; + void onWillStartRenderingMap() final; + void onDidFinishRenderingMap(mbgl::MapObserver::RenderMode mode) final; + void onDidFinishLoadingStyle() final; + void onSourceChanged(mbgl::style::Source &source) final; + +signals: + void mapChanged(Map::MapChange); + void mapLoadingFailed(Map::MapLoadingFailure, const QString &reason); + void copyrightsChanged(const QString ©rightsHtml); + +private: + Q_DISABLE_COPY(MapObserver) + + MapPrivate *d_ptrRef; +}; + +} // namespace QMapLibre diff --git a/third_party/maplibre-native-qt/include/map_p.hpp b/third_party/maplibre-native-qt/include/map_p.hpp new file mode 100644 index 0000000000..9ca0c7e6f5 --- /dev/null +++ b/third_party/maplibre-native-qt/include/map_p.hpp @@ -0,0 +1,79 @@ +// Copyright (C) 2023 MapLibre contributors +// Copyright (C) 2019 Mapbox, Inc. + +// SPDX-License-Identifier: BSD-2-Clause + +#pragma once + +#include "map.hpp" +#include "map_observer_p.hpp" +#include "map_renderer_p.hpp" + +#include +#include +#include +#include +#include + +#include +#include + +#include +#include + +namespace QMapLibre { + +class MapPrivate : public QObject, public mbgl::RendererFrontend { + Q_OBJECT + +public: + explicit MapPrivate(Map *map, const Settings &settings, const QSize &size, qreal pixelRatio); + ~MapPrivate() override; + + // mbgl::RendererFrontend implementation. + void reset() final {} + void setObserver(mbgl::RendererObserver &observer) final; + void update(std::shared_ptr parameters) final; + + // These need to be called on the same thread. + void createRenderer(); + void destroyRenderer(); + void render(); + void setFramebufferObject(quint32 fbo, const QSize &size); + + using PropertySetter = std::optional (mbgl::style::Layer::*)( + const std::string &, const mbgl::style::conversion::Convertible &); + [[nodiscard]] bool setProperty(const PropertySetter &setter, + const QString &layerId, + const QString &name, + const QVariant &value) const; + + mbgl::EdgeInsets margins; + std::unique_ptr mapObj{}; + +public slots: + void requestRendering(); + +signals: + void needsRendering(); + +private: + Q_DISABLE_COPY(MapPrivate) + + std::recursive_mutex m_mapRendererMutex; + std::shared_ptr m_rendererObserver{}; + std::shared_ptr m_updateParameters{}; + + std::unique_ptr m_mapObserver{}; + std::unique_ptr m_mapRenderer{}; + std::unique_ptr> m_resourceTransform{}; + + Settings::GLContextMode m_mode; + qreal m_pixelRatio; + + QString m_localFontFamily; + + std::atomic_flag m_renderQueued = ATOMIC_FLAG_INIT; +}; + +} // namespace QMapLibre diff --git a/third_party/maplibre-native-qt/include/map_renderer_p.hpp b/third_party/maplibre-native-qt/include/map_renderer_p.hpp new file mode 100644 index 0000000000..b9a087c392 --- /dev/null +++ b/third_party/maplibre-native-qt/include/map_renderer_p.hpp @@ -0,0 +1,63 @@ +// Copyright (C) 2023 MapLibre contributors +// Copyright (C) 2019 Mapbox, Inc. + +// SPDX-License-Identifier: BSD-2-Clause + +#pragma once + +#include "settings.hpp" + +#include "utils/renderer_backend.hpp" + +#include +#include +#include + +#include + +#include + +#include +#include + +namespace mbgl { +class Renderer; +class UpdateParameters; +} // namespace mbgl + +namespace QMapLibre { + +class RendererBackend; + +class MapRenderer : public QObject { + Q_OBJECT + +public: + MapRenderer(qreal pixelRatio, Settings::GLContextMode, const QString &localFontFamily); + ~MapRenderer() override; + + void render(); + void updateFramebuffer(quint32 fbo, const mbgl::Size &size); + void setObserver(mbgl::RendererObserver *observer); + + // Thread-safe, called by the Frontend + void updateParameters(std::shared_ptr parameters); + +signals: + void needsRendering(); + +private: + MBGL_STORE_THREAD(tid) + + Q_DISABLE_COPY(MapRenderer) + + std::mutex m_updateMutex; + std::shared_ptr m_updateParameters; + + RendererBackend m_backend; + std::unique_ptr m_renderer{}; + + bool m_forceScheduler{}; +}; + +} // namespace QMapLibre diff --git a/third_party/maplibre-native-qt/include/qgeomap.hpp b/third_party/maplibre-native-qt/include/qgeomap.hpp new file mode 100644 index 0000000000..5eb0180503 --- /dev/null +++ b/third_party/maplibre-native-qt/include/qgeomap.hpp @@ -0,0 +1,54 @@ +// Copyright (C) 2023 MapLibre contributors +// Copyright (C) 2017 The Qt Company Ltd. +// Copyright (C) 2017 Mapbox, Inc. + +// SPDX-License-Identifier: LGPL-3.0-only OR GPL-2.0-only OR GPL-3.0-only + +#pragma once + +#include "export_location.hpp" + +#include +#include + +#include + +namespace QMapLibre { + +class QGeoMapMapLibrePrivate; + +class Q_MAPLIBRE_LOCATION_EXPORT QGeoMapMapLibre : public QGeoMap { + Q_OBJECT + Q_DECLARE_PRIVATE(QGeoMapMapLibre) + +public: + explicit QGeoMapMapLibre(QGeoMappingManagerEngine *engine, QObject *parent = nullptr); + ~QGeoMapMapLibre() override; + + [[nodiscard]] Capabilities capabilities() const override; + + void setSettings(const Settings &settings); + void setMapItemsBefore(const QString &mapItemsBefore); + + void addStyleParameter(StyleParameter *parameter); + void removeStyleParameter(StyleParameter *parameter); + void clearStyleParameters(); + +private Q_SLOTS: + // QMapLibre + void onMapChanged(Map::MapChange); + + // QDeclarativeGeoMapItemBase + void onMapItemPropertyChanged(); + void onMapItemSubPropertyChanged(); + void onMapItemUnsupportedPropertyChanged(); + void onMapItemGeometryChanged(); + + // StyleParameter + void onStyleParameterUpdated(StyleParameter *parameter); + +private: + QSGNode *updateSceneGraph(QSGNode *oldNode, QQuickWindow *window) override; +}; + +} // namespace QMapLibre diff --git a/third_party/maplibre-native-qt/include/qgeomap_p.hpp b/third_party/maplibre-native-qt/include/qgeomap_p.hpp new file mode 100644 index 0000000000..ce415d9bcf --- /dev/null +++ b/third_party/maplibre-native-qt/include/qgeomap_p.hpp @@ -0,0 +1,93 @@ +// Copyright (C) 2023 MapLibre contributors +// Copyright (C) 2017 The Qt Company Ltd. +// Copyright (C) 2017 Mapbox, Inc. + +// SPDX-License-Identifier: LGPL-3.0-only OR GPL-2.0-only OR GPL-3.0-only + +#pragma once + +#include "qgeomap.hpp" + +#include +#include + +#include + +#include +#include +#include +#include +#include +#include + +namespace QMapLibre { + +class Map; +class StyleChange; + +class QGeoMapMapLibrePrivate : public QGeoMapPrivate { + Q_DECLARE_PUBLIC(QGeoMapMapLibre) + +public: + explicit QGeoMapMapLibrePrivate(QGeoMappingManagerEngine *engine); + ~QGeoMapMapLibrePrivate() override; + + QSGNode *updateSceneGraph(QSGNode *oldNode, QQuickWindow *window); + + QGeoMap::ItemTypes supportedMapItemTypes() const override; + void addMapItem(QDeclarativeGeoMapItemBase *item) override; + void removeMapItem(QDeclarativeGeoMapItemBase *item) override; + + void addStyleParameter(StyleParameter *parameter); + void removeStyleParameter(StyleParameter *parameter); + void clearStyleParameters(); + + /* Data members */ + enum SyncState : int { + NoSync = 0, + ViewportSync = 1 << 0, + CameraDataSync = 1 << 1, + MapTypeSync = 1 << 2, + VisibleAreaSync = 1 << 3 + }; + Q_DECLARE_FLAGS(SyncStates, SyncState); + + Settings m_settings; + QString m_mapItemsBefore; + + QList m_mapParameters; + + QTimer m_refresh; + bool m_shouldRefresh = true; + bool m_warned = false; + bool m_threadedRendering = false; + bool m_styleLoaded = false; + + SyncStates m_syncState = NoSync; + + std::vector> m_styleChanges; + +protected: + void changeViewportSize(const QSize &size) override; + void changeCameraData(const QGeoCameraData &data) override; +#if QT_VERSION >= QT_VERSION_CHECK(6, 5, 0) + void changeActiveMapType(const QGeoMapType &mapType) override; +#else + void changeActiveMapType(const QGeoMapType mapType) override; +#endif + + void setVisibleArea(const QRectF &visibleArea) override; + QRectF visibleArea() const override; + +private: + Q_DISABLE_COPY(QGeoMapMapLibrePrivate); + + void syncStyleChanges(Map *map); + void threadedRenderingHack(QQuickWindow *window, Map *map); + + QRectF m_visibleArea; +}; + +Q_DECLARE_OPERATORS_FOR_FLAGS(QGeoMapMapLibrePrivate::SyncStates) + +} // namespace QMapLibre diff --git a/third_party/maplibre-native-qt/include/qmaplibre.hpp b/third_party/maplibre-native-qt/include/qmaplibre.hpp new file mode 100644 index 0000000000..a8dc445e2b --- /dev/null +++ b/third_party/maplibre-native-qt/include/qmaplibre.hpp @@ -0,0 +1,9 @@ +// Copyright (C) 2023 MapLibre contributors + +// SPDX-License-Identifier: BSD-2-Clause + +#include "export_core.hpp" +#include "map.hpp" +#include "settings.hpp" +#include "types.hpp" +#include "utils.hpp" diff --git a/third_party/maplibre-native-qt/include/qmaplibrewidgets.hpp b/third_party/maplibre-native-qt/include/qmaplibrewidgets.hpp new file mode 100644 index 0000000000..ebe9a8eea4 --- /dev/null +++ b/third_party/maplibre-native-qt/include/qmaplibrewidgets.hpp @@ -0,0 +1,6 @@ +// Copyright (C) 2023 MapLibre contributors + +// SPDX-License-Identifier: BSD-2-Clause + +#include "export_widgets.hpp" +#include "gl_widget.hpp" diff --git a/third_party/maplibre-native-qt/include/qt_mapping_engine.hpp b/third_party/maplibre-native-qt/include/qt_mapping_engine.hpp new file mode 100644 index 0000000000..67cb4b56ce --- /dev/null +++ b/third_party/maplibre-native-qt/include/qt_mapping_engine.hpp @@ -0,0 +1,31 @@ +// Copyright (C) 2023 MapLibre contributors +// Copyright (C) 2017 The Qt Company Ltd. +// Copyright (C) 2017 Mapbox, Inc. + +// SPDX-License-Identifier: LGPL-3.0-only OR GPL-2.0-only OR GPL-3.0-only + +#pragma once + +#include "export_location.hpp" + +#include + +#include +#include + +namespace QMapLibre { + +class Q_MAPLIBRE_LOCATION_EXPORT QtMappingEngine : public QGeoMappingManagerEngine { + Q_OBJECT + +public: + QtMappingEngine(const QVariantMap ¶meters, QGeoServiceProvider::Error *error, QString *errorString); + + QGeoMap *createMap() override; + +private: + Settings m_settings; + QString m_mapItemsBefore; +}; + +} // namespace QMapLibre diff --git a/third_party/maplibre-native-qt/include/settings.hpp b/third_party/maplibre-native-qt/include/settings.hpp new file mode 100644 index 0000000000..d6f88b871b --- /dev/null +++ b/third_party/maplibre-native-qt/include/settings.hpp @@ -0,0 +1,125 @@ +// Copyright (C) 2023 MapLibre contributors +// Copyright (C) 2019 Mapbox, Inc. + +// SPDX-License-Identifier: BSD-2-Clause + +#ifndef QMAPLIBRE_SETTINGS_H +#define QMAPLIBRE_SETTINGS_H + +#include +#include + +#include +#include + +#include +#include + +// TODO: this will be wrapped at some point +namespace mbgl { +class TileServerOptions; +} // namespace mbgl + +namespace QMapLibre { + +class SettingsPrivate; + +class Q_MAPLIBRE_CORE_EXPORT Settings { +public: + enum GLContextMode : bool { + UniqueGLContext, + SharedGLContext + }; + + enum MapMode { + Continuous = 0, + Static + }; + + enum ConstrainMode { + NoConstrain = 0, + ConstrainHeightOnly, + ConstrainWidthAndHeight + }; + + enum ViewportMode { + DefaultViewport = 0, + FlippedYViewport + }; + + enum ProviderTemplate { + NoProvider = 0, + MapLibreProvider, + MapTilerProvider, + MapboxProvider + }; + + using ResourceTransformFunction = std::function; + + explicit Settings(ProviderTemplate provider = NoProvider); + ~Settings(); + Settings(const Settings &s); + Settings(Settings &&s) noexcept; + Settings &operator=(const Settings &s); + Settings &operator=(Settings &&s) noexcept; + + [[nodiscard]] GLContextMode contextMode() const; + void setContextMode(GLContextMode); + + [[nodiscard]] MapMode mapMode() const; + void setMapMode(MapMode); + + [[nodiscard]] ConstrainMode constrainMode() const; + void setConstrainMode(ConstrainMode); + + [[nodiscard]] ViewportMode viewportMode() const; + void setViewportMode(ViewportMode); + + [[nodiscard]] unsigned cacheDatabaseMaximumSize() const; + void setCacheDatabaseMaximumSize(unsigned); + + [[nodiscard]] QString cacheDatabasePath() const; + void setCacheDatabasePath(const QString &path); + + [[nodiscard]] QString assetPath() const; + void setAssetPath(const QString &path); + + [[nodiscard]] QString apiKey() const; + void setApiKey(const QString &key); + + [[nodiscard]] QString apiBaseUrl() const; + void setApiBaseUrl(const QString &url); + + [[nodiscard]] QString localFontFamily() const; + void setLocalFontFamily(const QString &family); + + [[nodiscard]] QString clientName() const; + void setClientName(const QString &name); + + [[nodiscard]] QString clientVersion() const; + void setClientVersion(const QString &version); + + [[nodiscard]] ResourceTransformFunction resourceTransform() const; + void setResourceTransform(const ResourceTransformFunction &transform); + + void setProviderTemplate(ProviderTemplate providerTemplate); + void setStyles(const Styles &styles); + + [[nodiscard]] const Styles &styles() const; + [[nodiscard]] Styles providerStyles() const; + + [[nodiscard]] Coordinate defaultCoordinate() const; + void setDefaultCoordinate(const Coordinate &coordinate); + [[nodiscard]] double defaultZoom() const; + void setDefaultZoom(double zoom); + + [[nodiscard]] bool customTileServerOptions() const; + [[nodiscard]] const mbgl::TileServerOptions &tileServerOptions() const; + +private: + std::unique_ptr d_ptr; +}; + +} // namespace QMapLibre + +#endif // QMAPLIBRE_SETTINGS_H diff --git a/third_party/maplibre-native-qt/include/settings_p.hpp b/third_party/maplibre-native-qt/include/settings_p.hpp new file mode 100644 index 0000000000..257bdfd5a9 --- /dev/null +++ b/third_party/maplibre-native-qt/include/settings_p.hpp @@ -0,0 +1,57 @@ +// Copyright (C) 2023 MapLibre contributors +// Copyright (C) 2019 Mapbox, Inc. + +// SPDX-License-Identifier: BSD-2-Clause + +#pragma once + +#include "settings.hpp" +#include "types.hpp" + +#include + +#include +#include + +#include +#include + +namespace mbgl { +class TileServerOptions; +} // namespace mbgl + +namespace QMapLibre { + +class SettingsPrivate { +public: + SettingsPrivate(); + + void setProviderTemplate(Settings::ProviderTemplate providerTemplate); + void setProviderApiBaseUrl(const QString &url); + + Settings::GLContextMode m_contextMode{Settings::SharedGLContext}; + Settings::MapMode m_mapMode{Settings::Continuous}; + Settings::ConstrainMode m_constrainMode{Settings::ConstrainHeightOnly}; + Settings::ViewportMode m_viewportMode{Settings::DefaultViewport}; + Settings::ProviderTemplate m_providerTemplate{Settings::NoProvider}; + + unsigned m_cacheMaximumSize; + QString m_cacheDatabasePath; + QString m_assetPath; + QString m_apiKey; + QString m_localFontFamily; + QString m_clientName; + QString m_clientVersion; + + Coordinate m_defaultCoordinate{}; + double m_defaultZoom{}; + + Styles m_styles; + + std::function m_resourceTransform; + + bool m_customTileServerOptions{}; + mbgl::TileServerOptions m_tileServerOptions{}; +}; + +} // namespace QMapLibre diff --git a/third_party/maplibre-native-qt/include/style_change_utils_p.hpp b/third_party/maplibre-native-qt/include/style_change_utils_p.hpp new file mode 100644 index 0000000000..991bb4077e --- /dev/null +++ b/third_party/maplibre-native-qt/include/style_change_utils_p.hpp @@ -0,0 +1,34 @@ +// Copyright (C) 2023 MapLibre contributors +// Copyright (C) 2017 Mapbox, Inc. + +// SPDX-License-Identifier: LGPL-3.0-only OR GPL-2.0-only OR GPL-3.0-only + +#pragma once + +#include + +#include +#include +#include +#include +#include + +namespace QMapLibre::StyleChangeUtils { + +Feature featureFromMapRectangle(QDeclarativeRectangleMapItem *item); +Feature featureFromMapCircle(QDeclarativeCircleMapItem *item); +Feature featureFromMapPolygon(QDeclarativePolygonMapItem *item); +Feature featureFromMapPolyline(QDeclarativePolylineMapItem *item); +Feature featureFromMapItem(QDeclarativeGeoMapItemBase *item); + +QString featureId(QDeclarativeGeoMapItemBase *item); +std::vector featureLayoutPropertiesFromMapPolyline(QDeclarativePolylineMapItem *item); +std::vector featureLayoutPropertiesFromMapItem(QDeclarativeGeoMapItemBase *item); +std::vector featurePaintPropertiesFromMapRectangle(QDeclarativeRectangleMapItem *item); +std::vector featurePaingPropertiesFromMapCircle(QDeclarativeCircleMapItem *item); +std::vector featurePaintPropertiesFromMapPolygon(QDeclarativePolygonMapItem *item); +std::vector featurePaintPropertiesFromMapPolyline(QDeclarativePolylineMapItem *item); +std::vector featurePaintPropertiesFromMapItem(QDeclarativeGeoMapItemBase *item); +std::vector featurePropertiesFromMapItem(QDeclarativeGeoMapItemBase *item); + +} // namespace QMapLibre::StyleChangeUtils diff --git a/third_party/maplibre-native-qt/include/texture_node.hpp b/third_party/maplibre-native-qt/include/texture_node.hpp new file mode 100644 index 0000000000..96f63b3534 --- /dev/null +++ b/third_party/maplibre-native-qt/include/texture_node.hpp @@ -0,0 +1,42 @@ +// Copyright (C) 2023 MapLibre contributors +// Copyright (C) 2017 The Qt Company Ltd. +// Copyright (C) 2017 Mapbox, Inc. + +// SPDX-License-Identifier: LGPL-3.0-only OR GPL-2.0-only OR GPL-3.0-only + +#pragma once + +#include +#include +#include +#if QT_VERSION >= QT_VERSION_CHECK(6, 0, 0) +#include +#else +#include +#endif + +#include + +namespace QMapLibre { + +class QGeoMapMapLibre; + +class TextureNode : public QSGSimpleTextureNode { +public: + TextureNode(const Settings &setting, const QSize &size, qreal pixelRatio, QGeoMapMapLibre *geoMap); + + [[nodiscard]] Map *map() const; + +#if QT_VERSION >= QT_VERSION_CHECK(6, 0, 0) + void resize(const QSize &size, qreal pixelRatio, QQuickWindow *window); +#else + void resize(const QSize &size, qreal pixelRatio); +#endif + void render(QQuickWindow *); + +private: + std::unique_ptr m_map{}; + std::unique_ptr m_fbo{}; +}; + +} // namespace QMapLibre diff --git a/third_party/maplibre-native-qt/include/types.hpp b/third_party/maplibre-native-qt/include/types.hpp new file mode 100644 index 0000000000..696fab1a88 --- /dev/null +++ b/third_party/maplibre-native-qt/include/types.hpp @@ -0,0 +1,206 @@ +// Copyright (C) 2023 MapLibre contributors +// Copyright (C) 2019 Mapbox, Inc. + +// SPDX-License-Identifier: BSD-2-Clause + +#ifndef QMAPLIBRE_TYPES_H +#define QMAPLIBRE_TYPES_H + +#include + +#include +#include +#include +#include +#include +#include + +namespace QMapLibre { + +using Coordinate = QPair; +using CoordinateZoom = QPair; +using ProjectedMeters = QPair; + +using Coordinates = QVector; +using CoordinatesCollection = QVector; + +using CoordinatesCollections = QVector; + +struct Q_MAPLIBRE_CORE_EXPORT Style { + enum Type { // Taken from Qt to be in sync with QtLocation + NoMap = 0, + StreetMap, + SatelliteMapDay, + SatelliteMapNight, + TerrainMap, + HybridMap, + TransitMap, + GrayStreetMap, + PedestrianMap, + CarNavigationMap, + CycleMap, + CustomMap = 100 + }; + +#if QT_VERSION >= QT_VERSION_CHECK(5, 15, 0) + explicit Style(QString url_, QString name_ = QString()) + : url(std::move(url_)), + name(std::move(name_)) {} +#else + explicit Style(QString url_ = QString(), QString name_ = QString()) + : url(std::move(url_)), + name(std::move(name_)) {} +#endif + + QString url; + QString name; + QString description; + bool night{}; + Type type{CustomMap}; +}; + +using Styles = QVector