git-subtree-dir: libraries/extensions/ros2-bridge git-subtree-mainline:tags/v0.2.5-alpha.28e7688a593git-subtree-split:c08bb14406
| @@ -0,0 +1,66 @@ | |||
| name: CI | |||
| on: | |||
| push: | |||
| pull_request: | |||
| env: | |||
| CARGO_TERM_COLOR: always | |||
| RUST_LOG: trace | |||
| jobs: | |||
| build_and_examples: | |||
| strategy: | |||
| matrix: | |||
| platform: [ubuntu-latest] | |||
| fail-fast: false | |||
| runs-on: ${{ matrix.platform }} | |||
| env: | |||
| QT_QPA_PLATFORM: offscreen | |||
| steps: | |||
| - uses: actions/checkout@v3 | |||
| - uses: r7kamura/rust-problem-matchers@v1.1.0 | |||
| - run: cargo --version --verbose | |||
| - uses: Swatinem/rust-cache@v2 | |||
| - name: Build | |||
| run: cargo build --verbose | |||
| - name: Run tests | |||
| run: cargo test --verbose | |||
| - uses: ros-tooling/setup-ros@v0.6 | |||
| with: | |||
| required-ros-distributions: humble | |||
| - run: 'source /opt/ros/humble/setup.bash && echo AMENT_PREFIX_PATH=${AMENT_PREFIX_PATH} >> "$GITHUB_ENV"' | |||
| - name: "Build examples" | |||
| timeout-minutes: 30 | |||
| run: cargo build --examples | |||
| - name: "Rust standalone" | |||
| timeout-minutes: 30 | |||
| run: | | |||
| source /opt/ros/humble/setup.bash && ros2 run turtlesim turtlesim_node & | |||
| cargo run --example random_turtle --features="ros2-examples" | |||
| - name: "Rust Dataflow example" | |||
| timeout-minutes: 30 | |||
| run: | | |||
| source /opt/ros/humble/setup.bash && ros2 run turtlesim turtlesim_node & | |||
| cargo build -p rust-ros2-dataflow-example-node --features ros2 | |||
| cargo run --example rust-ros2-dataflow --features="ros2-examples" | |||
| - name: "Python Dataflow example" | |||
| timeout-minutes: 30 | |||
| run: | | |||
| source /opt/ros/humble/setup.bash && ros2 run turtlesim turtlesim_node & | |||
| pip3 install -r ./examples/python-ros2-dataflow/requirements.txt | |||
| maturin build -m python/Cargo.toml | |||
| pip install target/wheels/*.whl | |||
| cargo run --example python-ros2-dataflow --features="ros2-examples" | |||
| - name: "Python Standalone" | |||
| timeout-minutes: 30 | |||
| run: | | |||
| source /opt/ros/humble/setup.bash && ros2 run turtlesim turtlesim_node & | |||
| python3 -m venv examples/.env && | |||
| source examples/.env/bin/activate && | |||
| python3 examples/python-standalone-bridge/random_turtle.py | |||
| @@ -0,0 +1,146 @@ | |||
| # This file has been originally generated by maturin v0.14.17 | |||
| # To update, you can check | |||
| # | |||
| # maturin generate-ci github --zig | |||
| # | |||
| # But note that some manual modification has been done. | |||
| # Check the diffs to make sure that you haven't broken anything. | |||
| name: pip-release | |||
| on: | |||
| release: | |||
| types: | |||
| - "published" | |||
| permissions: | |||
| contents: write | |||
| jobs: | |||
| linux: | |||
| runs-on: ubuntu-latest | |||
| strategy: | |||
| matrix: | |||
| target: [x86_64, x86, aarch64] | |||
| steps: | |||
| - uses: actions/checkout@v3 | |||
| - uses: actions/setup-python@v4 | |||
| with: | |||
| python-version: "3.7" | |||
| - name: Install dependencies | |||
| run: | | |||
| pip install patchelf --upgrade | |||
| - name: Build wheels | |||
| uses: PyO3/maturin-action@v1 | |||
| with: | |||
| target: ${{ matrix.target }} | |||
| args: --release --out dist --zig | |||
| sccache: "true" | |||
| manylinux: auto | |||
| working-directory: python | |||
| - name: Upload wheels | |||
| uses: actions/upload-artifact@v3 | |||
| with: | |||
| name: wheels | |||
| path: python/dist | |||
| - name: Upload to release | |||
| uses: svenstaro/upload-release-action@v2 | |||
| with: | |||
| repo_token: ${{ secrets.GITHUB_TOKEN }} | |||
| file: python/dist/* | |||
| tag: ${{ github.ref }} | |||
| file_glob: true | |||
| windows: | |||
| runs-on: windows-latest | |||
| strategy: | |||
| matrix: | |||
| target: [x64, x86] | |||
| steps: | |||
| - uses: actions/checkout@v3 | |||
| - uses: actions/setup-python@v4 | |||
| with: | |||
| python-version: "3.7" | |||
| architecture: ${{ matrix.target }} | |||
| - name: Build wheels | |||
| uses: PyO3/maturin-action@v1 | |||
| with: | |||
| target: ${{ matrix.target }} | |||
| args: --release --out dist | |||
| sccache: "true" | |||
| working-directory: python | |||
| - name: Upload wheels | |||
| uses: actions/upload-artifact@v3 | |||
| with: | |||
| name: wheels | |||
| path: python/dist | |||
| - name: Upload to release | |||
| uses: svenstaro/upload-release-action@v2 | |||
| with: | |||
| repo_token: ${{ secrets.GITHUB_TOKEN }} | |||
| file: python/dist/* | |||
| tag: ${{ github.ref }} | |||
| file_glob: true | |||
| macos: | |||
| runs-on: macos-latest | |||
| strategy: | |||
| matrix: | |||
| target: [x86_64, aarch64] | |||
| steps: | |||
| - uses: actions/checkout@v3 | |||
| - uses: actions/setup-python@v4 | |||
| with: | |||
| python-version: "3.7" | |||
| - name: Build wheels | |||
| uses: PyO3/maturin-action@v1 | |||
| with: | |||
| target: ${{ matrix.target }} | |||
| args: --release --out dist | |||
| sccache: "true" | |||
| working-directory: python | |||
| - name: Upload wheels | |||
| uses: actions/upload-artifact@v3 | |||
| with: | |||
| name: wheels | |||
| path: python/dist | |||
| - name: Upload to release | |||
| uses: svenstaro/upload-release-action@v2 | |||
| with: | |||
| repo_token: ${{ secrets.GITHUB_TOKEN }} | |||
| file: python/dist/* | |||
| tag: ${{ github.ref }} | |||
| file_glob: true | |||
| sdist: | |||
| runs-on: ubuntu-latest | |||
| steps: | |||
| - uses: actions/checkout@v3 | |||
| - name: Build sdist | |||
| uses: PyO3/maturin-action@v1 | |||
| with: | |||
| command: sdist | |||
| args: --out dist | |||
| working-directory: python | |||
| - name: Upload sdist | |||
| uses: actions/upload-artifact@v3 | |||
| with: | |||
| name: wheels | |||
| path: python/dist | |||
| release: | |||
| name: Release | |||
| runs-on: ubuntu-latest | |||
| if: "startsWith(github.ref, 'refs/tags/')" | |||
| needs: [linux, windows, macos, sdist] | |||
| steps: | |||
| - uses: actions/download-artifact@v3 | |||
| with: | |||
| name: wheels | |||
| - name: Publish to PyPI | |||
| uses: PyO3/maturin-action@v1 | |||
| env: | |||
| MATURIN_PYPI_TOKEN: ${{ secrets.PYPI_PASS }} | |||
| with: | |||
| command: upload | |||
| args: --skip-existing * | |||
| @@ -0,0 +1 @@ | |||
| /target | |||
| @@ -0,0 +1,63 @@ | |||
| [workspace] | |||
| members = [ | |||
| "msg-gen", | |||
| "msg-gen-macro", | |||
| "python", | |||
| "examples/rust-ros2-dataflow/*", | |||
| ] | |||
| [package] | |||
| name = "dora-ros2-bridge" | |||
| version = "0.1.0" | |||
| edition = "2021" | |||
| # See more keys and their definitions at https://doc.rust-lang.org/cargo/reference/manifest.html | |||
| [workspace.package] | |||
| # Make sure to also bump `apis/node/python/__init__.py` version. | |||
| version = "0.1.0" | |||
| description = "`dora` goal is to be a low latency, composable, and distributed data flow." | |||
| documentation = "https://dora.carsmos.ai" | |||
| license = "Apache-2.0" | |||
| [workspace.dependencies] | |||
| dora-ros2-bridge = { path = "." } | |||
| [features] | |||
| default = ["generate-messages"] | |||
| generate-messages = ["dep:dora-ros2-bridge-msg-gen-macro"] | |||
| # enables examples that depend on a sourced ROS2 installation | |||
| ros2-examples = ["eyre", "tokio", "dora-daemon"] | |||
| [dependencies] | |||
| array-init = "2.1.0" | |||
| dora-ros2-bridge-msg-gen-macro = { path = "msg-gen-macro", optional = true } | |||
| serde = { version = "1.0.164", features = ["derive"] } | |||
| serde-big-array = "0.5.1" | |||
| widestring = "1.0.2" | |||
| ros2-client = { git = "https://github.com/dora-rs/ros2-client.git", branch = "deserialize-seed" } | |||
| rustdds = { git = "https://github.com/dora-rs/RustDDS.git", branch = "deserialize-seed" } | |||
| eyre = { version = "0.6.8", optional = true } | |||
| tokio = { version = "1.29.1", features = ["full"], optional = true } | |||
| dora-daemon = { git = "https://github.com/dora-rs/dora.git", optional = true } | |||
| tracing = "0.1.37" | |||
| tracing-subscriber = "0.3.17" | |||
| [dev-dependencies] | |||
| rand = "0.8.5" | |||
| futures = { version = "0.3.28", default-features = false } | |||
| [[example]] | |||
| name = "random_turtle" | |||
| path = "examples/rust-standalone-bridge/random_turtle.rs" | |||
| required-features = ["ros2-examples"] | |||
| [[example]] | |||
| name = "rust-ros2-dataflow" | |||
| path = "examples/rust-ros2-dataflow/run.rs" | |||
| required-features = ["ros2-examples"] | |||
| [[example]] | |||
| name = "python-ros2-dataflow" | |||
| path = "examples/python-ros2-dataflow/run.rs" | |||
| required-features = ["ros2-examples"] | |||
| @@ -0,0 +1,201 @@ | |||
| Apache License | |||
| Version 2.0, January 2004 | |||
| http://www.apache.org/licenses/ | |||
| TERMS AND CONDITIONS FOR USE, REPRODUCTION, AND DISTRIBUTION | |||
| 1. Definitions. | |||
| "License" shall mean the terms and conditions for use, reproduction, | |||
| and distribution as defined by Sections 1 through 9 of this document. | |||
| "Licensor" shall mean the copyright owner or entity authorized by | |||
| the copyright owner that is granting the License. | |||
| "Legal Entity" shall mean the union of the acting entity and all | |||
| other entities that control, are controlled by, or are under common | |||
| control with that entity. For the purposes of this definition, | |||
| "control" means (i) the power, direct or indirect, to cause the | |||
| direction or management of such entity, whether by contract or | |||
| otherwise, or (ii) ownership of fifty percent (50%) or more of the | |||
| outstanding shares, or (iii) beneficial ownership of such entity. | |||
| "You" (or "Your") shall mean an individual or Legal Entity | |||
| exercising permissions granted by this License. | |||
| "Source" form shall mean the preferred form for making modifications, | |||
| including but not limited to software source code, documentation | |||
| source, and configuration files. | |||
| "Object" form shall mean any form resulting from mechanical | |||
| transformation or translation of a Source form, including but | |||
| not limited to compiled object code, generated documentation, | |||
| and conversions to other media types. | |||
| "Work" shall mean the work of authorship, whether in Source or | |||
| Object form, made available under the License, as indicated by a | |||
| copyright notice that is included in or attached to the work | |||
| (an example is provided in the Appendix below). | |||
| "Derivative Works" shall mean any work, whether in Source or Object | |||
| form, that is based on (or derived from) the Work and for which the | |||
| editorial revisions, annotations, elaborations, or other modifications | |||
| represent, as a whole, an original work of authorship. For the purposes | |||
| of this License, Derivative Works shall not include works that remain | |||
| separable from, or merely link (or bind by name) to the interfaces of, | |||
| the Work and Derivative Works thereof. | |||
| "Contribution" shall mean any work of authorship, including | |||
| the original version of the Work and any modifications or additions | |||
| to that Work or Derivative Works thereof, that is intentionally | |||
| submitted to Licensor for inclusion in the Work by the copyright owner | |||
| or by an individual or Legal Entity authorized to submit on behalf of | |||
| the copyright owner. For the purposes of this definition, "submitted" | |||
| means any form of electronic, verbal, or written communication sent | |||
| to the Licensor or its representatives, including but not limited to | |||
| communication on electronic mailing lists, source code control systems, | |||
| and issue tracking systems that are managed by, or on behalf of, the | |||
| Licensor for the purpose of discussing and improving the Work, but | |||
| excluding communication that is conspicuously marked or otherwise | |||
| designated in writing by the copyright owner as "Not a Contribution." | |||
| "Contributor" shall mean Licensor and any individual or Legal Entity | |||
| on behalf of whom a Contribution has been received by Licensor and | |||
| subsequently incorporated within the Work. | |||
| 2. Grant of Copyright License. Subject to the terms and conditions of | |||
| this License, each Contributor hereby grants to You a perpetual, | |||
| worldwide, non-exclusive, no-charge, royalty-free, irrevocable | |||
| copyright license to reproduce, prepare Derivative Works of, | |||
| publicly display, publicly perform, sublicense, and distribute the | |||
| Work and such Derivative Works in Source or Object form. | |||
| 3. Grant of Patent License. Subject to the terms and conditions of | |||
| this License, each Contributor hereby grants to You a perpetual, | |||
| worldwide, non-exclusive, no-charge, royalty-free, irrevocable | |||
| (except as stated in this section) patent license to make, have made, | |||
| use, offer to sell, sell, import, and otherwise transfer the Work, | |||
| where such license applies only to those patent claims licensable | |||
| by such Contributor that are necessarily infringed by their | |||
| Contribution(s) alone or by combination of their Contribution(s) | |||
| with the Work to which such Contribution(s) was submitted. If You | |||
| institute patent litigation against any entity (including a | |||
| cross-claim or counterclaim in a lawsuit) alleging that the Work | |||
| or a Contribution incorporated within the Work constitutes direct | |||
| or contributory patent infringement, then any patent licenses | |||
| granted to You under this License for that Work shall terminate | |||
| as of the date such litigation is filed. | |||
| 4. Redistribution. You may reproduce and distribute copies of the | |||
| Work or Derivative Works thereof in any medium, with or without | |||
| modifications, and in Source or Object form, provided that You | |||
| meet the following conditions: | |||
| (a) You must give any other recipients of the Work or | |||
| Derivative Works a copy of this License; and | |||
| (b) You must cause any modified files to carry prominent notices | |||
| stating that You changed the files; and | |||
| (c) You must retain, in the Source form of any Derivative Works | |||
| that You distribute, all copyright, patent, trademark, and | |||
| attribution notices from the Source form of the Work, | |||
| excluding those notices that do not pertain to any part of | |||
| the Derivative Works; and | |||
| (d) If the Work includes a "NOTICE" text file as part of its | |||
| distribution, then any Derivative Works that You distribute must | |||
| include a readable copy of the attribution notices contained | |||
| within such NOTICE file, excluding those notices that do not | |||
| pertain to any part of the Derivative Works, in at least one | |||
| of the following places: within a NOTICE text file distributed | |||
| as part of the Derivative Works; within the Source form or | |||
| documentation, if provided along with the Derivative Works; or, | |||
| within a display generated by the Derivative Works, if and | |||
| wherever such third-party notices normally appear. The contents | |||
| of the NOTICE file are for informational purposes only and | |||
| do not modify the License. You may add Your own attribution | |||
| notices within Derivative Works that You distribute, alongside | |||
| or as an addendum to the NOTICE text from the Work, provided | |||
| that such additional attribution notices cannot be construed | |||
| as modifying the License. | |||
| You may add Your own copyright statement to Your modifications and | |||
| may provide additional or different license terms and conditions | |||
| for use, reproduction, or distribution of Your modifications, or | |||
| for any such Derivative Works as a whole, provided Your use, | |||
| reproduction, and distribution of the Work otherwise complies with | |||
| the conditions stated in this License. | |||
| 5. Submission of Contributions. Unless You explicitly state otherwise, | |||
| any Contribution intentionally submitted for inclusion in the Work | |||
| by You to the Licensor shall be under the terms and conditions of | |||
| this License, without any additional terms or conditions. | |||
| Notwithstanding the above, nothing herein shall supersede or modify | |||
| the terms of any separate license agreement you may have executed | |||
| with Licensor regarding such Contributions. | |||
| 6. Trademarks. This License does not grant permission to use the trade | |||
| names, trademarks, service marks, or product names of the Licensor, | |||
| except as required for reasonable and customary use in describing the | |||
| origin of the Work and reproducing the content of the NOTICE file. | |||
| 7. Disclaimer of Warranty. Unless required by applicable law or | |||
| agreed to in writing, Licensor provides the Work (and each | |||
| Contributor provides its Contributions) on an "AS IS" BASIS, | |||
| WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or | |||
| implied, including, without limitation, any warranties or conditions | |||
| of TITLE, NON-INFRINGEMENT, MERCHANTABILITY, or FITNESS FOR A | |||
| PARTICULAR PURPOSE. You are solely responsible for determining the | |||
| appropriateness of using or redistributing the Work and assume any | |||
| risks associated with Your exercise of permissions under this License. | |||
| 8. Limitation of Liability. In no event and under no legal theory, | |||
| whether in tort (including negligence), contract, or otherwise, | |||
| unless required by applicable law (such as deliberate and grossly | |||
| negligent acts) or agreed to in writing, shall any Contributor be | |||
| liable to You for damages, including any direct, indirect, special, | |||
| incidental, or consequential damages of any character arising as a | |||
| result of this License or out of the use or inability to use the | |||
| Work (including but not limited to damages for loss of goodwill, | |||
| work stoppage, computer failure or malfunction, or any and all | |||
| other commercial damages or losses), even if such Contributor | |||
| has been advised of the possibility of such damages. | |||
| 9. Accepting Warranty or Additional Liability. While redistributing | |||
| the Work or Derivative Works thereof, You may choose to offer, | |||
| and charge a fee for, acceptance of support, warranty, indemnity, | |||
| or other liability obligations and/or rights consistent with this | |||
| License. However, in accepting such obligations, You may act only | |||
| on Your own behalf and on Your sole responsibility, not on behalf | |||
| of any other Contributor, and only if You agree to indemnify, | |||
| defend, and hold each Contributor harmless for any liability | |||
| incurred by, or claims asserted against, such Contributor by reason | |||
| of your accepting any such warranty or additional liability. | |||
| END OF TERMS AND CONDITIONS | |||
| APPENDIX: How to apply the Apache License to your work. | |||
| To apply the Apache License to your work, attach the following | |||
| boilerplate notice, with the fields enclosed by brackets "[]" | |||
| replaced with your own identifying information. (Don't include | |||
| the brackets!) The text should be enclosed in the appropriate | |||
| comment syntax for the file format. We also recommend that a | |||
| file or class name and description of purpose be included on the | |||
| same "printed page" as the copyright notice for easier | |||
| identification within third-party archives. | |||
| Copyright [yyyy] [name of copyright owner] | |||
| Licensed under the Apache License, Version 2.0 (the "License"); | |||
| you may not use this file except in compliance with the License. | |||
| You may obtain a copy of the License at | |||
| http://www.apache.org/licenses/LICENSE-2.0 | |||
| Unless required by applicable law or agreed to in writing, software | |||
| distributed under the License is distributed on an "AS IS" BASIS, | |||
| WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. | |||
| See the License for the specific language governing permissions and | |||
| limitations under the License. | |||
| @@ -0,0 +1 @@ | |||
| # Dora ROS2 Bridge | |||
| @@ -0,0 +1 @@ | |||
| .env | |||
| @@ -0,0 +1,27 @@ | |||
| #!/usr/bin/env python | |||
| # -*- coding: utf-8 -*- | |||
| import random | |||
| from dora_ros2_bridge import Node | |||
| import pyarrow as pa | |||
| node = Node() | |||
| for i in range(500): | |||
| event = node.next() | |||
| if event is None: | |||
| break | |||
| if event["type"] == "INPUT": | |||
| print( | |||
| f"""Node received: | |||
| id: {event["id"]}, | |||
| value: {event["data"]}, | |||
| metadata: {event["metadata"]}""" | |||
| ) | |||
| node.send_output( | |||
| "direction", | |||
| pa.array( | |||
| [1, 0, 0, 0, 0, 1], | |||
| type=pa.uint8(), | |||
| ), | |||
| ) | |||
| @@ -0,0 +1,17 @@ | |||
| nodes: | |||
| - id: turtle | |||
| custom: | |||
| source: ./random_turtle.py | |||
| inputs: | |||
| direction: control/direction | |||
| tick: dora/timer/millis/50 | |||
| outputs: | |||
| - turtle_pose | |||
| - id: control | |||
| custom: | |||
| source: ./control_node.py | |||
| inputs: | |||
| turtle_pose: turtle/turtle_pose | |||
| outputs: | |||
| - direction | |||
| @@ -0,0 +1,67 @@ | |||
| #!/usr/bin/env python | |||
| # -*- coding: utf-8 -*- | |||
| import time, random | |||
| from dora_ros2_bridge import * | |||
| import pyarrow as pa | |||
| context = Ros2Context() | |||
| node = context.new_node("turtle_teleop", "/ros2_demo", Ros2NodeOptions(rosout=True)) | |||
| topic_qos = Ros2QosPolicies(reliable=True, max_blocking_time=0.1) | |||
| turtle_twist_topic = node.create_topic( | |||
| "/turtle1/cmd_vel", "geometry_msgs::Twist", topic_qos | |||
| ) | |||
| twist_writer = node.create_publisher(turtle_twist_topic) | |||
| turtle_pose_topic = node.create_topic("/turtle1/pose", "turtlesim::Pose", topic_qos) | |||
| pose_reader = node.create_subscription_stream(turtle_pose_topic) | |||
| dora_node = Node() | |||
| dora_node.merge_external_events(pose_reader) | |||
| print("looping", flush=True) | |||
| for i in range(500): | |||
| event = dora_node.next() | |||
| if event is None: | |||
| break | |||
| match event["kind"]: | |||
| case "dora": | |||
| match event["type"]: | |||
| case "INPUT": | |||
| match event["id"]: | |||
| case "direction": | |||
| direction = { | |||
| "linear": { | |||
| "x": event["data"][0], | |||
| }, | |||
| "angular": { | |||
| "z": event["data"][5], | |||
| }, | |||
| } | |||
| print(direction, flush=True) | |||
| twist_writer.publish(pa.array(direction)) | |||
| case "tick": | |||
| pass | |||
| case "external": | |||
| pose = event.inner()[0].as_py() | |||
| assert ( | |||
| pose["x"] != 5.544445 | |||
| ), "turtle should not be at initial x axis" | |||
| dora_node.send_output( | |||
| "turtle_pose", | |||
| pa.array( | |||
| [ | |||
| pose["x"], | |||
| pose["y"], | |||
| pose["theta"], | |||
| pose["linear_velocity"], | |||
| pose["angular_velocity"], | |||
| ], | |||
| type=pa.float64(), | |||
| ), | |||
| ) | |||
| @@ -0,0 +1,2 @@ | |||
| pyarrow | |||
| maturin | |||
| @@ -0,0 +1,70 @@ | |||
| use eyre::{ContextCompat, WrapErr}; | |||
| use std::path::Path; | |||
| use tracing_subscriber::{ | |||
| filter::{FilterExt, LevelFilter}, | |||
| prelude::*, | |||
| EnvFilter, Registry, | |||
| }; | |||
| #[tokio::main] | |||
| async fn main() -> eyre::Result<()> { | |||
| set_up_tracing()?; | |||
| let root = Path::new(env!("CARGO_MANIFEST_DIR")); | |||
| std::env::set_current_dir(root.join(file!()).parent().unwrap()) | |||
| .wrap_err("failed to set working dir")?; | |||
| run(&["python3", "-m", "venv", "../.env"], None).await?; | |||
| let venv = &root.join("examples").join(".env"); | |||
| std::env::set_var( | |||
| "VIRTUAL_ENV", | |||
| venv.to_str() | |||
| .context("venv path not valid unicode")? | |||
| .to_owned(), | |||
| ); | |||
| let orig_path = std::env::var("PATH")?; | |||
| let venv_bin = venv.join("bin"); | |||
| std::env::set_var( | |||
| "PATH", | |||
| format!( | |||
| "{}:{orig_path}", | |||
| venv_bin.to_str().context("venv path not valid unicode")? | |||
| ), | |||
| ); | |||
| run(&["pip", "install", "--upgrade", "pip"], None).await?; | |||
| run(&["pip", "install", "-r", "requirements.txt"], None).await?; | |||
| run(&["maturin", "develop"], Some(&root.join("python"))).await?; | |||
| let dataflow = Path::new("dataflow.yml"); | |||
| dora_daemon::Daemon::run_dataflow(dataflow).await?; | |||
| Ok(()) | |||
| } | |||
| async fn run(cmd: &[&str], pwd: Option<&Path>) -> eyre::Result<()> { | |||
| let mut run = tokio::process::Command::new(cmd[0]); | |||
| run.args(&cmd[1..]); | |||
| if let Some(pwd) = pwd { | |||
| run.current_dir(pwd); | |||
| } | |||
| if !run.status().await?.success() { | |||
| eyre::bail!("failed to run {cmd:?}"); | |||
| }; | |||
| Ok(()) | |||
| } | |||
| pub fn set_up_tracing() -> eyre::Result<()> { | |||
| // Filter log using `RUST_LOG`. More useful for CLI. | |||
| let filter = EnvFilter::from_default_env().or(LevelFilter::DEBUG); | |||
| let stdout_log = tracing_subscriber::fmt::layer() | |||
| .pretty() | |||
| .with_filter(filter); | |||
| let registry = Registry::default().with(stdout_log); | |||
| tracing::subscriber::set_global_default(registry) | |||
| .context("failed to set tracing global subscriber") | |||
| } | |||
| @@ -0,0 +1,33 @@ | |||
| from dora_ros2_bridge import * | |||
| import time, random | |||
| import pyarrow as pa | |||
| context = Ros2Context() | |||
| node = context.new_node("turtle_teleop", "/ros2_demo", Ros2NodeOptions(rosout=True)) | |||
| topic_qos = Ros2QosPolicies(reliable=True, max_blocking_time=0.1) | |||
| turtle_twist_topic = node.create_topic( | |||
| "/turtle1/cmd_vel", "geometry_msgs::Twist", topic_qos | |||
| ) | |||
| twist_writer = node.create_publisher(turtle_twist_topic) | |||
| turtle_pose_topic = node.create_topic("/turtle1/pose", "turtlesim::Pose", topic_qos) | |||
| pose_reader = node.create_subscription(turtle_pose_topic) | |||
| for i in range(500): | |||
| direction = { | |||
| "linear": { | |||
| "x": random.random() + 1, | |||
| }, | |||
| "angular": { | |||
| "z": (random.random() - 0.5) * 5, | |||
| }, | |||
| } | |||
| twist_writer.publish(pa.array([direction])) | |||
| while True: | |||
| pose = pose_reader.next() | |||
| if pose == None: | |||
| break | |||
| print(f"pose: {pose.to_pylist()}") | |||
| time.sleep(0.5) | |||
| @@ -0,0 +1,21 @@ | |||
| # `rust-ros2-dataflow` Example | |||
| This example shows how to publish/subscribe to both ROS2 and Dora. The dataflow consists of a single node that sends random movement commands to the [ROS2 `turtlesim_node`](https://docs.ros.org/en/iron/Tutorials/Beginner-CLI-Tools/Introducing-Turtlesim/Introducing-Turtlesim.html). | |||
| ## Setup | |||
| This examples requires a sourced ROS2 installation. | |||
| - To set up ROS2, follow the [ROS2 installation](https://docs.ros.org/en/iron/Installation.html) guide. | |||
| - Don't forget to [source the ROS2 setup files](https://docs.ros.org/en/iron/Tutorials/Beginner-CLI-Tools/Configuring-ROS2-Environment.html#source-the-setup-files) | |||
| - Follow tasks 1 and 2 of the [ROS2 turtlesim tutorial](https://docs.ros.org/en/iron/Tutorials/Beginner-CLI-Tools/Introducing-Turtlesim/Introducing-Turtlesim.html#id3) | |||
| - Install the turtlesim package | |||
| - Start the turtlesim node through `ros2 run turtlesim turtlesim_node` | |||
| ## Running | |||
| After sourcing the ROS2 installation and starting the `turtlesim` node, you can run this example to move the turtle in random directions: | |||
| ``` | |||
| cargo run --example rust-ros2-dataflow --features ros2-examples | |||
| ``` | |||
| @@ -0,0 +1,8 @@ | |||
| nodes: | |||
| - id: rust-node | |||
| custom: | |||
| source: ../../target/debug/rust-ros2-dataflow-example-node | |||
| inputs: | |||
| tick: dora/timer/millis/500 | |||
| outputs: | |||
| - pose | |||
| @@ -0,0 +1,25 @@ | |||
| [package] | |||
| name = "rust-ros2-dataflow-example-node" | |||
| version.workspace = true | |||
| edition = "2021" | |||
| # See more keys and their definitions at https://doc.rust-lang.org/cargo/reference/manifest.html | |||
| [features] | |||
| # enables binaries that depend on a sourced ROS2 installation | |||
| ros2 = [] | |||
| [[bin]] | |||
| name = "rust-ros2-dataflow-example-node" | |||
| required-features = ["ros2"] | |||
| [dependencies] | |||
| dora-node-api = { git = "https://github.com/dora-rs/dora.git", features = [ | |||
| "tracing", | |||
| ] } | |||
| eyre = "0.6.8" | |||
| futures = "0.3.21" | |||
| rand = "0.8.5" | |||
| tokio = { version = "1.24.2", features = ["rt", "macros"] } | |||
| dora-ros2-bridge = { workspace = true } | |||
| serde_json = "1.0.99" | |||
| @@ -0,0 +1,134 @@ | |||
| use dora_node_api::{ | |||
| self, | |||
| dora_core::config::DataId, | |||
| merged::{MergeExternal, MergedEvent}, | |||
| DoraNode, Event, | |||
| }; | |||
| use dora_ros2_bridge::{ | |||
| geometry_msgs::msg::{Twist, Vector3}, | |||
| ros2_client::{self, ros2, NodeOptions}, | |||
| rustdds::{self, policy}, | |||
| turtlesim::msg::Pose, | |||
| }; | |||
| use eyre::Context; | |||
| fn main() -> eyre::Result<()> { | |||
| let mut ros_node = init_ros_node()?; | |||
| let turtle_vel_publisher = create_vel_publisher(&mut ros_node)?; | |||
| let turtle_pose_reader = create_pose_reader(&mut ros_node)?; | |||
| let output = DataId::from("pose".to_owned()); | |||
| let (mut node, dora_events) = DoraNode::init_from_env()?; | |||
| let merged = dora_events.merge_external(Box::pin(turtle_pose_reader.async_stream())); | |||
| let mut events = futures::executor::block_on_stream(merged); | |||
| for i in 0..500 { | |||
| let event = match events.next() { | |||
| Some(input) => input, | |||
| None => break, | |||
| }; | |||
| match event { | |||
| MergedEvent::Dora(event) => match event { | |||
| Event::Input { | |||
| id, | |||
| metadata: _, | |||
| data: _, | |||
| } => match id.as_str() { | |||
| "tick" => { | |||
| let direction = Twist { | |||
| linear: Vector3 { | |||
| x: rand::random::<f64>() + 1.0, | |||
| ..Default::default() | |||
| }, | |||
| angular: Vector3 { | |||
| z: (rand::random::<f64>() - 0.5) * 5.0, | |||
| ..Default::default() | |||
| }, | |||
| }; | |||
| println!("tick {i}, sending {direction:?}"); | |||
| turtle_vel_publisher.publish(direction).unwrap(); | |||
| } | |||
| other => eprintln!("Ignoring unexpected input `{other}`"), | |||
| }, | |||
| Event::Stop => println!("Received manual stop"), | |||
| other => eprintln!("Received unexpected input: {other:?}"), | |||
| }, | |||
| MergedEvent::External(pose) => { | |||
| println!("received pose event: {pose:?}"); | |||
| if let Ok((pose, _)) = pose { | |||
| let serialized = serde_json::to_string(&pose)?; | |||
| node.send_output_bytes( | |||
| output.clone(), | |||
| Default::default(), | |||
| serialized.len(), | |||
| serialized.as_bytes(), | |||
| )?; | |||
| } | |||
| } | |||
| } | |||
| } | |||
| Ok(()) | |||
| } | |||
| fn init_ros_node() -> eyre::Result<ros2_client::Node> { | |||
| let ros_context = ros2_client::Context::new().unwrap(); | |||
| ros_context | |||
| .new_node( | |||
| "turtle_teleop", // name | |||
| "/ros2_demo", // namespace | |||
| NodeOptions::new().enable_rosout(true), | |||
| ) | |||
| .context("failed to create ros2 node") | |||
| } | |||
| fn create_vel_publisher( | |||
| ros_node: &mut ros2_client::Node, | |||
| ) -> eyre::Result<ros2_client::Publisher<Twist>> { | |||
| let topic_qos: rustdds::QosPolicies = { | |||
| rustdds::QosPolicyBuilder::new() | |||
| .durability(policy::Durability::Volatile) | |||
| .liveliness(policy::Liveliness::Automatic { | |||
| lease_duration: ros2::Duration::DURATION_INFINITE, | |||
| }) | |||
| .reliability(policy::Reliability::Reliable { | |||
| max_blocking_time: ros2::Duration::from_millis(100), | |||
| }) | |||
| .history(policy::History::KeepLast { depth: 1 }) | |||
| .build() | |||
| }; | |||
| let turtle_cmd_vel_topic = ros_node | |||
| .create_topic( | |||
| "/turtle1/cmd_vel", | |||
| String::from("geometry_msgs::msg::dds_::Twist_"), | |||
| &topic_qos, | |||
| ) | |||
| .context("failed to create topic")?; | |||
| // The point here is to publish Twist for the turtle | |||
| let turtle_cmd_vel_writer = ros_node | |||
| .create_publisher::<Twist>(&turtle_cmd_vel_topic, None) | |||
| .context("failed to create publisher")?; | |||
| Ok(turtle_cmd_vel_writer) | |||
| } | |||
| fn create_pose_reader( | |||
| ros_node: &mut ros2_client::Node, | |||
| ) -> eyre::Result<ros2_client::Subscription<Pose>> { | |||
| let turtle_pose_topic = ros_node | |||
| .create_topic( | |||
| "/turtle1/pose", | |||
| String::from("turtlesim::msg::dds_::Pose_"), | |||
| &Default::default(), | |||
| ) | |||
| .context("failed to create topic")?; | |||
| let turtle_pose_reader = ros_node | |||
| .create_subscription::<Pose>(&turtle_pose_topic, None) | |||
| .context("failed to create subscription")?; | |||
| Ok(turtle_pose_reader) | |||
| } | |||
| @@ -0,0 +1,50 @@ | |||
| use eyre::WrapErr; | |||
| use std::path::Path; | |||
| use tracing_subscriber::{ | |||
| filter::{FilterExt, LevelFilter}, | |||
| prelude::*, | |||
| EnvFilter, Registry, | |||
| }; | |||
| #[tokio::main] | |||
| async fn main() -> eyre::Result<()> { | |||
| set_up_tracing()?; | |||
| let root = Path::new(env!("CARGO_MANIFEST_DIR")); | |||
| std::env::set_current_dir(root.join(file!()).parent().unwrap()) | |||
| .wrap_err("failed to set working dir")?; | |||
| build_package("rust-ros2-dataflow-example-node") | |||
| .await | |||
| .wrap_err("failed to build rust-ros2-dataflow-example-node")?; | |||
| let dataflow = Path::new("dataflow.yml"); | |||
| dora_daemon::Daemon::run_dataflow(dataflow).await?; | |||
| Ok(()) | |||
| } | |||
| async fn build_package(name: &str) -> eyre::Result<()> { | |||
| let cargo = std::env::var("CARGO").unwrap(); | |||
| let mut cmd = tokio::process::Command::new(&cargo); | |||
| cmd.arg("build"); | |||
| cmd.arg("--package").arg(name); | |||
| cmd.arg("--features").arg("ros2"); | |||
| if !cmd.status().await?.success() { | |||
| eyre::bail!("failed to build dataflow"); | |||
| }; | |||
| Ok(()) | |||
| } | |||
| pub fn set_up_tracing() -> eyre::Result<()> { | |||
| // Filter log using `RUST_LOG`. More useful for CLI. | |||
| let filter = EnvFilter::from_default_env().or(LevelFilter::DEBUG); | |||
| let stdout_log = tracing_subscriber::fmt::layer() | |||
| .pretty() | |||
| .with_filter(filter); | |||
| let registry = Registry::default().with(stdout_log); | |||
| tracing::subscriber::set_global_default(registry) | |||
| .context("failed to set tracing global subscriber") | |||
| } | |||
| @@ -0,0 +1,104 @@ | |||
| //! Instructions: | |||
| //! | |||
| //! - Source the ROS2 setup files (e.g. `source /opt/ros/iron/setup.bash`) | |||
| //! - Run `ros2 run turtlesim turtlesim_node` | |||
| //! - Open a second terminal and source the ROS2 setup files again. | |||
| //! - Run this example to move the turtle in random directions: `cargo run --example random_turtle` | |||
| use std::time::Duration; | |||
| use dora_ros2_bridge::{ | |||
| self, | |||
| geometry_msgs::msg::{Twist, Vector3}, | |||
| ros2_client::{self, ros2, NodeOptions}, | |||
| rustdds::{self, policy}, | |||
| turtlesim::srv::SetPen_Request, | |||
| }; | |||
| use futures::FutureExt; | |||
| fn main() { | |||
| let ros_context = ros2_client::Context::new().unwrap(); | |||
| let mut ros_node = ros_context | |||
| .new_node( | |||
| "turtle_teleop", // name | |||
| "/ros2_demo", // namespace | |||
| NodeOptions::new().enable_rosout(true), | |||
| ) | |||
| .unwrap(); | |||
| let topic_qos: rustdds::QosPolicies = { | |||
| rustdds::QosPolicyBuilder::new() | |||
| .durability(policy::Durability::Volatile) | |||
| .liveliness(policy::Liveliness::Automatic { | |||
| lease_duration: ros2::Duration::DURATION_INFINITE, | |||
| }) | |||
| .reliability(policy::Reliability::Reliable { | |||
| max_blocking_time: ros2::Duration::from_millis(100), | |||
| }) | |||
| .history(policy::History::KeepLast { depth: 1 }) | |||
| .build() | |||
| }; | |||
| let turtle_cmd_vel_topic = ros_node | |||
| .create_topic( | |||
| "/turtle1/cmd_vel", | |||
| String::from("geometry_msgs::msg::dds_::Twist_"), | |||
| &topic_qos, | |||
| ) | |||
| .unwrap(); | |||
| // The point here is to publish Twist for the turtle | |||
| let turtle_cmd_vel_writer = ros_node | |||
| .create_publisher::<Twist>(&turtle_cmd_vel_topic, None) | |||
| .unwrap(); | |||
| let turtle_pose_topic = ros_node | |||
| .create_topic( | |||
| "/turtle1/pose", | |||
| String::from("turtlesim::msg::dds_::Pose_"), | |||
| &Default::default(), | |||
| ) | |||
| .unwrap(); | |||
| let turtle_pose_reader = ros_node | |||
| .create_subscription::<dora_ros2_bridge::turtlesim::msg::Pose>(&turtle_pose_topic, None) | |||
| .unwrap(); | |||
| for _ in 0..100 { | |||
| let direction = Twist { | |||
| linear: Vector3 { | |||
| x: rand::random::<f64>() + 1.0, | |||
| ..Default::default() | |||
| }, | |||
| angular: Vector3 { | |||
| z: (rand::random::<f64>() - 0.5) * 5.0, | |||
| ..Default::default() | |||
| }, | |||
| }; | |||
| println!("sending {direction:?}"); | |||
| turtle_cmd_vel_writer.publish(direction).unwrap(); | |||
| std::thread::sleep(Duration::from_millis(500)); | |||
| while let Some(Ok((pose, _info))) = turtle_pose_reader.async_take().now_or_never() { | |||
| println!("{pose:?}"); | |||
| } | |||
| } | |||
| } | |||
| #[derive(Debug)] | |||
| pub enum RosCommand { | |||
| StopEventLoop, | |||
| TurtleCmdVel { | |||
| turtle_id: i32, | |||
| twist: Twist, | |||
| }, | |||
| Reset, | |||
| SetPen(SetPen_Request), | |||
| Spawn(String), | |||
| Kill(String), | |||
| RotateAbsolute { | |||
| heading: f32, | |||
| }, | |||
| #[allow(non_camel_case_types)] | |||
| RotateAbsolute_Cancel, | |||
| } | |||
| @@ -0,0 +1,22 @@ | |||
| [package] | |||
| name = "dora-ros2-bridge-msg-gen-macro" | |||
| version = "0.1.0" | |||
| edition = "2021" | |||
| authors = ["Yuma Hiramatsu <yuma.hiramatsu@gmail.com>"] | |||
| license = "Apache-2.0" | |||
| workspace = ".." | |||
| [dependencies] | |||
| anyhow = "1.0" | |||
| heck = "0.3" | |||
| nom = "7" | |||
| proc-macro2 = "1.0" | |||
| quote = "1.0" | |||
| regex = "1" | |||
| syn = "1.0" | |||
| thiserror = "1.0" | |||
| dora-ros2-bridge-msg-gen = { path = "../msg-gen" } | |||
| [lib] | |||
| proc-macro = true | |||
| @@ -0,0 +1,25 @@ | |||
| use std::path::Path; | |||
| fn main() { | |||
| let ament_prefix_path = match std::env::var("AMENT_PREFIX_PATH") { | |||
| Ok(path) => path, | |||
| Err(std::env::VarError::NotPresent) => { | |||
| println!("cargo:warning='AMENT_PREFIX_PATH not set'"); | |||
| String::new() | |||
| } | |||
| Err(std::env::VarError::NotUnicode(s)) => { | |||
| panic!( | |||
| "AMENT_PREFIX_PATH is not valid unicode: `{}`", | |||
| s.to_string_lossy() | |||
| ); | |||
| } | |||
| }; | |||
| println!("cargo:rerun-if-env-changed=AMENT_PREFIX_PATH"); | |||
| let paths = ament_prefix_path.split(':').map(Path::new); | |||
| for path in paths { | |||
| println!("cargo:rerun-if-changed={}", path.display()); | |||
| } | |||
| println!("cargo:rustc-env=DETECTED_AMENT_PREFIX_PATH={ament_prefix_path}"); | |||
| } | |||
| @@ -0,0 +1,43 @@ | |||
| // Based on https://github.com/rclrust/rclrust/tree/3a48dbb8f23a3d67d3031351da3ed236a354f039/rclrust-msg-gen | |||
| #![warn( | |||
| rust_2018_idioms, | |||
| elided_lifetimes_in_paths, | |||
| clippy::all, | |||
| clippy::nursery | |||
| )] | |||
| use std::path::Path; | |||
| use dora_ros2_bridge_msg_gen::get_packages; | |||
| use proc_macro::TokenStream; | |||
| use quote::quote; | |||
| #[proc_macro] | |||
| pub fn msg_include_all(_input: TokenStream) -> TokenStream { | |||
| let ament_prefix_path = std::env!("DETECTED_AMENT_PREFIX_PATH").trim(); | |||
| if ament_prefix_path.is_empty() { | |||
| quote! { | |||
| /// **No messages are available because the `AMENT_PREFIX_PATH` environment variable | |||
| /// was not set during build.** | |||
| pub const AMENT_PREFIX_PATH_NOT_SET: () = (); | |||
| } | |||
| .into() | |||
| } else { | |||
| let paths = ament_prefix_path | |||
| .split(':') | |||
| .map(Path::new) | |||
| .collect::<Vec<_>>(); | |||
| let packages = get_packages(&paths) | |||
| .unwrap() | |||
| .iter() | |||
| .map(|v| v.token_stream()) | |||
| .collect::<Vec<_>>(); | |||
| (quote! { | |||
| #(#packages)* | |||
| }) | |||
| .into() | |||
| } | |||
| } | |||
| @@ -0,0 +1,8 @@ | |||
| #goal definition | |||
| int32 order | |||
| --- | |||
| #result definition | |||
| int32[] sequence | |||
| --- | |||
| #feedback | |||
| int32[] sequence | |||
| @@ -0,0 +1,34 @@ | |||
| # Arrays of different types | |||
| bool[3] bool_values | |||
| byte[3] byte_values | |||
| char[3] char_values | |||
| float32[3] float32_values | |||
| float64[3] float64_values | |||
| int8[3] int8_values | |||
| uint8[3] uint8_values | |||
| int16[3] int16_values | |||
| uint16[3] uint16_values | |||
| int32[3] int32_values | |||
| uint32[3] uint32_values | |||
| int64[3] int64_values | |||
| uint64[3] uint64_values | |||
| string[3] string_values | |||
| BasicTypes[3] basic_types_values | |||
| Constants[3] constants_values | |||
| Defaults[3] defaults_values | |||
| bool[3] bool_values_default [false, true, false] | |||
| byte[3] byte_values_default [0, 1, 255] | |||
| char[3] char_values_default [0, 1, 127] | |||
| float32[3] float32_values_default [1.125, 0.0, -1.125] | |||
| float64[3] float64_values_default [3.1415, 0.0, -3.1415] | |||
| int8[3] int8_values_default [0, 127, -128] | |||
| uint8[3] uint8_values_default [0, 1, 255] | |||
| int16[3] int16_values_default [0, 32767, -32768] | |||
| uint16[3] uint16_values_default [0, 1, 65535] | |||
| int32[3] int32_values_default [0, 2147483647, -2147483648] | |||
| uint32[3] uint32_values_default [0, 1, 4294967295] | |||
| int64[3] int64_values_default [0, 9223372036854775807, -9223372036854775808] | |||
| uint64[3] uint64_values_default [0, 1, 18446744073709551615] | |||
| string[3] string_values_default ["", "max value", "min value"] | |||
| # Regression test: check alignment of basic field after an array field is correct | |||
| int32 alignment_check | |||
| @@ -0,0 +1,13 @@ | |||
| bool bool_value | |||
| byte byte_value | |||
| char char_value | |||
| float32 float32_value | |||
| float64 float64_value | |||
| int8 int8_value | |||
| uint8 uint8_value | |||
| int16 int16_value | |||
| uint16 uint16_value | |||
| int32 int32_value | |||
| uint32 uint32_value | |||
| int64 int64_value | |||
| uint64 uint64_value | |||
| @@ -0,0 +1,34 @@ | |||
| # Bounded sequences of different types | |||
| bool[<=3] bool_values | |||
| byte[<=3] byte_values | |||
| char[<=3] char_values | |||
| float32[<=3] float32_values | |||
| float64[<=3] float64_values | |||
| int8[<=3] int8_values | |||
| uint8[<=3] uint8_values | |||
| int16[<=3] int16_values | |||
| uint16[<=3] uint16_values | |||
| int32[<=3] int32_values | |||
| uint32[<=3] uint32_values | |||
| int64[<=3] int64_values | |||
| uint64[<=3] uint64_values | |||
| string[<=3] string_values | |||
| BasicTypes[<=3] basic_types_values | |||
| Constants[<=3] constants_values | |||
| Defaults[<=3] defaults_values | |||
| bool[<=3] bool_values_default [false, true, false] | |||
| byte[<=3] byte_values_default [0, 1, 255] | |||
| char[<=3] char_values_default [0, 1, 127] | |||
| float32[<=3] float32_values_default [1.125, 0.0, -1.125] | |||
| float64[<=3] float64_values_default [3.1415, 0.0, -3.1415] | |||
| int8[<=3] int8_values_default [0, 127, -128] | |||
| uint8[<=3] uint8_values_default [0, 1, 255] | |||
| int16[<=3] int16_values_default [0, 32767, -32768] | |||
| uint16[<=3] uint16_values_default [0, 1, 65535] | |||
| int32[<=3] int32_values_default [0, 2147483647, -2147483648] | |||
| uint32[<=3] uint32_values_default [0, 1, 4294967295] | |||
| int64[<=3] int64_values_default [0, 9223372036854775807, -9223372036854775808] | |||
| uint64[<=3] uint64_values_default [0, 1, 18446744073709551615] | |||
| string[<=3] string_values_default ["", "max value", "min value"] | |||
| # Regression test: check alignment of basic field after a sequence field is correct | |||
| int32 alignment_check | |||
| @@ -0,0 +1,13 @@ | |||
| bool BOOL_CONST=true | |||
| byte BYTE_CONST=50 | |||
| char CHAR_CONST=100 | |||
| float32 FLOAT32_CONST=1.125 | |||
| float64 FLOAT64_CONST=1.125 | |||
| int8 INT8_CONST=-50 | |||
| uint8 UINT8_CONST=200 | |||
| int16 INT16_CONST=-1000 | |||
| uint16 UINT16_CONST=2000 | |||
| int32 INT32_CONST=-30000 | |||
| uint32 UINT32_CONST=60000 | |||
| int64 INT64_CONST=-40000000 | |||
| uint64 UINT64_CONST=50000000 | |||
| @@ -0,0 +1,13 @@ | |||
| bool bool_value true | |||
| byte byte_value 50 | |||
| char char_value 100 | |||
| float32 float32_value 1.125 | |||
| float64 float64_value 1.125 | |||
| int8 int8_value -50 | |||
| uint8 uint8_value 200 | |||
| int16 int16_value -1000 | |||
| uint16 uint16_value 2000 | |||
| int32 int32_value -30000 | |||
| uint32 uint32_value 60000 | |||
| int64 int64_value -40000000 | |||
| uint64 uint64_value 50000000 | |||
| @@ -0,0 +1,10 @@ | |||
| # Mulitple levels of nested messages | |||
| Arrays[3] array_of_arrays | |||
| BoundedSequences[3] array_of_bounded_sequences | |||
| UnboundedSequences[3] array_of_unbounded_sequences | |||
| Arrays[<=3] bounded_sequence_of_arrays | |||
| BoundedSequences[<=3] bounded_sequence_of_bounded_sequences | |||
| UnboundedSequences[<=3] bounded_sequence_of_unbounded_sequences | |||
| Arrays[] unbounded_sequence_of_arrays | |||
| BoundedSequences[] unbounded_sequence_of_bounded_sequences | |||
| UnboundedSequences[] unbounded_sequence_of_unbounded_sequences | |||
| @@ -0,0 +1 @@ | |||
| BasicTypes basic_types_value | |||
| @@ -0,0 +1,13 @@ | |||
| string string_value | |||
| string string_value_default1 "Hello world!" | |||
| string string_value_default2 "Hello'world!" | |||
| string string_value_default3 'Hello"world!' | |||
| string string_value_default4 'Hello\'world!' | |||
| string string_value_default5 "Hello\"world!" | |||
| string STRING_CONST="Hello world!" | |||
| string<=22 bounded_string_value | |||
| string<=22 bounded_string_value_default1 "Hello world!" | |||
| string<=22 bounded_string_value_default2 "Hello'world!" | |||
| string<=22 bounded_string_value_default3 'Hello"world!' | |||
| string<=22 bounded_string_value_default4 'Hello\'world!' | |||
| string<=22 bounded_string_value_default5 "Hello\"world!" | |||
| @@ -0,0 +1,34 @@ | |||
| # Unbounded sequences of different types | |||
| bool[] bool_values | |||
| byte[] byte_values | |||
| char[] char_values | |||
| float32[] float32_values | |||
| float64[] float64_values | |||
| int8[] int8_values | |||
| uint8[] uint8_values | |||
| int16[] int16_values | |||
| uint16[] uint16_values | |||
| int32[] int32_values | |||
| uint32[] uint32_values | |||
| int64[] int64_values | |||
| uint64[] uint64_values | |||
| string[] string_values | |||
| BasicTypes[] basic_types_values | |||
| Constants[] constants_values | |||
| Defaults[] defaults_values | |||
| bool[] bool_values_default [false, true, false] | |||
| byte[] byte_values_default [0, 1, 255] | |||
| char[] char_values_default [0, 1, 127] | |||
| float32[] float32_values_default [1.125, 0.0, -1.125] | |||
| float64[] float64_values_default [3.1415, 0.0, -3.1415] | |||
| int8[] int8_values_default [0, 127, -128] | |||
| uint8[] uint8_values_default [0, 1, 255] | |||
| int16[] int16_values_default [0, 32767, -32768] | |||
| uint16[] uint16_values_default [0, 1, 65535] | |||
| int32[] int32_values_default [0, 2147483647, -2147483648] | |||
| uint32[] uint32_values_default [0, 1, 4294967295] | |||
| int64[] int64_values_default [0, 9223372036854775807, -9223372036854775808] | |||
| uint64[] uint64_values_default [0, 1, 18446744073709551615] | |||
| string[] string_values_default ["", "max value", "min value"] | |||
| # Regression test: check alignment of basic field after a sequence field is correct | |||
| int32 alignment_check | |||
| @@ -0,0 +1,10 @@ | |||
| wstring wstring_value | |||
| wstring wstring_value_default1 "Hello world!" | |||
| wstring wstring_value_default2 "Hellö wörld!" | |||
| wstring wstring_value_default3 "ハローワールド" | |||
| #wstring WSTRING_CONST="Hello world!" | |||
| #wstring<=22 bounded_wstring_value | |||
| #wstring<=22 bounded_wstring_value_default1 "Hello world!" | |||
| wstring[3] array_of_wstrings | |||
| wstring[<=3] bounded_sequence_of_wstrings | |||
| wstring[] unbounded_sequence_of_wstrings | |||
| @@ -0,0 +1,63 @@ | |||
| bool[3] bool_values | |||
| byte[3] byte_values | |||
| char[3] char_values | |||
| float32[3] float32_values | |||
| float64[3] float64_values | |||
| int8[3] int8_values | |||
| uint8[3] uint8_values | |||
| int16[3] int16_values | |||
| uint16[3] uint16_values | |||
| int32[3] int32_values | |||
| uint32[3] uint32_values | |||
| int64[3] int64_values | |||
| uint64[3] uint64_values | |||
| string[3] string_values | |||
| BasicTypes[3] basic_types_values | |||
| Constants[3] constants_values | |||
| Defaults[3] defaults_values | |||
| bool[3] bool_values_default [false, true, false] | |||
| byte[3] byte_values_default [0, 1, 255] | |||
| char[3] char_values_default [0, 1, 127] | |||
| float32[3] float32_values_default [1.125, 0.0, -1.125] | |||
| float64[3] float64_values_default [3.1415, 0.0, -3.1415] | |||
| int8[3] int8_values_default [0, 127, -128] | |||
| uint8[3] uint8_values_default [0, 1, 255] | |||
| int16[3] int16_values_default [0, 32767, -32768] | |||
| uint16[3] uint16_values_default [0, 1, 65535] | |||
| int32[3] int32_values_default [0, 2147483647, -2147483648] | |||
| uint32[3] uint32_values_default [0, 1, 4294967295] | |||
| int64[3] int64_values_default [0, 9223372036854775807, -9223372036854775808] | |||
| uint64[3] uint64_values_default [0, 1, 18446744073709551615] | |||
| string[3] string_values_default ["", "max value", "min value"] | |||
| --- | |||
| bool[3] bool_values | |||
| byte[3] byte_values | |||
| char[3] char_values | |||
| float32[3] float32_values | |||
| float64[3] float64_values | |||
| int8[3] int8_values | |||
| uint8[3] uint8_values | |||
| int16[3] int16_values | |||
| uint16[3] uint16_values | |||
| int32[3] int32_values | |||
| uint32[3] uint32_values | |||
| int64[3] int64_values | |||
| uint64[3] uint64_values | |||
| string[3] string_values | |||
| BasicTypes[3] basic_types_values | |||
| Constants[3] constants_values | |||
| Defaults[3] defaults_values | |||
| bool[3] bool_values_default [false, true, false] | |||
| byte[3] byte_values_default [0, 1, 255] | |||
| char[3] char_values_default [0, 1, 127] | |||
| float32[3] float32_values_default [1.125, 0.0, -1.125] | |||
| float64[3] float64_values_default [3.1415, 0.0, -3.1415] | |||
| int8[3] int8_values_default [0, 127, -128] | |||
| uint8[3] uint8_values_default [0, 1, 255] | |||
| int16[3] int16_values_default [0, 32767, -32768] | |||
| uint16[3] uint16_values_default [0, 1, 65535] | |||
| int32[3] int32_values_default [0, 2147483647, -2147483648] | |||
| uint32[3] uint32_values_default [0, 1, 4294967295] | |||
| int64[3] int64_values_default [0, 9223372036854775807, -9223372036854775808] | |||
| uint64[3] uint64_values_default [0, 1, 18446744073709551615] | |||
| string[3] string_values_default ["", "max value", "min value"] | |||
| @@ -0,0 +1,29 @@ | |||
| bool bool_value | |||
| byte byte_value | |||
| char char_value | |||
| float32 float32_value | |||
| float64 float64_value | |||
| int8 int8_value | |||
| uint8 uint8_value | |||
| int16 int16_value | |||
| uint16 uint16_value | |||
| int32 int32_value | |||
| uint32 uint32_value | |||
| int64 int64_value | |||
| uint64 uint64_value | |||
| string string_value | |||
| --- | |||
| bool bool_value | |||
| byte byte_value | |||
| char char_value | |||
| float32 float32_value | |||
| float64 float64_value | |||
| int8 int8_value | |||
| uint8 uint8_value | |||
| int16 int16_value | |||
| uint16 uint16_value | |||
| int32 int32_value | |||
| uint32 uint32_value | |||
| int64 int64_value | |||
| uint64 uint64_value | |||
| string string_value | |||
| @@ -0,0 +1 @@ | |||
| --- | |||
| @@ -0,0 +1,18 @@ | |||
| [package] | |||
| name = "dora-ros2-bridge-msg-gen" | |||
| version = "0.1.0" | |||
| edition = "2021" | |||
| authors = ["Yuma Hiramatsu <yuma.hiramatsu@gmail.com>"] | |||
| license = "Apache-2.0" | |||
| workspace = ".." | |||
| [dependencies] | |||
| anyhow = "1.0" | |||
| heck = "0.3" | |||
| nom = "7" | |||
| proc-macro2 = "1.0" | |||
| quote = "1.0" | |||
| regex = "1" | |||
| syn = "1.0" | |||
| thiserror = "1.0" | |||
| @@ -0,0 +1,25 @@ | |||
| use std::path::Path; | |||
| fn main() { | |||
| let ament_prefix_path = match std::env::var("AMENT_PREFIX_PATH") { | |||
| Ok(path) => path, | |||
| Err(std::env::VarError::NotPresent) => { | |||
| println!("cargo:warning='AMENT_PREFIX_PATH not set'"); | |||
| String::new() | |||
| } | |||
| Err(std::env::VarError::NotUnicode(s)) => { | |||
| panic!( | |||
| "AMENT_PREFIX_PATH is not valid unicode: `{}`", | |||
| s.to_string_lossy() | |||
| ); | |||
| } | |||
| }; | |||
| println!("cargo:rerun-if-env-changed=AMENT_PREFIX_PATH"); | |||
| let paths = ament_prefix_path.split(':').map(Path::new); | |||
| for path in paths { | |||
| println!("cargo:rerun-if-changed={}", path.display()); | |||
| } | |||
| println!("cargo:rustc-env=DETECTED_AMENT_PREFIX_PATH={ament_prefix_path}"); | |||
| } | |||
| @@ -0,0 +1,13 @@ | |||
| // Based on https://github.com/rclrust/rclrust/tree/3a48dbb8f23a3d67d3031351da3ed236a354f039/rclrust-msg-gen | |||
| #![warn( | |||
| rust_2018_idioms, | |||
| elided_lifetimes_in_paths, | |||
| clippy::all, | |||
| clippy::nursery | |||
| )] | |||
| pub mod parser; | |||
| pub mod types; | |||
| pub use crate::parser::get_packages; | |||
| @@ -0,0 +1,107 @@ | |||
| use std::{fs, path::Path}; | |||
| use anyhow::{Context, Result}; | |||
| use regex::Regex; | |||
| use super::{error::RclMsgError, message::parse_message_string}; | |||
| use crate::types::Action; | |||
| const ACTION_GOAL_SUFFIX: &str = "_Goal"; | |||
| const ACTION_RESULT_SUFFIX: &str = "_Result"; | |||
| const ACTION_FEEDBACK_SUFFIX: &str = "_Feedback"; | |||
| pub fn parse_action_file<P: AsRef<Path>>(pkg_name: &str, interface_file: P) -> Result<Action> { | |||
| parse_action_string( | |||
| pkg_name, | |||
| interface_file | |||
| .as_ref() | |||
| .file_stem() | |||
| .unwrap() | |||
| .to_str() | |||
| .unwrap(), | |||
| fs::read_to_string(interface_file.as_ref())?.as_str(), | |||
| ) | |||
| .with_context(|| format!("Parse file error: {}", interface_file.as_ref().display())) | |||
| } | |||
| fn parse_action_string(pkg_name: &str, action_name: &str, action_string: &str) -> Result<Action> { | |||
| let re = Regex::new(r"(?m)^---$").unwrap(); | |||
| let action_blocks: Vec<_> = re.split(action_string).collect(); | |||
| if action_blocks.len() != 3 { | |||
| return Err(RclMsgError::InvalidActionSpecification( | |||
| "Number of '---' separators nonconformant with action definition".into(), | |||
| ) | |||
| .into()); | |||
| } | |||
| Ok(Action { | |||
| package: pkg_name.into(), | |||
| name: action_name.into(), | |||
| goal: parse_message_string( | |||
| pkg_name, | |||
| &format!("{}{}", action_name, ACTION_GOAL_SUFFIX), | |||
| action_blocks[0], | |||
| )?, | |||
| result: parse_message_string( | |||
| pkg_name, | |||
| &format!("{}{}", action_name, ACTION_RESULT_SUFFIX), | |||
| action_blocks[1], | |||
| )?, | |||
| feedback: parse_message_string( | |||
| pkg_name, | |||
| &format!("{}{}", action_name, ACTION_FEEDBACK_SUFFIX), | |||
| action_blocks[2], | |||
| )?, | |||
| }) | |||
| } | |||
| #[cfg(test)] | |||
| mod test { | |||
| use std::path::PathBuf; | |||
| use super::*; | |||
| use crate::types::{primitives::*, sequences::*, MemberType}; | |||
| fn parse_action_def(srv_name: &str) -> Result<Action> { | |||
| let path = PathBuf::from(env!("CARGO_MANIFEST_DIR")) | |||
| .join(format!("test_msgs/action/{}.action", srv_name)); | |||
| parse_action_file("test_msgs", path) | |||
| } | |||
| #[test] | |||
| fn parse_fibonacci() -> Result<()> { | |||
| let action = parse_action_def("Fibonacci")?; | |||
| assert_eq!(action.package, "test_msgs".to_string()); | |||
| assert_eq!(action.name, "Fibonacci".to_string()); | |||
| assert_eq!(action.goal.name, "Fibonacci_Goal".to_string()); | |||
| assert_eq!(action.goal.members.len(), 1); | |||
| assert_eq!(action.goal.members[0].name, "order".to_string()); | |||
| assert_eq!(action.goal.members[0].r#type, BasicType::I32.into()); | |||
| assert_eq!(action.goal.constants.len(), 0); | |||
| assert_eq!(action.result.name, "Fibonacci_Result".to_string()); | |||
| assert_eq!(action.result.members.len(), 1); | |||
| assert_eq!(action.result.members[0].name, "sequence".to_string()); | |||
| assert_eq!( | |||
| action.result.members[0].r#type, | |||
| MemberType::Sequence(Sequence { | |||
| value_type: NestableType::BasicType(BasicType::I32) | |||
| }) | |||
| ); | |||
| assert_eq!(action.result.constants.len(), 0); | |||
| assert_eq!(action.feedback.name, "Fibonacci_Feedback".to_string()); | |||
| assert_eq!(action.feedback.members.len(), 1); | |||
| assert_eq!(action.feedback.members[0].name, "sequence".to_string()); | |||
| assert_eq!( | |||
| action.feedback.members[0].r#type, | |||
| MemberType::Sequence(Sequence { | |||
| value_type: NestableType::BasicType(BasicType::I32) | |||
| }) | |||
| ); | |||
| assert_eq!(action.feedback.constants.len(), 0); | |||
| Ok(()) | |||
| } | |||
| } | |||
| @@ -0,0 +1,85 @@ | |||
| use anyhow::{ensure, Result}; | |||
| use nom::{ | |||
| bytes::complete::is_not, | |||
| character::complete::{char, space0, space1}, | |||
| combinator::{eof, recognize}, | |||
| multi::separated_list1, | |||
| sequence::tuple, | |||
| }; | |||
| use super::{error::RclMsgError, ident, literal, types}; | |||
| use crate::types::{primitives::PrimitiveType, Constant, ConstantType}; | |||
| fn validate_value(r#type: ConstantType, value: &str) -> Result<Vec<String>> { | |||
| match r#type { | |||
| ConstantType::PrimitiveType(t) => match t { | |||
| PrimitiveType::BasicType(t) => { | |||
| let (rest, value) = literal::get_basic_type_literal_parser(t)(value) | |||
| .map_err(|_| RclMsgError::ParseConstantValueError(value.into()))?; | |||
| ensure!(rest.is_empty()); | |||
| Ok(vec![value]) | |||
| } | |||
| PrimitiveType::GenericUnboundedString(t) => { | |||
| let (rest, default) = literal::get_string_literal_parser(t.into())(value) | |||
| .map_err(|_| RclMsgError::ParseDefaultValueError(value.into()))?; | |||
| ensure!(rest.is_empty()); | |||
| Ok(vec![default]) | |||
| } | |||
| }, | |||
| ConstantType::PrimitiveArray(array_t) => match array_t.value_type { | |||
| PrimitiveType::BasicType(t) => { | |||
| let (rest, values) = literal::basic_type_sequence(t, value) | |||
| .map_err(|_| RclMsgError::ParseDefaultValueError(value.into()))?; | |||
| ensure!(rest.is_empty()); | |||
| ensure!(values.len() == array_t.size); | |||
| Ok(values) | |||
| } | |||
| PrimitiveType::GenericUnboundedString(_) => { | |||
| let (rest, values) = literal::string_literal_sequence(value) | |||
| .map_err(|_| RclMsgError::ParseDefaultValueError(value.into()))?; | |||
| ensure!(rest.is_empty()); | |||
| Ok(values) | |||
| } | |||
| }, | |||
| } | |||
| } | |||
| pub fn constant_def(line: &str) -> Result<Constant> { | |||
| let (_, (r#type, _, name, _, _, _, value, _, _)) = tuple(( | |||
| types::parse_constant_type, | |||
| space1, | |||
| ident::constant_name, | |||
| space0, | |||
| char('='), | |||
| space0, | |||
| recognize(separated_list1(space1, is_not(" \t"))), | |||
| space0, | |||
| eof, | |||
| ))(line) | |||
| .map_err(|e| RclMsgError::ParseConstantError { | |||
| reason: e.to_string(), | |||
| input: line.into(), | |||
| })?; | |||
| Ok(Constant { | |||
| name: name.into(), | |||
| r#type: r#type.clone(), | |||
| value: validate_value(r#type, value)?, | |||
| }) | |||
| } | |||
| #[cfg(test)] | |||
| mod test { | |||
| use super::*; | |||
| use crate::types::primitives::BasicType; | |||
| #[test] | |||
| fn parse_member_def_with_default() -> Result<()> { | |||
| let result = constant_def("int32 AAA=30")?; | |||
| assert_eq!(result.name, "AAA"); | |||
| assert_eq!(result.r#type, BasicType::I32.into()); | |||
| assert_eq!(result.value, vec!["30"]); | |||
| Ok(()) | |||
| } | |||
| } | |||
| @@ -0,0 +1,25 @@ | |||
| use thiserror::Error; | |||
| #[derive(Debug, Error)] | |||
| pub enum RclMsgError { | |||
| #[error("Fail to parse member definition: {reason}\ninput: {input}")] | |||
| ParseMemberError { input: String, reason: String }, | |||
| #[error("{0} can not have default value")] | |||
| InvalidDefaultError(String), | |||
| #[error("Fail to parse default value: {0}")] | |||
| ParseDefaultValueError(String), | |||
| #[error("Fail to parse constant definition: {reason}\ninput: {input}")] | |||
| ParseConstantError { input: String, reason: String }, | |||
| #[error("Fail to parse constant value: {0}")] | |||
| ParseConstantValueError(String), | |||
| #[error("Invalid service specification: {0}")] | |||
| InvalidServiceSpecification(String), | |||
| #[error("Invalid action specification: {0}")] | |||
| InvalidActionSpecification(String), | |||
| } | |||
| @@ -0,0 +1,92 @@ | |||
| use nom::{ | |||
| branch::alt, | |||
| character::complete::{alphanumeric0, char, one_of}, | |||
| combinator::{opt, recognize}, | |||
| multi::{many1, separated_list0, separated_list1}, | |||
| sequence::{pair, tuple}, | |||
| IResult, | |||
| }; | |||
| fn upperalpha(s: &str) -> IResult<&str, char> { | |||
| one_of("ABCDEFGHIJKLMNOPQRSTUVWXYZ")(s) | |||
| } | |||
| fn loweralpha(s: &str) -> IResult<&str, char> { | |||
| one_of("abcdefghijklmnopqrstuvwxyz")(s) | |||
| } | |||
| fn numeric(s: &str) -> IResult<&str, char> { | |||
| one_of("0123456789")(s) | |||
| } | |||
| pub fn package_name(s: &str) -> IResult<&str, &str> { | |||
| recognize(tuple(( | |||
| loweralpha, | |||
| opt(char('_')), | |||
| separated_list1(char('_'), many1(alt((loweralpha, numeric)))), | |||
| )))(s) | |||
| } | |||
| pub fn member_name(s: &str) -> IResult<&str, &str> { | |||
| recognize(tuple(( | |||
| loweralpha, | |||
| opt(char('_')), | |||
| separated_list0(char('_'), many1(alt((loweralpha, numeric)))), | |||
| )))(s) | |||
| } | |||
| pub fn message_name(s: &str) -> IResult<&str, &str> { | |||
| recognize(pair(upperalpha, alphanumeric0))(s) | |||
| } | |||
| pub fn constant_name(s: &str) -> IResult<&str, &str> { | |||
| recognize(separated_list1( | |||
| char('_'), | |||
| many1(alt((upperalpha, numeric))), | |||
| ))(s) | |||
| } | |||
| #[cfg(test)] | |||
| mod test { | |||
| use anyhow::Result; | |||
| use super::*; | |||
| #[test] | |||
| fn parse_member_name() -> Result<()> { | |||
| assert_eq!(member_name("abc034_fs3_u3")?.1, "abc034_fs3_u3"); | |||
| Ok(()) | |||
| } | |||
| #[test] | |||
| fn parse_member_name_should_fail_if_starting_with_underscore() { | |||
| assert!(member_name("_invalid_indentifier").is_err()); | |||
| } | |||
| #[test] | |||
| fn parse_member_name_should_fail_if_starting_with_number() { | |||
| assert!(member_name("0invalid_indentifier").is_err()); | |||
| } | |||
| #[test] | |||
| fn parse_message_name() -> Result<()> { | |||
| assert_eq!(message_name("StdMsgs12")?.1, "StdMsgs12"); | |||
| Ok(()) | |||
| } | |||
| #[test] | |||
| fn parse_message_name_should_fail_if_starting_with_wrong_char() { | |||
| assert!(message_name("aStdMsgs12").is_err()); | |||
| } | |||
| #[test] | |||
| fn parse_constant_name() -> Result<()> { | |||
| assert_eq!(constant_name("C_O_N_STAN_T")?.1, "C_O_N_STAN_T"); | |||
| Ok(()) | |||
| } | |||
| #[test] | |||
| fn parse_constant_name_should_fail_if_starting_with_underscore() { | |||
| assert!(constant_name("_C_O_N_STAN_Ta").is_err()); | |||
| } | |||
| } | |||
| @@ -0,0 +1,294 @@ | |||
| use std::convert::TryFrom; | |||
| use nom::{ | |||
| branch::alt, | |||
| bytes::complete::{is_not, tag, tag_no_case, take_while}, | |||
| character::complete::{anychar, char, digit1, hex_digit1, none_of, oct_digit1, one_of, space0}, | |||
| combinator::{eof, map, map_res, opt, recognize, rest, value, verify}, | |||
| multi::{many0, separated_list1}, | |||
| number::complete::recognize_float, | |||
| sequence::{delimited, pair, tuple}, | |||
| IResult, | |||
| }; | |||
| use crate::types::primitives::{BasicType, GenericString}; | |||
| pub fn usize_literal(s: &str) -> IResult<&str, usize> { | |||
| map_res(dec_literal, usize::try_from)(s) | |||
| } | |||
| fn validate_integer_literal<T>(s: &str) -> IResult<&str, String> | |||
| where | |||
| T: TryFrom<i128> + ToString, | |||
| { | |||
| map_res(integer_literal, |v| T::try_from(v).map(|v| v.to_string()))(s) | |||
| } | |||
| fn validate_floating_point_literal(s: &str) -> IResult<&str, String> { | |||
| map(recognize_float, |v: &str| v.to_string())(s) | |||
| } | |||
| fn validate_boolean_literal(s: &str) -> IResult<&str, String> { | |||
| map(bool_literal, |v| v.to_string())(s) | |||
| } | |||
| pub fn get_basic_type_literal_parser(basic_type: BasicType) -> fn(&str) -> IResult<&str, String> { | |||
| match basic_type { | |||
| BasicType::U8 | BasicType::Char | BasicType::Byte => validate_integer_literal::<u8>, | |||
| BasicType::U16 => validate_integer_literal::<u16>, | |||
| BasicType::U32 => validate_integer_literal::<u32>, | |||
| BasicType::U64 => validate_integer_literal::<u64>, | |||
| BasicType::I8 => validate_integer_literal::<i8>, | |||
| BasicType::I16 => validate_integer_literal::<i16>, | |||
| BasicType::I32 => validate_integer_literal::<i32>, | |||
| BasicType::I64 => validate_integer_literal::<i64>, | |||
| BasicType::F32 | BasicType::F64 => validate_floating_point_literal, | |||
| BasicType::Bool => validate_boolean_literal, | |||
| } | |||
| } | |||
| pub fn basic_type_sequence(basic_type: BasicType, s: &str) -> IResult<&str, Vec<String>> { | |||
| delimited( | |||
| pair(char('['), space0), | |||
| separated_list1( | |||
| char(','), | |||
| delimited(space0, get_basic_type_literal_parser(basic_type), space0), | |||
| ), | |||
| pair(space0, char(']')), | |||
| )(s) | |||
| } | |||
| #[inline] | |||
| fn flag_if_exist(s: &str) -> IResult<&str, char> { | |||
| map(opt(one_of("+-")), |flag| flag.unwrap_or('+'))(s) | |||
| } | |||
| fn dec_literal(s: &str) -> IResult<&str, i128> { | |||
| map_res( | |||
| tuple((flag_if_exist, separated_list1(char('_'), digit1))), | |||
| |(flag, digits)| format!("{}{}", flag, digits.join("")).parse::<i128>(), | |||
| )(s) | |||
| } | |||
| fn integer_literal(s: &str) -> IResult<&str, i128> { | |||
| alt(( | |||
| map_res( | |||
| tuple(( | |||
| flag_if_exist, | |||
| tag_no_case("0b"), | |||
| separated_list1(char('_'), take_while(|c| c == '0' || c == '1')), | |||
| )), | |||
| |(flag, _, digits)| i128::from_str_radix(&format!("{}{}", flag, digits.join("")), 2), | |||
| ), | |||
| map_res( | |||
| tuple(( | |||
| flag_if_exist, | |||
| tag_no_case("0o"), | |||
| separated_list1(char('_'), oct_digit1), | |||
| )), | |||
| |(flag, _, digits)| i128::from_str_radix(&format!("{}{}", flag, digits.join("")), 8), | |||
| ), | |||
| map_res( | |||
| tuple(( | |||
| flag_if_exist, | |||
| tag_no_case("0x"), | |||
| separated_list1(char('_'), hex_digit1), | |||
| )), | |||
| |(flag, _, digits)| i128::from_str_radix(&format!("{}{}", flag, digits.join("")), 16), | |||
| ), | |||
| dec_literal, | |||
| ))(s) | |||
| } | |||
| fn bool_literal(s: &str) -> IResult<&str, bool> { | |||
| alt(( | |||
| value(true, alt((tag("true"), tag("1")))), | |||
| value(false, alt((tag("false"), tag("0")))), | |||
| ))(s) | |||
| } | |||
| pub fn get_string_literal_parser( | |||
| string_type: GenericString, | |||
| ) -> Box<dyn FnMut(&str) -> IResult<&str, String>> { | |||
| match string_type { | |||
| GenericString::String | GenericString::WString => Box::new(string_literal), | |||
| GenericString::BoundedString(max_size) | GenericString::BoundedWString(max_size) => { | |||
| Box::new(move |s| verify(string_literal, |s: &str| s.len() <= max_size)(s)) | |||
| } | |||
| } | |||
| } | |||
| fn string_literal(s: &str) -> IResult<&str, String> { | |||
| alt(( | |||
| delimited( | |||
| char('"'), | |||
| map( | |||
| many0(alt(( | |||
| value(r#"""#, tag(r#"\""#)), | |||
| tag(r#"\"#), | |||
| recognize(is_not(r#"\""#)), | |||
| ))), | |||
| |v| v.join("").trim().to_string(), | |||
| ), | |||
| char('"'), | |||
| ), | |||
| delimited( | |||
| char('\''), | |||
| map( | |||
| many0(alt(( | |||
| value("'", tag(r#"\'"#)), | |||
| tag(r#"\"#), | |||
| recognize(is_not(r#"\'"#)), | |||
| ))), | |||
| |v| v.join("").trim().to_string(), | |||
| ), | |||
| char('\''), | |||
| ), | |||
| value("".to_string(), one_of(r#""'"#)), | |||
| map( | |||
| verify(recognize(many0(anychar)), |v: &str| { | |||
| let v = v.trim(); | |||
| !(v.starts_with('"') && v.ends_with('"') | |||
| || v.starts_with('\'') && v.ends_with('\'')) | |||
| }), | |||
| |v: &str| v.trim().to_string(), | |||
| ), | |||
| ))(s) | |||
| } | |||
| pub fn string_literal_sequence(s: &str) -> IResult<&str, Vec<String>> { | |||
| verify(rest, |v: &str| v.starts_with('[') && v.ends_with(']'))(s)?; | |||
| delimited( | |||
| space0, | |||
| separated_list1( | |||
| char(','), | |||
| delimited( | |||
| space0, | |||
| alt(( | |||
| delimited( | |||
| char('"'), | |||
| map( | |||
| many0(alt(( | |||
| value(r#"""#, tag(r#"\""#)), | |||
| tag(r#"\"#), | |||
| recognize(is_not(r#"\""#)), | |||
| ))), | |||
| |v| v.join("").trim().to_string(), | |||
| ), | |||
| char('"'), | |||
| ), | |||
| delimited( | |||
| char('\''), | |||
| map( | |||
| many0(alt(( | |||
| value("'", tag(r#"\'"#)), | |||
| tag(r#"\"#), | |||
| recognize(is_not(r#"\'"#)), | |||
| ))), | |||
| |v| v.join("").trim().to_string(), | |||
| ), | |||
| char('\''), | |||
| ), | |||
| map( | |||
| recognize(pair(none_of("\"',"), opt(is_not(",")))), | |||
| |s: &str| s.trim().to_string(), | |||
| ), | |||
| )), | |||
| space0, | |||
| ), | |||
| ), | |||
| tuple((opt(char(',')), space0, eof)), | |||
| )(s.strip_prefix('[').unwrap().strip_suffix(']').unwrap()) | |||
| } | |||
| #[cfg(test)] | |||
| mod test { | |||
| use anyhow::Result; | |||
| use super::*; | |||
| #[test] | |||
| fn parse_integer_literal() -> Result<()> { | |||
| assert_eq!(integer_literal("101_010")?.1, 101010); | |||
| Ok(()) | |||
| } | |||
| #[test] | |||
| fn parse_bin_literal() -> Result<()> { | |||
| assert_eq!(integer_literal("0b101_010")?.1, 0b101010); | |||
| assert_eq!(integer_literal("+0b101_010")?.1, 0b101010); | |||
| assert_eq!(integer_literal("-0b101_010")?.1, -0b101010); | |||
| Ok(()) | |||
| } | |||
| #[test] | |||
| fn parse_oct_literal() -> Result<()> { | |||
| assert_eq!(integer_literal("0o12_345_670")?.1, 0o12345670); | |||
| assert_eq!(integer_literal("+0o12_345_670")?.1, 0o12345670); | |||
| assert_eq!(integer_literal("-0o12_345_670")?.1, -0o12345670); | |||
| Ok(()) | |||
| } | |||
| #[test] | |||
| fn parse_dec_literal() -> Result<()> { | |||
| assert_eq!(integer_literal("123_456_789")?.1, 123456789); | |||
| assert_eq!(integer_literal("+123_456_789")?.1, 123456789); | |||
| assert_eq!(integer_literal("-123_456_789")?.1, -123456789); | |||
| Ok(()) | |||
| } | |||
| #[test] | |||
| fn parse_hex_literal() -> Result<()> { | |||
| assert_eq!(integer_literal("0x789_aBc")?.1, 0x789abc); | |||
| assert_eq!(integer_literal("+0x789_aBc")?.1, 0x789abc); | |||
| assert_eq!(integer_literal("-0x789_aBc")?.1, -0x789abc); | |||
| Ok(()) | |||
| } | |||
| #[test] | |||
| fn parse_bool_literal() -> Result<()> { | |||
| assert!(bool_literal("true")?.1); | |||
| assert!(!bool_literal("false")?.1); | |||
| assert!(bool_literal("1")?.1); | |||
| assert!(!bool_literal("0")?.1); | |||
| Ok(()) | |||
| } | |||
| #[test] | |||
| fn parse_integer_sequenc() -> Result<()> { | |||
| assert_eq!( | |||
| basic_type_sequence(BasicType::I8, "[-1, 0x10, 0o10, -0b10]")?.1, | |||
| vec!["-1", "16", "8", "-2"] | |||
| ); | |||
| Ok(()) | |||
| } | |||
| #[test] | |||
| fn parse_string() -> Result<()> { | |||
| assert_eq!(string_literal(r#""aaa\"aaa" "#)?.1, r#"aaa"aaa"#); | |||
| assert_eq!(string_literal(r#"'aaa\'aaa' "#)?.1, "aaa'aaa"); | |||
| Ok(()) | |||
| } | |||
| #[test] | |||
| fn parse_string_sequence() -> Result<()> { | |||
| assert_eq!( | |||
| string_literal_sequence(r#"[aaa, "bbb", 'ccc']"#)?.1, | |||
| vec!["aaa", "bbb", "ccc"] | |||
| ); | |||
| assert_eq!( | |||
| string_literal_sequence(r#"[aaa, "bbb", 'ccc',]"#)?.1, | |||
| vec!["aaa", "bbb", "ccc"] | |||
| ); | |||
| assert_eq!( | |||
| string_literal_sequence(r#"["aaa, \"bbb", 'ccc']"#)?.1, | |||
| vec![r#"aaa, "bbb"#, "ccc"] | |||
| ); | |||
| assert_eq!( | |||
| string_literal_sequence(r#"[ aaa , "bbb" , 'ccc' ]"#)?.1, | |||
| vec!["aaa", "bbb", "ccc"] | |||
| ); | |||
| Ok(()) | |||
| } | |||
| } | |||
| @@ -0,0 +1,133 @@ | |||
| use anyhow::{ensure, Result}; | |||
| use nom::{ | |||
| bytes::complete::is_not, | |||
| character::complete::{space0, space1}, | |||
| combinator::{eof, opt, recognize}, | |||
| multi::separated_list1, | |||
| sequence::{preceded, tuple}, | |||
| }; | |||
| use super::{error::RclMsgError, ident, literal, types}; | |||
| use crate::types::{primitives::NestableType, Member, MemberType}; | |||
| fn nestable_type_default(nestable_type: NestableType, default: &str) -> Result<Vec<String>> { | |||
| match nestable_type { | |||
| NestableType::BasicType(t) => { | |||
| let (rest, default) = literal::get_basic_type_literal_parser(t)(default) | |||
| .map_err(|_| RclMsgError::ParseDefaultValueError(default.into()))?; | |||
| ensure!(rest.is_empty()); | |||
| Ok(vec![default]) | |||
| } | |||
| NestableType::NamedType(t) => { | |||
| Err(RclMsgError::InvalidDefaultError(format!("{}", t)).into()) | |||
| } | |||
| NestableType::NamespacedType(t) => { | |||
| Err(RclMsgError::InvalidDefaultError(format!("{}", t)).into()) | |||
| } | |||
| NestableType::GenericString(t) => { | |||
| let (rest, default) = literal::get_string_literal_parser(t)(default) | |||
| .map_err(|_| RclMsgError::ParseDefaultValueError(default.into()))?; | |||
| ensure!(rest.is_empty()); | |||
| Ok(vec![default]) | |||
| } | |||
| } | |||
| } | |||
| fn array_type_default(value_type: NestableType, default: &str) -> Result<Vec<String>> { | |||
| match value_type { | |||
| NestableType::BasicType(t) => { | |||
| let (rest, default) = literal::basic_type_sequence(t, default) | |||
| .map_err(|_| RclMsgError::ParseDefaultValueError(default.into()))?; | |||
| ensure!(rest.is_empty()); | |||
| Ok(default) | |||
| } | |||
| NestableType::NamedType(t) => { | |||
| Err(RclMsgError::InvalidDefaultError(format!("{}", t)).into()) | |||
| } | |||
| NestableType::NamespacedType(t) => { | |||
| Err(RclMsgError::InvalidDefaultError(format!("{}", t)).into()) | |||
| } | |||
| NestableType::GenericString(_) => { | |||
| let (rest, default) = literal::string_literal_sequence(default) | |||
| .map_err(|_| RclMsgError::ParseDefaultValueError(default.into()))?; | |||
| ensure!(rest.is_empty()); | |||
| Ok(default) | |||
| } | |||
| } | |||
| } | |||
| fn validate_default(r#type: MemberType, default: &str) -> Result<Vec<String>> { | |||
| match r#type { | |||
| MemberType::NestableType(t) => nestable_type_default(t, default), | |||
| MemberType::Array(t) => { | |||
| let default = array_type_default(t.value_type, default)?; | |||
| ensure!(default.len() == t.size); | |||
| Ok(default) | |||
| } | |||
| MemberType::Sequence(t) => array_type_default(t.value_type, default), | |||
| MemberType::BoundedSequence(t) => { | |||
| let default = array_type_default(t.value_type, default)?; | |||
| ensure!(default.len() <= t.max_size); | |||
| Ok(default) | |||
| } | |||
| } | |||
| } | |||
| pub fn member_def(line: &str) -> Result<Member> { | |||
| let (_, (r#type, _, name, default, _, _)) = tuple(( | |||
| types::parse_member_type, | |||
| space1, | |||
| ident::member_name, | |||
| opt(preceded( | |||
| space1, | |||
| recognize(separated_list1(space1, is_not(" \t"))), | |||
| )), | |||
| space0, | |||
| eof, | |||
| ))(line) | |||
| .map_err(|e| RclMsgError::ParseMemberError { | |||
| input: line.into(), | |||
| reason: e.to_string(), | |||
| })?; | |||
| Ok(Member { | |||
| name: name.into(), | |||
| r#type: r#type.clone(), | |||
| default: match default { | |||
| Some(v) => Some(validate_default(r#type, v)?), | |||
| None => None, | |||
| }, | |||
| }) | |||
| } | |||
| #[cfg(test)] | |||
| mod test { | |||
| use anyhow::Result; | |||
| use super::*; | |||
| use crate::types::primitives::BasicType; | |||
| #[test] | |||
| fn parse_member_def() -> Result<()> { | |||
| let result = member_def("int32 aaa")?; | |||
| assert_eq!(result.name, "aaa"); | |||
| assert_eq!(result.r#type, BasicType::I32.into()); | |||
| Ok(()) | |||
| } | |||
| #[test] | |||
| fn parse_member_def_with_default() -> Result<()> { | |||
| let result = member_def("int32 aaa 30")?; | |||
| assert_eq!(result.name, "aaa"); | |||
| assert_eq!(result.r#type, BasicType::I32.into()); | |||
| assert_eq!(result.default, Some(vec!["30".into()])); | |||
| Ok(()) | |||
| } | |||
| #[test] | |||
| fn parse_member_def_with_invalid_default() -> Result<()> { | |||
| assert!(member_def("uint8 aaa -1").is_err()); | |||
| assert!(member_def("uint8 aaa 256").is_err()); | |||
| Ok(()) | |||
| } | |||
| } | |||
| @@ -0,0 +1,160 @@ | |||
| use std::{fs, path::Path}; | |||
| use anyhow::{Context, Result}; | |||
| use super::{constant::constant_def, member::member_def}; | |||
| use crate::types::Message; | |||
| fn split_once(s: &'_ str, pat: char) -> (&'_ str, Option<&'_ str>) { | |||
| let mut items = s.splitn(2, pat); | |||
| (items.next().unwrap(), items.next()) | |||
| } | |||
| pub fn parse_message_file<P: AsRef<Path>>(pkg_name: &str, interface_file: P) -> Result<Message> { | |||
| parse_message_string( | |||
| pkg_name, | |||
| interface_file | |||
| .as_ref() | |||
| .file_stem() | |||
| .unwrap() | |||
| .to_str() | |||
| .unwrap(), | |||
| fs::read_to_string(interface_file.as_ref())?.as_str(), | |||
| ) | |||
| .with_context(|| format!("Parse file error: {}", interface_file.as_ref().display())) | |||
| } | |||
| pub fn parse_message_string( | |||
| pkg_name: &str, | |||
| msg_name: &str, | |||
| message_string: &str, | |||
| ) -> Result<Message> { | |||
| let mut members = vec![]; | |||
| let mut constants = vec![]; | |||
| for line in message_string.lines() { | |||
| let (line, _) = split_once(line, '#'); | |||
| let line = line.trim(); | |||
| if line.is_empty() { | |||
| continue; | |||
| } | |||
| let (_, rest) = split_once(line, ' '); | |||
| match rest.unwrap().find('=') { | |||
| Some(_) => constants.push(constant_def(line)?), | |||
| None => members.push(member_def(line)?), | |||
| } | |||
| } | |||
| Ok(Message { | |||
| package: pkg_name.into(), | |||
| name: msg_name.into(), | |||
| members, | |||
| constants, | |||
| }) | |||
| } | |||
| #[cfg(test)] | |||
| mod test { | |||
| use std::path::PathBuf; | |||
| use super::*; | |||
| use crate::types::{primitives::*, sequences::*, *}; | |||
| #[test] | |||
| fn test_split_once() { | |||
| assert_eq!(split_once("abc", 'b'), ("a", Some("c"))); | |||
| assert_eq!(split_once("abc", 'c'), ("ab", Some(""))); | |||
| assert_eq!(split_once("abc", 'd'), ("abc", None)); | |||
| } | |||
| fn parse_msg_def(msg_name: &str) -> Result<Message> { | |||
| let path = PathBuf::from(env!("CARGO_MANIFEST_DIR")) | |||
| .join(format!("test_msgs/msg/{}.msg", msg_name)); | |||
| parse_message_file("test_msgs", path) | |||
| } | |||
| #[test] | |||
| fn parse_arrays() -> Result<()> { | |||
| let message = parse_msg_def("Arrays")?; | |||
| assert_eq!(message.package, "test_msgs".to_string()); | |||
| assert_eq!(message.name, "Arrays".to_string()); | |||
| assert_eq!(message.members[0].name, "bool_values".to_string()); | |||
| assert_eq!( | |||
| message.members[0].r#type, | |||
| MemberType::Array(Array { | |||
| value_type: BasicType::Bool.into(), | |||
| size: 3, | |||
| }) | |||
| ); | |||
| Ok(()) | |||
| } | |||
| #[test] | |||
| fn parse_basic_types() -> Result<()> { | |||
| let result = parse_msg_def("BasicTypes")?; | |||
| assert_eq!(result.members[0].name, "bool_value".to_string()); | |||
| assert_eq!(result.members[0].r#type, BasicType::Bool.into()); | |||
| assert_eq!(result.members[0].default, None); | |||
| Ok(()) | |||
| } | |||
| #[test] | |||
| fn parse_bounded_sequences() -> Result<()> { | |||
| let _result = parse_msg_def("BoundedSequences")?; | |||
| Ok(()) | |||
| } | |||
| #[test] | |||
| fn parse_constants() -> Result<()> { | |||
| let _result = parse_msg_def("Constants")?; | |||
| Ok(()) | |||
| } | |||
| #[test] | |||
| fn parse_defaults() -> Result<()> { | |||
| let _result = parse_msg_def("Defaults")?; | |||
| Ok(()) | |||
| } | |||
| #[test] | |||
| fn parse_empty() -> Result<()> { | |||
| let _result = parse_msg_def("Empty")?; | |||
| Ok(()) | |||
| } | |||
| #[test] | |||
| fn parse_multi_nested() -> Result<()> { | |||
| let _result = parse_msg_def("MultiNested")?; | |||
| Ok(()) | |||
| } | |||
| #[test] | |||
| fn parse_nested() -> Result<()> { | |||
| let _result = parse_msg_def("Nested")?; | |||
| Ok(()) | |||
| } | |||
| #[test] | |||
| fn parse_strings() -> Result<()> { | |||
| let _result = parse_msg_def("Strings")?; | |||
| Ok(()) | |||
| } | |||
| #[test] | |||
| fn parse_unbounded_sequences() -> Result<()> { | |||
| let _result = parse_msg_def("UnboundedSequences")?; | |||
| Ok(()) | |||
| } | |||
| #[test] | |||
| fn parse_wstrings() -> Result<()> { | |||
| let _result = parse_msg_def("WStrings")?; | |||
| Ok(()) | |||
| } | |||
| } | |||
| @@ -0,0 +1,12 @@ | |||
| pub mod action; | |||
| pub mod constant; | |||
| pub mod error; | |||
| pub mod ident; | |||
| pub mod literal; | |||
| pub mod member; | |||
| pub mod message; | |||
| mod package; | |||
| pub mod service; | |||
| pub mod types; | |||
| pub use package::get_packages; | |||
| @@ -0,0 +1,152 @@ | |||
| use std::{ | |||
| fs::{self, File}, | |||
| io::{BufRead, BufReader}, | |||
| path::Path, | |||
| }; | |||
| use anyhow::Result; | |||
| use super::{action::parse_action_file, message::parse_message_file, service::parse_service_file}; | |||
| use crate::types::Package; | |||
| const ROSIDL_INTERFACES: &str = "share/ament_index/resource_index/rosidl_interfaces"; | |||
| const NAMESPACES: &[&str] = &["msg", "srv", "action"]; | |||
| fn parse_line(line: &str) -> Option<(&str, &str)> { | |||
| if !line.ends_with(".idl") { | |||
| return None; | |||
| } | |||
| for &namespace in NAMESPACES { | |||
| if line.starts_with(&format!("{}/", namespace)) { | |||
| let name = &line[namespace.len() + 1..line.len() - 4]; | |||
| return Some((namespace, name)); | |||
| } | |||
| } | |||
| println!("Unknown type: {:?}", line); | |||
| None | |||
| } | |||
| fn get_ros_msgs_each_package<P: AsRef<Path>>(root_dir: P) -> Result<Vec<Package>> { | |||
| let dir = root_dir.as_ref().join(ROSIDL_INTERFACES); | |||
| let mut packages = Vec::new(); | |||
| let paths = match fs::read_dir(dir) { | |||
| Ok(paths) => paths, | |||
| Err(_) => { | |||
| return Ok(packages); | |||
| } | |||
| }; | |||
| for path in paths { | |||
| let path = path?.path(); | |||
| let file_name = path | |||
| .clone() | |||
| .file_name() | |||
| .unwrap() | |||
| .to_str() | |||
| .unwrap() | |||
| .to_string(); | |||
| // Hack | |||
| if file_name == "libstatistics_collector" { | |||
| continue; | |||
| } | |||
| let mut package = Package::new(file_name.clone()); | |||
| for line in BufReader::new(File::open(path)?).lines() { | |||
| match parse_line(&line?) { | |||
| Some(("msg", v)) => { | |||
| let msg = parse_message_file( | |||
| &file_name, | |||
| root_dir | |||
| .as_ref() | |||
| .join(format!("share/{}/msg/{}.msg", file_name, v)), | |||
| )?; | |||
| package.messages.push(msg); | |||
| } | |||
| Some(("srv", v)) => { | |||
| let srv = parse_service_file( | |||
| &file_name, | |||
| root_dir | |||
| .as_ref() | |||
| .join(format!("share/{}/srv/{}.srv", file_name, v)), | |||
| )?; | |||
| package.services.push(srv); | |||
| } | |||
| Some(("action", v)) => { | |||
| let action = parse_action_file( | |||
| &file_name, | |||
| root_dir | |||
| .as_ref() | |||
| .join(format!("share/{}/action/{}.action", file_name, v)), | |||
| )?; | |||
| package.actions.push(action); | |||
| } | |||
| Some(_) => unreachable!(), | |||
| None => {} | |||
| } | |||
| } | |||
| packages.push(package); | |||
| } | |||
| Ok(packages) | |||
| } | |||
| pub fn get_packages(paths: &[&Path]) -> Result<Vec<Package>> { | |||
| let mut packages = paths | |||
| .iter() | |||
| .map(|&path| get_ros_msgs_each_package(path)) | |||
| .collect::<Result<Vec<_>>>()? | |||
| .into_iter() | |||
| .flatten() | |||
| .filter(|p| !p.is_empty()) | |||
| .collect::<Vec<_>>(); | |||
| packages.sort_by_key(|p| p.name.clone()); | |||
| packages.dedup_by_key(|p| p.name.clone()); | |||
| Ok(packages) | |||
| } | |||
| #[cfg(test)] | |||
| mod tests { | |||
| use super::*; | |||
| #[test] | |||
| fn parse_line_msg() { | |||
| let result = parse_line("msg/TestHoge.idl").unwrap(); | |||
| assert_eq!(result.0, "msg"); | |||
| assert_eq!(result.1, "TestHoge"); | |||
| } | |||
| #[test] | |||
| fn parse_line_srv() { | |||
| let result = parse_line("srv/TestHoge.idl").unwrap(); | |||
| assert_eq!(result.0, "srv"); | |||
| assert_eq!(result.1, "TestHoge"); | |||
| } | |||
| #[test] | |||
| fn parse_line_action() { | |||
| let result = parse_line("action/TestHoge.idl").unwrap(); | |||
| assert_eq!(result.0, "action"); | |||
| assert_eq!(result.1, "TestHoge"); | |||
| } | |||
| #[test] | |||
| fn parse_line_wrong_namespace() { | |||
| assert!(parse_line("test/Test.msg").is_none()); | |||
| assert!(parse_line("test/Test.srv").is_none()); | |||
| assert!(parse_line("test/Test.action").is_none()); | |||
| } | |||
| #[test] | |||
| fn parse_line_wrong_suffix() { | |||
| assert!(parse_line("msg/Test.test").is_none()); | |||
| assert!(parse_line("srv/Test.test").is_none()); | |||
| assert!(parse_line("action/Test.test").is_none()); | |||
| } | |||
| } | |||
| @@ -0,0 +1,86 @@ | |||
| use std::{fs, path::Path}; | |||
| use anyhow::{Context, Result}; | |||
| use regex::Regex; | |||
| use super::{error::RclMsgError, message::parse_message_string}; | |||
| use crate::types::Service; | |||
| const SERVICE_REQUEST_SUFFIX: &str = "_Request"; | |||
| const SERVICE_RESPONSE_SUFFIX: &str = "_Response"; | |||
| pub fn parse_service_file<P: AsRef<Path>>(pkg_name: &str, interface_file: P) -> Result<Service> { | |||
| let interface_file = interface_file.as_ref(); | |||
| let service_string = fs::read_to_string(interface_file)?.replace("\r\n", "\n"); | |||
| parse_service_string( | |||
| pkg_name, | |||
| interface_file.file_stem().unwrap().to_str().unwrap(), | |||
| &service_string, | |||
| ) | |||
| .with_context(|| format!("Parse file error: {}", interface_file.display())) | |||
| } | |||
| fn parse_service_string(pkg_name: &str, srv_name: &str, service_string: &str) -> Result<Service> { | |||
| let re = Regex::new(r"(?m)^---$").unwrap(); | |||
| let service_blocks: Vec<_> = re.split(service_string).collect(); | |||
| if service_blocks.len() != 2 { | |||
| return Err(RclMsgError::InvalidServiceSpecification(format!( | |||
| "Expect one '---' seperator in {}/{} service definition, but get {}", | |||
| pkg_name, | |||
| srv_name, | |||
| service_blocks.len() - 1 | |||
| )) | |||
| .into()); | |||
| } | |||
| Ok(Service { | |||
| package: pkg_name.into(), | |||
| name: srv_name.into(), | |||
| request: parse_message_string( | |||
| pkg_name, | |||
| &format!("{}{}", srv_name, SERVICE_REQUEST_SUFFIX), | |||
| service_blocks[0], | |||
| )?, | |||
| response: parse_message_string( | |||
| pkg_name, | |||
| &format!("{}{}", srv_name, SERVICE_RESPONSE_SUFFIX), | |||
| service_blocks[1], | |||
| )?, | |||
| }) | |||
| } | |||
| #[cfg(test)] | |||
| mod test { | |||
| use std::path::PathBuf; | |||
| use super::*; | |||
| fn parse_srv_def(srv_name: &str) -> Result<Service> { | |||
| let path = PathBuf::from(env!("CARGO_MANIFEST_DIR")) | |||
| .join(format!("test_msgs/srv/{}.srv", srv_name)); | |||
| parse_service_file("test_msgs", path) | |||
| } | |||
| #[test] | |||
| fn parse_arrays() -> Result<()> { | |||
| let result = parse_srv_def("Arrays")?; | |||
| assert_eq!(result.package, "test_msgs".to_string()); | |||
| assert_eq!(result.name, "Arrays".to_string()); | |||
| assert_eq!(result.request.name, "Arrays_Request".to_string()); | |||
| assert_eq!(result.response.name, "Arrays_Response".to_string()); | |||
| Ok(()) | |||
| } | |||
| #[test] | |||
| fn parse_basic_types() -> Result<()> { | |||
| let _result = parse_srv_def("BasicTypes")?; | |||
| Ok(()) | |||
| } | |||
| #[test] | |||
| fn parse_empty() -> Result<()> { | |||
| let _result = parse_srv_def("Empty")?; | |||
| Ok(()) | |||
| } | |||
| } | |||
| @@ -0,0 +1,347 @@ | |||
| use anyhow::anyhow; | |||
| use nom::{ | |||
| branch::alt, | |||
| bytes::complete::tag, | |||
| character::complete::{char, space1}, | |||
| combinator::{eof, map, map_res, opt, peek}, | |||
| sequence::{delimited, pair, preceded, tuple}, | |||
| IResult, | |||
| }; | |||
| use super::{ | |||
| ident::{message_name, package_name}, | |||
| literal::usize_literal, | |||
| }; | |||
| use crate::types::{ | |||
| primitives::*, | |||
| sequences::{Array, BoundedSequence, PrimitiveArray, Sequence}, | |||
| ConstantType, MemberType, | |||
| }; | |||
| pub fn parse_member_type(s: &str) -> IResult<&str, MemberType> { | |||
| map_res( | |||
| tuple(( | |||
| nestable_type, | |||
| opt(delimited( | |||
| char('['), | |||
| pair(opt(tag("<=")), opt(usize_literal)), | |||
| char(']'), | |||
| )), | |||
| peek(alt((space1, eof))), | |||
| )), | |||
| |(value_type, seq_info, _)| { | |||
| Ok(match seq_info { | |||
| None => value_type.into(), | |||
| Some((None, None)) => Sequence { value_type }.into(), | |||
| Some((None, Some(size))) => Array { value_type, size }.into(), | |||
| Some((Some(_), Some(size))) => BoundedSequence { | |||
| value_type, | |||
| max_size: size, | |||
| } | |||
| .into(), | |||
| Some((Some(_), None)) => { | |||
| return Err(anyhow!("max_size should be specified")); | |||
| } | |||
| }) | |||
| }, | |||
| )(s) | |||
| } | |||
| pub fn parse_constant_type(s: &str) -> IResult<&str, ConstantType> { | |||
| map( | |||
| tuple(( | |||
| primitive_type, | |||
| opt(delimited(char('['), usize_literal, char(']'))), | |||
| peek(alt((space1, eof))), | |||
| )), | |||
| |(value_type, size, _)| match size { | |||
| None => value_type.into(), | |||
| Some(size) => PrimitiveArray { value_type, size }.into(), | |||
| }, | |||
| )(s) | |||
| } | |||
| fn basic_type(s: &str) -> IResult<&str, BasicType> { | |||
| map( | |||
| alt(( | |||
| tag("uint8"), | |||
| tag("uint16"), | |||
| tag("uint32"), | |||
| tag("uint64"), | |||
| tag("int8"), | |||
| tag("int16"), | |||
| tag("int32"), | |||
| tag("int64"), | |||
| tag("int64"), | |||
| tag("int64"), | |||
| tag("float32"), | |||
| tag("float64"), | |||
| tag("bool"), | |||
| tag("char"), | |||
| tag("byte"), | |||
| )), | |||
| |s| BasicType::parse(s).unwrap(), | |||
| )(s) | |||
| } | |||
| fn named_type(s: &str) -> IResult<&str, NamedType> { | |||
| map(message_name, |name| NamedType(name.into()))(s) | |||
| } | |||
| fn namespaced_type(s: &str) -> IResult<&str, NamespacedType> { | |||
| map( | |||
| tuple((package_name, char('/'), message_name)), | |||
| |(package, _, name)| NamespacedType { | |||
| package: package.into(), | |||
| namespace: "msg".into(), | |||
| name: name.into(), | |||
| }, | |||
| )(s) | |||
| } | |||
| fn generic_string(s: &str) -> IResult<&str, GenericString> { | |||
| map( | |||
| pair( | |||
| alt((tag("string"), tag("wstring"))), | |||
| opt(preceded(tag("<="), usize_literal)), | |||
| ), | |||
| |(type_str, array_info)| { | |||
| array_info.map_or_else( | |||
| || match type_str { | |||
| "string" => GenericString::String, | |||
| "wstring" => GenericString::WString, | |||
| _ => unreachable!(), | |||
| }, | |||
| |max_size| match type_str { | |||
| "string" => GenericString::BoundedString(max_size), | |||
| "wstring" => GenericString::BoundedWString(max_size), | |||
| _ => unreachable!(), | |||
| }, | |||
| ) | |||
| }, | |||
| )(s) | |||
| } | |||
| fn generic_unbounded_string(s: &str) -> IResult<&str, GenericUnboundedString> { | |||
| map( | |||
| alt((tag("string"), tag("wstring"))), | |||
| |type_str| match type_str { | |||
| "string" => GenericUnboundedString::String, | |||
| "wstring" => GenericUnboundedString::WString, | |||
| _ => unreachable!(), | |||
| }, | |||
| )(s) | |||
| } | |||
| fn nestable_type(s: &str) -> IResult<&str, NestableType> { | |||
| alt(( | |||
| map(basic_type, |type_| type_.into()), | |||
| map(generic_string, |type_| type_.into()), | |||
| map(namespaced_type, |type_| type_.into()), | |||
| map(named_type, |type_| type_.into()), | |||
| ))(s) | |||
| } | |||
| fn primitive_type(s: &str) -> IResult<&str, PrimitiveType> { | |||
| alt(( | |||
| map(basic_type, |type_| type_.into()), | |||
| map(generic_unbounded_string, |type_| type_.into()), | |||
| ))(s) | |||
| } | |||
| #[cfg(test)] | |||
| mod test { | |||
| use anyhow::Result; | |||
| use super::*; | |||
| #[test] | |||
| fn test_parse_member_type_basic_type() -> Result<()> { | |||
| assert_eq!(parse_member_type("int8")?.1, BasicType::I8.into()); | |||
| assert_eq!(parse_member_type("int16")?.1, BasicType::I16.into()); | |||
| assert_eq!(parse_member_type("int32")?.1, BasicType::I32.into()); | |||
| assert_eq!(parse_member_type("int64")?.1, BasicType::I64.into()); | |||
| assert_eq!(parse_member_type("uint8")?.1, BasicType::U8.into()); | |||
| assert_eq!(parse_member_type("uint16")?.1, BasicType::U16.into()); | |||
| assert_eq!(parse_member_type("uint32")?.1, BasicType::U32.into()); | |||
| assert_eq!(parse_member_type("uint64")?.1, BasicType::U64.into()); | |||
| assert_eq!(parse_member_type("float32")?.1, BasicType::F32.into()); | |||
| assert_eq!(parse_member_type("float64")?.1, BasicType::F64.into()); | |||
| assert_eq!(parse_member_type("bool")?.1, BasicType::Bool.into()); | |||
| assert_eq!(parse_member_type("char")?.1, BasicType::Char.into()); | |||
| assert_eq!(parse_member_type("byte")?.1, BasicType::Byte.into()); | |||
| Ok(()) | |||
| } | |||
| #[test] | |||
| fn test_parse_member_type_named_type() -> Result<()> { | |||
| assert_eq!(parse_member_type("ABC")?.1, NamedType("ABC".into()).into()); | |||
| Ok(()) | |||
| } | |||
| #[test] | |||
| fn test_parse_member_type_namespaced_type() -> Result<()> { | |||
| assert_eq!( | |||
| parse_member_type("std_msgs/Bool")?.1, | |||
| NamespacedType { | |||
| package: "std_msgs".into(), | |||
| namespace: "msg".into(), | |||
| name: "Bool".into() | |||
| } | |||
| .into() | |||
| ); | |||
| Ok(()) | |||
| } | |||
| #[test] | |||
| fn test_parse_member_type_generic_string() -> Result<()> { | |||
| assert_eq!(parse_member_type("string")?.1, GenericString::String.into()); | |||
| assert_eq!( | |||
| parse_member_type("wstring")?.1, | |||
| GenericString::WString.into() | |||
| ); | |||
| assert_eq!( | |||
| parse_member_type("string<=5")?.1, | |||
| GenericString::BoundedString(5).into() | |||
| ); | |||
| assert_eq!( | |||
| parse_member_type("wstring<=5")?.1, | |||
| GenericString::BoundedWString(5).into() | |||
| ); | |||
| Ok(()) | |||
| } | |||
| #[test] | |||
| fn test_parse_member_type_array() -> Result<()> { | |||
| assert_eq!( | |||
| parse_member_type("string[5]")?.1, | |||
| Array { | |||
| value_type: GenericString::String.into(), | |||
| size: 5, | |||
| } | |||
| .into() | |||
| ); | |||
| assert_eq!( | |||
| parse_member_type("string<=6[5]")?.1, | |||
| Array { | |||
| value_type: GenericString::BoundedString(6).into(), | |||
| size: 5, | |||
| } | |||
| .into() | |||
| ); | |||
| Ok(()) | |||
| } | |||
| #[test] | |||
| fn test_parse_member_type_sequence() -> Result<()> { | |||
| assert_eq!( | |||
| parse_member_type("string[]")?.1, | |||
| Sequence { | |||
| value_type: GenericString::String.into(), | |||
| } | |||
| .into() | |||
| ); | |||
| assert_eq!( | |||
| parse_member_type("string<=6[]")?.1, | |||
| Sequence { | |||
| value_type: GenericString::BoundedString(6).into(), | |||
| } | |||
| .into() | |||
| ); | |||
| Ok(()) | |||
| } | |||
| #[test] | |||
| fn test_parse_member_type_bounded_sequence() -> Result<()> { | |||
| assert_eq!( | |||
| parse_member_type("string[<=5]")?.1, | |||
| BoundedSequence { | |||
| value_type: GenericString::String.into(), | |||
| max_size: 5, | |||
| } | |||
| .into() | |||
| ); | |||
| assert_eq!( | |||
| parse_member_type("string<=6[<=5]")?.1, | |||
| BoundedSequence { | |||
| value_type: GenericString::BoundedString(6).into(), | |||
| max_size: 5, | |||
| } | |||
| .into() | |||
| ); | |||
| Ok(()) | |||
| } | |||
| #[test] | |||
| fn test_parse_constant_type_basic_type() -> Result<()> { | |||
| assert_eq!(parse_constant_type("int8")?.1, BasicType::I8.into()); | |||
| assert_eq!(parse_constant_type("int16")?.1, BasicType::I16.into()); | |||
| assert_eq!(parse_constant_type("int32")?.1, BasicType::I32.into()); | |||
| assert_eq!(parse_constant_type("int64")?.1, BasicType::I64.into()); | |||
| assert_eq!(parse_constant_type("uint8")?.1, BasicType::U8.into()); | |||
| assert_eq!(parse_constant_type("uint16")?.1, BasicType::U16.into()); | |||
| assert_eq!(parse_constant_type("uint32")?.1, BasicType::U32.into()); | |||
| assert_eq!(parse_constant_type("uint64")?.1, BasicType::U64.into()); | |||
| assert_eq!(parse_constant_type("float32")?.1, BasicType::F32.into()); | |||
| assert_eq!(parse_constant_type("float64")?.1, BasicType::F64.into()); | |||
| assert_eq!(parse_constant_type("bool")?.1, BasicType::Bool.into()); | |||
| assert_eq!(parse_constant_type("char")?.1, BasicType::Char.into()); | |||
| assert_eq!(parse_constant_type("byte")?.1, BasicType::Byte.into()); | |||
| Ok(()) | |||
| } | |||
| #[test] | |||
| fn test_parse_constant_type_named_type() -> Result<()> { | |||
| assert!(parse_constant_type("ABC").is_err()); | |||
| Ok(()) | |||
| } | |||
| #[test] | |||
| fn test_parse_constant_type_namespaced_type() -> Result<()> { | |||
| assert!(parse_constant_type("std_msgs/Bool").is_err()); | |||
| Ok(()) | |||
| } | |||
| #[test] | |||
| fn test_parse_constant_type_generic_string() -> Result<()> { | |||
| assert_eq!( | |||
| parse_constant_type("string")?.1, | |||
| GenericUnboundedString::String.into() | |||
| ); | |||
| assert_eq!( | |||
| parse_constant_type("wstring")?.1, | |||
| GenericUnboundedString::WString.into() | |||
| ); | |||
| assert!(parse_constant_type("string<=5").is_err()); | |||
| assert!(parse_constant_type("wstring<=5").is_err()); | |||
| Ok(()) | |||
| } | |||
| #[test] | |||
| fn test_parse_constant_type_array() -> Result<()> { | |||
| assert_eq!( | |||
| parse_constant_type("string[5]")?.1, | |||
| PrimitiveArray { | |||
| value_type: GenericUnboundedString::String.into(), | |||
| size: 5, | |||
| } | |||
| .into() | |||
| ); | |||
| assert!(parse_constant_type("string<=6[5]").is_err()); | |||
| Ok(()) | |||
| } | |||
| #[test] | |||
| fn test_parse_constant_type_sequence() -> Result<()> { | |||
| assert!(parse_constant_type("string[]").is_err()); | |||
| assert!(parse_constant_type("string<=6[]").is_err()); | |||
| Ok(()) | |||
| } | |||
| #[test] | |||
| fn test_parse_const_type_bounded_sequence() -> Result<()> { | |||
| assert!(parse_constant_type("string[<=5]").is_err()); | |||
| assert!(parse_constant_type("string<=6[<=5]").is_err()); | |||
| Ok(()) | |||
| } | |||
| } | |||
| @@ -0,0 +1,237 @@ | |||
| use heck::SnakeCase; | |||
| use quote::{format_ident, quote, ToTokens}; | |||
| use super::{primitives::*, Member, Message, Service}; | |||
| /// An action definition | |||
| #[derive(Debug, Clone)] | |||
| pub struct Action { | |||
| /// The name of The package | |||
| pub package: String, | |||
| /// The name of The action | |||
| pub name: String, | |||
| /// The type of the goal | |||
| pub goal: Message, | |||
| /// The type of the result | |||
| pub result: Message, | |||
| /// The type of the feedback | |||
| pub feedback: Message, | |||
| } | |||
| impl Action { | |||
| fn send_goal_srv(&self) -> Service { | |||
| let common = format!("{}_SendGoal", self.name); | |||
| let request = Message { | |||
| package: self.package.clone(), | |||
| name: format!("{}_Request", common), | |||
| members: vec![ | |||
| goal_id_type(), | |||
| Member { | |||
| name: "goal".into(), | |||
| r#type: NamespacedType { | |||
| package: self.package.clone(), | |||
| namespace: "action".into(), | |||
| name: format!("{}_Goal", self.name), | |||
| } | |||
| .into(), | |||
| default: None, | |||
| }, | |||
| ], | |||
| constants: vec![], | |||
| }; | |||
| let response = Message { | |||
| package: self.package.clone(), | |||
| name: format!("{}_Response", common), | |||
| members: vec![ | |||
| Member { | |||
| name: "accepted".into(), | |||
| r#type: BasicType::Bool.into(), | |||
| default: None, | |||
| }, | |||
| Member { | |||
| name: "stamp".into(), | |||
| r#type: NamespacedType { | |||
| package: "builtin_interfaces".into(), | |||
| namespace: "msg".into(), | |||
| name: "Time".into(), | |||
| } | |||
| .into(), | |||
| default: None, | |||
| }, | |||
| ], | |||
| constants: vec![], | |||
| }; | |||
| Service { | |||
| package: self.package.clone(), | |||
| name: common, | |||
| request, | |||
| response, | |||
| } | |||
| } | |||
| fn get_result_srv(&self) -> Service { | |||
| let common = format!("{}_GetResult", self.name); | |||
| let request = Message { | |||
| package: self.package.clone(), | |||
| name: format!("{}_Request", common), | |||
| members: vec![goal_id_type()], | |||
| constants: vec![], | |||
| }; | |||
| let response = Message { | |||
| package: self.package.clone(), | |||
| name: format!("{}_Response", common), | |||
| members: vec![ | |||
| Member { | |||
| name: "status".into(), | |||
| r#type: BasicType::I8.into(), | |||
| default: None, | |||
| }, | |||
| Member { | |||
| name: "result".into(), | |||
| r#type: NamespacedType { | |||
| package: self.package.clone(), | |||
| namespace: "action".into(), | |||
| name: format!("{}_Result", self.name), | |||
| } | |||
| .into(), | |||
| default: None, | |||
| }, | |||
| ], | |||
| constants: vec![], | |||
| }; | |||
| Service { | |||
| package: self.package.clone(), | |||
| name: common, | |||
| request, | |||
| response, | |||
| } | |||
| } | |||
| fn feedback_message_msg(&self) -> Message { | |||
| Message { | |||
| package: self.package.clone(), | |||
| name: format!("{}_FeedbackMessage", self.name), | |||
| members: vec![ | |||
| goal_id_type(), | |||
| Member { | |||
| name: "feedback".into(), | |||
| r#type: NamespacedType { | |||
| package: self.package.clone(), | |||
| namespace: "action".into(), | |||
| name: format!("{}_Feedback", self.name), | |||
| } | |||
| .into(), | |||
| default: None, | |||
| }, | |||
| ], | |||
| constants: vec![], | |||
| } | |||
| } | |||
| pub fn token_stream_with_mod(&self) -> impl ToTokens { | |||
| let mod_name = format_ident!("_{}", self.name.to_snake_case()); | |||
| let inner = self.token_stream(); | |||
| quote! { | |||
| pub use #mod_name::*; | |||
| mod #mod_name { | |||
| #inner | |||
| } | |||
| } | |||
| } | |||
| pub fn token_stream(&self) -> impl ToTokens { | |||
| let action_type = format_ident!("{}", self.name); | |||
| let goal_type = format_ident!("{}_Goal", self.name); | |||
| let result_type = format_ident!("{}_Result", self.name); | |||
| let feedback_type = format_ident!("{}_Feedback", self.name); | |||
| let send_goal_type = format_ident!("{}_SendGoal", self.name); | |||
| let get_result_type = format_ident!("{}_GetResult", self.name); | |||
| let feeback_message_type = format_ident!("{}_FeedbackMessage", self.name); | |||
| let goal_body = self.goal.token_stream(); | |||
| let result_body = self.result.token_stream(); | |||
| let feedback_body = self.feedback.token_stream(); | |||
| let send_goal_body = self.send_goal_srv().token_stream(); | |||
| let get_result_body = self.get_result_srv().token_stream(); | |||
| let feedback_message_body = self.feedback_message_msg().token_stream(); | |||
| quote! { | |||
| use std::os::raw::c_void; | |||
| pub use self::goal::*; | |||
| pub use self::result::*; | |||
| pub use self::feedback::*; | |||
| pub use self::send_goal::*; | |||
| pub use self::get_result::*; | |||
| pub use self::feedback_message::*; | |||
| #[allow(non_camel_case_types)] | |||
| #[derive(std::fmt::Debug)] | |||
| pub struct #action_type; | |||
| impl crate::_core::ActionT for #action_type { | |||
| type Goal = #goal_type; | |||
| type Result = #result_type; | |||
| type Feedback = #feedback_type; | |||
| type SendGoal = #send_goal_type; | |||
| type GetResult = #get_result_type; | |||
| type FeedbackMessage = #feeback_message_type; | |||
| } | |||
| mod goal { | |||
| #goal_body | |||
| } // mod goal | |||
| mod result { | |||
| #result_body | |||
| } // mod result | |||
| mod feedback { | |||
| #feedback_body | |||
| } // mod feedback | |||
| mod send_goal { | |||
| #send_goal_body | |||
| } // mod send_goal | |||
| mod get_result { | |||
| #get_result_body | |||
| } // mod get_result | |||
| mod feedback_message { | |||
| #feedback_message_body | |||
| } // mod feedback_message | |||
| #[cfg(test)] | |||
| mod test { | |||
| use super::*; | |||
| use crate::_core::ActionT; | |||
| #[test] | |||
| fn test_type_support() { | |||
| let ptr = #action_type::type_support(); | |||
| assert!(!ptr.is_null()); | |||
| } | |||
| } | |||
| } | |||
| } | |||
| } | |||
| fn goal_id_type() -> Member { | |||
| Member { | |||
| name: "goal_id".into(), | |||
| r#type: NamespacedType { | |||
| package: "unique_identifier_msgs".into(), | |||
| namespace: "msg".into(), | |||
| name: "UUID".into(), | |||
| } | |||
| .into(), | |||
| default: None, | |||
| } | |||
| } | |||
| @@ -0,0 +1,68 @@ | |||
| use quote::{quote, ToTokens}; | |||
| use super::{ | |||
| primitives::{BasicType, GenericUnboundedString, PrimitiveType}, | |||
| sequences::PrimitiveArray, | |||
| }; | |||
| macro_rules! define_enum_from { | |||
| ($into_t:ty, $from_t:ty, $path:path) => { | |||
| impl From<$from_t> for $into_t { | |||
| fn from(t: $from_t) -> Self { | |||
| $path(t) | |||
| } | |||
| } | |||
| }; | |||
| } | |||
| /// A type which is available for constant | |||
| #[derive(Debug, Clone, PartialEq, Eq)] | |||
| pub enum ConstantType { | |||
| PrimitiveType(PrimitiveType), | |||
| PrimitiveArray(PrimitiveArray), | |||
| } | |||
| impl ConstantType { | |||
| pub fn type_tokens(&self) -> impl ToTokens { | |||
| match self { | |||
| ConstantType::PrimitiveType(t) => { | |||
| let token = t.type_tokens(); | |||
| quote! { #token } | |||
| } | |||
| ConstantType::PrimitiveArray(t) => { | |||
| let token = t.type_tokens(); | |||
| quote! { #token } | |||
| } | |||
| } | |||
| } | |||
| pub fn value_tokens(&self, values: &[String]) -> impl ToTokens { | |||
| match self { | |||
| ConstantType::PrimitiveType(t) => { | |||
| assert_eq!(values.len(), 1); | |||
| let token = t.value_tokens(&values[0]); | |||
| quote! { #token } | |||
| } | |||
| ConstantType::PrimitiveArray(t) => { | |||
| assert_eq!(values.len(), t.size); | |||
| let tokens = values.iter().map(|v| t.value_type.value_tokens(v)); | |||
| quote! { [#(#tokens,)*] } | |||
| } | |||
| } | |||
| } | |||
| } | |||
| define_enum_from!(ConstantType, PrimitiveType, Self::PrimitiveType); | |||
| define_enum_from!(ConstantType, PrimitiveArray, Self::PrimitiveArray); | |||
| impl From<BasicType> for ConstantType { | |||
| fn from(t: BasicType) -> Self { | |||
| Self::PrimitiveType(PrimitiveType::BasicType(t)) | |||
| } | |||
| } | |||
| impl From<GenericUnboundedString> for ConstantType { | |||
| fn from(t: GenericUnboundedString) -> Self { | |||
| Self::PrimitiveType(PrimitiveType::GenericUnboundedString(t)) | |||
| } | |||
| } | |||
| @@ -0,0 +1,142 @@ | |||
| use quote::{quote, ToTokens}; | |||
| use super::{primitives::*, sequences::*}; | |||
| macro_rules! define_enum_from { | |||
| ($into_t:ty, $from_t:ty, $path:path) => { | |||
| impl From<$from_t> for $into_t { | |||
| fn from(t: $from_t) -> Self { | |||
| $path(t) | |||
| } | |||
| } | |||
| }; | |||
| } | |||
| /// A type which is available for member | |||
| #[derive(Debug, Clone, PartialEq, Eq)] | |||
| pub enum MemberType { | |||
| NestableType(NestableType), | |||
| Array(Array), | |||
| Sequence(Sequence), | |||
| BoundedSequence(BoundedSequence), | |||
| } | |||
| impl MemberType { | |||
| pub fn type_tokens(&self, package: &str) -> (impl ToTokens, impl ToTokens) { | |||
| match self { | |||
| Self::NestableType(t) => { | |||
| let token = t.type_tokens(package); | |||
| (quote! {}, quote! { #token }) | |||
| } | |||
| Self::Array(t) => { | |||
| let token = t.type_tokens(package); | |||
| ( | |||
| quote! { #[serde(with = "serde_big_array::BigArray")] }, | |||
| quote! { #token }, | |||
| ) | |||
| } | |||
| Self::Sequence(t) => { | |||
| let token = t.type_tokens(package); | |||
| (quote! {}, quote! { #token }) | |||
| } | |||
| Self::BoundedSequence(t) => { | |||
| let token = t.type_tokens(package); | |||
| (quote! {}, quote! { #token }) | |||
| } | |||
| } | |||
| } | |||
| pub fn raw_type_tokens(&self, package: &str) -> impl ToTokens { | |||
| match self { | |||
| Self::NestableType(t) => { | |||
| let token = t.raw_type_tokens(package); | |||
| quote! { #token } | |||
| } | |||
| Self::Array(t) => { | |||
| let token = t.raw_type_tokens(package); | |||
| quote! { #token } | |||
| } | |||
| Self::Sequence(t) => { | |||
| let token = t.raw_type_tokens(package); | |||
| quote! { #token } | |||
| } | |||
| Self::BoundedSequence(t) => { | |||
| let token = t.raw_type_tokens(package); | |||
| quote! { #token } | |||
| } | |||
| } | |||
| } | |||
| pub fn raw_ref_type_tokens(&self, package: &str) -> impl ToTokens { | |||
| match self { | |||
| Self::NestableType(t) => { | |||
| let token = t.raw_ref_type_tokens(package); | |||
| quote! { #token } | |||
| } | |||
| Self::Array(t) => { | |||
| let token = t.raw_ref_type_tokens(package); | |||
| quote! { #token } | |||
| } | |||
| Self::Sequence(t) => { | |||
| let token = t.raw_ref_type_tokens(package); | |||
| quote! { #token } | |||
| } | |||
| Self::BoundedSequence(t) => { | |||
| let token = t.raw_ref_type_tokens(package); | |||
| quote! { #token } | |||
| } | |||
| } | |||
| } | |||
| pub fn value_tokens(&self, default: &[String]) -> impl ToTokens { | |||
| match self { | |||
| Self::NestableType(t) => { | |||
| let token = t.value_tokens(&default[0]); | |||
| quote! { #token } | |||
| } | |||
| Self::Array(t) => { | |||
| assert_eq!(default.len(), t.size); | |||
| let tokens = default.iter().map(|v| t.value_type.value_tokens(v)); | |||
| quote! { [#(#tokens,)*] } | |||
| } | |||
| Self::Sequence(t) => { | |||
| let tokens = default.iter().map(|v| t.value_type.value_tokens(v)); | |||
| quote! { vec![#(#tokens,)*] } | |||
| } | |||
| Self::BoundedSequence(t) => { | |||
| assert!(default.len() <= t.max_size); | |||
| let tokens = default.iter().map(|v| t.value_type.value_tokens(v)); | |||
| quote! { vec![#(#tokens,)*] } | |||
| } | |||
| } | |||
| } | |||
| } | |||
| define_enum_from!(MemberType, NestableType, Self::NestableType); | |||
| define_enum_from!(MemberType, Array, Self::Array); | |||
| define_enum_from!(MemberType, Sequence, Self::Sequence); | |||
| define_enum_from!(MemberType, BoundedSequence, Self::BoundedSequence); | |||
| impl From<BasicType> for MemberType { | |||
| fn from(t: BasicType) -> Self { | |||
| Self::NestableType(NestableType::BasicType(t)) | |||
| } | |||
| } | |||
| impl From<NamedType> for MemberType { | |||
| fn from(t: NamedType) -> Self { | |||
| Self::NestableType(NestableType::NamedType(t)) | |||
| } | |||
| } | |||
| impl From<NamespacedType> for MemberType { | |||
| fn from(t: NamespacedType) -> Self { | |||
| Self::NestableType(NestableType::NamespacedType(t)) | |||
| } | |||
| } | |||
| impl From<GenericString> for MemberType { | |||
| fn from(t: GenericString) -> Self { | |||
| Self::NestableType(NestableType::GenericString(t)) | |||
| } | |||
| } | |||
| @@ -0,0 +1,296 @@ | |||
| use heck::SnakeCase; | |||
| use quote::{format_ident, quote, ToTokens}; | |||
| use super::{primitives::*, sequences::Array, ConstantType, MemberType}; | |||
| /// A member of a structure | |||
| #[derive(Debug, Clone)] | |||
| pub struct Member { | |||
| /// The name of the member | |||
| pub name: String, | |||
| /// The type of the member | |||
| pub r#type: MemberType, | |||
| /// The default value of the member (optional) | |||
| pub default: Option<Vec<String>>, | |||
| } | |||
| impl Member { | |||
| fn dummy() -> Self { | |||
| Self { | |||
| name: "structure_needs_at_least_one_member".into(), | |||
| r#type: BasicType::U8.into(), | |||
| default: None, | |||
| } | |||
| } | |||
| fn name_token(&self) -> impl ToTokens { | |||
| if RUST_KEYWORDS.contains(&self.name.as_str()) { | |||
| format_ident!("{}_", self.name) | |||
| } else { | |||
| format_ident!("{}", self.name) | |||
| } | |||
| } | |||
| fn rust_type_def(&self, package: &str) -> impl ToTokens { | |||
| let name = self.name_token(); | |||
| let (attr, type_) = self.r#type.type_tokens(package); | |||
| quote! { #attr pub #name: #type_, } | |||
| } | |||
| fn default_value(&self) -> impl ToTokens { | |||
| let name = self.name_token(); | |||
| self.default.as_ref().map_or_else( | |||
| || quote! { #name: crate::_core::InternalDefault::_default(), }, | |||
| |default| { | |||
| let default = self.r#type.value_tokens(default); | |||
| quote! { #name: #default, } | |||
| }, | |||
| ) | |||
| } | |||
| fn raw_type_def(&self, package: &str) -> impl ToTokens { | |||
| let name = self.name_token(); | |||
| let type_ = self.r#type.raw_type_tokens(package); | |||
| quote! { pub #name: #type_, } | |||
| } | |||
| fn ffi_to_rust(&self) -> impl ToTokens { | |||
| let name = self.name_token(); | |||
| let value = match &self.r#type { | |||
| MemberType::NestableType(NestableType::BasicType(_)) => quote! { self.#name }, | |||
| MemberType::Array(Array { | |||
| value_type: NestableType::BasicType(_), | |||
| .. | |||
| }) => quote! { self.#name.clone() }, | |||
| _ => quote! { self.#name.to_rust() }, | |||
| }; | |||
| quote! { #name: #value, } | |||
| } | |||
| fn raw_ref_type_def(&self, package: &str) -> impl ToTokens { | |||
| let name = self.name_token(); | |||
| let type_ = self.r#type.raw_ref_type_tokens(package); | |||
| quote! { pub #name: #type_, } | |||
| } | |||
| fn ffi_from_rust(&self) -> impl ToTokens { | |||
| let name = self.name_token(); | |||
| let value = match &self.r#type { | |||
| MemberType::NestableType(NestableType::BasicType(_)) => quote! { from.#name }, | |||
| MemberType::Array(Array { | |||
| value_type: NestableType::BasicType(_), | |||
| .. | |||
| }) => quote! { from.#name.clone() }, | |||
| _ => quote! { _FFIFromRust::from_rust(&from.#name) }, | |||
| }; | |||
| quote! { #name: #value, } | |||
| } | |||
| } | |||
| /// A constant definition | |||
| #[derive(Debug, Clone)] | |||
| pub struct Constant { | |||
| /// The name of the constant | |||
| pub name: String, | |||
| /// The type of the constant | |||
| pub r#type: ConstantType, | |||
| /// The value of the constant | |||
| pub value: Vec<String>, | |||
| } | |||
| impl Constant { | |||
| fn token_stream(&self) -> impl ToTokens { | |||
| let name = format_ident!("{}", self.name); | |||
| let type_ = self.r#type.type_tokens(); | |||
| let value = self.r#type.value_tokens(&self.value); | |||
| quote! { pub const #name: #type_ = #value; } | |||
| } | |||
| } | |||
| /// A message definition | |||
| #[derive(Debug, Clone)] | |||
| pub struct Message { | |||
| /// The package name | |||
| pub package: String, | |||
| /// The name of the message | |||
| pub name: String, | |||
| /// The list of the members | |||
| pub members: Vec<Member>, | |||
| /// The list of the constants | |||
| pub constants: Vec<Constant>, | |||
| } | |||
| impl Message { | |||
| pub fn token_stream_with_mod(&self) -> impl ToTokens { | |||
| let mod_name = format_ident!("_{}", self.name.to_snake_case()); | |||
| let inner = self.token_stream(); | |||
| quote! { | |||
| pub use #mod_name::*; | |||
| mod #mod_name { | |||
| #inner | |||
| } | |||
| } | |||
| } | |||
| pub fn token_stream(&self) -> impl ToTokens { | |||
| let rust_type = format_ident!("{}", self.name); | |||
| let raw_type = format_ident!("{}_Raw", self.name); | |||
| let raw_ref_type = format_ident!("{}_RawRef", self.name); | |||
| let members_for_c = if self.members.is_empty() { | |||
| vec![Member::dummy()] | |||
| } else { | |||
| self.members.clone() | |||
| }; | |||
| let rust_type_def_inner = self.members.iter().map(|m| m.rust_type_def(&self.package)); | |||
| let constants_def_inner = self.constants.iter().map(|c| c.token_stream()); | |||
| let rust_type_default_inner = self.members.iter().map(|m| m.default_value()); | |||
| let raw_type_def_inner = members_for_c.iter().map(|m| m.raw_type_def(&self.package)); | |||
| let raw_type_to_rust_inner = self.members.iter().map(|m| m.ffi_to_rust()); | |||
| let raw_ref_type_def_inner = members_for_c | |||
| .iter() | |||
| .map(|m| m.raw_ref_type_def(&self.package)); | |||
| let raw_ref_type_from_rust_inner = if self.members.is_empty() { | |||
| vec![quote! { structure_needs_at_least_one_member: 0, }] | |||
| } else { | |||
| self.members | |||
| .iter() | |||
| .map(|m| { | |||
| let token = m.ffi_from_rust(); | |||
| quote! { #token } | |||
| }) | |||
| .collect::<Vec<_>>() | |||
| }; | |||
| quote! { | |||
| #[allow(unused_imports)] | |||
| use std::convert::TryInto as _; | |||
| use std::os::raw::c_void; | |||
| use crate::_core::{ | |||
| InternalDefault as _, | |||
| FFIFromRust as _FFIFromRust, | |||
| FFIToRust as _FFIToRust, | |||
| }; | |||
| #[allow(non_camel_case_types)] | |||
| #[derive(std::fmt::Debug, std::clone::Clone, std::cmp::PartialEq, serde::Serialize, serde::Deserialize)] | |||
| pub struct #rust_type { | |||
| #(#rust_type_def_inner)* | |||
| } | |||
| impl #rust_type { | |||
| #(#constants_def_inner)* | |||
| } | |||
| impl crate::_core::MessageT for #rust_type { | |||
| type Raw = #raw_type; | |||
| type RawRef = #raw_ref_type; | |||
| } | |||
| impl crate::_core::InternalDefault for #rust_type { | |||
| fn _default() -> Self { | |||
| Self { | |||
| #(#rust_type_default_inner)* | |||
| } | |||
| } | |||
| } | |||
| impl std::default::Default for #rust_type { | |||
| #[inline] | |||
| fn default() -> Self { | |||
| crate::_core::InternalDefault::_default() | |||
| } | |||
| } | |||
| #[allow(non_camel_case_types)] | |||
| #[repr(C)] | |||
| #[derive(std::fmt::Debug)] | |||
| pub struct #raw_type { | |||
| #(#raw_type_def_inner)* | |||
| } | |||
| impl crate::_core::FFIToRust for #raw_type { | |||
| type Target = #rust_type; | |||
| unsafe fn to_rust(&self) -> Self::Target { | |||
| Self::Target { | |||
| #(#raw_type_to_rust_inner)* | |||
| } | |||
| } | |||
| } | |||
| unsafe impl std::marker::Send for #raw_type {} | |||
| unsafe impl std::marker::Sync for #raw_type {} | |||
| #[allow(non_camel_case_types)] | |||
| #[doc(hidden)] | |||
| #[repr(C)] | |||
| #[derive(std::fmt::Debug)] | |||
| pub struct #raw_ref_type { | |||
| #(#raw_ref_type_def_inner)* | |||
| } | |||
| impl crate::_core::FFIFromRust for #raw_ref_type { | |||
| type From = #rust_type; | |||
| #[allow(unused_variables)] | |||
| unsafe fn from_rust(from: &Self::From) -> Self { | |||
| Self { | |||
| #(#raw_ref_type_from_rust_inner)* | |||
| } | |||
| } | |||
| } | |||
| #[cfg(test)] | |||
| mod test { | |||
| use super::*; | |||
| use crate::_core::MessageT; | |||
| #[test] | |||
| fn test_rust_default() { | |||
| let _ = #rust_type::default(); | |||
| } | |||
| #[test] | |||
| fn test_raw_default() { | |||
| let _ = #raw_type::default(); | |||
| } | |||
| #[test] | |||
| fn test_type_support() { | |||
| let ptr = #rust_type::type_support(); | |||
| assert!(!ptr.is_null()); | |||
| } | |||
| } | |||
| } | |||
| } | |||
| } | |||
| /// Keywords in Rust | |||
| /// | |||
| /// <https://doc.rust-lang.org/reference/keywords.html> | |||
| const RUST_KEYWORDS: [&str; 51] = [ | |||
| // Strict keywords | |||
| "as", "break", "const", "continue", "crate", "else", "enum", "extern", "false", "fn", "for", | |||
| "if", "impl", "in", "let", "loop", "match", "mod", "move", "mut", "pub", "ref", "return", | |||
| "self", "Self", "static", "struct", "super", "trait", "true", "type", "unsafe", "use", "where", | |||
| "while", // | |||
| // Strict keywords (2018+) | |||
| "async", "await", "dyn", // | |||
| // Reserved keywords | |||
| "abstract", "become", "box", "do", "final", "macro", "override", "priv", "typeof", "unsized", | |||
| "virtual", "yield", // | |||
| // Reserved keywords (2018+) | |||
| "try", | |||
| ]; | |||
| @@ -0,0 +1,15 @@ | |||
| mod action; | |||
| mod constant; | |||
| mod member; | |||
| mod message; | |||
| mod package; | |||
| pub mod primitives; | |||
| pub mod sequences; | |||
| mod service; | |||
| pub use action::Action; | |||
| pub use constant::ConstantType; | |||
| pub use member::MemberType; | |||
| pub use message::{Constant, Member, Message}; | |||
| pub use package::Package; | |||
| pub use service::Service; | |||
| @@ -0,0 +1,88 @@ | |||
| use proc_macro2::Span; | |||
| use quote::{quote, ToTokens}; | |||
| use syn::Ident; | |||
| use crate::types::{Action, Message, Service}; | |||
| #[derive(Debug)] | |||
| pub struct Package { | |||
| pub name: String, | |||
| pub messages: Vec<Message>, | |||
| pub services: Vec<Service>, | |||
| pub actions: Vec<Action>, | |||
| } | |||
| impl Package { | |||
| pub const fn new(name: String) -> Self { | |||
| Self { | |||
| name, | |||
| messages: Vec::new(), | |||
| services: Vec::new(), | |||
| actions: Vec::new(), | |||
| } | |||
| } | |||
| pub fn is_empty(&self) -> bool { | |||
| self.messages.is_empty() && self.services.is_empty() && self.actions.is_empty() | |||
| } | |||
| fn messages_block(&self) -> impl ToTokens { | |||
| if self.messages.is_empty() { | |||
| quote! { | |||
| // empty msg | |||
| } | |||
| } else { | |||
| let items = self.messages.iter().map(|v| v.token_stream_with_mod()); | |||
| quote! { | |||
| pub mod msg { | |||
| #(#items)* | |||
| } // msg | |||
| } | |||
| } | |||
| } | |||
| fn services_block(&self) -> impl ToTokens { | |||
| if self.services.is_empty() { | |||
| quote! { | |||
| // empty srv | |||
| } | |||
| } else { | |||
| let items = self.services.iter().map(|v| v.token_stream_with_mod()); | |||
| quote! { | |||
| pub mod srv { | |||
| #(#items)* | |||
| } // srv | |||
| } | |||
| } | |||
| } | |||
| fn actions_block(&self) -> impl ToTokens { | |||
| if self.actions.is_empty() { | |||
| quote! { | |||
| // empty srv | |||
| } | |||
| } else { | |||
| let items = self.actions.iter().map(|v| v.token_stream_with_mod()); | |||
| quote! { | |||
| pub mod action { | |||
| #(#items)* | |||
| } // action | |||
| } | |||
| } | |||
| } | |||
| pub fn token_stream(&self) -> impl ToTokens { | |||
| let name = Ident::new(&self.name, Span::call_site()); | |||
| let messages_block = self.messages_block(); | |||
| let services_block = self.services_block(); | |||
| let actions_block = self.actions_block(); | |||
| quote! { | |||
| pub mod #name { | |||
| #messages_block | |||
| #services_block | |||
| #actions_block | |||
| } | |||
| } | |||
| } | |||
| } | |||
| @@ -0,0 +1,411 @@ | |||
| use std::fmt; | |||
| use proc_macro2::{Ident, Literal, Span}; | |||
| use quote::{format_ident, quote, ToTokens}; | |||
| macro_rules! define_enum_from { | |||
| ($into_t:ty, $from_t:ty, $path:path) => { | |||
| impl From<$from_t> for $into_t { | |||
| fn from(t: $from_t) -> Self { | |||
| $path(t) | |||
| } | |||
| } | |||
| }; | |||
| } | |||
| /// A basic type according to the IDL specification. | |||
| #[derive(Debug, Clone, Copy, PartialEq, Eq)] | |||
| pub enum BasicType { | |||
| // signed integer type | |||
| /// Rust: [i8], C++: `int8_t` | |||
| I8, | |||
| /// Rust: [i16], C++: `int16_t` | |||
| I16, | |||
| /// Rust: [i32], C++: `int32_t` | |||
| I32, | |||
| /// Rust: [i64], C++: `int64_t` | |||
| I64, | |||
| // unsigned integer type | |||
| /// Rust: [u8], C++: `uint8_t` | |||
| U8, | |||
| /// Rust: [u16], C++: `uint16_t` | |||
| U16, | |||
| /// Rust: [u32], C++: `uint32_t` | |||
| U32, | |||
| /// Rust: [u64], C++: `uint64_t` | |||
| U64, | |||
| // floating point type | |||
| /// Rust: [f32], C++: `float` | |||
| F32, | |||
| /// Rust: [f64], C++: `double` | |||
| F64, | |||
| // long double is not supported | |||
| // boolean type | |||
| /// Rust: [bool], C++: `bool` | |||
| Bool, | |||
| // duplicated type | |||
| /// Rust: [u8], C++: `unsigned char` | |||
| Char, | |||
| /// Rust: [u8], C++: `unsigned char` | |||
| Byte, | |||
| } | |||
| impl BasicType { | |||
| pub fn parse(s: &str) -> Option<Self> { | |||
| Some(match s { | |||
| "int8" => Self::I8, | |||
| "int16" => Self::I16, | |||
| "int32" => Self::I32, | |||
| "int64" => Self::I64, | |||
| "uint8" => Self::U8, | |||
| "uint16" => Self::U16, | |||
| "uint32" => Self::U32, | |||
| "uint64" => Self::U64, | |||
| "float32" => Self::F32, | |||
| "float64" => Self::F64, | |||
| "bool" => Self::Bool, | |||
| "char" => Self::Char, | |||
| "byte" => Self::Byte, | |||
| _ => { | |||
| return None; | |||
| } | |||
| }) | |||
| } | |||
| pub fn type_tokens(self) -> impl ToTokens { | |||
| match self { | |||
| Self::I8 => quote! { i8 }, | |||
| Self::I16 => quote! { i16 }, | |||
| Self::I32 => quote! { i32 }, | |||
| Self::I64 => quote! { i64 }, | |||
| Self::U8 | Self::Char | Self::Byte => quote! { u8 }, | |||
| Self::U16 => quote! { u16 }, | |||
| Self::U32 => quote! { u32 }, | |||
| Self::U64 => quote! { u64 }, | |||
| Self::F32 => quote! { f32 }, | |||
| Self::F64 => quote! { f64 }, | |||
| Self::Bool => quote! { bool }, | |||
| } | |||
| } | |||
| fn value_literal(self, value: &str) -> Option<Literal> { | |||
| Some(match self { | |||
| Self::I8 => Literal::i8_suffixed(value.parse().unwrap()), | |||
| Self::I16 => Literal::i16_suffixed(value.parse().unwrap()), | |||
| Self::I32 => Literal::i32_suffixed(value.parse().unwrap()), | |||
| Self::I64 => Literal::i64_suffixed(value.parse().unwrap()), | |||
| Self::U8 | Self::Char | Self::Byte => Literal::u8_suffixed(value.parse().unwrap()), | |||
| Self::U16 => Literal::u16_suffixed(value.parse().unwrap()), | |||
| Self::U32 => Literal::u32_suffixed(value.parse().unwrap()), | |||
| Self::U64 => Literal::u64_suffixed(value.parse().unwrap()), | |||
| Self::F32 => Literal::f32_suffixed(value.parse().unwrap()), | |||
| Self::F64 => Literal::f64_suffixed(value.parse().unwrap()), | |||
| // bool is Ident not Literal! | |||
| Self::Bool => return None, | |||
| }) | |||
| } | |||
| fn value_tokens(self, value: &str) -> impl ToTokens { | |||
| match self { | |||
| Self::Bool => match value { | |||
| "true" => quote! { true }, | |||
| "false" => quote! { false }, | |||
| _ => unreachable!(), | |||
| }, | |||
| _ => { | |||
| let value = self.value_literal(value).unwrap(); | |||
| quote! { #value } | |||
| } | |||
| } | |||
| } | |||
| } | |||
| /// A type identified by the name | |||
| #[derive(Debug, Clone, PartialEq, Eq)] | |||
| pub struct NamedType(pub String); | |||
| impl NamedType { | |||
| fn type_tokens(&self, package: &str) -> impl ToTokens { | |||
| let package = Ident::new(package, Span::call_site()); | |||
| let namespace = Ident::new("msg", Span::call_site()); | |||
| let name = Ident::new(&self.0, Span::call_site()); | |||
| quote! { crate::#package::#namespace::#name } | |||
| } | |||
| fn raw_type_tokens(&self, package: &str) -> impl ToTokens { | |||
| let package = Ident::new(package, Span::call_site()); | |||
| let namespace = Ident::new("msg", Span::call_site()); | |||
| let name = format_ident!("{}_Raw", self.0); | |||
| quote! { crate::#package::#namespace::#name } | |||
| } | |||
| fn raw_ref_type_tokens(&self, package: &str) -> impl ToTokens { | |||
| let package = Ident::new(package, Span::call_site()); | |||
| let namespace = Ident::new("msg", Span::call_site()); | |||
| let name = format_ident!("{}_RawRef", self.0); | |||
| quote! { crate::#package::#namespace::#name } | |||
| } | |||
| } | |||
| impl fmt::Display for NamedType { | |||
| fn fmt(&self, f: &mut fmt::Formatter<'_>) -> fmt::Result { | |||
| write!(f, "{}", self.0) | |||
| } | |||
| } | |||
| /// A type identified by a name in a namespaced scope | |||
| #[derive(Debug, Clone, PartialEq, Eq)] | |||
| pub struct NamespacedType { | |||
| /// A package name which this type belongs to | |||
| /// e.g. `std_msgs` | |||
| pub package: String, | |||
| /// msg or action | |||
| pub namespace: String, | |||
| /// A name of message | |||
| /// e.g. `Bool` | |||
| pub name: String, | |||
| } | |||
| impl NamespacedType { | |||
| fn type_tokens(&self) -> impl ToTokens { | |||
| let package = Ident::new(&self.package, Span::call_site()); | |||
| let namespace = Ident::new(&self.namespace, Span::call_site()); | |||
| let name = Ident::new(&self.name, Span::call_site()); | |||
| quote! { crate::#package::#namespace::#name } | |||
| } | |||
| fn raw_type_tokens(&self) -> impl ToTokens { | |||
| let package = Ident::new(&self.package, Span::call_site()); | |||
| let namespace = Ident::new(&self.namespace, Span::call_site()); | |||
| let name = format_ident!("{}_Raw", self.name); | |||
| quote! { crate::#package::#namespace::#name } | |||
| } | |||
| fn raw_ref_type_tokens(&self) -> impl ToTokens { | |||
| let package = Ident::new(&self.package, Span::call_site()); | |||
| let namespace = Ident::new(&self.namespace, Span::call_site()); | |||
| let name = format_ident!("{}_RawRef", self.name); | |||
| quote! { crate::#package::#namespace::#name } | |||
| } | |||
| } | |||
| impl fmt::Display for NamespacedType { | |||
| fn fmt(&self, f: &mut fmt::Formatter<'_>) -> fmt::Result { | |||
| write!(f, "{}/{}/{}", self.package, self.namespace, self.name) | |||
| } | |||
| } | |||
| /// A string type | |||
| #[derive(Debug, Clone, Copy, PartialEq, Eq)] | |||
| pub enum GenericString { | |||
| String, | |||
| WString, | |||
| BoundedString(usize), | |||
| BoundedWString(usize), | |||
| } | |||
| impl GenericString { | |||
| const fn is_wide(self) -> bool { | |||
| matches!(self, Self::WString | Self::BoundedWString(_)) | |||
| } | |||
| fn type_tokens(self) -> impl ToTokens { | |||
| if self.is_wide() { | |||
| quote! { crate::_core::string::U16String } | |||
| } else { | |||
| quote! { ::std::string::String } | |||
| } | |||
| } | |||
| fn raw_type_tokens(self) -> impl ToTokens { | |||
| if self.is_wide() { | |||
| quote! { crate::_core::FFIWString } | |||
| } else { | |||
| quote! { crate::_core::FFIString } | |||
| } | |||
| } | |||
| fn raw_ref_type_tokens(self) -> impl ToTokens { | |||
| if self.is_wide() { | |||
| quote! { crate::_core::OwnedFFIWString } | |||
| } else { | |||
| quote! { crate::_core::OwnedFFIString } | |||
| } | |||
| } | |||
| fn value_tokens(self, value: &str) -> impl ToTokens { | |||
| // TODO: Assertion | |||
| let value = Literal::string(value); | |||
| if self.is_wide() { | |||
| quote! { ::widestring::U16String::from_str(#value) } | |||
| } else { | |||
| quote! { ::std::string::String::from(#value) } | |||
| } | |||
| } | |||
| } | |||
| impl From<GenericUnboundedString> for GenericString { | |||
| fn from(t: GenericUnboundedString) -> Self { | |||
| match t { | |||
| GenericUnboundedString::String => Self::String, | |||
| GenericUnboundedString::WString => Self::WString, | |||
| } | |||
| } | |||
| } | |||
| /// A generic unbounded string type | |||
| #[derive(Debug, Clone, Copy, PartialEq, Eq)] | |||
| pub enum GenericUnboundedString { | |||
| String, | |||
| WString, | |||
| } | |||
| impl GenericUnboundedString { | |||
| fn type_tokens(self) -> impl ToTokens { | |||
| quote! { &'static str } | |||
| } | |||
| fn value_tokens(self, value: &str) -> impl ToTokens { | |||
| let value = Literal::string(value); | |||
| quote! { #value } | |||
| } | |||
| } | |||
| /// A type which can be used inside nested types | |||
| #[derive(Debug, Clone, PartialEq, Eq)] | |||
| pub enum NestableType { | |||
| BasicType(BasicType), | |||
| NamedType(NamedType), | |||
| NamespacedType(NamespacedType), | |||
| GenericString(GenericString), | |||
| } | |||
| impl NestableType { | |||
| pub fn type_tokens(&self, package: &str) -> impl ToTokens { | |||
| match self { | |||
| Self::BasicType(t) => { | |||
| let token = t.type_tokens(); | |||
| quote! { #token } | |||
| } | |||
| Self::NamedType(t) => { | |||
| let token = t.type_tokens(package); | |||
| quote! { #token } | |||
| } | |||
| Self::NamespacedType(t) => { | |||
| let token = t.type_tokens(); | |||
| quote! { #token } | |||
| } | |||
| Self::GenericString(t) => { | |||
| let token = t.type_tokens(); | |||
| quote! { #token } | |||
| } | |||
| } | |||
| } | |||
| pub fn raw_type_tokens(&self, package: &str) -> impl ToTokens { | |||
| match self { | |||
| Self::BasicType(t) => { | |||
| let token = t.type_tokens(); | |||
| quote! { #token } | |||
| } | |||
| Self::NamedType(t) => { | |||
| let token = t.raw_type_tokens(package); | |||
| quote! { #token } | |||
| } | |||
| Self::NamespacedType(t) => { | |||
| let token = t.raw_type_tokens(); | |||
| quote! { #token } | |||
| } | |||
| Self::GenericString(t) => { | |||
| let token = t.raw_type_tokens(); | |||
| quote! { #token } | |||
| } | |||
| } | |||
| } | |||
| pub fn raw_ref_type_tokens(&self, package: &str) -> impl ToTokens { | |||
| match self { | |||
| Self::BasicType(t) => { | |||
| let token = t.type_tokens(); | |||
| quote! { #token } | |||
| } | |||
| Self::NamedType(t) => { | |||
| let token = t.raw_ref_type_tokens(package); | |||
| quote! { #token } | |||
| } | |||
| Self::NamespacedType(t) => { | |||
| let token = t.raw_ref_type_tokens(); | |||
| quote! { #token } | |||
| } | |||
| Self::GenericString(t) => { | |||
| let token = t.raw_ref_type_tokens(); | |||
| quote! { #token } | |||
| } | |||
| } | |||
| } | |||
| pub fn value_tokens(&self, default: &str) -> impl ToTokens { | |||
| match self { | |||
| Self::BasicType(t) => { | |||
| let token = t.value_tokens(default); | |||
| quote! { #token } | |||
| } | |||
| Self::GenericString(t) => { | |||
| let token = t.value_tokens(default); | |||
| quote! { #token } | |||
| } | |||
| _ => unreachable!(), | |||
| } | |||
| } | |||
| } | |||
| define_enum_from!(NestableType, BasicType, Self::BasicType); | |||
| define_enum_from!(NestableType, NamedType, Self::NamedType); | |||
| define_enum_from!(NestableType, NamespacedType, Self::NamespacedType); | |||
| define_enum_from!(NestableType, GenericString, Self::GenericString); | |||
| /// A primitive type which can be used for constant | |||
| #[derive(Debug, Clone, Copy, PartialEq, Eq)] | |||
| pub enum PrimitiveType { | |||
| BasicType(BasicType), | |||
| GenericUnboundedString(GenericUnboundedString), | |||
| } | |||
| impl PrimitiveType { | |||
| pub fn type_tokens(self) -> impl ToTokens { | |||
| match self { | |||
| Self::BasicType(t) => { | |||
| let token = t.type_tokens(); | |||
| quote! { #token } | |||
| } | |||
| Self::GenericUnboundedString(t) => { | |||
| let token = t.type_tokens(); | |||
| quote! { #token } | |||
| } | |||
| } | |||
| } | |||
| pub fn value_tokens(self, value: &str) -> impl ToTokens { | |||
| match self { | |||
| Self::BasicType(t) => { | |||
| let token = t.value_tokens(value); | |||
| quote! { #token } | |||
| } | |||
| Self::GenericUnboundedString(t) => { | |||
| let token = t.value_tokens(value); | |||
| quote! { #token } | |||
| } | |||
| } | |||
| } | |||
| } | |||
| define_enum_from!(PrimitiveType, BasicType, Self::BasicType); | |||
| define_enum_from!( | |||
| PrimitiveType, | |||
| GenericUnboundedString, | |||
| Self::GenericUnboundedString | |||
| ); | |||
| @@ -0,0 +1,109 @@ | |||
| use quote::{quote, ToTokens}; | |||
| use super::primitives::*; | |||
| /// An array type with a static size | |||
| #[derive(Debug, Clone, PartialEq, Eq)] | |||
| pub struct Array { | |||
| /// The type of the elements | |||
| pub value_type: NestableType, | |||
| /// The number of elements in the array | |||
| pub size: usize, | |||
| } | |||
| impl Array { | |||
| pub fn type_tokens(&self, package: &str) -> impl ToTokens { | |||
| let inner_type = self.value_type.type_tokens(package); | |||
| let size = self.size; | |||
| quote! { [#inner_type; #size] } | |||
| } | |||
| pub fn raw_type_tokens(&self, package: &str) -> impl ToTokens { | |||
| let inner_type = self.value_type.raw_type_tokens(package); | |||
| let size = self.size; | |||
| quote! { [#inner_type; #size] } | |||
| } | |||
| pub fn raw_ref_type_tokens(&self, package: &str) -> impl ToTokens { | |||
| let inner_type = self.value_type.raw_ref_type_tokens(package); | |||
| let size = self.size; | |||
| quote! { [#inner_type; #size] } | |||
| } | |||
| } | |||
| /// A sequence type with an unlimited number of elements | |||
| #[derive(Debug, Clone, PartialEq, Eq)] | |||
| pub struct Sequence { | |||
| /// The type of the elements | |||
| pub value_type: NestableType, | |||
| } | |||
| impl Sequence { | |||
| pub fn type_tokens(&self, package: &str) -> impl ToTokens { | |||
| let inner_type = self.value_type.type_tokens(package); | |||
| quote! { std::vec::Vec<#inner_type> } | |||
| } | |||
| pub fn raw_type_tokens(&self, package: &str) -> impl ToTokens { | |||
| let inner_type = self.value_type.raw_type_tokens(package); | |||
| quote! { crate::_core::FFISeq<#inner_type> } | |||
| } | |||
| pub fn raw_ref_type_tokens(&self, package: &str) -> impl ToTokens { | |||
| let inner_type = self.value_type.raw_ref_type_tokens(package); | |||
| match self.value_type { | |||
| NestableType::BasicType(_) => { | |||
| quote! { crate::_core::RefFFISeq<#inner_type> } | |||
| } | |||
| _ => quote! { crate::_core::OwnedFFISeq<#inner_type> }, | |||
| } | |||
| } | |||
| } | |||
| /// A sequence type with a maximum number of elements | |||
| #[derive(Debug, Clone, PartialEq, Eq)] | |||
| pub struct BoundedSequence { | |||
| /// The type of the elements | |||
| pub value_type: NestableType, | |||
| /// The maximum number of elements in the sequence | |||
| pub max_size: usize, | |||
| } | |||
| impl BoundedSequence { | |||
| pub fn type_tokens(&self, package: &str) -> impl ToTokens { | |||
| let inner_type = self.value_type.type_tokens(package); | |||
| quote! { std::vec::Vec<#inner_type> } | |||
| } | |||
| pub fn raw_type_tokens(&self, package: &str) -> impl ToTokens { | |||
| let inner_type = self.value_type.raw_type_tokens(package); | |||
| quote! { crate::_core::FFISeq<#inner_type> } | |||
| } | |||
| pub fn raw_ref_type_tokens(&self, package: &str) -> impl ToTokens { | |||
| let inner_type = self.value_type.raw_ref_type_tokens(package); | |||
| match self.value_type { | |||
| NestableType::BasicType(_) => { | |||
| quote! { crate::_core::RefFFISeq<#inner_type> } | |||
| } | |||
| _ => quote! { crate::_core::OwnedFFISeq<#inner_type> }, | |||
| } | |||
| } | |||
| } | |||
| /// An array type of a primitive type | |||
| #[derive(Debug, Clone, PartialEq, Eq)] | |||
| pub struct PrimitiveArray { | |||
| /// The type of the elements | |||
| pub value_type: PrimitiveType, | |||
| /// The number of elements in the array | |||
| pub size: usize, | |||
| } | |||
| impl PrimitiveArray { | |||
| pub fn type_tokens(&self) -> impl ToTokens { | |||
| let inner_type = self.value_type.type_tokens(); | |||
| let size = self.size; | |||
| quote! { [#inner_type; #size] } | |||
| } | |||
| } | |||
| @@ -0,0 +1,76 @@ | |||
| use heck::SnakeCase; | |||
| use quote::{format_ident, quote, ToTokens}; | |||
| use super::Message; | |||
| /// A service definition | |||
| #[derive(Debug, Clone)] | |||
| pub struct Service { | |||
| /// The name of The package | |||
| pub package: String, | |||
| /// The name of the service | |||
| pub name: String, | |||
| /// The type of the request | |||
| pub request: Message, | |||
| /// The type of the response | |||
| pub response: Message, | |||
| } | |||
| impl Service { | |||
| pub fn token_stream_with_mod(&self) -> impl ToTokens { | |||
| let mod_name = format_ident!("_{}", self.name.to_snake_case()); | |||
| let inner = self.token_stream(); | |||
| quote! { | |||
| pub use #mod_name::*; | |||
| mod #mod_name { | |||
| #inner | |||
| } | |||
| } | |||
| } | |||
| pub fn token_stream(&self) -> impl ToTokens { | |||
| let srv_type = format_ident!("{}", self.name); | |||
| let req_type = format_ident!("{}_Request", self.name); | |||
| let res_type = format_ident!("{}_Response", self.name); | |||
| let request_body = self.request.token_stream(); | |||
| let response_body = self.response.token_stream(); | |||
| quote! { | |||
| use std::os::raw::c_void; | |||
| pub use self::request::*; | |||
| pub use self::response::*; | |||
| #[allow(non_camel_case_types)] | |||
| #[derive(std::fmt::Debug)] | |||
| pub struct #srv_type; | |||
| impl crate::_core::ServiceT for #srv_type { | |||
| type Request = #req_type; | |||
| type Response = #res_type; | |||
| } | |||
| mod request { | |||
| #request_body | |||
| } // mod request | |||
| mod response { | |||
| #response_body | |||
| } // mod response | |||
| #[cfg(test)] | |||
| mod test { | |||
| use super::*; | |||
| use crate::_core::ServiceT; | |||
| #[test] | |||
| fn test_type_support() { | |||
| let ptr = #srv_type::type_support(); | |||
| assert!(!ptr.is_null()); | |||
| } | |||
| } | |||
| } | |||
| } | |||
| } | |||
| @@ -0,0 +1,8 @@ | |||
| #goal definition | |||
| int32 order | |||
| --- | |||
| #result definition | |||
| int32[] sequence | |||
| --- | |||
| #feedback | |||
| int32[] sequence | |||
| @@ -0,0 +1,34 @@ | |||
| # Arrays of different types | |||
| bool[3] bool_values | |||
| byte[3] byte_values | |||
| char[3] char_values | |||
| float32[3] float32_values | |||
| float64[3] float64_values | |||
| int8[3] int8_values | |||
| uint8[3] uint8_values | |||
| int16[3] int16_values | |||
| uint16[3] uint16_values | |||
| int32[3] int32_values | |||
| uint32[3] uint32_values | |||
| int64[3] int64_values | |||
| uint64[3] uint64_values | |||
| string[3] string_values | |||
| BasicTypes[3] basic_types_values | |||
| Constants[3] constants_values | |||
| Defaults[3] defaults_values | |||
| bool[3] bool_values_default [false, true, false] | |||
| byte[3] byte_values_default [0, 1, 255] | |||
| char[3] char_values_default [0, 1, 127] | |||
| float32[3] float32_values_default [1.125, 0.0, -1.125] | |||
| float64[3] float64_values_default [3.1415, 0.0, -3.1415] | |||
| int8[3] int8_values_default [0, 127, -128] | |||
| uint8[3] uint8_values_default [0, 1, 255] | |||
| int16[3] int16_values_default [0, 32767, -32768] | |||
| uint16[3] uint16_values_default [0, 1, 65535] | |||
| int32[3] int32_values_default [0, 2147483647, -2147483648] | |||
| uint32[3] uint32_values_default [0, 1, 4294967295] | |||
| int64[3] int64_values_default [0, 9223372036854775807, -9223372036854775808] | |||
| uint64[3] uint64_values_default [0, 1, 18446744073709551615] | |||
| string[3] string_values_default ["", "max value", "min value"] | |||
| # Regression test: check alignment of basic field after an array field is correct | |||
| int32 alignment_check | |||
| @@ -0,0 +1,13 @@ | |||
| bool bool_value | |||
| byte byte_value | |||
| char char_value | |||
| float32 float32_value | |||
| float64 float64_value | |||
| int8 int8_value | |||
| uint8 uint8_value | |||
| int16 int16_value | |||
| uint16 uint16_value | |||
| int32 int32_value | |||
| uint32 uint32_value | |||
| int64 int64_value | |||
| uint64 uint64_value | |||
| @@ -0,0 +1,34 @@ | |||
| # Bounded sequences of different types | |||
| bool[<=3] bool_values | |||
| byte[<=3] byte_values | |||
| char[<=3] char_values | |||
| float32[<=3] float32_values | |||
| float64[<=3] float64_values | |||
| int8[<=3] int8_values | |||
| uint8[<=3] uint8_values | |||
| int16[<=3] int16_values | |||
| uint16[<=3] uint16_values | |||
| int32[<=3] int32_values | |||
| uint32[<=3] uint32_values | |||
| int64[<=3] int64_values | |||
| uint64[<=3] uint64_values | |||
| string[<=3] string_values | |||
| BasicTypes[<=3] basic_types_values | |||
| Constants[<=3] constants_values | |||
| Defaults[<=3] defaults_values | |||
| bool[<=3] bool_values_default [false, true, false] | |||
| byte[<=3] byte_values_default [0, 1, 255] | |||
| char[<=3] char_values_default [0, 1, 127] | |||
| float32[<=3] float32_values_default [1.125, 0.0, -1.125] | |||
| float64[<=3] float64_values_default [3.1415, 0.0, -3.1415] | |||
| int8[<=3] int8_values_default [0, 127, -128] | |||
| uint8[<=3] uint8_values_default [0, 1, 255] | |||
| int16[<=3] int16_values_default [0, 32767, -32768] | |||
| uint16[<=3] uint16_values_default [0, 1, 65535] | |||
| int32[<=3] int32_values_default [0, 2147483647, -2147483648] | |||
| uint32[<=3] uint32_values_default [0, 1, 4294967295] | |||
| int64[<=3] int64_values_default [0, 9223372036854775807, -9223372036854775808] | |||
| uint64[<=3] uint64_values_default [0, 1, 18446744073709551615] | |||
| string[<=3] string_values_default ["", "max value", "min value"] | |||
| # Regression test: check alignment of basic field after a sequence field is correct | |||
| int32 alignment_check | |||
| @@ -0,0 +1,13 @@ | |||
| bool BOOL_CONST=true | |||
| byte BYTE_CONST=50 | |||
| char CHAR_CONST=100 | |||
| float32 FLOAT32_CONST=1.125 | |||
| float64 FLOAT64_CONST=1.125 | |||
| int8 INT8_CONST=-50 | |||
| uint8 UINT8_CONST=200 | |||
| int16 INT16_CONST=-1000 | |||
| uint16 UINT16_CONST=2000 | |||
| int32 INT32_CONST=-30000 | |||
| uint32 UINT32_CONST=60000 | |||
| int64 INT64_CONST=-40000000 | |||
| uint64 UINT64_CONST=50000000 | |||
| @@ -0,0 +1,13 @@ | |||
| bool bool_value true | |||
| byte byte_value 50 | |||
| char char_value 100 | |||
| float32 float32_value 1.125 | |||
| float64 float64_value 1.125 | |||
| int8 int8_value -50 | |||
| uint8 uint8_value 200 | |||
| int16 int16_value -1000 | |||
| uint16 uint16_value 2000 | |||
| int32 int32_value -30000 | |||
| uint32 uint32_value 60000 | |||
| int64 int64_value -40000000 | |||
| uint64 uint64_value 50000000 | |||
| @@ -0,0 +1,10 @@ | |||
| # Mulitple levels of nested messages | |||
| Arrays[3] array_of_arrays | |||
| BoundedSequences[3] array_of_bounded_sequences | |||
| UnboundedSequences[3] array_of_unbounded_sequences | |||
| Arrays[<=3] bounded_sequence_of_arrays | |||
| BoundedSequences[<=3] bounded_sequence_of_bounded_sequences | |||
| UnboundedSequences[<=3] bounded_sequence_of_unbounded_sequences | |||
| Arrays[] unbounded_sequence_of_arrays | |||
| BoundedSequences[] unbounded_sequence_of_bounded_sequences | |||
| UnboundedSequences[] unbounded_sequence_of_unbounded_sequences | |||
| @@ -0,0 +1 @@ | |||
| BasicTypes basic_types_value | |||
| @@ -0,0 +1,13 @@ | |||
| string string_value | |||
| string string_value_default1 "Hello world!" | |||
| string string_value_default2 "Hello'world!" | |||
| string string_value_default3 'Hello"world!' | |||
| string string_value_default4 'Hello\'world!' | |||
| string string_value_default5 "Hello\"world!" | |||
| string STRING_CONST="Hello world!" | |||
| string<=22 bounded_string_value | |||
| string<=22 bounded_string_value_default1 "Hello world!" | |||
| string<=22 bounded_string_value_default2 "Hello'world!" | |||
| string<=22 bounded_string_value_default3 'Hello"world!' | |||
| string<=22 bounded_string_value_default4 'Hello\'world!' | |||
| string<=22 bounded_string_value_default5 "Hello\"world!" | |||
| @@ -0,0 +1,34 @@ | |||
| # Unbounded sequences of different types | |||
| bool[] bool_values | |||
| byte[] byte_values | |||
| char[] char_values | |||
| float32[] float32_values | |||
| float64[] float64_values | |||
| int8[] int8_values | |||
| uint8[] uint8_values | |||
| int16[] int16_values | |||
| uint16[] uint16_values | |||
| int32[] int32_values | |||
| uint32[] uint32_values | |||
| int64[] int64_values | |||
| uint64[] uint64_values | |||
| string[] string_values | |||
| BasicTypes[] basic_types_values | |||
| Constants[] constants_values | |||
| Defaults[] defaults_values | |||
| bool[] bool_values_default [false, true, false] | |||
| byte[] byte_values_default [0, 1, 255] | |||
| char[] char_values_default [0, 1, 127] | |||
| float32[] float32_values_default [1.125, 0.0, -1.125] | |||
| float64[] float64_values_default [3.1415, 0.0, -3.1415] | |||
| int8[] int8_values_default [0, 127, -128] | |||
| uint8[] uint8_values_default [0, 1, 255] | |||
| int16[] int16_values_default [0, 32767, -32768] | |||
| uint16[] uint16_values_default [0, 1, 65535] | |||
| int32[] int32_values_default [0, 2147483647, -2147483648] | |||
| uint32[] uint32_values_default [0, 1, 4294967295] | |||
| int64[] int64_values_default [0, 9223372036854775807, -9223372036854775808] | |||
| uint64[] uint64_values_default [0, 1, 18446744073709551615] | |||
| string[] string_values_default ["", "max value", "min value"] | |||
| # Regression test: check alignment of basic field after a sequence field is correct | |||
| int32 alignment_check | |||
| @@ -0,0 +1,10 @@ | |||
| wstring wstring_value | |||
| wstring wstring_value_default1 "Hello world!" | |||
| wstring wstring_value_default2 "Hellö wörld!" | |||
| wstring wstring_value_default3 "ハローワールド" | |||
| #wstring WSTRING_CONST="Hello world!" | |||
| #wstring<=22 bounded_wstring_value | |||
| #wstring<=22 bounded_wstring_value_default1 "Hello world!" | |||
| wstring[3] array_of_wstrings | |||
| wstring[<=3] bounded_sequence_of_wstrings | |||
| wstring[] unbounded_sequence_of_wstrings | |||
| @@ -0,0 +1,63 @@ | |||
| bool[3] bool_values | |||
| byte[3] byte_values | |||
| char[3] char_values | |||
| float32[3] float32_values | |||
| float64[3] float64_values | |||
| int8[3] int8_values | |||
| uint8[3] uint8_values | |||
| int16[3] int16_values | |||
| uint16[3] uint16_values | |||
| int32[3] int32_values | |||
| uint32[3] uint32_values | |||
| int64[3] int64_values | |||
| uint64[3] uint64_values | |||
| string[3] string_values | |||
| BasicTypes[3] basic_types_values | |||
| Constants[3] constants_values | |||
| Defaults[3] defaults_values | |||
| bool[3] bool_values_default [false, true, false] | |||
| byte[3] byte_values_default [0, 1, 255] | |||
| char[3] char_values_default [0, 1, 127] | |||
| float32[3] float32_values_default [1.125, 0.0, -1.125] | |||
| float64[3] float64_values_default [3.1415, 0.0, -3.1415] | |||
| int8[3] int8_values_default [0, 127, -128] | |||
| uint8[3] uint8_values_default [0, 1, 255] | |||
| int16[3] int16_values_default [0, 32767, -32768] | |||
| uint16[3] uint16_values_default [0, 1, 65535] | |||
| int32[3] int32_values_default [0, 2147483647, -2147483648] | |||
| uint32[3] uint32_values_default [0, 1, 4294967295] | |||
| int64[3] int64_values_default [0, 9223372036854775807, -9223372036854775808] | |||
| uint64[3] uint64_values_default [0, 1, 18446744073709551615] | |||
| string[3] string_values_default ["", "max value", "min value"] | |||
| --- | |||
| bool[3] bool_values | |||
| byte[3] byte_values | |||
| char[3] char_values | |||
| float32[3] float32_values | |||
| float64[3] float64_values | |||
| int8[3] int8_values | |||
| uint8[3] uint8_values | |||
| int16[3] int16_values | |||
| uint16[3] uint16_values | |||
| int32[3] int32_values | |||
| uint32[3] uint32_values | |||
| int64[3] int64_values | |||
| uint64[3] uint64_values | |||
| string[3] string_values | |||
| BasicTypes[3] basic_types_values | |||
| Constants[3] constants_values | |||
| Defaults[3] defaults_values | |||
| bool[3] bool_values_default [false, true, false] | |||
| byte[3] byte_values_default [0, 1, 255] | |||
| char[3] char_values_default [0, 1, 127] | |||
| float32[3] float32_values_default [1.125, 0.0, -1.125] | |||
| float64[3] float64_values_default [3.1415, 0.0, -3.1415] | |||
| int8[3] int8_values_default [0, 127, -128] | |||
| uint8[3] uint8_values_default [0, 1, 255] | |||
| int16[3] int16_values_default [0, 32767, -32768] | |||
| uint16[3] uint16_values_default [0, 1, 65535] | |||
| int32[3] int32_values_default [0, 2147483647, -2147483648] | |||
| uint32[3] uint32_values_default [0, 1, 4294967295] | |||
| int64[3] int64_values_default [0, 9223372036854775807, -9223372036854775808] | |||
| uint64[3] uint64_values_default [0, 1, 18446744073709551615] | |||
| string[3] string_values_default ["", "max value", "min value"] | |||
| @@ -0,0 +1,29 @@ | |||
| bool bool_value | |||
| byte byte_value | |||
| char char_value | |||
| float32 float32_value | |||
| float64 float64_value | |||
| int8 int8_value | |||
| uint8 uint8_value | |||
| int16 int16_value | |||
| uint16 uint16_value | |||
| int32 int32_value | |||
| uint32 uint32_value | |||
| int64 int64_value | |||
| uint64 uint64_value | |||
| string string_value | |||
| --- | |||
| bool bool_value | |||
| byte byte_value | |||
| char char_value | |||
| float32 float32_value | |||
| float64 float64_value | |||
| int8 int8_value | |||
| uint8 uint8_value | |||
| int16 int16_value | |||
| uint16 uint16_value | |||
| int32 int32_value | |||
| uint32 uint32_value | |||
| int64 int64_value | |||
| uint64 uint64_value | |||
| string string_value | |||
| @@ -0,0 +1 @@ | |||
| --- | |||
| @@ -0,0 +1,20 @@ | |||
| [package] | |||
| name = "dora-ros2-bridge-python" | |||
| version = "0.1.0" | |||
| edition = "2021" | |||
| [dependencies] | |||
| dora-ros2-bridge = { path = "..", default-features = false } | |||
| dora-ros2-bridge-msg-gen = { path = "../msg-gen" } | |||
| pyo3 = { version = "0.19", features = ["eyre", "abi3-py37", "serde"] } | |||
| eyre = "0.6" | |||
| serde = "1.0.166" | |||
| flume = "0.10.14" | |||
| arrow = { version = "45.0.0", features = ["pyarrow"] } | |||
| dora-node-api-python = { git = "https://github.com/dora-rs/dora.git" } | |||
| futures = "0.3.28" | |||
| [lib] | |||
| name = "dora_ros2_bridge" | |||
| crate-type = ["cdylib"] | |||
| @@ -0,0 +1,11 @@ | |||
| ## Building | |||
| To build the Python module for development: | |||
| ````bash | |||
| python3 -m venv .env | |||
| source .env/bin/activate | |||
| pip install maturin | |||
| maturin develop | |||
| ```` | |||
| @@ -0,0 +1,10 @@ | |||
| [build-system] | |||
| requires = ["maturin>=0.13.2"] | |||
| build-backend = "maturin" | |||
| [project] | |||
| name = "dora-ros2-bridge" | |||
| dependencies = ['pyarrow'] | |||
| [tool.maturin] | |||
| features = ["pyo3/extension-module"] | |||
| @@ -0,0 +1,291 @@ | |||
| use std::{ | |||
| collections::HashMap, | |||
| path::{Path, PathBuf}, | |||
| sync::Arc, | |||
| }; | |||
| use ::dora_ros2_bridge::{ros2_client, rustdds}; | |||
| use arrow::pyarrow::{FromPyArrow, ToPyArrow}; | |||
| use dora::{ExternalEventStream, Node}; | |||
| use dora_ros2_bridge_msg_gen::types::Message; | |||
| use eyre::{eyre, Context, ContextCompat}; | |||
| use futures::{Stream, StreamExt}; | |||
| use pyo3::{ | |||
| prelude::{pyclass, pymethods, pymodule}, | |||
| types::PyModule, | |||
| wrap_pyfunction, PyAny, PyErr, PyObject, PyResult, Python, ToPyObject, | |||
| }; | |||
| use typed::{ | |||
| deserialize::{Ros2Value, TypedDeserializer}, | |||
| for_message, TypeInfo, TypedValue, | |||
| }; | |||
| pub mod qos; | |||
| pub mod typed; | |||
| #[pyclass] | |||
| pub struct Ros2Context { | |||
| context: ros2_client::Context, | |||
| messages: Arc<HashMap<String, HashMap<String, Message>>>, | |||
| } | |||
| #[pymethods] | |||
| impl Ros2Context { | |||
| #[new] | |||
| pub fn new(ros_paths: Option<Vec<PathBuf>>) -> eyre::Result<Self> { | |||
| let ament_prefix_path = std::env::var("AMENT_PREFIX_PATH"); | |||
| let empty = String::new(); | |||
| let paths: Vec<_> = match &ros_paths { | |||
| Some(paths) => paths.iter().map(|p| p.as_path()).collect(), | |||
| None => { | |||
| let ament_prefix_path_parsed = match &ament_prefix_path { | |||
| Ok(path) => path, | |||
| Err(std::env::VarError::NotPresent) => &empty, | |||
| Err(std::env::VarError::NotUnicode(s)) => { | |||
| eyre::bail!( | |||
| "AMENT_PREFIX_PATH is not valid unicode: `{}`", | |||
| s.to_string_lossy() | |||
| ); | |||
| } | |||
| }; | |||
| ament_prefix_path_parsed.split(':').map(Path::new).collect() | |||
| } | |||
| }; | |||
| let packages = dora_ros2_bridge_msg_gen::get_packages(&paths) | |||
| .map_err(|err| eyre!(err)) | |||
| .context("failed to parse ROS2 message types")?; | |||
| let mut messages = HashMap::new(); | |||
| for message in packages.into_iter().flat_map(|p| p.messages.into_iter()) { | |||
| let entry: &mut HashMap<String, Message> = | |||
| messages.entry(message.package.clone()).or_default(); | |||
| entry.insert(message.name.clone(), message); | |||
| } | |||
| Ok(Self { | |||
| context: ros2_client::Context::new()?, | |||
| messages: Arc::new(messages), | |||
| }) | |||
| } | |||
| /// Create a new ROS2 node | |||
| pub fn new_node( | |||
| &self, | |||
| name: &str, | |||
| namespace: &str, | |||
| options: Ros2NodeOptions, | |||
| ) -> eyre::Result<Ros2Node> { | |||
| Ok(Ros2Node { | |||
| node: self.context.new_node(name, namespace, options.into())?, | |||
| messages: self.messages.clone(), | |||
| }) | |||
| } | |||
| } | |||
| #[pyclass] | |||
| pub struct Ros2Node { | |||
| node: ros2_client::Node, | |||
| messages: Arc<HashMap<String, HashMap<String, Message>>>, | |||
| } | |||
| #[pymethods] | |||
| impl Ros2Node { | |||
| pub fn create_topic( | |||
| &self, | |||
| name: &str, | |||
| message_type: String, | |||
| qos: qos::Ros2QosPolicies, | |||
| ) -> eyre::Result<Ros2Topic> { | |||
| let (namespace_name, message_name) = message_type.split_once("::").with_context(|| { | |||
| format!( | |||
| "message type must be of form `package::type`, is `{}`", | |||
| message_type | |||
| ) | |||
| })?; | |||
| let encoded_type_name = format!("{namespace_name}::msg::dds_::{message_name}_"); | |||
| let topic = self | |||
| .node | |||
| .create_topic(name, encoded_type_name, &qos.into())?; | |||
| let type_info = for_message(&self.messages, namespace_name, message_name) | |||
| .context("failed to determine type info for message")?; | |||
| Ok(Ros2Topic { topic, type_info }) | |||
| } | |||
| pub fn create_publisher( | |||
| &mut self, | |||
| topic: &Ros2Topic, | |||
| qos: Option<qos::Ros2QosPolicies>, | |||
| ) -> eyre::Result<Ros2Publisher> { | |||
| let publisher = self | |||
| .node | |||
| .create_publisher(&topic.topic, qos.map(Into::into))?; | |||
| Ok(Ros2Publisher { | |||
| publisher, | |||
| type_info: topic.type_info.clone(), | |||
| }) | |||
| } | |||
| pub fn create_subscription( | |||
| &mut self, | |||
| topic: &Ros2Topic, | |||
| qos: Option<qos::Ros2QosPolicies>, | |||
| ) -> eyre::Result<Ros2Subscription> { | |||
| let subscription = self | |||
| .node | |||
| .create_subscription(&topic.topic, qos.map(Into::into))?; | |||
| Ok(Ros2Subscription { | |||
| subscription, | |||
| deserializer: TypedDeserializer::new(topic.type_info.clone()), | |||
| }) | |||
| } | |||
| pub fn create_subscription_stream( | |||
| &mut self, | |||
| topic: &Ros2Topic, | |||
| qos: Option<qos::Ros2QosPolicies>, | |||
| ) -> eyre::Result<ExternalEventStream> { | |||
| let subscription = self.create_subscription(topic, qos)?; | |||
| let stream = futures::stream::poll_fn(move |cx| { | |||
| let s = subscription.as_stream().map(|item| { | |||
| match item.context("failed to read ROS2 message") { | |||
| Ok((value, _info)) => Python::with_gil(|py| { | |||
| value | |||
| .to_pyarrow(py) | |||
| .context("failed to convert value to pyarrow") | |||
| .unwrap_or_else(|err| PyErr::from(err).to_object(py)) | |||
| }), | |||
| Err(err) => Python::with_gil(|py| PyErr::from(err).to_object(py)), | |||
| } | |||
| }); | |||
| futures::pin_mut!(s); | |||
| s.poll_next_unpin(cx) | |||
| }); | |||
| Ok(ExternalEventStream::from(stream)) | |||
| } | |||
| } | |||
| #[derive(Debug, Clone, Default)] | |||
| #[pyclass] | |||
| #[non_exhaustive] | |||
| pub struct Ros2NodeOptions { | |||
| pub rosout: bool, | |||
| } | |||
| #[pymethods] | |||
| impl Ros2NodeOptions { | |||
| #[new] | |||
| pub fn new(rosout: Option<bool>) -> Self { | |||
| Self { | |||
| rosout: rosout.unwrap_or(false), | |||
| } | |||
| } | |||
| } | |||
| impl From<Ros2NodeOptions> for ros2_client::NodeOptions { | |||
| fn from(value: Ros2NodeOptions) -> Self { | |||
| ros2_client::NodeOptions::new().enable_rosout(value.rosout) | |||
| } | |||
| } | |||
| #[pyclass] | |||
| #[non_exhaustive] | |||
| pub struct Ros2Topic { | |||
| topic: rustdds::Topic, | |||
| type_info: TypeInfo, | |||
| } | |||
| #[pyclass] | |||
| #[non_exhaustive] | |||
| pub struct Ros2Publisher { | |||
| publisher: ros2_client::Publisher<TypedValue<'static>>, | |||
| type_info: TypeInfo, | |||
| } | |||
| #[pymethods] | |||
| impl Ros2Publisher { | |||
| pub fn publish(&self, data: &PyAny) -> eyre::Result<()> { | |||
| // TODO: add support for arrow types | |||
| let value = arrow::array::ArrayData::from_pyarrow(data)?; | |||
| //// add type info to ensure correct serialization (e.g. struct types | |||
| //// and map types need to be serialized differently) | |||
| let typed_value = TypedValue { | |||
| value: &value, | |||
| type_info: &self.type_info, | |||
| }; | |||
| self.publisher | |||
| .publish(typed_value) | |||
| .map_err(|e| e.forget_data()) | |||
| .context("publish failed")?; | |||
| Ok(()) | |||
| } | |||
| } | |||
| #[pyclass] | |||
| #[non_exhaustive] | |||
| pub struct Ros2Subscription { | |||
| deserializer: TypedDeserializer, | |||
| subscription: ros2_client::Subscription<Ros2Value>, | |||
| } | |||
| #[pymethods] | |||
| impl Ros2Subscription { | |||
| pub fn next(&self, py: Python) -> eyre::Result<Option<PyObject>> { | |||
| let message = self | |||
| .subscription | |||
| .take_seed(self.deserializer.clone()) | |||
| .context("failed to take next message from subscription")?; | |||
| let Some((value, _info)) = message else { | |||
| return Ok(None) | |||
| }; | |||
| let message = value.to_pyarrow(py)?; | |||
| // TODO: add `info` | |||
| Ok(Some(message)) | |||
| } | |||
| } | |||
| impl Ros2Subscription { | |||
| fn as_stream( | |||
| &self, | |||
| ) -> impl Stream<Item = Result<(Ros2Value, ros2_client::MessageInfo), rustdds::dds::ReadError>> + '_ | |||
| { | |||
| self.subscription | |||
| .async_stream_seed(self.deserializer.clone()) | |||
| } | |||
| } | |||
| impl Stream for Ros2Subscription { | |||
| type Item = Result<(Ros2Value, ros2_client::MessageInfo), rustdds::dds::ReadError>; | |||
| fn poll_next( | |||
| self: std::pin::Pin<&mut Self>, | |||
| cx: &mut std::task::Context<'_>, | |||
| ) -> std::task::Poll<Option<Self::Item>> { | |||
| let s = self.as_stream(); | |||
| futures::pin_mut!(s); | |||
| s.poll_next_unpin(cx) | |||
| } | |||
| } | |||
| #[pymodule] | |||
| fn dora_ros2_bridge(_py: Python, m: &PyModule) -> PyResult<()> { | |||
| m.add_class::<Ros2Context>()?; | |||
| m.add_class::<Ros2Node>()?; | |||
| m.add_class::<Ros2NodeOptions>()?; | |||
| m.add_class::<Ros2Topic>()?; | |||
| m.add_class::<Ros2Publisher>()?; | |||
| m.add_class::<Ros2Subscription>()?; | |||
| m.add_class::<qos::Ros2QosPolicies>()?; | |||
| m.add_class::<qos::Ros2Durability>()?; | |||
| m.add_class::<qos::Ros2Liveliness>()?; | |||
| m.add_function(wrap_pyfunction!(dora::start_runtime, m)?)?; | |||
| m.add_class::<Node>().unwrap(); | |||
| Ok(()) | |||
| } | |||
| @@ -0,0 +1,111 @@ | |||
| use ::dora_ros2_bridge::rustdds::{self, policy}; | |||
| use pyo3::prelude::{pyclass, pymethods}; | |||
| #[derive(Debug, Clone)] | |||
| #[pyclass(get_all, set_all)] | |||
| #[non_exhaustive] | |||
| pub struct Ros2QosPolicies { | |||
| pub durability: Ros2Durability, | |||
| pub liveliness: Ros2Liveliness, | |||
| pub lease_duration: f64, | |||
| pub reliable: bool, | |||
| pub max_blocking_time: f64, | |||
| pub keep_all: bool, | |||
| pub keep_last: i32, | |||
| } | |||
| #[pymethods] | |||
| impl Ros2QosPolicies { | |||
| #[new] | |||
| pub fn new( | |||
| durability: Option<Ros2Durability>, | |||
| liveliness: Option<Ros2Liveliness>, | |||
| reliable: Option<bool>, | |||
| keep_all: Option<bool>, | |||
| lease_duration: Option<f64>, | |||
| max_blocking_time: Option<f64>, | |||
| keep_last: Option<i32>, | |||
| ) -> Self { | |||
| Self { | |||
| durability: durability.unwrap_or(Ros2Durability::Volatile), | |||
| liveliness: liveliness.unwrap_or(Ros2Liveliness::Automatic), | |||
| lease_duration: lease_duration.unwrap_or(f64::INFINITY), | |||
| reliable: reliable.unwrap_or(false), | |||
| max_blocking_time: max_blocking_time.unwrap_or(0.0), | |||
| keep_all: keep_all.unwrap_or(false), | |||
| keep_last: keep_last.unwrap_or(1), | |||
| } | |||
| } | |||
| } | |||
| impl From<Ros2QosPolicies> for rustdds::QosPolicies { | |||
| fn from(value: Ros2QosPolicies) -> Self { | |||
| rustdds::QosPolicyBuilder::new() | |||
| .durability(value.durability.into()) | |||
| .liveliness(value.liveliness.convert(value.lease_duration)) | |||
| .reliability(if value.reliable { | |||
| policy::Reliability::Reliable { | |||
| max_blocking_time: rustdds::Duration::from_frac_seconds( | |||
| value.max_blocking_time, | |||
| ), | |||
| } | |||
| } else { | |||
| policy::Reliability::BestEffort | |||
| }) | |||
| .history(if value.keep_all { | |||
| policy::History::KeepAll | |||
| } else { | |||
| policy::History::KeepLast { | |||
| depth: value.keep_last, | |||
| } | |||
| }) | |||
| .build() | |||
| } | |||
| } | |||
| /// DDS 2.2.3.4 DURABILITY | |||
| #[derive(Copy, Clone, Debug, PartialEq, Eq, PartialOrd, Ord, Hash)] | |||
| #[pyclass] | |||
| pub enum Ros2Durability { | |||
| Volatile, | |||
| TransientLocal, | |||
| Transient, | |||
| Persistent, | |||
| } | |||
| impl From<Ros2Durability> for policy::Durability { | |||
| fn from(value: Ros2Durability) -> Self { | |||
| match value { | |||
| Ros2Durability::Volatile => policy::Durability::Volatile, | |||
| Ros2Durability::TransientLocal => policy::Durability::TransientLocal, | |||
| Ros2Durability::Transient => policy::Durability::Transient, | |||
| Ros2Durability::Persistent => policy::Durability::Persistent, | |||
| } | |||
| } | |||
| } | |||
| /// DDS 2.2.3.11 LIVELINESS | |||
| #[derive(Copy, Clone, Debug, PartialEq)] | |||
| #[pyclass] | |||
| pub enum Ros2Liveliness { | |||
| Automatic, | |||
| ManualByParticipant, | |||
| ManualByTopic, | |||
| } | |||
| impl Ros2Liveliness { | |||
| fn convert(self, lease_duration: f64) -> policy::Liveliness { | |||
| let lease_duration = if lease_duration.is_infinite() { | |||
| rustdds::Duration::DURATION_INFINITE | |||
| } else { | |||
| rustdds::Duration::from_frac_seconds(lease_duration) | |||
| }; | |||
| match self { | |||
| Ros2Liveliness::Automatic => policy::Liveliness::Automatic { lease_duration }, | |||
| Ros2Liveliness::ManualByParticipant => { | |||
| policy::Liveliness::ManualByParticipant { lease_duration } | |||
| } | |||
| Ros2Liveliness::ManualByTopic => policy::Liveliness::ManualByTopic { lease_duration }, | |||
| } | |||
| } | |||
| } | |||
| @@ -0,0 +1,410 @@ | |||
| use super::TypeInfo; | |||
| use arrow::{ | |||
| array::{ | |||
| make_array, Array, ArrayData, BooleanBuilder, Float32Builder, Float64Builder, Int16Builder, | |||
| Int32Builder, Int64Builder, Int8Builder, ListArray, NullArray, StringBuilder, StructArray, | |||
| UInt16Builder, UInt32Builder, UInt64Builder, UInt8Builder, | |||
| }, | |||
| buffer::OffsetBuffer, | |||
| compute::concat, | |||
| datatypes::{DataType, Field, Fields}, | |||
| }; | |||
| use core::fmt; | |||
| use std::{ops::Deref, sync::Arc}; | |||
| #[derive(Debug, Clone, PartialEq)] | |||
| pub struct Ros2Value(ArrayData); | |||
| impl Deref for Ros2Value { | |||
| type Target = ArrayData; | |||
| fn deref(&self) -> &Self::Target { | |||
| &self.0 | |||
| } | |||
| } | |||
| #[derive(Debug, Clone, PartialEq)] | |||
| pub struct TypedDeserializer { | |||
| type_info: TypeInfo, | |||
| } | |||
| impl TypedDeserializer { | |||
| pub fn new(type_info: TypeInfo) -> Self { | |||
| Self { type_info } | |||
| } | |||
| } | |||
| impl<'de> serde::de::DeserializeSeed<'de> for TypedDeserializer { | |||
| type Value = Ros2Value; | |||
| fn deserialize<D>(self, deserializer: D) -> Result<Self::Value, D::Error> | |||
| where | |||
| D: serde::Deserializer<'de>, | |||
| { | |||
| let data_type = self.type_info.data_type; | |||
| let value = match data_type.clone() { | |||
| DataType::Struct(fields) => { | |||
| /// Serde requires that struct and field names are known at | |||
| /// compile time with a `'static` lifetime, which is not | |||
| /// possible in this case. Thus, we need to use dummy names | |||
| /// instead. | |||
| /// | |||
| /// The actual names do not really matter because | |||
| /// the CDR format of ROS2 does not encode struct or field | |||
| /// names. | |||
| const DUMMY_STRUCT_NAME: &str = "struct"; | |||
| const DUMMY_FIELDS: &[&str] = &[""; 100]; | |||
| deserializer.deserialize_struct( | |||
| DUMMY_STRUCT_NAME, | |||
| &DUMMY_FIELDS[..fields.len()], | |||
| StructVisitor { | |||
| fields, | |||
| defaults: self.type_info.defaults, | |||
| }, | |||
| ) | |||
| } | |||
| DataType::List(field) => deserializer.deserialize_seq(ListVisitor { | |||
| field, | |||
| defaults: self.type_info.defaults, | |||
| }), | |||
| DataType::UInt8 => deserializer.deserialize_u8(PrimitiveValueVisitor), | |||
| DataType::UInt16 => deserializer.deserialize_u16(PrimitiveValueVisitor), | |||
| DataType::UInt32 => deserializer.deserialize_u32(PrimitiveValueVisitor), | |||
| DataType::UInt64 => deserializer.deserialize_u64(PrimitiveValueVisitor), | |||
| DataType::Int8 => deserializer.deserialize_i8(PrimitiveValueVisitor), | |||
| DataType::Int16 => deserializer.deserialize_i16(PrimitiveValueVisitor), | |||
| DataType::Int32 => deserializer.deserialize_i32(PrimitiveValueVisitor), | |||
| DataType::Int64 => deserializer.deserialize_i64(PrimitiveValueVisitor), | |||
| DataType::Float32 => deserializer.deserialize_f32(PrimitiveValueVisitor), | |||
| DataType::Float64 => deserializer.deserialize_f64(PrimitiveValueVisitor), | |||
| DataType::Utf8 => deserializer.deserialize_str(PrimitiveValueVisitor), | |||
| _ => todo!(), | |||
| }?; | |||
| debug_assert!( | |||
| value.data_type() == &data_type, | |||
| "Datatype does not correspond to default data type.\n Expected: {:#?} \n but got: {:#?}, with value: {:#?}", data_type, value.data_type(), value | |||
| ); | |||
| Ok(Ros2Value(value)) | |||
| } | |||
| } | |||
| /// Based on https://docs.rs/serde_yaml/0.9.22/src/serde_yaml/value/de.rs.html#14-121 | |||
| struct PrimitiveValueVisitor; | |||
| impl<'de> serde::de::Visitor<'de> for PrimitiveValueVisitor { | |||
| type Value = ArrayData; | |||
| fn expecting(&self, formatter: &mut fmt::Formatter) -> fmt::Result { | |||
| formatter.write_str("a primitive value") | |||
| } | |||
| fn visit_bool<E>(self, b: bool) -> Result<Self::Value, E> | |||
| where | |||
| E: serde::de::Error, | |||
| { | |||
| let mut array = BooleanBuilder::new(); | |||
| array.append_value(b); | |||
| Ok(array.finish().into()) | |||
| } | |||
| fn visit_i8<E>(self, u: i8) -> Result<Self::Value, E> | |||
| where | |||
| E: serde::de::Error, | |||
| { | |||
| let mut array = Int8Builder::new(); | |||
| array.append_value(u); | |||
| Ok(array.finish().into()) | |||
| } | |||
| fn visit_i16<E>(self, u: i16) -> Result<Self::Value, E> | |||
| where | |||
| E: serde::de::Error, | |||
| { | |||
| let mut array = Int16Builder::new(); | |||
| array.append_value(u); | |||
| Ok(array.finish().into()) | |||
| } | |||
| fn visit_i32<E>(self, u: i32) -> Result<Self::Value, E> | |||
| where | |||
| E: serde::de::Error, | |||
| { | |||
| let mut array = Int32Builder::new(); | |||
| array.append_value(u); | |||
| Ok(array.finish().into()) | |||
| } | |||
| fn visit_i64<E>(self, i: i64) -> Result<Self::Value, E> | |||
| where | |||
| E: serde::de::Error, | |||
| { | |||
| let mut array = Int64Builder::new(); | |||
| array.append_value(i); | |||
| Ok(array.finish().into()) | |||
| } | |||
| fn visit_u8<E>(self, u: u8) -> Result<Self::Value, E> | |||
| where | |||
| E: serde::de::Error, | |||
| { | |||
| let mut array = UInt8Builder::new(); | |||
| array.append_value(u); | |||
| Ok(array.finish().into()) | |||
| } | |||
| fn visit_u16<E>(self, u: u16) -> Result<Self::Value, E> | |||
| where | |||
| E: serde::de::Error, | |||
| { | |||
| let mut array = UInt16Builder::new(); | |||
| array.append_value(u); | |||
| Ok(array.finish().into()) | |||
| } | |||
| fn visit_u32<E>(self, u: u32) -> Result<Self::Value, E> | |||
| where | |||
| E: serde::de::Error, | |||
| { | |||
| let mut array = UInt32Builder::new(); | |||
| array.append_value(u); | |||
| Ok(array.finish().into()) | |||
| } | |||
| fn visit_u64<E>(self, u: u64) -> Result<Self::Value, E> | |||
| where | |||
| E: serde::de::Error, | |||
| { | |||
| let mut array = UInt64Builder::new(); | |||
| array.append_value(u); | |||
| Ok(array.finish().into()) | |||
| } | |||
| fn visit_f32<E>(self, f: f32) -> Result<Self::Value, E> | |||
| where | |||
| E: serde::de::Error, | |||
| { | |||
| let mut array = Float32Builder::new(); | |||
| array.append_value(f); | |||
| Ok(array.finish().into()) | |||
| } | |||
| fn visit_f64<E>(self, f: f64) -> Result<Self::Value, E> | |||
| where | |||
| E: serde::de::Error, | |||
| { | |||
| let mut array = Float64Builder::new(); | |||
| array.append_value(f); | |||
| Ok(array.finish().into()) | |||
| } | |||
| fn visit_str<E>(self, s: &str) -> Result<Self::Value, E> | |||
| where | |||
| E: serde::de::Error, | |||
| { | |||
| let mut array = StringBuilder::new(); | |||
| array.append_value(s); | |||
| Ok(array.finish().into()) | |||
| } | |||
| fn visit_string<E>(self, s: String) -> Result<Self::Value, E> | |||
| where | |||
| E: serde::de::Error, | |||
| { | |||
| let mut array = StringBuilder::new(); | |||
| array.append_value(s); | |||
| Ok(array.finish().into()) | |||
| } | |||
| fn visit_unit<E>(self) -> Result<Self::Value, E> | |||
| where | |||
| E: serde::de::Error, | |||
| { | |||
| let array = NullArray::new(0); | |||
| Ok(array.into()) | |||
| } | |||
| fn visit_none<E>(self) -> Result<Self::Value, E> | |||
| where | |||
| E: serde::de::Error, | |||
| { | |||
| let array = NullArray::new(0); | |||
| Ok(array.into()) | |||
| } | |||
| } | |||
| struct StructVisitor { | |||
| fields: Fields, | |||
| defaults: ArrayData, | |||
| } | |||
| impl<'de> serde::de::Visitor<'de> for StructVisitor { | |||
| type Value = ArrayData; | |||
| fn expecting(&self, formatter: &mut fmt::Formatter) -> fmt::Result { | |||
| formatter.write_str("a struct encoded as sequence") | |||
| } | |||
| fn visit_seq<A>(self, mut data: A) -> Result<Self::Value, A::Error> | |||
| where | |||
| A: serde::de::SeqAccess<'de>, | |||
| { | |||
| let mut fields = vec![]; | |||
| let defaults: StructArray = self.defaults.clone().into(); | |||
| for field in self.fields.iter() { | |||
| let default = match defaults.column_by_name(field.name()) { | |||
| Some(value) => value.clone(), | |||
| None => { | |||
| return Err(serde::de::Error::custom(format!( | |||
| "missing field {} for deserialization", | |||
| &field.name() | |||
| ))) | |||
| } | |||
| }; | |||
| let value = match data.next_element_seed(TypedDeserializer { | |||
| type_info: TypeInfo { | |||
| data_type: field.data_type().clone(), | |||
| defaults: default.to_data(), | |||
| }, | |||
| })? { | |||
| Some(value) => make_array(value.0), | |||
| None => default, | |||
| }; | |||
| fields.push(( | |||
| // Recreate a new field as List(UInt8) can be converted to UInt8 | |||
| Arc::new(Field::new(field.name(), value.data_type().clone(), true)), | |||
| value, | |||
| )); | |||
| } | |||
| let struct_array: StructArray = fields.into(); | |||
| Ok(struct_array.into()) | |||
| } | |||
| } | |||
| struct ListVisitor { | |||
| field: Arc<Field>, | |||
| defaults: ArrayData, | |||
| } | |||
| impl<'de> serde::de::Visitor<'de> for ListVisitor { | |||
| type Value = ArrayData; | |||
| fn expecting(&self, formatter: &mut fmt::Formatter) -> fmt::Result { | |||
| formatter.write_str("an array encoded as sequence") | |||
| } | |||
| fn visit_seq<A>(self, mut data: A) -> Result<Self::Value, A::Error> | |||
| where | |||
| A: serde::de::SeqAccess<'de>, | |||
| { | |||
| let data = match self.field.data_type().clone() { | |||
| DataType::UInt8 => { | |||
| let mut array = UInt8Builder::new(); | |||
| while let Some(value) = data.next_element::<u8>()? { | |||
| array.append_value(value); | |||
| } | |||
| Ok(array.finish().into()) | |||
| } | |||
| DataType::UInt16 => { | |||
| let mut array = UInt16Builder::new(); | |||
| while let Some(value) = data.next_element::<u16>()? { | |||
| array.append_value(value); | |||
| } | |||
| Ok(array.finish().into()) | |||
| } | |||
| DataType::UInt32 => { | |||
| let mut array = UInt32Builder::new(); | |||
| while let Some(value) = data.next_element::<u32>()? { | |||
| array.append_value(value); | |||
| } | |||
| Ok(array.finish().into()) | |||
| } | |||
| DataType::UInt64 => { | |||
| let mut array = UInt64Builder::new(); | |||
| while let Some(value) = data.next_element::<u64>()? { | |||
| array.append_value(value); | |||
| } | |||
| Ok(array.finish().into()) | |||
| } | |||
| DataType::Int8 => { | |||
| let mut array = Int8Builder::new(); | |||
| while let Some(value) = data.next_element::<i8>()? { | |||
| array.append_value(value); | |||
| } | |||
| Ok(array.finish().into()) | |||
| } | |||
| DataType::Int16 => { | |||
| let mut array = Int16Builder::new(); | |||
| while let Some(value) = data.next_element::<i16>()? { | |||
| array.append_value(value); | |||
| } | |||
| Ok(array.finish().into()) | |||
| } | |||
| DataType::Int32 => { | |||
| let mut array = Int32Builder::new(); | |||
| while let Some(value) = data.next_element::<i32>()? { | |||
| array.append_value(value); | |||
| } | |||
| Ok(array.finish().into()) | |||
| } | |||
| DataType::Int64 => { | |||
| let mut array = Int64Builder::new(); | |||
| while let Some(value) = data.next_element::<i64>()? { | |||
| array.append_value(value); | |||
| } | |||
| Ok(array.finish().into()) | |||
| } | |||
| DataType::Float32 => { | |||
| let mut array = Float32Builder::new(); | |||
| while let Some(value) = data.next_element::<f32>()? { | |||
| array.append_value(value); | |||
| } | |||
| Ok(array.finish().into()) | |||
| } | |||
| DataType::Float64 => { | |||
| let mut array = Float64Builder::new(); | |||
| while let Some(value) = data.next_element::<f64>()? { | |||
| array.append_value(value); | |||
| } | |||
| Ok(array.finish().into()) | |||
| } | |||
| DataType::Utf8 => { | |||
| let mut array = StringBuilder::new(); | |||
| while let Some(value) = data.next_element::<String>()? { | |||
| array.append_value(value); | |||
| } | |||
| Ok(array.finish().into()) | |||
| } | |||
| _ => { | |||
| let mut buffer = vec![]; | |||
| while let Some(value) = data.next_element_seed(TypedDeserializer { | |||
| type_info: TypeInfo { | |||
| data_type: self.field.data_type().clone(), | |||
| defaults: self.defaults.clone(), | |||
| }, | |||
| })? { | |||
| let element = make_array(value.0); | |||
| buffer.push(element); | |||
| } | |||
| concat( | |||
| buffer | |||
| .iter() | |||
| .map(|data| data.as_ref()) | |||
| .collect::<Vec<_>>() | |||
| .as_slice(), | |||
| ) | |||
| .map(|op| op.to_data()) | |||
| } | |||
| }; | |||
| if let Ok(values) = data { | |||
| let offsets = OffsetBuffer::new(vec![0, values.len() as i32].into()); | |||
| let array = | |||
| ListArray::new(self.field, offsets.clone(), make_array(values), None).to_data(); | |||
| Ok(array) | |||
| } else { | |||
| Ok(self.defaults) // TODO: Better handle deserialization error | |||
| } | |||
| } | |||
| } | |||
| @@ -0,0 +1,283 @@ | |||
| use arrow::{ | |||
| array::{ | |||
| make_array, Array, ArrayData, ArrayRef, BooleanArray, Float32Array, Float64Array, | |||
| Int16Array, Int32Array, Int64Array, Int8Array, StringArray, StructArray, UInt16Array, | |||
| UInt32Array, UInt64Array, UInt8Array, | |||
| }, | |||
| buffer::Buffer, | |||
| compute::concat, | |||
| datatypes::{DataType, Field}, | |||
| }; | |||
| use dora_ros2_bridge_msg_gen::types::{ | |||
| primitives::{BasicType, NestableType}, | |||
| MemberType, Message, | |||
| }; | |||
| use eyre::{Context, ContextCompat, Result}; | |||
| use std::{collections::HashMap, sync::Arc}; | |||
| pub use serialize::TypedValue; | |||
| pub mod deserialize; | |||
| pub mod serialize; | |||
| #[derive(Debug, Clone, PartialEq)] | |||
| pub struct TypeInfo { | |||
| data_type: DataType, | |||
| defaults: ArrayData, | |||
| } | |||
| pub fn for_message( | |||
| messages: &HashMap<String, HashMap<String, Message>>, | |||
| package_name: &str, | |||
| message_name: &str, | |||
| ) -> eyre::Result<TypeInfo> { | |||
| let empty = HashMap::new(); | |||
| let package_messages = messages.get(package_name).unwrap_or(&empty); | |||
| let message = package_messages | |||
| .get(message_name) | |||
| .context("unknown type name")?; | |||
| let default_struct_vec: Vec<(Arc<Field>, Arc<dyn Array>)> = message | |||
| .members | |||
| .iter() | |||
| .map(|m| { | |||
| let default = make_array(default_for_member(m, package_name, messages)?); | |||
| Result::<_, eyre::Report>::Ok(( | |||
| Arc::new(Field::new( | |||
| m.name.clone(), | |||
| default.data_type().clone(), | |||
| true, | |||
| )), | |||
| default, | |||
| )) | |||
| }) | |||
| .collect::<Result<_, _>>()?; | |||
| let default_struct: StructArray = default_struct_vec.into(); | |||
| Ok(TypeInfo { | |||
| data_type: default_struct.data_type().clone(), | |||
| defaults: default_struct.into(), | |||
| }) | |||
| } | |||
| pub fn default_for_member( | |||
| m: &dora_ros2_bridge_msg_gen::types::Member, | |||
| package_name: &str, | |||
| messages: &HashMap<String, HashMap<String, Message>>, | |||
| ) -> eyre::Result<ArrayData> { | |||
| let value = match &m.r#type { | |||
| MemberType::NestableType(t) => match t { | |||
| NestableType::BasicType(_) | NestableType::GenericString(_) => match &m | |||
| .default | |||
| .as_deref() | |||
| { | |||
| Some([]) => eyre::bail!("empty default value not supported"), | |||
| Some([default]) => preset_default_for_basic_type(t, &default) | |||
| .with_context(|| format!("failed to parse default value for `{}`", m.name))?, | |||
| Some(_) => eyre::bail!( | |||
| "there should be only a single default value for non-sequence types" | |||
| ), | |||
| None => default_for_nestable_type(t, package_name, messages)?, | |||
| }, | |||
| NestableType::NamedType(_) => { | |||
| if m.default.is_some() { | |||
| eyre::bail!("default values for nested types are not supported") | |||
| } else { | |||
| default_for_nestable_type(t, package_name, messages)? | |||
| } | |||
| } | |||
| NestableType::NamespacedType(_) => { | |||
| default_for_nestable_type(t, package_name, messages)? | |||
| } | |||
| }, | |||
| MemberType::Array(array) => { | |||
| list_default_values(m, &array.value_type, package_name, messages)? | |||
| } | |||
| MemberType::Sequence(seq) => { | |||
| list_default_values(m, &seq.value_type, package_name, messages)? | |||
| } | |||
| MemberType::BoundedSequence(seq) => { | |||
| list_default_values(m, &seq.value_type, package_name, messages)? | |||
| } | |||
| }; | |||
| Ok(value) | |||
| } | |||
| fn default_for_nestable_type( | |||
| t: &NestableType, | |||
| package_name: &str, | |||
| messages: &HashMap<String, HashMap<String, Message>>, | |||
| ) -> Result<ArrayData> { | |||
| let empty = HashMap::new(); | |||
| let package_messages = messages.get(package_name).unwrap_or(&empty); | |||
| let array = match t { | |||
| NestableType::BasicType(t) => match t { | |||
| BasicType::I8 => Int8Array::from(vec![0]).into(), | |||
| BasicType::I16 => Int16Array::from(vec![0]).into(), | |||
| BasicType::I32 => Int32Array::from(vec![0]).into(), | |||
| BasicType::I64 => Int64Array::from(vec![0]).into(), | |||
| BasicType::U8 => UInt8Array::from(vec![0]).into(), | |||
| BasicType::U16 => UInt16Array::from(vec![0]).into(), | |||
| BasicType::U32 => UInt32Array::from(vec![0]).into(), | |||
| BasicType::U64 => UInt64Array::from(vec![0]).into(), | |||
| BasicType::F32 => Float32Array::from(vec![0.]).into(), | |||
| BasicType::F64 => Float64Array::from(vec![0.]).into(), | |||
| BasicType::Char => StringArray::from(vec![""]).into(), | |||
| BasicType::Byte => UInt8Array::from(vec![0u8] as Vec<u8>).into(), | |||
| BasicType::Bool => BooleanArray::from(vec![false]).into(), | |||
| }, | |||
| NestableType::GenericString(_) => StringArray::from(vec![""]).into(), | |||
| NestableType::NamedType(name) => { | |||
| let referenced_message = package_messages | |||
| .get(&name.0) | |||
| .context("unknown referenced message")?; | |||
| default_for_referenced_message(referenced_message, package_name, messages)? | |||
| } | |||
| NestableType::NamespacedType(t) => { | |||
| let referenced_package_messages = messages.get(&t.package).unwrap_or(&empty); | |||
| let referenced_message = referenced_package_messages | |||
| .get(&t.name) | |||
| .context("unknown referenced message")?; | |||
| default_for_referenced_message(referenced_message, &t.package, messages)? | |||
| } | |||
| }; | |||
| Ok(array) | |||
| } | |||
| fn preset_default_for_basic_type(t: &NestableType, preset: &str) -> Result<ArrayData> { | |||
| Ok(match t { | |||
| NestableType::BasicType(t) => match t { | |||
| BasicType::I8 => Int8Array::from(vec![preset | |||
| .parse::<i8>() | |||
| .context("Could not parse preset default value")?]) | |||
| .into(), | |||
| BasicType::I16 => Int16Array::from(vec![preset | |||
| .parse::<i16>() | |||
| .context("Could not parse preset default value")?]) | |||
| .into(), | |||
| BasicType::I32 => Int32Array::from(vec![preset | |||
| .parse::<i32>() | |||
| .context("Could not parse preset default value")?]) | |||
| .into(), | |||
| BasicType::I64 => Int64Array::from(vec![preset | |||
| .parse::<i64>() | |||
| .context("Could not parse preset default value")?]) | |||
| .into(), | |||
| BasicType::U8 => UInt8Array::from(vec![preset | |||
| .parse::<u8>() | |||
| .context("Could not parse preset default value")?]) | |||
| .into(), | |||
| BasicType::U16 => UInt16Array::from(vec![preset | |||
| .parse::<u16>() | |||
| .context("Could not parse preset default value")?]) | |||
| .into(), | |||
| BasicType::U32 => UInt32Array::from(vec![preset | |||
| .parse::<u32>() | |||
| .context("Could not parse preset default value")?]) | |||
| .into(), | |||
| BasicType::U64 => UInt64Array::from(vec![preset | |||
| .parse::<u64>() | |||
| .context("Could not parse preset default value")?]) | |||
| .into(), | |||
| BasicType::F32 => Float32Array::from(vec![preset | |||
| .parse::<f32>() | |||
| .context("Could not parse preset default value")?]) | |||
| .into(), | |||
| BasicType::F64 => Float64Array::from(vec![preset | |||
| .parse::<f64>() | |||
| .context("Could not parse preset default value")?]) | |||
| .into(), | |||
| BasicType::Char => StringArray::from(vec![preset]).into(), | |||
| BasicType::Byte => UInt8Array::from(preset.as_bytes().to_owned()).into(), | |||
| BasicType::Bool => BooleanArray::from(vec![preset | |||
| .parse::<bool>() | |||
| .context("could not parse preset default value")?]) | |||
| .into(), | |||
| }, | |||
| NestableType::GenericString(_) => StringArray::from(vec![preset]).into(), | |||
| _ => todo!(), | |||
| }) | |||
| } | |||
| fn default_for_referenced_message( | |||
| referenced_message: &Message, | |||
| package_name: &str, | |||
| messages: &HashMap<String, HashMap<String, Message>>, | |||
| ) -> eyre::Result<ArrayData> { | |||
| let fields: Vec<(Arc<Field>, Arc<dyn Array>)> = referenced_message | |||
| .members | |||
| .iter() | |||
| .map(|m| { | |||
| let default = default_for_member(m, package_name, messages)?; | |||
| Result::<_, eyre::Report>::Ok(( | |||
| Arc::new(Field::new( | |||
| m.name.clone(), | |||
| default.data_type().clone(), | |||
| true, | |||
| )), | |||
| make_array(default), | |||
| )) | |||
| }) | |||
| .collect::<Result<_, _>>()?; | |||
| let struct_array: StructArray = fields.into(); | |||
| Ok(struct_array.into()) | |||
| } | |||
| fn list_default_values( | |||
| m: &dora_ros2_bridge_msg_gen::types::Member, | |||
| value_type: &NestableType, | |||
| package_name: &str, | |||
| messages: &HashMap<String, HashMap<String, Message>>, | |||
| ) -> Result<ArrayData> { | |||
| let defaults = match &m.default.as_deref() { | |||
| Some([]) => eyre::bail!("empty default value not supported"), | |||
| Some(defaults) => { | |||
| let raw_array: Vec<Arc<dyn Array>> = defaults | |||
| .iter() | |||
| .map(|default| { | |||
| preset_default_for_basic_type(value_type, &default) | |||
| .with_context(|| format!("failed to parse default value for `{}`", m.name)) | |||
| .map(|data| make_array(data)) | |||
| }) | |||
| .collect::<Result<_, _>>()?; | |||
| let default_values = concat( | |||
| raw_array | |||
| .iter() | |||
| .map(|data| data.as_ref()) | |||
| .collect::<Vec<_>>() | |||
| .as_slice(), | |||
| ) | |||
| .context("Failed to concatenate default list value")?; | |||
| default_values.to_data() | |||
| } | |||
| None => { | |||
| let default_nested_type = | |||
| default_for_nestable_type(&value_type, package_name, messages)?; | |||
| if false { | |||
| //let NestableType::BasicType(_t) = seq.value_type { | |||
| default_nested_type.into() | |||
| } else { | |||
| let value_offsets = Buffer::from_slice_ref([0i64, 1]); | |||
| let list_data_type = DataType::List(Arc::new(Field::new( | |||
| &m.name, | |||
| default_nested_type.data_type().clone(), | |||
| true, | |||
| ))); | |||
| // Construct a list array from the above two | |||
| let array = ArrayData::builder(list_data_type) | |||
| .len(1) | |||
| .add_buffer(value_offsets.clone()) | |||
| .add_child_data(default_nested_type.clone()) | |||
| .build() | |||
| .unwrap(); | |||
| array.into() | |||
| } | |||
| } | |||
| }; | |||
| Ok(defaults) | |||
| } | |||
| @@ -0,0 +1,166 @@ | |||
| use arrow::array::ArrayData; | |||
| use arrow::array::Float32Array; | |||
| use arrow::array::Float64Array; | |||
| use arrow::array::Int16Array; | |||
| use arrow::array::Int32Array; | |||
| use arrow::array::Int64Array; | |||
| use arrow::array::Int8Array; | |||
| use arrow::array::ListArray; | |||
| use arrow::array::StringArray; | |||
| use arrow::array::StructArray; | |||
| use arrow::array::UInt16Array; | |||
| use arrow::array::UInt32Array; | |||
| use arrow::array::UInt64Array; | |||
| use arrow::array::UInt8Array; | |||
| use arrow::datatypes::DataType; | |||
| use serde::ser::SerializeSeq; | |||
| use serde::ser::SerializeStruct; | |||
| use super::TypeInfo; | |||
| #[derive(Debug, Clone, PartialEq)] | |||
| pub struct TypedValue<'a> { | |||
| pub value: &'a ArrayData, | |||
| pub type_info: &'a TypeInfo, | |||
| } | |||
| impl serde::Serialize for TypedValue<'_> { | |||
| fn serialize<S>(&self, serializer: S) -> Result<S::Ok, S::Error> | |||
| where | |||
| S: serde::Serializer, | |||
| { | |||
| match &self.value.data_type() { | |||
| DataType::UInt8 => { | |||
| let uint_array: UInt8Array = self.value.clone().into(); | |||
| let number = uint_array.value(0); | |||
| serializer.serialize_u8(number) | |||
| } | |||
| DataType::UInt16 => { | |||
| let uint_array: UInt16Array = self.value.clone().into(); | |||
| let number = uint_array.value(0); | |||
| serializer.serialize_u16(number) | |||
| } | |||
| DataType::UInt32 => { | |||
| let uint_array: UInt32Array = self.value.clone().into(); | |||
| let number = uint_array.value(0); | |||
| serializer.serialize_u32(number) | |||
| } | |||
| DataType::UInt64 => { | |||
| let uint_array: UInt64Array = self.value.clone().into(); | |||
| let number = uint_array.value(0); | |||
| serializer.serialize_u64(number) | |||
| } | |||
| DataType::Int8 => { | |||
| let int_array: Int8Array = self.value.clone().into(); | |||
| let number = int_array.value(0); | |||
| serializer.serialize_i8(number) | |||
| } | |||
| DataType::Int16 => { | |||
| let int_array: Int16Array = self.value.clone().into(); | |||
| let number = int_array.value(0); | |||
| serializer.serialize_i16(number) | |||
| } | |||
| DataType::Int32 => { | |||
| let int_array: Int32Array = self.value.clone().into(); | |||
| let number = int_array.value(0); | |||
| serializer.serialize_i32(number) | |||
| } | |||
| DataType::Int64 => { | |||
| let int_array: Int64Array = self.value.clone().into(); | |||
| let number = int_array.value(0); | |||
| serializer.serialize_i64(number) | |||
| } | |||
| DataType::Float32 => { | |||
| let int_array: Float32Array = self.value.clone().into(); | |||
| let number = int_array.value(0); | |||
| serializer.serialize_f32(number) | |||
| } | |||
| DataType::Float64 => { | |||
| let int_array: Float64Array = self.value.clone().into(); | |||
| let number = int_array.value(0); | |||
| serializer.serialize_f64(number) | |||
| } | |||
| DataType::Utf8 => { | |||
| let int_array: StringArray = self.value.clone().into(); | |||
| let string = int_array.value(0); | |||
| serializer.serialize_str(string) | |||
| } | |||
| DataType::List(_field) => { | |||
| let list_array: ListArray = self.value.clone().into(); | |||
| if let DataType::List(field) = self.type_info.data_type.clone() { | |||
| let values = list_array.values(); | |||
| let mut s = serializer.serialize_seq(Some(values.len()))?; | |||
| for value in list_array.iter() { | |||
| let value = match value { | |||
| Some(value) => value.to_data(), | |||
| None => { | |||
| return Err(serde::ser::Error::custom(format!( | |||
| "Value in ListArray is null and not yet supported", | |||
| ))) | |||
| } | |||
| }; | |||
| s.serialize_element(&TypedValue { | |||
| value: &value, | |||
| type_info: &TypeInfo { | |||
| data_type: field.data_type().clone(), | |||
| defaults: self.type_info.defaults.clone(), | |||
| }, | |||
| })?; | |||
| } | |||
| s.end() | |||
| } else { | |||
| return Err(serde::ser::Error::custom(format!("Wrong fields type",))); | |||
| } | |||
| } | |||
| DataType::Struct(_fields) => { | |||
| /// Serde requires that struct and field names are known at | |||
| /// compile time with a `'static` lifetime, which is not | |||
| /// possible in this case. Thus, we need to use dummy names | |||
| /// instead. | |||
| /// | |||
| /// The actual names do not really matter because | |||
| /// the CDR format of ROS2 does not encode struct or field | |||
| /// names. | |||
| const DUMMY_STRUCT_NAME: &str = "struct"; | |||
| const DUMMY_FIELD_NAME: &str = "field"; | |||
| let struct_array: StructArray = self.value.clone().into(); | |||
| if let DataType::Struct(fields) = self.type_info.data_type.clone() { | |||
| let mut s = serializer.serialize_struct(DUMMY_STRUCT_NAME, fields.len())?; | |||
| let defaults: StructArray = self.type_info.defaults.clone().into(); | |||
| for field in fields.iter() { | |||
| let default = match defaults.column_by_name(field.name()) { | |||
| Some(value) => value.to_data(), | |||
| None => { | |||
| return Err(serde::ser::Error::custom(format!( | |||
| "missing field {} for serialization", | |||
| &field.name() | |||
| ))) | |||
| } | |||
| }; | |||
| let field_value = match struct_array.column_by_name(field.name()) { | |||
| Some(value) => value.to_data(), | |||
| None => default.clone(), | |||
| }; | |||
| s.serialize_field( | |||
| DUMMY_FIELD_NAME, | |||
| &TypedValue { | |||
| value: &field_value, | |||
| type_info: &TypeInfo { | |||
| data_type: field.data_type().clone(), | |||
| defaults: default, | |||
| }, | |||
| }, | |||
| )?; | |||
| } | |||
| s.end() | |||
| } else { | |||
| return Err(serde::ser::Error::custom(format!("Wrong fields type",))); | |||
| } | |||
| } | |||
| _ => todo!(), | |||
| } | |||
| } | |||
| } | |||
| @@ -0,0 +1,12 @@ | |||
| pub use widestring; | |||
| pub mod sequence; | |||
| pub mod string; | |||
| pub mod traits; | |||
| pub use sequence::{FFISeq, OwnedFFISeq, RefFFISeq}; | |||
| pub use string::{FFIString, FFIWString, OwnedFFIString, OwnedFFIWString}; | |||
| pub use traits::{ActionT, FFIFromRust, FFIToRust, InternalDefault, MessageT, ServiceT}; | |||
| pub type ServiceRequestRaw<Srv> = <<Srv as ServiceT>::Request as MessageT>::Raw; | |||
| pub type ServiceResponseRaw<Srv> = <<Srv as ServiceT>::Response as MessageT>::Raw; | |||
| @@ -0,0 +1,184 @@ | |||
| use std::{mem::ManuallyDrop, ops::Deref}; | |||
| use super::traits::{FFIFromRust, FFIToRust}; | |||
| #[repr(C)] | |||
| #[derive(Debug)] | |||
| pub struct FFISeq<T> { | |||
| data: *mut T, | |||
| size: usize, | |||
| capacity: usize, | |||
| } | |||
| impl<T> FFISeq<T> { | |||
| /// Extracts a slice. | |||
| pub fn as_slice(&self) -> &[T] { | |||
| self | |||
| } | |||
| /// Returns the length of the sequence. | |||
| pub const fn len(&self) -> usize { | |||
| self.size | |||
| } | |||
| /// Returns `true` if the sequence has a length of 0. | |||
| pub const fn is_empty(&self) -> bool { | |||
| self.len() == 0 | |||
| } | |||
| } | |||
| impl<T> FFIToRust for FFISeq<T> | |||
| where | |||
| T: FFIToRust, | |||
| { | |||
| type Target = Vec<T::Target>; | |||
| unsafe fn to_rust(&self) -> Self::Target { | |||
| self.iter().map(|v| v.to_rust()).collect() | |||
| } | |||
| } | |||
| macro_rules! impl_traits_to_primitive { | |||
| ($type: ty) => { | |||
| impl FFIToRust for FFISeq<$type> { | |||
| type Target = Vec<$type>; | |||
| unsafe fn to_rust(&self) -> Self::Target { | |||
| self.iter().cloned().collect() | |||
| } | |||
| } | |||
| }; | |||
| } | |||
| impl_traits_to_primitive!(i8); | |||
| impl_traits_to_primitive!(i16); | |||
| impl_traits_to_primitive!(i32); | |||
| impl_traits_to_primitive!(i64); | |||
| impl_traits_to_primitive!(u8); | |||
| impl_traits_to_primitive!(u16); | |||
| impl_traits_to_primitive!(u32); | |||
| impl_traits_to_primitive!(u64); | |||
| impl_traits_to_primitive!(f32); | |||
| impl_traits_to_primitive!(f64); | |||
| impl_traits_to_primitive!(bool); | |||
| impl<T> Deref for FFISeq<T> { | |||
| type Target = [T]; | |||
| fn deref(&self) -> &[T] { | |||
| unsafe { std::slice::from_raw_parts(self.data, self.len()) } | |||
| } | |||
| } | |||
| impl<T> AsRef<[T]> for FFISeq<T> { | |||
| fn as_ref(&self) -> &[T] { | |||
| self | |||
| } | |||
| } | |||
| #[repr(C)] | |||
| #[derive(Debug)] | |||
| pub struct OwnedFFISeq<T> { | |||
| data: *mut T, | |||
| size: usize, | |||
| capacity: usize, | |||
| } | |||
| impl<T> OwnedFFISeq<T> { | |||
| /// Extracts a slice. | |||
| pub fn as_slice(&self) -> &[T] { | |||
| unsafe { std::slice::from_raw_parts(self.data, self.len()) } | |||
| } | |||
| /// Returns the length of the sequence. | |||
| pub const fn len(&self) -> usize { | |||
| self.size | |||
| } | |||
| /// Returns `true` if the sequence has a length of 0. | |||
| pub const fn is_empty(&self) -> bool { | |||
| self.len() == 0 | |||
| } | |||
| } | |||
| impl<T> FFIFromRust for OwnedFFISeq<T> | |||
| where | |||
| T: FFIFromRust, | |||
| { | |||
| type From = Vec<T::From>; | |||
| unsafe fn from_rust(vec: &Self::From) -> Self { | |||
| if vec.is_empty() { | |||
| Self { | |||
| data: std::ptr::null_mut(), | |||
| size: 0, | |||
| capacity: 0, | |||
| } | |||
| } else { | |||
| let mut new_vec = vec | |||
| .iter() | |||
| .map(|v| FFIFromRust::from_rust(v)) | |||
| .collect::<Vec<_>>(); | |||
| new_vec.shrink_to_fit(); | |||
| assert_eq!(new_vec.len(), new_vec.capacity()); | |||
| let mut new_vec = ManuallyDrop::new(new_vec); | |||
| Self { | |||
| data: new_vec.as_mut_ptr(), | |||
| size: new_vec.len(), | |||
| capacity: new_vec.len(), | |||
| } | |||
| } | |||
| } | |||
| } | |||
| impl<T> Drop for OwnedFFISeq<T> { | |||
| fn drop(&mut self) { | |||
| unsafe { Vec::from_raw_parts(self.data, self.size, self.capacity) }; | |||
| } | |||
| } | |||
| /// Temporally borrowed buffer from `Vec<T>` | |||
| #[repr(C)] | |||
| #[derive(Debug)] | |||
| pub struct RefFFISeq<T> { | |||
| data: *mut T, | |||
| size: usize, | |||
| capacity: usize, | |||
| } | |||
| impl<T> RefFFISeq<T> { | |||
| /// Extracts a slice. | |||
| pub fn as_slice(&self) -> &[T] { | |||
| unsafe { std::slice::from_raw_parts(self.data, self.len()) } | |||
| } | |||
| /// Returns the length of the sequence. | |||
| pub const fn len(&self) -> usize { | |||
| self.size | |||
| } | |||
| /// Returns `true` if the sequence has a length of 0. | |||
| pub const fn is_empty(&self) -> bool { | |||
| self.len() == 0 | |||
| } | |||
| } | |||
| impl<T> FFIFromRust for RefFFISeq<T> { | |||
| type From = Vec<T>; | |||
| unsafe fn from_rust(vec: &Self::From) -> Self { | |||
| if vec.is_empty() { | |||
| Self { | |||
| data: std::ptr::null_mut(), | |||
| size: 0, | |||
| capacity: 0, | |||
| } | |||
| } else { | |||
| Self { | |||
| data: vec.as_ptr() as *mut _, | |||
| size: vec.len(), | |||
| capacity: vec.len(), | |||
| } | |||
| } | |||
| } | |||
| } | |||
| @@ -0,0 +1,252 @@ | |||
| use std::{ | |||
| ffi::{CStr, CString}, | |||
| ops::{Deref, DerefMut}, | |||
| os::raw::c_char, | |||
| }; | |||
| use widestring::{U16CStr, U16CString}; | |||
| use super::traits::{FFIFromRust, FFIToRust}; | |||
| #[derive( | |||
| Debug, | |||
| Default, | |||
| Clone, | |||
| PartialEq, | |||
| Eq, | |||
| PartialOrd, | |||
| Ord, | |||
| Hash, | |||
| serde::Serialize, | |||
| serde::Deserialize, | |||
| )] | |||
| #[serde(from = "Vec<u16>", into = "Vec<u16>")] | |||
| #[repr(transparent)] | |||
| pub struct U16String(widestring::U16String); | |||
| impl U16String { | |||
| pub fn new() -> Self { | |||
| Self(widestring::U16String::new()) | |||
| } | |||
| pub fn from_str(arg: &str) -> U16String { | |||
| Self(widestring::U16String::from_str(arg)) | |||
| } | |||
| } | |||
| impl Deref for U16String { | |||
| type Target = widestring::U16String; | |||
| fn deref(&self) -> &Self::Target { | |||
| &self.0 | |||
| } | |||
| } | |||
| impl DerefMut for U16String { | |||
| fn deref_mut(&mut self) -> &mut Self::Target { | |||
| &mut self.0 | |||
| } | |||
| } | |||
| impl AsRef<widestring::U16Str> for U16String { | |||
| fn as_ref(&self) -> &widestring::U16Str { | |||
| self.0.as_ref() | |||
| } | |||
| } | |||
| impl From<U16String> for Vec<u16> { | |||
| fn from(value: U16String) -> Self { | |||
| value.0.into_vec() | |||
| } | |||
| } | |||
| impl From<Vec<u16>> for U16String { | |||
| fn from(value: Vec<u16>) -> Self { | |||
| Self(value.into()) | |||
| } | |||
| } | |||
| /// An array of 8-bit characters terminated by a null character. | |||
| #[repr(C)] | |||
| #[derive(Debug)] | |||
| pub struct FFIString { | |||
| data: *mut c_char, | |||
| size: usize, | |||
| capacity: usize, | |||
| } | |||
| impl FFIString { | |||
| /// Returns the length of the string (excluding the null byte) | |||
| pub const fn len(&self) -> usize { | |||
| self.size | |||
| } | |||
| /// Returns `true` if the string has a length of 0. | |||
| pub const fn is_empty(&self) -> bool { | |||
| self.len() == 0 | |||
| } | |||
| pub unsafe fn to_str(&self) -> Result<&str, std::str::Utf8Error> { | |||
| if self.is_empty() { | |||
| Ok("") | |||
| } else { | |||
| CStr::from_ptr(self.data).to_str() | |||
| } | |||
| } | |||
| } | |||
| impl FFIToRust for FFIString { | |||
| type Target = String; | |||
| unsafe fn to_rust(&self) -> Self::Target { | |||
| self.to_str().expect("CStr::to_str failed").to_string() | |||
| } | |||
| } | |||
| #[repr(C)] | |||
| #[derive(Debug)] | |||
| pub struct OwnedFFIString { | |||
| data: *mut c_char, | |||
| size: usize, | |||
| capacity: usize, | |||
| } | |||
| impl OwnedFFIString { | |||
| /// Returns the length of the string (excluding the null byte) | |||
| pub const fn len(&self) -> usize { | |||
| self.size | |||
| } | |||
| /// Returns `true` if the string has a length of 0. | |||
| pub const fn is_empty(&self) -> bool { | |||
| self.len() == 0 | |||
| } | |||
| } | |||
| impl FFIFromRust for OwnedFFIString { | |||
| type From = String; | |||
| unsafe fn from_rust(string: &Self::From) -> Self { | |||
| let cstring = CString::new(string.clone()).expect("CString::new failed"); | |||
| let len = cstring.as_bytes().len(); | |||
| Self { | |||
| data: cstring.into_raw(), | |||
| size: len, | |||
| capacity: len + 1, | |||
| } | |||
| } | |||
| } | |||
| impl Drop for OwnedFFIString { | |||
| fn drop(&mut self) { | |||
| unsafe { | |||
| std::mem::drop(CString::from_raw(self.data)); | |||
| } | |||
| } | |||
| } | |||
| /// An array of 16-bit characters terminated by a null character. | |||
| #[repr(C)] | |||
| #[derive(Debug)] | |||
| pub struct FFIWString { | |||
| data: *mut u16, | |||
| size: usize, | |||
| capacity: usize, | |||
| } | |||
| impl FFIWString { | |||
| /// Returns the length of the string (excluding the null byte) | |||
| pub const fn len(&self) -> usize { | |||
| self.size | |||
| } | |||
| /// Returns `true` if the sequence has a length of 0. | |||
| pub const fn is_empty(&self) -> bool { | |||
| self.len() == 0 | |||
| } | |||
| } | |||
| impl FFIToRust for FFIWString { | |||
| type Target = U16String; | |||
| unsafe fn to_rust(&self) -> Self::Target { | |||
| if self.is_empty() { | |||
| Self::Target::new() | |||
| } else { | |||
| U16String(U16CStr::from_ptr_str(self.data).to_ustring()) | |||
| } | |||
| } | |||
| } | |||
| #[repr(C)] | |||
| #[derive(Debug)] | |||
| pub struct OwnedFFIWString { | |||
| data: *mut u16, | |||
| size: usize, | |||
| capacity: usize, | |||
| } | |||
| impl OwnedFFIWString { | |||
| /// Returns the length of the string (excluding the null byte) | |||
| pub const fn len(&self) -> usize { | |||
| self.size | |||
| } | |||
| /// Returns `true` if the sequence has a length of 0. | |||
| pub const fn is_empty(&self) -> bool { | |||
| self.len() == 0 | |||
| } | |||
| } | |||
| impl FFIFromRust for OwnedFFIWString { | |||
| type From = U16String; | |||
| unsafe fn from_rust(string: &Self::From) -> Self { | |||
| let cstring = U16CString::from_ustr(string).expect("U16CString::new failed"); | |||
| let len = cstring.len(); | |||
| Self { | |||
| data: cstring.into_raw(), | |||
| size: len, | |||
| capacity: len + 1, | |||
| } | |||
| } | |||
| } | |||
| impl Drop for OwnedFFIWString { | |||
| fn drop(&mut self) { | |||
| unsafe { | |||
| std::mem::drop(U16CString::from_raw(self.data)); | |||
| } | |||
| } | |||
| } | |||
| #[cfg(test)] | |||
| mod test { | |||
| use super::*; | |||
| #[test] | |||
| fn owned_ffi_string_new() { | |||
| let string = "abcde".into(); | |||
| let cstring = unsafe { OwnedFFIString::from_rust(&string) }; | |||
| let native_string = FFIString { | |||
| data: cstring.data, | |||
| size: cstring.size, | |||
| capacity: cstring.capacity, | |||
| }; | |||
| assert_eq!(string, unsafe { native_string.to_rust() }); | |||
| } | |||
| #[test] | |||
| fn owned_ffi_wstring_new() { | |||
| let wstring = U16String::from_str("あいうえお"); | |||
| let cwstring = unsafe { OwnedFFIWString::from_rust(&wstring) }; | |||
| let native_wstring = FFIWString { | |||
| data: cwstring.data, | |||
| size: cwstring.size, | |||
| capacity: cwstring.capacity, | |||
| }; | |||
| assert_eq!(wstring, unsafe { native_wstring.to_rust() }); | |||
| } | |||
| } | |||
| @@ -0,0 +1,118 @@ | |||
| use std::convert::TryInto; | |||
| use super::string::U16String; | |||
| use array_init::array_init; | |||
| pub trait MessageT: Default + Send + Sync { | |||
| type Raw: FFIToRust<Target = Self> + Send + Sync; | |||
| type RawRef: FFIFromRust<From = Self>; | |||
| unsafe fn from_raw(from: &Self::Raw) -> Self { | |||
| from.to_rust() | |||
| } | |||
| unsafe fn to_raw_ref(&self) -> Self::RawRef { | |||
| Self::RawRef::from_rust(self) | |||
| } | |||
| } | |||
| pub trait ServiceT: Send { | |||
| type Request: MessageT; | |||
| type Response: MessageT; | |||
| } | |||
| pub trait ActionT: Send { | |||
| type Goal: MessageT; | |||
| type Result: MessageT; | |||
| type Feedback: MessageT; | |||
| type SendGoal: ServiceT; | |||
| type GetResult: ServiceT; | |||
| type FeedbackMessage: MessageT; | |||
| } | |||
| // I was going to use `std::default::Default`, however generic arrays do not implement `std::default::Default`. | |||
| pub trait InternalDefault { | |||
| fn _default() -> Self; | |||
| } | |||
| impl<T> InternalDefault for Vec<T> { | |||
| fn _default() -> Self { | |||
| Self::new() | |||
| } | |||
| } | |||
| impl<T, const N: usize> InternalDefault for [T; N] | |||
| where | |||
| T: InternalDefault + std::fmt::Debug, | |||
| { | |||
| fn _default() -> Self { | |||
| array_init(|_| InternalDefault::_default()) | |||
| } | |||
| } | |||
| macro_rules! impl_trait { | |||
| ($type: ty) => { | |||
| impl InternalDefault for $type { | |||
| fn _default() -> Self { | |||
| Self::default() | |||
| } | |||
| } | |||
| }; | |||
| } | |||
| impl_trait!(i8); | |||
| impl_trait!(i16); | |||
| impl_trait!(i32); | |||
| impl_trait!(i64); | |||
| impl_trait!(u8); | |||
| impl_trait!(u16); | |||
| impl_trait!(u32); | |||
| impl_trait!(u64); | |||
| impl_trait!(f32); | |||
| impl_trait!(f64); | |||
| impl_trait!(bool); | |||
| impl_trait!(String); | |||
| impl_trait!(U16String); | |||
| pub trait FFIToRust { | |||
| type Target; | |||
| unsafe fn to_rust(&self) -> Self::Target; | |||
| } | |||
| impl<T, const N: usize> FFIToRust for [T; N] | |||
| where | |||
| T: FFIToRust, | |||
| T::Target: std::fmt::Debug, | |||
| { | |||
| type Target = [T::Target; N]; | |||
| unsafe fn to_rust(&self) -> <Self as FFIToRust>::Target { | |||
| self.iter() | |||
| .map(|v| v.to_rust()) | |||
| .collect::<Vec<_>>() | |||
| .try_into() | |||
| .unwrap() | |||
| } | |||
| } | |||
| pub trait FFIFromRust { | |||
| type From; | |||
| unsafe fn from_rust(from: &Self::From) -> Self; | |||
| } | |||
| impl<T, const N: usize> FFIFromRust for [T; N] | |||
| where | |||
| T: FFIFromRust + std::fmt::Debug, | |||
| { | |||
| type From = [T::From; N]; | |||
| unsafe fn from_rust(from: &Self::From) -> Self { | |||
| from.iter() | |||
| .map(|v| FFIFromRust::from_rust(v)) | |||
| .collect::<Vec<_>>() | |||
| .try_into() | |||
| .unwrap() | |||
| } | |||
| } | |||
| @@ -0,0 +1,7 @@ | |||
| pub use ros2_client; | |||
| pub use rustdds; | |||
| #[cfg(feature = "generate-messages")] | |||
| dora_ros2_bridge_msg_gen_macro::msg_include_all!(); | |||
| pub mod _core; | |||